From 5907f8ee9d6b100bebf7cfcfd4808504e3703967 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 3 Dec 2021 15:37:49 +0100 Subject: [PATCH 01/56] Added CFDP packet stack This PR adds the packet stack for the CCSDS File Delivery Protocol. It also refactors the existing TMTC infastructure to allow sending of CFDP packets to the CCSDS handlers. This includes the whole PDU (Protocol Data Unit) stack: - File Data PDUs and all file directive PDUs - ACK PDU - NAK PDU - Metadata PDU - Finished PDU - Prompt PDU - Keep Alive PDU - EOF PDU The PR includes a full set of unittests for the packet stack with a coverage of 90+ %. The refactoring of the existing TMTC infastructure includes non-ideal solutions like diamond inheritance. Avoiding this solution would require refactoring the packet stack. This would be a good idea anyway because the existing stack is tightly coupled to the FSFW, making reuse more difficult if only the stack is planned to be used without the store functionalities etc. The PDU implementation provided here is only weakly coupled to the FSFW, only using components like returnvalues or the Serialization modules. There are dedicated serializers and deserializers, which also helps in creating small focused modules which are easy to test. Some of the modules here were provied by Matthias Tompert. --- CMakeLists.txt | 4 +- README.md | 2 +- .../fsfwconfig/devices/logicalAddresses.h | 2 +- src/fsfw/CMakeLists.txt | 1 + src/fsfw/FSFW.h.in | 4 + src/fsfw/cfdp/CFDPHandler.cpp | 60 ++ src/fsfw/cfdp/CFDPHandler.h | 62 ++ src/fsfw/cfdp/CFDPMessage.cpp | 21 + src/fsfw/cfdp/CFDPMessage.h | 23 + src/fsfw/cfdp/CMakeLists.txt | 7 + src/fsfw/cfdp/FileSize.h | 83 +++ src/fsfw/cfdp/definitions.h | 153 +++++ src/fsfw/cfdp/pdu/AckInfo.cpp | 52 ++ src/fsfw/cfdp/pdu/AckInfo.h | 33 + src/fsfw/cfdp/pdu/AckPduDeserializer.cpp | 38 ++ src/fsfw/cfdp/pdu/AckPduDeserializer.h | 26 + src/fsfw/cfdp/pdu/AckPduSerializer.cpp | 38 ++ src/fsfw/cfdp/pdu/AckPduSerializer.h | 30 + src/fsfw/cfdp/pdu/CMakeLists.txt | 32 + src/fsfw/cfdp/pdu/EofInfo.cpp | 58 ++ src/fsfw/cfdp/pdu/EofInfo.h | 33 + src/fsfw/cfdp/pdu/EofPduDeserializer.cpp | 68 ++ src/fsfw/cfdp/pdu/EofPduDeserializer.h | 18 + src/fsfw/cfdp/pdu/EofPduSerializer.cpp | 46 ++ src/fsfw/cfdp/pdu/EofPduSerializer.h | 22 + src/fsfw/cfdp/pdu/FileDataDeserializer.cpp | 52 ++ src/fsfw/cfdp/pdu/FileDataDeserializer.h | 22 + src/fsfw/cfdp/pdu/FileDataInfo.cpp | 104 +++ src/fsfw/cfdp/pdu/FileDataInfo.h | 45 ++ src/fsfw/cfdp/pdu/FileDataSerializer.cpp | 54 ++ src/fsfw/cfdp/pdu/FileDataSerializer.h | 23 + .../cfdp/pdu/FileDirectiveDeserializer.cpp | 55 ++ src/fsfw/cfdp/pdu/FileDirectiveDeserializer.h | 41 ++ src/fsfw/cfdp/pdu/FileDirectiveSerializer.cpp | 39 ++ src/fsfw/cfdp/pdu/FileDirectiveSerializer.h | 28 + src/fsfw/cfdp/pdu/FinishedInfo.cpp | 111 ++++ src/fsfw/cfdp/pdu/FinishedInfo.h | 45 ++ src/fsfw/cfdp/pdu/FinishedPduDeserializer.cpp | 90 +++ src/fsfw/cfdp/pdu/FinishedPduDeserializer.h | 21 + src/fsfw/cfdp/pdu/FinishedPduSerializer.cpp | 47 ++ src/fsfw/cfdp/pdu/FinishedPduSerializer.h | 22 + src/fsfw/cfdp/pdu/HeaderDeserializer.cpp | 136 ++++ src/fsfw/cfdp/pdu/HeaderDeserializer.h | 93 +++ src/fsfw/cfdp/pdu/HeaderSerializer.cpp | 135 ++++ src/fsfw/cfdp/pdu/HeaderSerializer.h | 64 ++ .../cfdp/pdu/KeepAlivePduDeserializer.cpp | 20 + src/fsfw/cfdp/pdu/KeepAlivePduDeserializer.h | 18 + src/fsfw/cfdp/pdu/KeepAlivePduSerializer.cpp | 26 + src/fsfw/cfdp/pdu/KeepAlivePduSerializer.h | 21 + src/fsfw/cfdp/pdu/MetadataInfo.cpp | 115 ++++ src/fsfw/cfdp/pdu/MetadataInfo.h | 49 ++ src/fsfw/cfdp/pdu/MetadataPduDeserializer.cpp | 58 ++ src/fsfw/cfdp/pdu/MetadataPduDeserializer.h | 18 + src/fsfw/cfdp/pdu/MetadataPduSerializer.cpp | 54 ++ src/fsfw/cfdp/pdu/MetadataPduSerializer.h | 23 + src/fsfw/cfdp/pdu/NakInfo.cpp | 83 +++ src/fsfw/cfdp/pdu/NakInfo.h | 40 ++ src/fsfw/cfdp/pdu/NakPduDeserializer.cpp | 58 ++ src/fsfw/cfdp/pdu/NakPduDeserializer.h | 22 + src/fsfw/cfdp/pdu/NakPduSerializer.cpp | 49 ++ src/fsfw/cfdp/pdu/NakPduSerializer.h | 41 ++ src/fsfw/cfdp/pdu/PduConfig.cpp | 8 + src/fsfw/cfdp/pdu/PduConfig.h | 36 ++ src/fsfw/cfdp/pdu/PduHeaderIF.h | 37 ++ src/fsfw/cfdp/pdu/PromptPduDeserializer.cpp | 22 + src/fsfw/cfdp/pdu/PromptPduDeserializer.h | 18 + src/fsfw/cfdp/pdu/PromptPduSerializer.cpp | 27 + src/fsfw/cfdp/pdu/PromptPduSerializer.h | 18 + src/fsfw/cfdp/pdu/VarLenField.cpp | 127 ++++ src/fsfw/cfdp/pdu/VarLenField.h | 45 ++ src/fsfw/cfdp/tlv/CMakeLists.txt | 10 + src/fsfw/cfdp/tlv/EntityIdTlv.cpp | 68 ++ src/fsfw/cfdp/tlv/EntityIdTlv.h | 39 ++ src/fsfw/cfdp/tlv/FaultHandlerOverrideTlv.cpp | 64 ++ src/fsfw/cfdp/tlv/FaultHandlerOverrideTlv.h | 39 ++ src/fsfw/cfdp/tlv/FilestoreRequestTlv.cpp | 83 +++ src/fsfw/cfdp/tlv/FilestoreRequestTlv.h | 45 ++ src/fsfw/cfdp/tlv/FilestoreResponseTlv.cpp | 124 ++++ src/fsfw/cfdp/tlv/FilestoreResponseTlv.h | 50 ++ src/fsfw/cfdp/tlv/FilestoreTlvBase.h | 176 ++++++ src/fsfw/cfdp/tlv/FlowLabelTlv.cpp | 5 + src/fsfw/cfdp/tlv/FlowLabelTlv.h | 13 + src/fsfw/cfdp/tlv/Lv.cpp | 88 +++ src/fsfw/cfdp/tlv/Lv.h | 53 ++ src/fsfw/cfdp/tlv/MessageToUserTlv.cpp | 8 + src/fsfw/cfdp/tlv/MessageToUserTlv.h | 13 + src/fsfw/cfdp/tlv/Tlv.cpp | 114 ++++ src/fsfw/cfdp/tlv/Tlv.h | 64 ++ src/fsfw/cfdp/tlv/TlvIF.h | 16 + src/fsfw/controller/ExtendedControllerBase.h | 7 +- src/fsfw/devicehandlers/AssemblyBase.h | 2 +- .../devicehandlers/DeviceCommunicationIF.h | 7 +- src/fsfw/devicehandlers/DeviceHandlerBase.h | 22 +- src/fsfw/devicehandlers/DeviceHandlerIF.h | 3 +- src/fsfw/ipc/FwMessageTypes.h | 1 + src/fsfw/objectmanager/frameworkObjects.h | 3 + src/fsfw/osal/linux/CMakeLists.txt | 1 + src/fsfw/osal/linux/MessageQueue.cpp | 6 +- src/fsfw/returnvalues/FwClassIds.h | 1 + src/fsfw/serialize/SerialBufferAdapter.cpp | 2 +- src/fsfw/serialize/SerialBufferAdapter.h | 2 +- src/fsfw/subsystem/SubsystemBase.h | 3 +- src/fsfw/tcdistribution/CCSDSDistributor.cpp | 116 ++-- src/fsfw/tcdistribution/CCSDSDistributor.h | 81 +-- src/fsfw/tcdistribution/CCSDSDistributorIF.h | 49 +- src/fsfw/tcdistribution/CFDPDistributor.cpp | 147 +++++ src/fsfw/tcdistribution/CFDPDistributor.h | 72 +++ src/fsfw/tcdistribution/CFDPDistributorIF.h | 27 + src/fsfw/tcdistribution/CMakeLists.txt | 5 +- src/fsfw/tcdistribution/PUSDistributor.cpp | 12 +- src/fsfw/tcdistribution/PUSDistributor.h | 108 ++-- src/fsfw/tcdistribution/PUSDistributorIF.h | 24 +- src/fsfw/tcdistribution/TcPacketCheckCFDP.cpp | 13 + src/fsfw/tcdistribution/TcPacketCheckCFDP.h | 35 ++ src/fsfw/tcdistribution/TcPacketCheckIF.h | 31 + ...TcPacketCheck.cpp => TcPacketCheckPUS.cpp} | 18 +- .../{TcPacketCheck.h => TcPacketCheckPUS.h} | 25 +- src/fsfw/tmtcpacket/CMakeLists.txt | 1 + .../tmtcpacket/RedirectableDataPointerIF.h | 34 + src/fsfw/tmtcpacket/SpacePacket.cpp | 26 +- src/fsfw/tmtcpacket/SpacePacket.h | 2 +- src/fsfw/tmtcpacket/SpacePacketBase.cpp | 12 +- src/fsfw/tmtcpacket/SpacePacketBase.h | 12 +- src/fsfw/tmtcpacket/cfdp/CFDPPacket.cpp | 20 + src/fsfw/tmtcpacket/cfdp/CFDPPacket.h | 27 + src/fsfw/tmtcpacket/cfdp/CFDPPacketStored.cpp | 97 +++ src/fsfw/tmtcpacket/cfdp/CFDPPacketStored.h | 67 ++ src/fsfw/tmtcpacket/cfdp/CMakeLists.txt | 4 + src/fsfw/tmtcpacket/pus/tc/CMakeLists.txt | 2 +- src/fsfw/tmtcpacket/pus/tc/TcPacketPus.cpp | 26 +- src/fsfw/tmtcpacket/pus/tc/TcPacketPus.h | 7 +- .../{TcPacketBase.cpp => TcPacketPusBase.cpp} | 8 +- .../tc/{TcPacketBase.h => TcPacketPusBase.h} | 12 +- .../tmtcpacket/pus/tc/TcPacketStoredBase.cpp | 12 +- .../tmtcpacket/pus/tc/TcPacketStoredBase.h | 12 +- src/fsfw/tmtcpacket/pus/tc/TcPacketStoredIF.h | 15 +- .../tmtcpacket/pus/tc/TcPacketStoredPus.cpp | 13 +- .../tmtcpacket/pus/tc/TcPacketStoredPus.h | 4 +- src/fsfw/tmtcpacket/pus/tm/TmPacketPusA.cpp | 10 +- src/fsfw/tmtcpacket/pus/tm/TmPacketPusA.h | 3 +- src/fsfw/tmtcpacket/pus/tm/TmPacketPusC.cpp | 13 +- src/fsfw/tmtcpacket/pus/tm/TmPacketPusC.h | 4 +- .../tmtcpacket/pus/tm/TmPacketStoredBase.cpp | 6 +- .../tmtcpacket/pus/tm/TmPacketStoredBase.h | 3 +- .../tmtcpacket/pus/tm/TmPacketStoredPusA.cpp | 8 +- .../tmtcpacket/pus/tm/TmPacketStoredPusA.h | 12 +- .../tmtcpacket/pus/tm/TmPacketStoredPusC.cpp | 9 +- .../tmtcpacket/pus/tm/TmPacketStoredPusC.h | 12 +- .../tmtcservices/CommandingServiceBase.cpp | 591 +++++++++--------- src/fsfw/tmtcservices/CommandingServiceBase.h | 560 ++++++++--------- src/fsfw/tmtcservices/PusServiceBase.cpp | 156 ++--- src/fsfw/tmtcservices/PusServiceBase.h | 226 +++---- src/fsfw/tmtcservices/PusVerificationReport.h | 2 +- .../tmtcservices/VerificationReporter.cpp | 4 +- src/fsfw/tmtcservices/VerificationReporter.h | 4 +- tests/src/fsfw_tests/unit/CMakeLists.txt | 1 + tests/src/fsfw_tests/unit/cfdp/CMakeLists.txt | 12 + tests/src/fsfw_tests/unit/cfdp/testAckPdu.cpp | 101 +++ tests/src/fsfw_tests/unit/cfdp/testCfdp.cpp | 372 +++++++++++ tests/src/fsfw_tests/unit/cfdp/testEofPdu.cpp | 124 ++++ .../src/fsfw_tests/unit/cfdp/testFileData.cpp | 175 ++++++ .../fsfw_tests/unit/cfdp/testFinishedPdu.cpp | 196 ++++++ .../fsfw_tests/unit/cfdp/testKeepAlivePdu.cpp | 84 +++ .../fsfw_tests/unit/cfdp/testMetadataPdu.cpp | 185 ++++++ tests/src/fsfw_tests/unit/cfdp/testNakPdu.cpp | 160 +++++ .../fsfw_tests/unit/cfdp/testPromptPdu.cpp | 71 +++ .../src/fsfw_tests/unit/cfdp/testTlvsLvs.cpp | 334 ++++++++++ 167 files changed, 7801 insertions(+), 1121 deletions(-) create mode 100644 src/fsfw/cfdp/CFDPHandler.cpp create mode 100644 src/fsfw/cfdp/CFDPHandler.h create mode 100644 src/fsfw/cfdp/CFDPMessage.cpp create mode 100644 src/fsfw/cfdp/CFDPMessage.h create mode 100644 src/fsfw/cfdp/CMakeLists.txt create mode 100644 src/fsfw/cfdp/FileSize.h create mode 100644 src/fsfw/cfdp/definitions.h create mode 100644 src/fsfw/cfdp/pdu/AckInfo.cpp create mode 100644 src/fsfw/cfdp/pdu/AckInfo.h create mode 100644 src/fsfw/cfdp/pdu/AckPduDeserializer.cpp create mode 100644 src/fsfw/cfdp/pdu/AckPduDeserializer.h create mode 100644 src/fsfw/cfdp/pdu/AckPduSerializer.cpp create mode 100644 src/fsfw/cfdp/pdu/AckPduSerializer.h create mode 100644 src/fsfw/cfdp/pdu/CMakeLists.txt create mode 100644 src/fsfw/cfdp/pdu/EofInfo.cpp create mode 100644 src/fsfw/cfdp/pdu/EofInfo.h create mode 100644 src/fsfw/cfdp/pdu/EofPduDeserializer.cpp create mode 100644 src/fsfw/cfdp/pdu/EofPduDeserializer.h create mode 100644 src/fsfw/cfdp/pdu/EofPduSerializer.cpp create mode 100644 src/fsfw/cfdp/pdu/EofPduSerializer.h create mode 100644 src/fsfw/cfdp/pdu/FileDataDeserializer.cpp create mode 100644 src/fsfw/cfdp/pdu/FileDataDeserializer.h create mode 100644 src/fsfw/cfdp/pdu/FileDataInfo.cpp create mode 100644 src/fsfw/cfdp/pdu/FileDataInfo.h create mode 100644 src/fsfw/cfdp/pdu/FileDataSerializer.cpp create mode 100644 src/fsfw/cfdp/pdu/FileDataSerializer.h create mode 100644 src/fsfw/cfdp/pdu/FileDirectiveDeserializer.cpp create mode 100644 src/fsfw/cfdp/pdu/FileDirectiveDeserializer.h create mode 100644 src/fsfw/cfdp/pdu/FileDirectiveSerializer.cpp create mode 100644 src/fsfw/cfdp/pdu/FileDirectiveSerializer.h create mode 100644 src/fsfw/cfdp/pdu/FinishedInfo.cpp create mode 100644 src/fsfw/cfdp/pdu/FinishedInfo.h create mode 100644 src/fsfw/cfdp/pdu/FinishedPduDeserializer.cpp create mode 100644 src/fsfw/cfdp/pdu/FinishedPduDeserializer.h create mode 100644 src/fsfw/cfdp/pdu/FinishedPduSerializer.cpp create mode 100644 src/fsfw/cfdp/pdu/FinishedPduSerializer.h create mode 100644 src/fsfw/cfdp/pdu/HeaderDeserializer.cpp create mode 100644 src/fsfw/cfdp/pdu/HeaderDeserializer.h create mode 100644 src/fsfw/cfdp/pdu/HeaderSerializer.cpp create mode 100644 src/fsfw/cfdp/pdu/HeaderSerializer.h create mode 100644 src/fsfw/cfdp/pdu/KeepAlivePduDeserializer.cpp create mode 100644 src/fsfw/cfdp/pdu/KeepAlivePduDeserializer.h create mode 100644 src/fsfw/cfdp/pdu/KeepAlivePduSerializer.cpp create mode 100644 src/fsfw/cfdp/pdu/KeepAlivePduSerializer.h create mode 100644 src/fsfw/cfdp/pdu/MetadataInfo.cpp create mode 100644 src/fsfw/cfdp/pdu/MetadataInfo.h create mode 100644 src/fsfw/cfdp/pdu/MetadataPduDeserializer.cpp create mode 100644 src/fsfw/cfdp/pdu/MetadataPduDeserializer.h create mode 100644 src/fsfw/cfdp/pdu/MetadataPduSerializer.cpp create mode 100644 src/fsfw/cfdp/pdu/MetadataPduSerializer.h create mode 100644 src/fsfw/cfdp/pdu/NakInfo.cpp create mode 100644 src/fsfw/cfdp/pdu/NakInfo.h create mode 100644 src/fsfw/cfdp/pdu/NakPduDeserializer.cpp create mode 100644 src/fsfw/cfdp/pdu/NakPduDeserializer.h create mode 100644 src/fsfw/cfdp/pdu/NakPduSerializer.cpp create mode 100644 src/fsfw/cfdp/pdu/NakPduSerializer.h create mode 100644 src/fsfw/cfdp/pdu/PduConfig.cpp create mode 100644 src/fsfw/cfdp/pdu/PduConfig.h create mode 100644 src/fsfw/cfdp/pdu/PduHeaderIF.h create mode 100644 src/fsfw/cfdp/pdu/PromptPduDeserializer.cpp create mode 100644 src/fsfw/cfdp/pdu/PromptPduDeserializer.h create mode 100644 src/fsfw/cfdp/pdu/PromptPduSerializer.cpp create mode 100644 src/fsfw/cfdp/pdu/PromptPduSerializer.h create mode 100644 src/fsfw/cfdp/pdu/VarLenField.cpp create mode 100644 src/fsfw/cfdp/pdu/VarLenField.h create mode 100644 src/fsfw/cfdp/tlv/CMakeLists.txt create mode 100644 src/fsfw/cfdp/tlv/EntityIdTlv.cpp create mode 100644 src/fsfw/cfdp/tlv/EntityIdTlv.h create mode 100644 src/fsfw/cfdp/tlv/FaultHandlerOverrideTlv.cpp create mode 100644 src/fsfw/cfdp/tlv/FaultHandlerOverrideTlv.h create mode 100644 src/fsfw/cfdp/tlv/FilestoreRequestTlv.cpp create mode 100644 src/fsfw/cfdp/tlv/FilestoreRequestTlv.h create mode 100644 src/fsfw/cfdp/tlv/FilestoreResponseTlv.cpp create mode 100644 src/fsfw/cfdp/tlv/FilestoreResponseTlv.h create mode 100644 src/fsfw/cfdp/tlv/FilestoreTlvBase.h create mode 100644 src/fsfw/cfdp/tlv/FlowLabelTlv.cpp create mode 100644 src/fsfw/cfdp/tlv/FlowLabelTlv.h create mode 100644 src/fsfw/cfdp/tlv/Lv.cpp create mode 100644 src/fsfw/cfdp/tlv/Lv.h create mode 100644 src/fsfw/cfdp/tlv/MessageToUserTlv.cpp create mode 100644 src/fsfw/cfdp/tlv/MessageToUserTlv.h create mode 100644 src/fsfw/cfdp/tlv/Tlv.cpp create mode 100644 src/fsfw/cfdp/tlv/Tlv.h create mode 100644 src/fsfw/cfdp/tlv/TlvIF.h create mode 100644 src/fsfw/tcdistribution/CFDPDistributor.cpp create mode 100644 src/fsfw/tcdistribution/CFDPDistributor.h create mode 100644 src/fsfw/tcdistribution/CFDPDistributorIF.h create mode 100644 src/fsfw/tcdistribution/TcPacketCheckCFDP.cpp create mode 100644 src/fsfw/tcdistribution/TcPacketCheckCFDP.h create mode 100644 src/fsfw/tcdistribution/TcPacketCheckIF.h rename src/fsfw/tcdistribution/{TcPacketCheck.cpp => TcPacketCheckPUS.cpp} (65%) rename src/fsfw/tcdistribution/{TcPacketCheck.h => TcPacketCheckPUS.h} (73%) create mode 100644 src/fsfw/tmtcpacket/RedirectableDataPointerIF.h create mode 100644 src/fsfw/tmtcpacket/cfdp/CFDPPacket.cpp create mode 100644 src/fsfw/tmtcpacket/cfdp/CFDPPacket.h create mode 100644 src/fsfw/tmtcpacket/cfdp/CFDPPacketStored.cpp create mode 100644 src/fsfw/tmtcpacket/cfdp/CFDPPacketStored.h create mode 100644 src/fsfw/tmtcpacket/cfdp/CMakeLists.txt rename src/fsfw/tmtcpacket/pus/tc/{TcPacketBase.cpp => TcPacketPusBase.cpp} (65%) rename src/fsfw/tmtcpacket/pus/tc/{TcPacketBase.h => TcPacketPusBase.h} (93%) create mode 100644 tests/src/fsfw_tests/unit/cfdp/CMakeLists.txt create mode 100644 tests/src/fsfw_tests/unit/cfdp/testAckPdu.cpp create mode 100644 tests/src/fsfw_tests/unit/cfdp/testCfdp.cpp create mode 100644 tests/src/fsfw_tests/unit/cfdp/testEofPdu.cpp create mode 100644 tests/src/fsfw_tests/unit/cfdp/testFileData.cpp create mode 100644 tests/src/fsfw_tests/unit/cfdp/testFinishedPdu.cpp create mode 100644 tests/src/fsfw_tests/unit/cfdp/testKeepAlivePdu.cpp create mode 100644 tests/src/fsfw_tests/unit/cfdp/testMetadataPdu.cpp create mode 100644 tests/src/fsfw_tests/unit/cfdp/testNakPdu.cpp create mode 100644 tests/src/fsfw_tests/unit/cfdp/testPromptPdu.cpp create mode 100644 tests/src/fsfw_tests/unit/cfdp/testTlvsLvs.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index e78e8929..bd65cfe1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -189,13 +189,13 @@ if(FSFW_BUILD_UNITTESTS) "--exclude-unreachable-branches" ) set(COVERAGE_EXCLUDES - "/c/msys64/mingw64/*" + "/c/msys64/mingw64/*" "*/fsfw_hal/*" ) elseif(UNIX) set(COVERAGE_EXCLUDES "/usr/include/*" "/usr/bin/*" "Catch2/*" "/usr/local/include/*" "*/fsfw_tests/*" - "*/catch2-src/*" + "*/catch2-src/*" "*/fsfw_hal/*" ) endif() diff --git a/README.md b/README.md index 312bc077..a6f52ca0 100644 --- a/README.md +++ b/README.md @@ -91,7 +91,7 @@ You can use the following commands inside the `fsfw` folder to set up the build ```sh mkdir build-Unittest && cd build-Unittest -cmake -DFSFW_BUILD_UNITTESTS=ON -DFSFW_OSAL=host .. +cmake -DFSFW_BUILD_UNITTESTS=ON -DFSFW_OSAL=host -DCMAKE_BUILD_TYPE=Debug .. ``` You can also use `-DFSFW_OSAL=linux` on Linux systems. diff --git a/misc/defaultcfg/fsfwconfig/devices/logicalAddresses.h b/misc/defaultcfg/fsfwconfig/devices/logicalAddresses.h index 53edcd54..8f263e9a 100644 --- a/misc/defaultcfg/fsfwconfig/devices/logicalAddresses.h +++ b/misc/defaultcfg/fsfwconfig/devices/logicalAddresses.h @@ -10,7 +10,7 @@ */ namespace addresses { /* Logical addresses have uint32_t datatype */ - enum logicalAddresses: address_t { + enum LogAddr: address_t { }; } diff --git a/src/fsfw/CMakeLists.txt b/src/fsfw/CMakeLists.txt index 7c665e28..12c673ed 100644 --- a/src/fsfw/CMakeLists.txt +++ b/src/fsfw/CMakeLists.txt @@ -1,6 +1,7 @@ # Core add_subdirectory(action) +add_subdirectory(cfdp) add_subdirectory(container) add_subdirectory(controller) add_subdirectory(datapool) diff --git a/src/fsfw/FSFW.h.in b/src/fsfw/FSFW.h.in index 7e52b646..d4a8f3ba 100644 --- a/src/fsfw/FSFW.h.in +++ b/src/fsfw/FSFW.h.in @@ -42,6 +42,10 @@ #define FSFW_USE_PUS_C_TELECOMMANDS 1 #endif +#ifndef FSFW_TCP_RECV_WIRETAPPING_ENABLED +#define FSFW_TCP_RECV_WIRETAPPING_ENABLED 0 +#endif + // FSFW HAL defines // Can be used for low-level debugging of the SPI bus diff --git a/src/fsfw/cfdp/CFDPHandler.cpp b/src/fsfw/cfdp/CFDPHandler.cpp new file mode 100644 index 00000000..79712bf2 --- /dev/null +++ b/src/fsfw/cfdp/CFDPHandler.cpp @@ -0,0 +1,60 @@ +#include "fsfw/ipc/CommandMessage.h" +#include "fsfw/storagemanager/storeAddress.h" +#include "fsfw/cfdp/CFDPHandler.h" +#include "fsfw/cfdp/CFDPMessage.h" + +#include "fsfw/tmtcservices/AcceptsTelemetryIF.h" +#include "fsfw/ipc/QueueFactory.h" +#include "fsfw/objectmanager/ObjectManager.h" + +object_id_t CFDPHandler::packetSource = 0; +object_id_t CFDPHandler::packetDestination = 0; + +CFDPHandler::CFDPHandler(object_id_t setObjectId, CFDPDistributor* dist) : SystemObject(setObjectId) { + requestQueue = QueueFactory::instance()->createMessageQueue(CFDP_HANDLER_MAX_RECEPTION); + distributor = dist; +} + +CFDPHandler::~CFDPHandler() {} + +ReturnValue_t CFDPHandler::initialize() { + ReturnValue_t result = SystemObject::initialize(); + if (result != RETURN_OK) { + return result; + } + this->distributor->registerHandler(this); + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t CFDPHandler::handleRequest(store_address_t storeId) { +#if FSFW_VERBOSE_LEVEL >= 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::debug << "CFDPHandler::handleRequest" << std::endl; +#else + sif::printDebug("CFDPHandler::handleRequest\n"); +#endif /* !FSFW_CPP_OSTREAM_ENABLED == 1 */ +#endif + + //TODO read out packet from store using storeId + + return RETURN_OK; +} + +ReturnValue_t CFDPHandler::performOperation(uint8_t opCode) { + ReturnValue_t status = RETURN_OK; + CommandMessage currentMessage; + for (status = this->requestQueue->receiveMessage(¤tMessage); status == RETURN_OK; + status = this->requestQueue->receiveMessage(¤tMessage)) { + store_address_t storeId = CFDPMessage::getStoreId(¤tMessage); + this->handleRequest(storeId); + } + return RETURN_OK; +} + +uint16_t CFDPHandler::getIdentifier() { + return 0; +} + +MessageQueueId_t CFDPHandler::getRequestQueue() { + return this->requestQueue->getId(); +} diff --git a/src/fsfw/cfdp/CFDPHandler.h b/src/fsfw/cfdp/CFDPHandler.h new file mode 100644 index 00000000..2f11eee3 --- /dev/null +++ b/src/fsfw/cfdp/CFDPHandler.h @@ -0,0 +1,62 @@ +#ifndef FSFW_CFDP_CFDPHANDLER_H_ +#define FSFW_CFDP_CFDPHANDLER_H_ + +#include "fsfw/tmtcservices/AcceptsTelecommandsIF.h" +#include "fsfw/objectmanager/SystemObject.h" +#include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "fsfw/tasks/ExecutableObjectIF.h" +#include "fsfw/tcdistribution/CFDPDistributor.h" + +#include "fsfw/ipc/MessageQueueIF.h" + +namespace Factory{ +void setStaticFrameworkObjectIds(); +} + +class CFDPHandler : + public ExecutableObjectIF, + public AcceptsTelecommandsIF, + public SystemObject, + public HasReturnvaluesIF { + friend void (Factory::setStaticFrameworkObjectIds)(); +public: + CFDPHandler(object_id_t setObjectId, CFDPDistributor* distributor); + /** + * The destructor is empty. + */ + virtual ~CFDPHandler(); + + virtual ReturnValue_t handleRequest(store_address_t storeId); + + virtual ReturnValue_t initialize() override; + virtual uint16_t getIdentifier() override; + MessageQueueId_t getRequestQueue() override; + ReturnValue_t performOperation(uint8_t opCode) override; + protected: + /** + * This is a complete instance of the telecommand reception queue + * of the class. It is initialized on construction of the class. + */ + MessageQueueIF* requestQueue = nullptr; + + CFDPDistributor* distributor = nullptr; + + /** + * The current CFDP packet to be processed. + * It is deleted after handleRequest was executed. + */ + CFDPPacketStored currentPacket; + + static object_id_t packetSource; + + static object_id_t packetDestination; + private: + /** + * This constant sets the maximum number of packets accepted per call. + * Remember that one packet must be completely handled in one + * #handleRequest call. + */ + static const uint8_t CFDP_HANDLER_MAX_RECEPTION = 100; +}; + +#endif /* FSFW_CFDP_CFDPHANDLER_H_ */ diff --git a/src/fsfw/cfdp/CFDPMessage.cpp b/src/fsfw/cfdp/CFDPMessage.cpp new file mode 100644 index 00000000..c75b6b2c --- /dev/null +++ b/src/fsfw/cfdp/CFDPMessage.cpp @@ -0,0 +1,21 @@ +#include "CFDPMessage.h" + +CFDPMessage::CFDPMessage() { +} + +CFDPMessage::~CFDPMessage() { +} + +void CFDPMessage::setCommand(CommandMessage *message, + store_address_t cfdpPacket) { + message->setParameter(cfdpPacket.raw); +} + +store_address_t CFDPMessage::getStoreId(const CommandMessage *message) { + store_address_t storeAddressCFDPPacket; + storeAddressCFDPPacket = message->getParameter(); + return storeAddressCFDPPacket; +} + +void CFDPMessage::clear(CommandMessage *message) { +} diff --git a/src/fsfw/cfdp/CFDPMessage.h b/src/fsfw/cfdp/CFDPMessage.h new file mode 100644 index 00000000..5b321975 --- /dev/null +++ b/src/fsfw/cfdp/CFDPMessage.h @@ -0,0 +1,23 @@ +#ifndef FSFW_CFDP_CFDPMESSAGE_H_ +#define FSFW_CFDP_CFDPMESSAGE_H_ + +#include "fsfw/ipc/CommandMessage.h" +#include "fsfw/objectmanager/ObjectManagerIF.h" +#include "fsfw/storagemanager/StorageManagerIF.h" + +class CFDPMessage { +private: + CFDPMessage(); +public: + static const uint8_t MESSAGE_ID = messagetypes::CFDP; + + virtual ~CFDPMessage(); + static void setCommand(CommandMessage* message, + store_address_t cfdpPacket); + + static store_address_t getStoreId(const CommandMessage* message); + + static void clear(CommandMessage* message); +}; + +#endif /* FSFW_CFDP_CFDPMESSAGE_H_ */ diff --git a/src/fsfw/cfdp/CMakeLists.txt b/src/fsfw/cfdp/CMakeLists.txt new file mode 100644 index 00000000..908dc32a --- /dev/null +++ b/src/fsfw/cfdp/CMakeLists.txt @@ -0,0 +1,7 @@ +target_sources(${LIB_FSFW_NAME} PRIVATE + CFDPHandler.cpp + CFDPMessage.cpp +) + +add_subdirectory(pdu) +add_subdirectory(tlv) diff --git a/src/fsfw/cfdp/FileSize.h b/src/fsfw/cfdp/FileSize.h new file mode 100644 index 00000000..3997d5a4 --- /dev/null +++ b/src/fsfw/cfdp/FileSize.h @@ -0,0 +1,83 @@ +#ifndef FSFW_SRC_FSFW_CFDP_FILESIZE_H_ +#define FSFW_SRC_FSFW_CFDP_FILESIZE_H_ + +#include "fsfw/serialize/SerializeAdapter.h" +#include "fsfw/serialize/SerializeIF.h" + +namespace cfdp { + +struct FileSize: public SerializeIF { +public: + FileSize(): largeFile(false) {}; + + FileSize(uint64_t fileSize, bool isLarge = false) { + setFileSize(fileSize, isLarge); + }; + + ReturnValue_t serialize(bool isLarge, uint8_t **buffer, size_t *size,size_t maxSize, + Endianness streamEndianness) { + this->largeFile = isLarge; + return serialize(buffer, size, maxSize, streamEndianness); + } + + ReturnValue_t serialize(uint8_t **buffer, size_t *size,size_t maxSize, + Endianness streamEndianness) const override { + if(not largeFile) { + uint32_t fileSizeTyped = fileSize; + return SerializeAdapter::serialize(&fileSizeTyped, buffer, size, maxSize, + streamEndianness); + + } + return SerializeAdapter::serialize(&fileSize, buffer, size, maxSize, streamEndianness); + } + + size_t getSerializedSize() const override { + if (largeFile) { + return 8; + } else { + return 4; + } + } + + ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) override { + if(largeFile) { + return SerializeAdapter::deSerialize(&size, buffer, size, streamEndianness); + } else { + uint32_t sizeTmp = 0; + ReturnValue_t result = SerializeAdapter::deSerialize(&sizeTmp, buffer, size, + streamEndianness); + if(result == HasReturnvaluesIF::RETURN_OK) { + fileSize = sizeTmp; + } + return result; + } + } + + ReturnValue_t setFileSize(uint64_t fileSize, bool largeFile) { + if (not largeFile and fileSize > UINT32_MAX) { + // TODO: emit warning here + return HasReturnvaluesIF::RETURN_FAILED; + } + this->fileSize = fileSize; + this->largeFile = largeFile; + return HasReturnvaluesIF::RETURN_OK; + } + + bool isLargeFile() const { + return largeFile; + } + uint64_t getSize(bool* largeFile = nullptr) const { + if(largeFile != nullptr) { + *largeFile = this->largeFile; + } + return fileSize; + } +private: + uint64_t fileSize = 0; + bool largeFile = false; +}; + +} + +#endif /* FSFW_SRC_FSFW_CFDP_FILESIZE_H_ */ diff --git a/src/fsfw/cfdp/definitions.h b/src/fsfw/cfdp/definitions.h new file mode 100644 index 00000000..ffcbca97 --- /dev/null +++ b/src/fsfw/cfdp/definitions.h @@ -0,0 +1,153 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_DEFINITIONS_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_DEFINITIONS_H_ + +#include +#include +#include +#include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "fsfw/returnvalues/FwClassIds.h" + +namespace cfdp { + +static constexpr uint8_t VERSION_BITS = 0b00100000; + +static constexpr uint8_t CFDP_CLASS_ID = CLASS_ID::CFDP; + +static constexpr ReturnValue_t INVALID_TLV_TYPE = + HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 1); +static constexpr ReturnValue_t INVALID_DIRECTIVE_FIELDS = + HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 2); +static constexpr ReturnValue_t INVALID_PDU_DATAFIELD_LEN = + HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 3); +static constexpr ReturnValue_t INVALID_ACK_DIRECTIVE_FIELDS = + HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 4); +//! Can not parse options. This can also occur because there are options +//! available but the user did not pass a valid options array +static constexpr ReturnValue_t METADATA_CANT_PARSE_OPTIONS = + HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 5); +static constexpr ReturnValue_t NAK_CANT_PARSE_OPTIONS = + HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 6); +static constexpr ReturnValue_t FINISHED_CANT_PARSE_FS_RESPONSES = + HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 6); +static constexpr ReturnValue_t FILESTORE_REQUIRES_SECOND_FILE = + HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 8); +//! Can not parse filestore response because user did not pass a valid instance +//! or remaining size is invalid +static constexpr ReturnValue_t FILESTORE_RESPONSE_CANT_PARSE_FS_MESSAGE = + HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 9); + +//! Checksum types according to the SANA Checksum Types registry +//! https://sanaregistry.org/r/checksum_identifiers/ +enum ChecksumType { + // Modular legacy checksum + MODULAR = 0, + CRC_32_PROXIMITY_1 = 1, + CRC_32C = 2, + CRC_32 = 3, + NULL_CHECKSUM = 15 +}; + +enum PduType: bool { + FILE_DIRECTIVE = 0, + FILE_DATA = 1 +}; + +enum TransmissionModes: bool { + ACKNOWLEDGED = 0, + UNACKNOWLEDGED = 1 +}; + +enum SegmentMetadataFlag: bool { + NOT_PRESENT = 0, + PRESENT = 1 +}; + +enum Direction: bool { + TOWARDS_RECEIVER = 0, + TOWARDS_SENDER = 1 +}; + +enum SegmentationControl: bool { + NO_RECORD_BOUNDARIES_PRESERVATION = 0, + RECORD_BOUNDARIES_PRESERVATION = 1 +}; + +enum WidthInBytes: uint8_t { + // Only those are supported for now + ONE_BYTE = 1, + TWO_BYTES = 2, + FOUR_BYTES = 4, +}; + +enum FileDirectives: uint8_t { + INVALID_DIRECTIVE = 0x0f, + EOF_DIRECTIVE = 0x04, + FINISH = 0x05, + ACK = 0x06, + METADATA = 0x07, + NAK = 0x08, + PROMPT = 0x09, + KEEP_ALIVE = 0x0c +}; + +enum ConditionCode: uint8_t { + NO_CONDITION_FIELD = 0xff, + NO_ERROR = 0b0000, + POSITIVE_ACK_LIMIT_REACHED = 0b0001, + KEEP_ALIVE_LIMIT_REACHED = 0b0010, + INVALID_TRANSMISSION_MODE = 0b0011, + FILESTORE_REJECTION = 0b0100, + FILE_CHECKSUM_FAILURE = 0b0101, + FILE_SIZE_ERROR = 0b0110, + NAK_LIMIT_REACHED = 0b0111, + INACTIVITY_DETECTED = 0b1000, + CHECK_LIMIT_REACHED = 0b1010, + UNSUPPORTED_CHECKSUM_TYPE = 0b1011, + SUSPEND_REQUEST_RECEIVED = 0b1110, + CANCEL_REQUEST_RECEIVED = 0b1111 +}; + +enum AckTransactionStatus { + UNDEFINED = 0b00, + ACTIVE = 0b01, + TERMINATED = 0b10, + UNRECOGNIZED = 0b11 +}; + +enum FinishedDeliveryCode { + DATA_COMPLETE = 0, + DATA_INCOMPLETE = 1 +}; + +enum FinishedFileStatus { + DISCARDED_DELIBERATELY = 0, + DISCARDED_FILESTORE_REJECTION = 1, + RETAINED_IN_FILESTORE = 2, + FILE_STATUS_UNREPORTED = 3 +}; + +enum PromptResponseRequired: bool { + PROMPT_NAK = 0, + PROMPT_KEEP_ALIVE = 1 +}; + +enum TlvTypes: uint8_t { + FILESTORE_REQUEST = 0x00, + FILESTORE_RESPONSE = 0x01, + MSG_TO_USER = 0x02, + FAULT_HANDLER = 0x04, + FLOW_LABEL = 0x05, + ENTITY_ID = 0x06, + INVALID_TLV = 0xff, +}; + +enum RecordContinuationState { + NO_START_NO_END = 0b00, + CONTAINS_START_NO_END = 0b01, + CONTAINS_END_NO_START = 0b10, + CONTAINS_START_AND_END = 0b11 +}; + +} + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_DEFINITIONS_H_ */ diff --git a/src/fsfw/cfdp/pdu/AckInfo.cpp b/src/fsfw/cfdp/pdu/AckInfo.cpp new file mode 100644 index 00000000..4095e8bf --- /dev/null +++ b/src/fsfw/cfdp/pdu/AckInfo.cpp @@ -0,0 +1,52 @@ +#include "AckInfo.h" + +AckInfo::AckInfo(cfdp::FileDirectives ackedDirective, cfdp::ConditionCode ackedConditionCode, + cfdp::AckTransactionStatus transactionStatus, uint8_t directiveSubtypeCode): + ackedDirective(ackedDirective), ackedConditionCode(ackedConditionCode), + transactionStatus(transactionStatus), directiveSubtypeCode(directiveSubtypeCode) { + if (ackedDirective == cfdp::FileDirectives::FINISH) { + this->directiveSubtypeCode = 0b0001; + } else { + this->directiveSubtypeCode = 0b0000; + } +} + +cfdp::ConditionCode AckInfo::getAckedConditionCode() const { + return ackedConditionCode; +} + +void AckInfo::setAckedConditionCode(cfdp::ConditionCode ackedConditionCode) { + this->ackedConditionCode = ackedConditionCode; + if (ackedDirective == cfdp::FileDirectives::FINISH) { + this->directiveSubtypeCode = 0b0001; + } else { + this->directiveSubtypeCode = 0b0000; + } +} + +cfdp::FileDirectives AckInfo::getAckedDirective() const { + return ackedDirective; +} + +void AckInfo::setAckedDirective(cfdp::FileDirectives ackedDirective) { + this->ackedDirective = ackedDirective; +} + +uint8_t AckInfo::getDirectiveSubtypeCode() const { + return directiveSubtypeCode; +} + +void AckInfo::setDirectiveSubtypeCode(uint8_t directiveSubtypeCode) { + this->directiveSubtypeCode = directiveSubtypeCode; +} + +cfdp::AckTransactionStatus AckInfo::getTransactionStatus() const { + return transactionStatus; +} + +AckInfo::AckInfo() { +} + +void AckInfo::setTransactionStatus(cfdp::AckTransactionStatus transactionStatus) { + this->transactionStatus = transactionStatus; +} diff --git a/src/fsfw/cfdp/pdu/AckInfo.h b/src/fsfw/cfdp/pdu/AckInfo.h new file mode 100644 index 00000000..2d54c535 --- /dev/null +++ b/src/fsfw/cfdp/pdu/AckInfo.h @@ -0,0 +1,33 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_ACKINFO_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_ACKINFO_H_ + +#include "../definitions.h" + +class AckInfo { +public: + AckInfo(); + AckInfo(cfdp::FileDirectives ackedDirective, cfdp::ConditionCode ackedConditionCode, + cfdp::AckTransactionStatus transactionStatus, uint8_t directiveSubtypeCode = 0); + + cfdp::ConditionCode getAckedConditionCode() const; + void setAckedConditionCode(cfdp::ConditionCode ackedConditionCode); + + cfdp::FileDirectives getAckedDirective() const; + void setAckedDirective(cfdp::FileDirectives ackedDirective); + + uint8_t getDirectiveSubtypeCode() const; + void setDirectiveSubtypeCode(uint8_t directiveSubtypeCode); + + cfdp::AckTransactionStatus getTransactionStatus() const; + void setTransactionStatus(cfdp::AckTransactionStatus transactionStatus); + +private: + cfdp::FileDirectives ackedDirective = cfdp::FileDirectives::INVALID_DIRECTIVE; + cfdp::ConditionCode ackedConditionCode = cfdp::ConditionCode::NO_CONDITION_FIELD; + cfdp::AckTransactionStatus transactionStatus = cfdp::AckTransactionStatus::UNDEFINED; + uint8_t directiveSubtypeCode = 0; +}; + + + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_ACKINFO_H_ */ diff --git a/src/fsfw/cfdp/pdu/AckPduDeserializer.cpp b/src/fsfw/cfdp/pdu/AckPduDeserializer.cpp new file mode 100644 index 00000000..b4f59a7a --- /dev/null +++ b/src/fsfw/cfdp/pdu/AckPduDeserializer.cpp @@ -0,0 +1,38 @@ +#include "AckPduDeserializer.h" + +AckPduDeserializer::AckPduDeserializer(const uint8_t *pduBuf, size_t maxSize, AckInfo& info): + FileDirectiveDeserializer(pduBuf, maxSize), info(info) { +} + +ReturnValue_t AckPduDeserializer::parseData() { + ReturnValue_t result = FileDirectiveDeserializer::parseData(); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + size_t currentIdx = FileDirectiveDeserializer::getHeaderSize(); + if (currentIdx + 2 > this->maxSize) { + return SerializeIF::BUFFER_TOO_SHORT; + } + if(not checkAndSetCodes(rawPtr[currentIdx], rawPtr[currentIdx + 1])) { + return cfdp::INVALID_ACK_DIRECTIVE_FIELDS; + } + return HasReturnvaluesIF::RETURN_OK; +} + +bool AckPduDeserializer::checkAndSetCodes(uint8_t firstByte, uint8_t secondByte) { + uint8_t ackedDirective = static_cast(firstByte >> 4); + + if(ackedDirective != cfdp::FileDirectives::EOF_DIRECTIVE and + ackedDirective != cfdp::FileDirectives::FINISH) { + return false; + } + this->info.setAckedDirective(static_cast(ackedDirective)); + uint8_t directiveSubtypeCode = firstByte & 0x0f; + if(directiveSubtypeCode != 0b0000 and directiveSubtypeCode != 0b0001) { + return false; + } + this->info.setDirectiveSubtypeCode(directiveSubtypeCode); + this->info.setAckedConditionCode(static_cast(secondByte >> 4)); + this->info.setTransactionStatus(static_cast(secondByte & 0x0f)); + return true; +} diff --git a/src/fsfw/cfdp/pdu/AckPduDeserializer.h b/src/fsfw/cfdp/pdu/AckPduDeserializer.h new file mode 100644 index 00000000..31f09c92 --- /dev/null +++ b/src/fsfw/cfdp/pdu/AckPduDeserializer.h @@ -0,0 +1,26 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_ACKPDUDESERIALIZER_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_ACKPDUDESERIALIZER_H_ + +#include "fsfw/cfdp/pdu/FileDirectiveDeserializer.h" +#include "AckInfo.h" + +class AckPduDeserializer: public FileDirectiveDeserializer { +public: + AckPduDeserializer(const uint8_t* pduBuf, size_t maxSize, AckInfo& info); + + /** + * + * @return + * - cfdp::INVALID_DIRECTIVE_FIELDS: Invalid fields + */ + ReturnValue_t parseData(); + +private: + bool checkAndSetCodes(uint8_t rawAckedByte, uint8_t rawAckedConditionCode); + AckInfo& info; + +}; + + + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_ACKPDUDESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/AckPduSerializer.cpp b/src/fsfw/cfdp/pdu/AckPduSerializer.cpp new file mode 100644 index 00000000..56fe8b33 --- /dev/null +++ b/src/fsfw/cfdp/pdu/AckPduSerializer.cpp @@ -0,0 +1,38 @@ +#include "AckPduSerializer.h" + +AckPduSerializer::AckPduSerializer(AckInfo& ackInfo, PduConfig &pduConf): + FileDirectiveSerializer(pduConf, cfdp::FileDirectives::ACK, 2), + ackInfo(ackInfo) { +} + +size_t AckPduSerializer::getSerializedSize() const { + return FileDirectiveSerializer::getWholePduSize(); +} + +ReturnValue_t AckPduSerializer::serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const { + ReturnValue_t result = FileDirectiveSerializer::serialize(buffer, size, maxSize, + streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + cfdp::FileDirectives ackedDirective = ackInfo.getAckedDirective(); + uint8_t directiveSubtypeCode = ackInfo.getDirectiveSubtypeCode(); + cfdp::ConditionCode ackedConditionCode = ackInfo.getAckedConditionCode(); + cfdp::AckTransactionStatus transactionStatus = ackInfo.getTransactionStatus(); + if(ackedDirective != cfdp::FileDirectives::FINISH and + ackedDirective != cfdp::FileDirectives::EOF_DIRECTIVE) { + // TODO: better returncode + return HasReturnvaluesIF::RETURN_FAILED; + } + if(*size + 2 > maxSize) { + return SerializeIF::BUFFER_TOO_SHORT; + } + **buffer = ackedDirective << 4 | directiveSubtypeCode; + *buffer += 1; + *size += 1; + **buffer = ackedConditionCode << 4 | transactionStatus; + *buffer += 1; + *size += 1; + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/src/fsfw/cfdp/pdu/AckPduSerializer.h b/src/fsfw/cfdp/pdu/AckPduSerializer.h new file mode 100644 index 00000000..de478c69 --- /dev/null +++ b/src/fsfw/cfdp/pdu/AckPduSerializer.h @@ -0,0 +1,30 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_ACKPDUSERIALIZER_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_ACKPDUSERIALIZER_H_ + +#include "AckInfo.h" +#include "FileDirectiveDeserializer.h" +#include "FileDirectiveSerializer.h" + +class AckPduSerializer: public FileDirectiveSerializer { +public: + /** + * @brief Serializer to pack ACK PDUs + * @details + * Please note that only Finished PDUs and EOF are acknowledged. + * @param ackedDirective + * @param ackedConditionCode + * @param transactionStatus + * @param pduConf + */ + AckPduSerializer(AckInfo& ackInfo, PduConfig& pduConf); + + size_t getSerializedSize() const override; + + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; + +private: + AckInfo& ackInfo; +}; + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_ACKPDUSERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/CMakeLists.txt b/src/fsfw/cfdp/pdu/CMakeLists.txt new file mode 100644 index 00000000..931db306 --- /dev/null +++ b/src/fsfw/cfdp/pdu/CMakeLists.txt @@ -0,0 +1,32 @@ +target_sources(${LIB_FSFW_NAME} PRIVATE + PduConfig.cpp + VarLenField.cpp + HeaderSerializer.cpp + HeaderDeserializer.cpp + FileDirectiveDeserializer.cpp + FileDirectiveSerializer.cpp + + AckInfo.cpp + AckPduSerializer.cpp + AckPduDeserializer.cpp + EofInfo.cpp + EofPduSerializer.cpp + EofPduDeserializer.cpp + NakInfo.cpp + NakPduSerializer.cpp + NakPduDeserializer.cpp + FinishedInfo.cpp + FinishedPduSerializer.cpp + FinishedPduDeserializer.cpp + MetadataInfo.cpp + MetadataPduSerializer.cpp + MetadataPduDeserializer.cpp + KeepAlivePduSerializer.cpp + KeepAlivePduDeserializer.cpp + PromptPduSerializer.cpp + PromptPduDeserializer.cpp + + FileDataSerializer.cpp + FileDataDeserializer.cpp + FileDataInfo.cpp +) \ No newline at end of file diff --git a/src/fsfw/cfdp/pdu/EofInfo.cpp b/src/fsfw/cfdp/pdu/EofInfo.cpp new file mode 100644 index 00000000..f7c41dbe --- /dev/null +++ b/src/fsfw/cfdp/pdu/EofInfo.cpp @@ -0,0 +1,58 @@ +#include "EofInfo.h" + +EofInfo::EofInfo(cfdp::ConditionCode conditionCode, uint32_t checksum, cfdp::FileSize fileSize, + EntityIdTlv* faultLoc): conditionCode(conditionCode), checksum(checksum), + fileSize(fileSize), faultLoc(faultLoc) { +} + +EofInfo::EofInfo(EntityIdTlv *faultLoc): conditionCode(cfdp::ConditionCode::NO_CONDITION_FIELD), + checksum(0), fileSize(0), faultLoc(faultLoc) { +} + +uint32_t EofInfo::getChecksum() const { + return checksum; +} + +cfdp::ConditionCode EofInfo::getConditionCode() const { + return conditionCode; +} + +EntityIdTlv* EofInfo::getFaultLoc() const { + return faultLoc; +} + +cfdp::FileSize& EofInfo::getFileSize() { + return fileSize; +} + +void EofInfo::setChecksum(uint32_t checksum) { + this->checksum = checksum; +} + +void EofInfo::setConditionCode(cfdp::ConditionCode conditionCode) { + this->conditionCode = conditionCode; +} + +void EofInfo::setFaultLoc(EntityIdTlv *faultLoc) { + this->faultLoc = faultLoc; +} + +size_t EofInfo::getSerializedSize(bool fssLarge) { + // Condition code + spare + 4 byte checksum + size_t size = 5; + if(fssLarge) { + size += 8; + } else { + size += 4; + } + // Do not account for fault location if the condition code is NO_ERROR. We assume that + // a serializer will not serialize the fault location here. + if(getFaultLoc() != nullptr and getConditionCode() != cfdp::ConditionCode::NO_ERROR) { + size+= faultLoc->getSerializedSize(); + } + return size; +} + +ReturnValue_t EofInfo::setFileSize(size_t fileSize, bool isLarge) { + return this->fileSize.setFileSize(fileSize, isLarge); +} diff --git a/src/fsfw/cfdp/pdu/EofInfo.h b/src/fsfw/cfdp/pdu/EofInfo.h new file mode 100644 index 00000000..33feb4fd --- /dev/null +++ b/src/fsfw/cfdp/pdu/EofInfo.h @@ -0,0 +1,33 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_EOFINFO_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_EOFINFO_H_ + +#include "fsfw/cfdp/tlv/EntityIdTlv.h" +#include "../definitions.h" +#include "../FileSize.h" + +struct EofInfo { +public: + EofInfo(EntityIdTlv* faultLoc = nullptr); + EofInfo(cfdp::ConditionCode conditionCode, uint32_t checksum, cfdp::FileSize fileSize, + EntityIdTlv* faultLoc = nullptr); + + size_t getSerializedSize(bool fssLarge = false); + + uint32_t getChecksum() const; + cfdp::ConditionCode getConditionCode() const; + + EntityIdTlv* getFaultLoc() const; + cfdp::FileSize& getFileSize(); + void setChecksum(uint32_t checksum); + void setConditionCode(cfdp::ConditionCode conditionCode); + void setFaultLoc(EntityIdTlv *faultLoc); + ReturnValue_t setFileSize(size_t size, bool isLarge); +private: + + cfdp::ConditionCode conditionCode; + uint32_t checksum; + cfdp::FileSize fileSize; + EntityIdTlv* faultLoc = nullptr; +}; + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_EOFINFO_H_ */ diff --git a/src/fsfw/cfdp/pdu/EofPduDeserializer.cpp b/src/fsfw/cfdp/pdu/EofPduDeserializer.cpp new file mode 100644 index 00000000..e5f607bf --- /dev/null +++ b/src/fsfw/cfdp/pdu/EofPduDeserializer.cpp @@ -0,0 +1,68 @@ +#include "EofPduDeserializer.h" +#include "fsfw/FSFW.h" +#include "fsfw/serviceinterface.h" + +EofPduDeserializer::EofPduDeserializer(const uint8_t *pduBuf, size_t maxSize, EofInfo& eofInfo): + FileDirectiveDeserializer(pduBuf, maxSize), info(eofInfo) { +} + +ReturnValue_t EofPduDeserializer::parseData() { + ReturnValue_t result = FileDirectiveDeserializer::parseData(); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + + const uint8_t* bufPtr = rawPtr; + size_t expectedFileFieldLen = 4; + if(this->getLargeFileFlag()) { + expectedFileFieldLen = 8; + } + size_t currentIdx = FileDirectiveDeserializer::getHeaderSize(); + size_t deserLen = maxSize; + if(maxSize < currentIdx + 5 + expectedFileFieldLen) { + return SerializeIF::STREAM_TOO_SHORT; + } + + bufPtr += currentIdx; + deserLen -= currentIdx; + info.setConditionCode(static_cast(*bufPtr >> 4)); + bufPtr += 1; + deserLen -= 1; + uint32_t checksum = 0; + auto endianness = getEndianness(); + result = SerializeAdapter::deSerialize(&checksum, &bufPtr, &deserLen, endianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + info.setChecksum(checksum); + if(this->getLargeFileFlag()) { + uint64_t fileSizeValue = 0; + result = SerializeAdapter::deSerialize(&fileSizeValue, &bufPtr, &deserLen, endianness); + info.setFileSize(fileSizeValue, true); + } + else { + uint32_t fileSizeValue = 0; + result = SerializeAdapter::deSerialize(&fileSizeValue, &bufPtr, &deserLen, endianness); + info.setFileSize(fileSizeValue, false); + } + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if(info.getConditionCode() != cfdp::ConditionCode::NO_ERROR) { + EntityIdTlv* tlvPtr = info.getFaultLoc(); + if(tlvPtr == nullptr) { +#if FSFW_VERBOSE_LEVEL >= 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "EofPduDeserializer::parseData: Ca not deserialize fault location," + " given TLV pointer invalid" << std::endl; +#else + sif::printWarning("EofPduDeserializer::parseData: Ca not deserialize fault location," + " given TLV pointer invalid"); +#endif +#endif /* FSFW_VERBOSE_LEVEL >= 1 */ + return HasReturnvaluesIF::RETURN_FAILED; + } + result = tlvPtr->deSerialize(&bufPtr, &deserLen, endianness); + } + return result; +} diff --git a/src/fsfw/cfdp/pdu/EofPduDeserializer.h b/src/fsfw/cfdp/pdu/EofPduDeserializer.h new file mode 100644 index 00000000..fea5f03f --- /dev/null +++ b/src/fsfw/cfdp/pdu/EofPduDeserializer.h @@ -0,0 +1,18 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_EOFPDUDESERIALIZER_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_EOFPDUDESERIALIZER_H_ + +#include "fsfw/cfdp/pdu/FileDirectiveDeserializer.h" +#include "EofInfo.h" + +class EofPduDeserializer: public FileDirectiveDeserializer { +public: + EofPduDeserializer(const uint8_t* pduBuf, size_t maxSize, EofInfo& eofInfo); + + virtual ReturnValue_t parseData() override; +private: + EofInfo& info; +}; + + + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_EOFPDUDESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/EofPduSerializer.cpp b/src/fsfw/cfdp/pdu/EofPduSerializer.cpp new file mode 100644 index 00000000..81bd98f1 --- /dev/null +++ b/src/fsfw/cfdp/pdu/EofPduSerializer.cpp @@ -0,0 +1,46 @@ +#include "fsfw/FSFW.h" +#include "fsfw/serviceinterface.h" +#include "EofPduSerializer.h" + +EofPduSerializer::EofPduSerializer(PduConfig &conf, EofInfo& info): + FileDirectiveSerializer(conf, cfdp::FileDirectives::EOF_DIRECTIVE, 9), info(info) { + setDirectiveDataFieldLen(info.getSerializedSize(getLargeFileFlag())); +} + +size_t EofPduSerializer::getSerializedSize() const { + return FileDirectiveSerializer::getWholePduSize(); +} + +ReturnValue_t EofPduSerializer::serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const { + ReturnValue_t result = FileDirectiveSerializer::serialize(buffer, size, maxSize, + streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if(*size + 1 > maxSize) { + return SerializeIF::BUFFER_TOO_SHORT; + } + **buffer = info.getConditionCode() << 4; + *buffer += 1; + *size += 1; + uint32_t checksum = info.getChecksum(); + result = SerializeAdapter::serialize(&checksum, buffer, size, maxSize, streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if(info.getFileSize().isLargeFile()) { + uint64_t fileSizeValue = info.getFileSize().getSize(); + result = SerializeAdapter::serialize(&fileSizeValue, buffer, size, + maxSize, streamEndianness); + } + else { + uint32_t fileSizeValue = info.getFileSize().getSize(); + result = SerializeAdapter::serialize(&fileSizeValue, buffer, size, + maxSize, streamEndianness); + } + if(info.getFaultLoc() != nullptr and info.getConditionCode() != cfdp::ConditionCode::NO_ERROR) { + result = info.getFaultLoc()->serialize(buffer, size, maxSize, streamEndianness); + } + return result; +} diff --git a/src/fsfw/cfdp/pdu/EofPduSerializer.h b/src/fsfw/cfdp/pdu/EofPduSerializer.h new file mode 100644 index 00000000..cdc9b0f1 --- /dev/null +++ b/src/fsfw/cfdp/pdu/EofPduSerializer.h @@ -0,0 +1,22 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_EOFPDUSERIALIZER_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_EOFPDUSERIALIZER_H_ + +#include "fsfw/cfdp/pdu/FileDirectiveSerializer.h" +#include "fsfw/cfdp/tlv/EntityIdTlv.h" +#include "EofInfo.h" + +class EofPduSerializer: public FileDirectiveSerializer { +public: + EofPduSerializer(PduConfig &conf, EofInfo& info); + + size_t getSerializedSize() const override; + + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; +private: + EofInfo& info; +}; + + + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_EOFPDUSERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/FileDataDeserializer.cpp b/src/fsfw/cfdp/pdu/FileDataDeserializer.cpp new file mode 100644 index 00000000..80106edf --- /dev/null +++ b/src/fsfw/cfdp/pdu/FileDataDeserializer.cpp @@ -0,0 +1,52 @@ +#include "FileDataDeserializer.h" + +FileDataDeserializer::FileDataDeserializer(const uint8_t *pduBuf, size_t maxSize, + FileDataInfo& info): + HeaderDeserializer(pduBuf, maxSize), info(info) { +} + +ReturnValue_t FileDataDeserializer::parseData() { + ReturnValue_t result = HeaderDeserializer::parseData(); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + size_t currentIdx = HeaderDeserializer::getHeaderSize(); + const uint8_t* buf = rawPtr + currentIdx; + size_t remSize = HeaderDeserializer::getWholePduSize() - currentIdx; + if (remSize < 1) { + return SerializeIF::STREAM_TOO_SHORT; + } + if(hasSegmentMetadataFlag()) { + info.setSegmentMetadataFlag(true); + info.setRecordContinuationState(static_cast( + (*buf >> 6) & 0b11)); + size_t segmentMetadataLen = *buf & 0b00111111; + info.setSegmentMetadataLen(segmentMetadataLen); + if(remSize < segmentMetadataLen + 1) { + return SerializeIF::STREAM_TOO_SHORT; + } + if(segmentMetadataLen > 0) { + buf += 1; + remSize -= 1; + info.setSegmentMetadata(buf); + buf += segmentMetadataLen; + remSize -= segmentMetadataLen; + } + } + result = info.getOffset().deSerialize(&buf, &remSize, this->getEndianness()); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if(remSize > 0) { + info.setFileData(buf, remSize); + } + return HasReturnvaluesIF::RETURN_OK; +} + +SerializeIF::Endianness FileDataDeserializer::getEndianness() const { + return endianness; +} + +void FileDataDeserializer::setEndianness(SerializeIF::Endianness endianness) { + this->endianness = endianness; +} diff --git a/src/fsfw/cfdp/pdu/FileDataDeserializer.h b/src/fsfw/cfdp/pdu/FileDataDeserializer.h new file mode 100644 index 00000000..13532d95 --- /dev/null +++ b/src/fsfw/cfdp/pdu/FileDataDeserializer.h @@ -0,0 +1,22 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_FILEDATADESERIALIZER_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_FILEDATADESERIALIZER_H_ + +#include "FileDataInfo.h" +#include "HeaderDeserializer.h" +#include "../definitions.h" + +class FileDataDeserializer: public HeaderDeserializer { +public: + FileDataDeserializer(const uint8_t* pduBuf, size_t maxSize, FileDataInfo& info); + + ReturnValue_t parseData(); + SerializeIF::Endianness getEndianness() const; + void setEndianness(SerializeIF::Endianness endianness = SerializeIF::Endianness::NETWORK); + +private: + + SerializeIF::Endianness endianness = SerializeIF::Endianness::NETWORK; + FileDataInfo& info; +}; + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_FILEDATADESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/FileDataInfo.cpp b/src/fsfw/cfdp/pdu/FileDataInfo.cpp new file mode 100644 index 00000000..1698f5e0 --- /dev/null +++ b/src/fsfw/cfdp/pdu/FileDataInfo.cpp @@ -0,0 +1,104 @@ +#include "FileDataInfo.h" + +FileDataInfo::FileDataInfo(cfdp::FileSize &offset, const uint8_t *fileData, size_t fileSize): + offset(offset), fileData(fileData), fileSize(fileSize) { +} + +FileDataInfo::FileDataInfo(cfdp::FileSize &offset): offset(offset) { +} + +void FileDataInfo::setSegmentMetadataFlag(bool enable) { + if(enable) { + segmentMetadataFlag = cfdp::SegmentMetadataFlag::PRESENT; + } else { + segmentMetadataFlag = cfdp::SegmentMetadataFlag::NOT_PRESENT; + } +} + +size_t FileDataInfo::getSerializedSize(bool largeFile) const { + size_t sz = 0; + if(segmentMetadataFlag == cfdp::SegmentMetadataFlag::PRESENT) { + sz += 1 + segmentMetadataLen; + } + if(largeFile) { + sz += 8; + } else { + sz += 4; + } + sz += fileSize; + return sz; +} + +cfdp::SegmentMetadataFlag FileDataInfo::getSegmentMetadataFlag() const { + return this->segmentMetadataFlag; +} + +bool FileDataInfo::hasSegmentMetadata() const { + if(segmentMetadataFlag == cfdp::SegmentMetadataFlag::PRESENT) { + return true; + } + return false; +} + +cfdp::RecordContinuationState FileDataInfo::getRecordContinuationState() const { + return this->recContState; +} + +size_t FileDataInfo::getSegmentMetadataLen() const { + return segmentMetadataLen; +} + +ReturnValue_t FileDataInfo::addSegmentMetadataInfo(cfdp::RecordContinuationState recContState, + const uint8_t* segmentMetadata, size_t segmentMetadataLen) { + this->segmentMetadataFlag = cfdp::SegmentMetadataFlag::PRESENT; + this->recContState = recContState; + if(segmentMetadataLen > 63) { + return HasReturnvaluesIF::RETURN_FAILED; + } + this->segmentMetadata = segmentMetadata; + this->segmentMetadataLen = segmentMetadataLen; + return HasReturnvaluesIF::RETURN_OK; +} + +const uint8_t* FileDataInfo::getFileData(size_t *fileSize) const { + if(fileSize != nullptr) { + *fileSize = this->fileSize; + } + return fileData; +} + +const uint8_t* FileDataInfo::getSegmentMetadata(size_t *segmentMetadataLen) { + if(segmentMetadataLen != nullptr) { + *segmentMetadataLen = this->segmentMetadataLen; + } + return segmentMetadata; +} + +cfdp::FileSize& FileDataInfo::getOffset() { + return offset; +} + +void FileDataInfo::setRecordContinuationState(cfdp::RecordContinuationState recContState) { + this->recContState = recContState; +} + +void FileDataInfo::setSegmentMetadataLen(size_t len) { + this->segmentMetadataLen = len; +} + +void FileDataInfo::setSegmentMetadata(const uint8_t *ptr) { + this->segmentMetadata = ptr; +} + +void FileDataInfo::setFileData(const uint8_t *fileData, size_t fileSize) { + this->fileData = fileData; + this->fileSize = fileSize; +} + +cfdp::SegmentationControl FileDataInfo::getSegmentationControl() const { + return segCtrl; +} + +void FileDataInfo::setSegmentationControl(cfdp::SegmentationControl segCtrl) { + this->segCtrl = segCtrl; +} diff --git a/src/fsfw/cfdp/pdu/FileDataInfo.h b/src/fsfw/cfdp/pdu/FileDataInfo.h new file mode 100644 index 00000000..1fcc6ff0 --- /dev/null +++ b/src/fsfw/cfdp/pdu/FileDataInfo.h @@ -0,0 +1,45 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_FILEDATAINFO_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_FILEDATAINFO_H_ + +#include +#include + +class FileDataInfo { +public: + FileDataInfo(cfdp::FileSize& offset); + FileDataInfo(cfdp::FileSize& offset, const uint8_t* fileData, size_t fileSize); + + size_t getSerializedSize(bool largeFile = false) const; + + cfdp::FileSize& getOffset(); + const uint8_t* getFileData(size_t* fileSize = nullptr) const; + void setFileData(const uint8_t* fileData, size_t fileSize); + + cfdp::SegmentMetadataFlag getSegmentMetadataFlag() const; + cfdp::SegmentationControl getSegmentationControl() const; + cfdp::RecordContinuationState getRecordContinuationState() const; + void setRecordContinuationState(cfdp::RecordContinuationState recContState); + void setSegmentationControl(cfdp::SegmentationControl segCtrl); + + size_t getSegmentMetadataLen() const; + void setSegmentMetadataLen(size_t len); + void setSegmentMetadata(const uint8_t* ptr); + bool hasSegmentMetadata() const; + void setSegmentMetadataFlag(bool enable); + ReturnValue_t addSegmentMetadataInfo(cfdp::RecordContinuationState recContState, + const uint8_t* segmentMetadata, size_t segmentMetadataLen); + const uint8_t* getSegmentMetadata(size_t* segmentMetadataLen = nullptr); + +private: + cfdp::SegmentMetadataFlag segmentMetadataFlag = cfdp::SegmentMetadataFlag::NOT_PRESENT; + cfdp::SegmentationControl segCtrl = + cfdp::SegmentationControl::NO_RECORD_BOUNDARIES_PRESERVATION; + cfdp::FileSize& offset; + const uint8_t* fileData = nullptr; + size_t fileSize = 0; + cfdp::RecordContinuationState recContState = cfdp::RecordContinuationState::NO_START_NO_END; + size_t segmentMetadataLen = 0; + const uint8_t* segmentMetadata = nullptr; +}; + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_FILEDATAINFO_H_ */ diff --git a/src/fsfw/cfdp/pdu/FileDataSerializer.cpp b/src/fsfw/cfdp/pdu/FileDataSerializer.cpp new file mode 100644 index 00000000..4488e368 --- /dev/null +++ b/src/fsfw/cfdp/pdu/FileDataSerializer.cpp @@ -0,0 +1,54 @@ +#include "FileDataSerializer.h" +#include + +FileDataSerializer::FileDataSerializer(PduConfig& conf, FileDataInfo& info): + HeaderSerializer(conf, cfdp::PduType::FILE_DATA, 0, info.getSegmentMetadataFlag()), + info(info) { + update(); +} + +void FileDataSerializer::update() { + this->setSegmentMetadataFlag(info.getSegmentMetadataFlag()); + this->setSegmentationControl(info.getSegmentationControl()); + setPduDataFieldLen(info.getSerializedSize(this->getLargeFileFlag())); +} + +ReturnValue_t FileDataSerializer::serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const { + ReturnValue_t result = HeaderSerializer::serialize(buffer, size, maxSize, streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if(*size + this->getSerializedSize() > maxSize) { + return SerializeIF::BUFFER_TOO_SHORT; + } + const uint8_t* readOnlyPtr = nullptr; + if (this->hasSegmentMetadataFlag()) { + size_t segmentMetadataLen = info.getSegmentMetadataLen(); + **buffer = info.getRecordContinuationState() << 6 | segmentMetadataLen; + *buffer += 1; + *size += 1; + readOnlyPtr = info.getSegmentMetadata(); + std::memcpy(*buffer, readOnlyPtr, segmentMetadataLen); + *buffer += segmentMetadataLen; + *size += segmentMetadataLen; + } + cfdp::FileSize& offset = info.getOffset(); + result = offset.serialize(this->getLargeFileFlag(), buffer, size, maxSize, streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + size_t fileSize = 0; + readOnlyPtr = info.getFileData(&fileSize); + if(*size + fileSize > maxSize) { + return SerializeIF::BUFFER_TOO_SHORT; + } + std::memcpy(*buffer, readOnlyPtr, fileSize); + *buffer += fileSize; + *size += fileSize; + return HasReturnvaluesIF::RETURN_OK; +} + +size_t FileDataSerializer::getSerializedSize() const { + return HeaderSerializer::getSerializedSize() + info.getSerializedSize(this->getLargeFileFlag()); +} diff --git a/src/fsfw/cfdp/pdu/FileDataSerializer.h b/src/fsfw/cfdp/pdu/FileDataSerializer.h new file mode 100644 index 00000000..b0153528 --- /dev/null +++ b/src/fsfw/cfdp/pdu/FileDataSerializer.h @@ -0,0 +1,23 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_FILEDATASERIALIZER_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_FILEDATASERIALIZER_H_ + +#include "FileDataInfo.h" +#include "../definitions.h" +#include "HeaderSerializer.h" + +class FileDataSerializer: public HeaderSerializer { +public: + FileDataSerializer(PduConfig& conf, FileDataInfo& info); + + void update(); + + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; + + size_t getSerializedSize() const override; + +private: + FileDataInfo& info; +}; + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_FILEDATADESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/FileDirectiveDeserializer.cpp b/src/fsfw/cfdp/pdu/FileDirectiveDeserializer.cpp new file mode 100644 index 00000000..b348c5bd --- /dev/null +++ b/src/fsfw/cfdp/pdu/FileDirectiveDeserializer.cpp @@ -0,0 +1,55 @@ +#include "FileDirectiveDeserializer.h" + +FileDirectiveDeserializer::FileDirectiveDeserializer(const uint8_t *pduBuf, size_t maxSize): + HeaderDeserializer(pduBuf, maxSize) { +} + +cfdp::FileDirectives FileDirectiveDeserializer::getFileDirective() const { + return fileDirective; +} + +ReturnValue_t FileDirectiveDeserializer::parseData() { + ReturnValue_t result = HeaderDeserializer::parseData(); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if(this->getPduDataFieldLen() < 1) { + return cfdp::INVALID_PDU_DATAFIELD_LEN; + } + if(FileDirectiveDeserializer::getWholePduSize() > maxSize) { + return SerializeIF::STREAM_TOO_SHORT; + } + size_t currentIdx = HeaderDeserializer::getHeaderSize(); + if(not checkFileDirective(rawPtr[currentIdx])) { + return cfdp::INVALID_DIRECTIVE_FIELDS; + } + setFileDirective(static_cast(rawPtr[currentIdx])); + return HasReturnvaluesIF::RETURN_OK; +} + +size_t FileDirectiveDeserializer::getHeaderSize() const { + // return size of header plus the directive byte + return HeaderDeserializer::getHeaderSize() + 1; +} + +bool FileDirectiveDeserializer::checkFileDirective(uint8_t rawByte) { + if(rawByte < cfdp::FileDirectives::EOF_DIRECTIVE or + (rawByte > cfdp::FileDirectives::PROMPT and + rawByte != cfdp::FileDirectives::KEEP_ALIVE)) { + // Invalid directive field. TODO: Custom returnvalue + return false; + } + return true; +} + +void FileDirectiveDeserializer::setFileDirective(cfdp::FileDirectives fileDirective) { + this->fileDirective = fileDirective; +} + +void FileDirectiveDeserializer::setEndianness(SerializeIF::Endianness endianness) { + this->endianness = endianness; +} + +SerializeIF::Endianness FileDirectiveDeserializer::getEndianness() const { + return endianness; +} diff --git a/src/fsfw/cfdp/pdu/FileDirectiveDeserializer.h b/src/fsfw/cfdp/pdu/FileDirectiveDeserializer.h new file mode 100644 index 00000000..257fb5c0 --- /dev/null +++ b/src/fsfw/cfdp/pdu/FileDirectiveDeserializer.h @@ -0,0 +1,41 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_FILEDIRECTIVEDESERIALIZER_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_FILEDIRECTIVEDESERIALIZER_H_ + +#include "../definitions.h" +#include "fsfw/cfdp/pdu/HeaderDeserializer.h" + +/** + * @brief This class is used to deserialize a PDU file directive header from raw memory. + * @details + * Base class for other file directives. + * This is a zero-copy implementation and #parseData needs to be called to ensure the data is + * valid. + */ +class FileDirectiveDeserializer: public HeaderDeserializer { +public: + FileDirectiveDeserializer(const uint8_t* pduBuf, size_t maxSize); + + /** + * This needs to be called before accessing the PDU fields to avoid segmentation faults. + * @return + */ + virtual ReturnValue_t parseData(); + size_t getHeaderSize() const; + + cfdp::FileDirectives getFileDirective() const; + + void setEndianness(SerializeIF::Endianness endianness); + SerializeIF::Endianness getEndianness() const; + +protected: + bool checkFileDirective(uint8_t rawByte); + +private: + void setFileDirective(cfdp::FileDirectives fileDirective); + cfdp::FileDirectives fileDirective = cfdp::FileDirectives::INVALID_DIRECTIVE; + SerializeIF::Endianness endianness = SerializeIF::Endianness::NETWORK; +}; + + + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_FILEDIRECTIVEDESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/FileDirectiveSerializer.cpp b/src/fsfw/cfdp/pdu/FileDirectiveSerializer.cpp new file mode 100644 index 00000000..89600d1d --- /dev/null +++ b/src/fsfw/cfdp/pdu/FileDirectiveSerializer.cpp @@ -0,0 +1,39 @@ +#include "FileDirectiveSerializer.h" + + +FileDirectiveSerializer::FileDirectiveSerializer(PduConfig &pduConf, + cfdp::FileDirectives directiveCode, size_t directiveParamFieldLen): + HeaderSerializer(pduConf, cfdp::PduType::FILE_DIRECTIVE, directiveParamFieldLen + 1), + directiveCode(directiveCode) { +} + +size_t FileDirectiveSerializer::getSerializedSize() const { + return HeaderSerializer::getSerializedSize() + 1; +} + +ReturnValue_t FileDirectiveSerializer::serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const { + if(buffer == nullptr or size == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if(FileDirectiveSerializer::getWholePduSize() > maxSize) { + return BUFFER_TOO_SHORT; + } + ReturnValue_t result = HeaderSerializer::serialize(buffer, size, maxSize, streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + + if(*size >= maxSize) { + return BUFFER_TOO_SHORT; + } + **buffer = directiveCode; + *buffer += 1; + *size += 1; + return HasReturnvaluesIF::RETURN_OK; +} + +void FileDirectiveSerializer::setDirectiveDataFieldLen(size_t len) { + // Set length of data field plus 1 byte for the directive octet + HeaderSerializer::setPduDataFieldLen(len + 1); +} diff --git a/src/fsfw/cfdp/pdu/FileDirectiveSerializer.h b/src/fsfw/cfdp/pdu/FileDirectiveSerializer.h new file mode 100644 index 00000000..75a3582d --- /dev/null +++ b/src/fsfw/cfdp/pdu/FileDirectiveSerializer.h @@ -0,0 +1,28 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_FILEDIRECTIVESERIALIZER_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_FILEDIRECTIVESERIALIZER_H_ + +#include "fsfw/cfdp/pdu/HeaderSerializer.h" + +class FileDirectiveSerializer: public HeaderSerializer { +public: + FileDirectiveSerializer(PduConfig& pduConf, cfdp::FileDirectives directiveCode, + size_t directiveParamFieldLen); + + /** + * This only returns the size of the PDU header + 1 for the directive code octet. + * Use FileDirectiveSerializer::getWholePduSize to get the full packet length, assuming + * the length fields was set correctly + * @return + */ + size_t getSerializedSize() const override; + + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; + + void setDirectiveDataFieldLen(size_t len); +private: + cfdp::FileDirectives directiveCode = cfdp::FileDirectives::INVALID_DIRECTIVE; + +}; + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_FILEDIRECTIVESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/FinishedInfo.cpp b/src/fsfw/cfdp/pdu/FinishedInfo.cpp new file mode 100644 index 00000000..e6b7e9b4 --- /dev/null +++ b/src/fsfw/cfdp/pdu/FinishedInfo.cpp @@ -0,0 +1,111 @@ +#include "FinishedInfo.h" + +FinishedInfo::FinishedInfo() { +} + + +FinishedInfo::FinishedInfo(cfdp::ConditionCode conditionCode, + cfdp::FinishedDeliveryCode deliveryCode, cfdp::FinishedFileStatus fileStatus): + conditionCode(conditionCode), deliveryCode(deliveryCode), fileStatus(fileStatus) { +} + +size_t FinishedInfo::getSerializedSize() const { + size_t size = 1; + if(hasFsResponses()) { + for(size_t idx = 0; idx < fsResponsesLen; idx++) { + size += fsResponses[idx]->getSerializedSize(); + } + } + if(this->faultLocation != nullptr) { + size += faultLocation->getSerializedSize(); + } + return size; +} + +bool FinishedInfo::hasFsResponses() const { + if(fsResponses != nullptr and fsResponsesLen > 0) { + return true; + } + return false; +} +bool FinishedInfo::canHoldFsResponses() const { + if(fsResponses != nullptr and fsResponsesMaxLen > 0) { + return true; + } + return false; +} + + +ReturnValue_t FinishedInfo::setFilestoreResponsesArray(FilestoreResponseTlv** fsResponses, + size_t* fsResponsesLen, const size_t* maxFsResponsesLen) { + this->fsResponses = fsResponses; + if(fsResponsesLen != nullptr) { + this->fsResponsesLen = *fsResponsesLen; + if(this->fsResponsesMaxLen < *fsResponsesLen) { + this->fsResponsesMaxLen = this->fsResponsesLen; + } + } + if(maxFsResponsesLen != nullptr) { + this->fsResponsesMaxLen = *maxFsResponsesLen; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t FinishedInfo::getFilestoreResonses(FilestoreResponseTlv ***fsResponses, + size_t *fsResponsesLen, size_t* fsResponsesMaxLen) { + if(fsResponses == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + *fsResponses = this->fsResponses; + if(fsResponsesLen != nullptr) { + *fsResponsesLen = this->fsResponsesLen; + } + if(fsResponsesMaxLen != nullptr) { + *fsResponsesMaxLen = this->fsResponsesMaxLen; + } + return HasReturnvaluesIF::RETURN_OK; +} + +void FinishedInfo::setFaultLocation(EntityIdTlv *faultLocation) { + this->faultLocation = faultLocation; +} + +ReturnValue_t FinishedInfo::getFaultLocation(EntityIdTlv** faultLocation) { + if(this->faultLocation == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + *faultLocation = this->faultLocation; + return HasReturnvaluesIF::RETURN_OK; +} + +cfdp::ConditionCode FinishedInfo::getConditionCode() const { + return conditionCode; +} + +void FinishedInfo::setConditionCode(cfdp::ConditionCode conditionCode) { + this->conditionCode = conditionCode; +} + +cfdp::FinishedDeliveryCode FinishedInfo::getDeliveryCode() const { + return deliveryCode; +} + +void FinishedInfo::setDeliveryCode(cfdp::FinishedDeliveryCode deliveryCode) { + this->deliveryCode = deliveryCode; +} + +cfdp::FinishedFileStatus FinishedInfo::getFileStatus() const { + return fileStatus; +} + +void FinishedInfo::setFilestoreResponsesArrayLen(size_t fsResponsesLen) { + this->fsResponsesLen = fsResponsesLen; +} + +size_t FinishedInfo::getFsResponsesLen() const { + return fsResponsesLen; +} + +void FinishedInfo::setFileStatus(cfdp::FinishedFileStatus fileStatus) { + this->fileStatus = fileStatus; +} diff --git a/src/fsfw/cfdp/pdu/FinishedInfo.h b/src/fsfw/cfdp/pdu/FinishedInfo.h new file mode 100644 index 00000000..18552df5 --- /dev/null +++ b/src/fsfw/cfdp/pdu/FinishedInfo.h @@ -0,0 +1,45 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_FINISHINFO_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_FINISHINFO_H_ + +#include "fsfw/cfdp/tlv/EntityIdTlv.h" +#include "fsfw/cfdp/tlv/FilestoreResponseTlv.h" +#include "../definitions.h" + +class FinishedInfo { +public: + FinishedInfo(); + FinishedInfo(cfdp::ConditionCode conditionCode, cfdp::FinishedDeliveryCode deliveryCode, + cfdp::FinishedFileStatus fileStatus); + + size_t getSerializedSize() const; + + bool hasFsResponses() const; + bool canHoldFsResponses() const; + + ReturnValue_t setFilestoreResponsesArray(FilestoreResponseTlv** fsResponses, + size_t* fsResponsesLen, const size_t* maxFsResponseLen); + void setFaultLocation(EntityIdTlv* entityId); + + ReturnValue_t getFilestoreResonses(FilestoreResponseTlv ***fsResponses, + size_t *fsResponsesLen, size_t* fsResponsesMaxLen); + size_t getFsResponsesLen() const; + void setFilestoreResponsesArrayLen(size_t fsResponsesLen); + ReturnValue_t getFaultLocation(EntityIdTlv** entityId); + cfdp::ConditionCode getConditionCode() const; + void setConditionCode(cfdp::ConditionCode conditionCode); + cfdp::FinishedDeliveryCode getDeliveryCode() const; + void setDeliveryCode(cfdp::FinishedDeliveryCode deliveryCode); + cfdp::FinishedFileStatus getFileStatus() const; + void setFileStatus(cfdp::FinishedFileStatus fileStatus); + +private: + cfdp::ConditionCode conditionCode = cfdp::ConditionCode::NO_CONDITION_FIELD; + cfdp::FinishedDeliveryCode deliveryCode = cfdp::FinishedDeliveryCode::DATA_COMPLETE; + cfdp::FinishedFileStatus fileStatus = cfdp::FinishedFileStatus::DISCARDED_DELIBERATELY; + FilestoreResponseTlv** fsResponses = nullptr; + size_t fsResponsesLen = 0; + size_t fsResponsesMaxLen = 0; + EntityIdTlv* faultLocation = nullptr; +}; + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_FINISHINFO_H_ */ diff --git a/src/fsfw/cfdp/pdu/FinishedPduDeserializer.cpp b/src/fsfw/cfdp/pdu/FinishedPduDeserializer.cpp new file mode 100644 index 00000000..55528650 --- /dev/null +++ b/src/fsfw/cfdp/pdu/FinishedPduDeserializer.cpp @@ -0,0 +1,90 @@ +#include "FinishedPduDeserializer.h" + +FinishPduDeserializer::FinishPduDeserializer(const uint8_t *pduBuf, size_t maxSize, + FinishedInfo &info): FileDirectiveDeserializer(pduBuf, maxSize), finishedInfo(info) { +} + +ReturnValue_t FinishPduDeserializer::parseData() { + ReturnValue_t result = FileDirectiveDeserializer::parseData(); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + size_t currentIdx = FileDirectiveDeserializer::getHeaderSize(); + const uint8_t* buf = rawPtr + currentIdx; + size_t remSize = FileDirectiveDeserializer::getWholePduSize() - currentIdx; + if (remSize < 1) { + return SerializeIF::STREAM_TOO_SHORT; + } + uint8_t firstByte = *buf; + cfdp::ConditionCode condCode = static_cast((firstByte >> 4) & 0x0f); + finishedInfo.setConditionCode(condCode); + finishedInfo.setDeliveryCode(static_cast(firstByte >> 2 & 0b1)); + finishedInfo.setFileStatus(static_cast(firstByte & 0b11)); + buf += 1; + remSize -= 1; + currentIdx += 1; + if(remSize > 0) { + result = parseTlvs(remSize, currentIdx, buf, condCode); + } + return result; +} + +FinishedInfo& FinishPduDeserializer::getInfo() { + return finishedInfo; +} + +ReturnValue_t FinishPduDeserializer::parseTlvs(size_t remLen, size_t currentIdx, + const uint8_t* buf, cfdp::ConditionCode conditionCode) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + size_t fsResponsesIdx = 0; + auto endianness = getEndianness(); + FilestoreResponseTlv** fsResponseArray = nullptr; + size_t fsResponseMaxArrayLen = 0; + EntityIdTlv* faultLocation = nullptr; + cfdp::TlvTypes nextTlv = cfdp::TlvTypes::INVALID_TLV; + while(remLen > 0) { + // Simply forward parse the TLV type. Every TLV type except the last one must be a Filestore + // Response TLV, and even the last one can be a Filestore Response TLV if the fault + // location is omitted + if (currentIdx + 2 > maxSize) { + return SerializeIF::STREAM_TOO_SHORT; + } + nextTlv = static_cast(*buf); + if (nextTlv == cfdp::TlvTypes::FILESTORE_RESPONSE) { + if(fsResponseArray == nullptr) { + if(not finishedInfo.canHoldFsResponses()) { + return cfdp::FINISHED_CANT_PARSE_FS_RESPONSES; + } + result = finishedInfo.getFilestoreResonses(&fsResponseArray, nullptr, + &fsResponseMaxArrayLen); + } + if(fsResponsesIdx == fsResponseMaxArrayLen) { + return cfdp::FINISHED_CANT_PARSE_FS_RESPONSES; + } + result = fsResponseArray[fsResponsesIdx]->deSerialize(&buf, &remLen, endianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + fsResponsesIdx += 1; + } else if(nextTlv == cfdp::TlvTypes::ENTITY_ID) { + // This needs to be the last TLV and it should not be here if the condition code + // is "No Error" or "Unsupported Checksum Type" + if(conditionCode == cfdp::ConditionCode::NO_ERROR or + conditionCode == cfdp::ConditionCode::UNSUPPORTED_CHECKSUM_TYPE) { + return cfdp::INVALID_TLV_TYPE; + } + result = finishedInfo.getFaultLocation(&faultLocation); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = faultLocation->deSerialize(&buf, &remLen, endianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + } else { + return cfdp::INVALID_TLV_TYPE; + } + } + finishedInfo.setFilestoreResponsesArrayLen(fsResponsesIdx); + return result; +} diff --git a/src/fsfw/cfdp/pdu/FinishedPduDeserializer.h b/src/fsfw/cfdp/pdu/FinishedPduDeserializer.h new file mode 100644 index 00000000..dcbc23bd --- /dev/null +++ b/src/fsfw/cfdp/pdu/FinishedPduDeserializer.h @@ -0,0 +1,21 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_FINISHEDPDUDESERIALIZER_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_FINISHEDPDUDESERIALIZER_H_ + +#include "fsfw/cfdp/pdu/FinishedInfo.h" +#include "fsfw/cfdp/pdu/FileDirectiveDeserializer.h" + +class FinishPduDeserializer: public FileDirectiveDeserializer { +public: + FinishPduDeserializer(const uint8_t *pduBuf, size_t maxSize, FinishedInfo& info); + + ReturnValue_t parseData() override; + + FinishedInfo& getInfo(); +private: + FinishedInfo& finishedInfo; + + ReturnValue_t parseTlvs(size_t remLen, size_t currentIdx, const uint8_t* buf, + cfdp::ConditionCode conditionCode); +}; + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_FINISHEDPDUDESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/FinishedPduSerializer.cpp b/src/fsfw/cfdp/pdu/FinishedPduSerializer.cpp new file mode 100644 index 00000000..98112ce2 --- /dev/null +++ b/src/fsfw/cfdp/pdu/FinishedPduSerializer.cpp @@ -0,0 +1,47 @@ +#include "FinishedPduSerializer.h" + +FinishPduSerializer::FinishPduSerializer(PduConfig &conf, FinishedInfo &finishInfo): + FileDirectiveSerializer(conf, cfdp::FileDirectives::FINISH, 0), finishInfo(finishInfo) { + updateDirectiveFieldLen(); +} + +size_t FinishPduSerializer::getSerializedSize() const { + return FinishPduSerializer::getWholePduSize(); +} + +void FinishPduSerializer::updateDirectiveFieldLen() { + setDirectiveDataFieldLen(finishInfo.getSerializedSize()); +} + +ReturnValue_t FinishPduSerializer::serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const { + ReturnValue_t result = FileDirectiveSerializer::serialize(buffer, size, maxSize, + streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if(*size + 1 >= maxSize) { + return SerializeIF::BUFFER_TOO_SHORT; + } + **buffer = finishInfo.getConditionCode() << 4 | finishInfo.getDeliveryCode() << 2 | + finishInfo.getFileStatus(); + *size += 1; + *buffer += 1; + + if(finishInfo.hasFsResponses()) { + FilestoreResponseTlv** fsResponsesArray = nullptr; + size_t fsResponsesArrayLen = 0; + finishInfo.getFilestoreResonses(&fsResponsesArray, &fsResponsesArrayLen, nullptr); + for(size_t idx = 0; idx < fsResponsesArrayLen; idx++) { + result = fsResponsesArray[idx]->serialize(buffer, size, maxSize, streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + } + } + EntityIdTlv* entityId = nullptr; + if(finishInfo.getFaultLocation(&entityId) == HasReturnvaluesIF::RETURN_OK) { + result = entityId->serialize(buffer, size, maxSize, streamEndianness); + } + return result; +} diff --git a/src/fsfw/cfdp/pdu/FinishedPduSerializer.h b/src/fsfw/cfdp/pdu/FinishedPduSerializer.h new file mode 100644 index 00000000..cfb067a5 --- /dev/null +++ b/src/fsfw/cfdp/pdu/FinishedPduSerializer.h @@ -0,0 +1,22 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_FINISHEDPDUSERIALIZER_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_FINISHEDPDUSERIALIZER_H_ + +#include "fsfw/cfdp/pdu/FileDirectiveSerializer.h" +#include "fsfw/cfdp/pdu/FileDataSerializer.h" +#include "FinishedInfo.h" + +class FinishPduSerializer: public FileDirectiveSerializer { +public: + FinishPduSerializer(PduConfig& pduConf, FinishedInfo& finishInfo); + + void updateDirectiveFieldLen(); + + size_t getSerializedSize() const override; + + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; +private: + FinishedInfo& finishInfo; +}; + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_FINISHEDPDUSERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/HeaderDeserializer.cpp b/src/fsfw/cfdp/pdu/HeaderDeserializer.cpp new file mode 100644 index 00000000..39994eb5 --- /dev/null +++ b/src/fsfw/cfdp/pdu/HeaderDeserializer.cpp @@ -0,0 +1,136 @@ +#include +#include "HeaderDeserializer.h" +#include + +HeaderDeserializer::HeaderDeserializer(const uint8_t *pduBuf, size_t maxSize): + rawPtr(pduBuf), maxSize(maxSize) { +} + +ReturnValue_t HeaderDeserializer::parseData() { + if (maxSize < 7) { + return SerializeIF::STREAM_TOO_SHORT; + } + return setData(const_cast(rawPtr), maxSize); +} + +ReturnValue_t HeaderDeserializer::setData(uint8_t *dataPtr, size_t maxSize, + void* args) { + if(dataPtr == nullptr) { + // Allowed for now + this->fixedHeader = nullptr; + return HasReturnvaluesIF::RETURN_OK; + } + this->fixedHeader = reinterpret_cast(const_cast(dataPtr)); + sourceIdRaw = static_cast(&fixedHeader->variableFieldsStart); + cfdp::WidthInBytes widthEntityIds = getLenEntityIds(); + cfdp::WidthInBytes widthSeqNum = getLenSeqNum(); + seqNumRaw = static_cast(sourceIdRaw) + static_cast(widthEntityIds); + destIdRaw = static_cast(seqNumRaw) + static_cast(widthSeqNum); + this->maxSize = maxSize; + return HasReturnvaluesIF::RETURN_OK; +} + +size_t HeaderDeserializer::getHeaderSize() const { + if(fixedHeader != nullptr) { + return getLenEntityIds() * 2 + getLenSeqNum() + 4; + } + return 0; +} + +size_t HeaderDeserializer::getPduDataFieldLen() const { + uint16_t pduFiedlLen = (fixedHeader->pduDataFieldLenH << 8) | fixedHeader->pduDataFieldLenL; + return pduFiedlLen; +} + +size_t HeaderDeserializer::getWholePduSize() const { + return getPduDataFieldLen() + getHeaderSize(); +} + +cfdp::PduType HeaderDeserializer::getPduType() const { + return static_cast((fixedHeader->firstByte >> 4) & 0x01); +} + +cfdp::Direction HeaderDeserializer::getDirection() const { + return static_cast((fixedHeader->firstByte >> 3) & 0x01); +} + +cfdp::TransmissionModes HeaderDeserializer::getTransmissionMode() const { + return static_cast((fixedHeader->firstByte >> 2) & 0x01); +} + +bool HeaderDeserializer::getCrcFlag() const { + return (fixedHeader->firstByte >> 1) & 0x01; +} + +bool HeaderDeserializer::getLargeFileFlag() const { + return fixedHeader->firstByte & 0x01; +} + +cfdp::SegmentationControl HeaderDeserializer::getSegmentationControl() const { + return static_cast((fixedHeader->fourthByte >> 7) & 0x01); +} + +cfdp::WidthInBytes HeaderDeserializer::getLenEntityIds() const { + return static_cast((fixedHeader->fourthByte >> 4) & 0x07); +} + +cfdp::WidthInBytes HeaderDeserializer::getLenSeqNum() const { + return static_cast(fixedHeader->fourthByte & 0x07); +} + +cfdp::SegmentMetadataFlag HeaderDeserializer::getSegmentMetadataFlag() const { + return static_cast((fixedHeader->fourthByte >> 3) & 0x01); +} + +void HeaderDeserializer::getSourceId(cfdp::EntityId &sourceId) const { + assignVarLenField(dynamic_cast(&sourceId), getLenEntityIds(), + this->sourceIdRaw); +} + +void HeaderDeserializer::getDestId(cfdp::EntityId &destId) const { + assignVarLenField(dynamic_cast(&destId), getLenEntityIds(), + this->destIdRaw); +} + +void HeaderDeserializer::getTransactionSeqNum(cfdp::TransactionSeqNum &seqNum) const { + assignVarLenField(dynamic_cast(&seqNum), getLenSeqNum(), + this->seqNumRaw); +} + +void HeaderDeserializer::assignVarLenField(cfdp::VarLenField* field, cfdp::WidthInBytes width, + void *sourcePtr) const { + switch(width) { + case(cfdp::WidthInBytes::ONE_BYTE): { + uint8_t* fieldTyped = static_cast(sourcePtr); + field->setValue(width, *fieldTyped); + break; + } + case(cfdp::WidthInBytes::TWO_BYTES): { + uint16_t fieldTyped = 0; + size_t deserSize = 0; + SerializeAdapter::deSerialize(&fieldTyped, static_cast(sourcePtr), &deserSize, + SerializeIF::Endianness::NETWORK); + field->setValue(width, fieldTyped); + break; + } + case(cfdp::WidthInBytes::FOUR_BYTES): { + uint32_t fieldTyped = 0; + size_t deserSize = 0; + SerializeAdapter::deSerialize(&fieldTyped, static_cast(sourcePtr), &deserSize, + SerializeIF::Endianness::NETWORK); + field->setValue(width, fieldTyped); + break; + } + } +} + +size_t HeaderDeserializer::getMaxSize() const { + return maxSize; +} + +bool HeaderDeserializer::hasSegmentMetadataFlag() const { + if(this->getSegmentMetadataFlag() == cfdp::SegmentMetadataFlag::PRESENT) { + return true; + } + return false; +} diff --git a/src/fsfw/cfdp/pdu/HeaderDeserializer.h b/src/fsfw/cfdp/pdu/HeaderDeserializer.h new file mode 100644 index 00000000..d44d538f --- /dev/null +++ b/src/fsfw/cfdp/pdu/HeaderDeserializer.h @@ -0,0 +1,93 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_HEADERDESERIALIZER_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_HEADERDESERIALIZER_H_ + +#include "PduConfig.h" +#include "PduHeaderIF.h" +#include "fsfw/serialize/SerializeIF.h" +#include "fsfw/tmtcpacket/RedirectableDataPointerIF.h" +#include +#include + +struct PduHeaderFixedStruct { + uint8_t firstByte; + uint8_t pduDataFieldLenH; + uint8_t pduDataFieldLenL; + uint8_t fourthByte; + uint8_t variableFieldsStart; +}; + +/** + * @brief This class is used to deserialize a PDU header from raw memory. + * @details + * This is a zero-copy implementation and #parseData needs to be called to ensure the data is + * valid. + */ +class HeaderDeserializer: + public RedirectableDataPointerIF, + public PduHeaderIF { +public: + /** + * Initialize a PDU header from raw data. This is a zero-copy implementation and #parseData + * needs to be called to ensure the data is valid + * @param pduBuf + * @param maxSize + */ + HeaderDeserializer(const uint8_t* pduBuf, size_t maxSize); + + /** + * This needs to be called before accessing the PDU fields to avoid segmentation faults. + * @return + * - RETURN_OK on parse success + * - RETURN_FAILED Invalid raw data + * - SerializeIF::BUFFER_TOO_SHORT if buffer is shorter than expected + */ + virtual ReturnValue_t parseData(); + size_t getHeaderSize() const; + + size_t getPduDataFieldLen() const override; + size_t getWholePduSize() const override; + + cfdp::PduType getPduType() const override; + cfdp::Direction getDirection() const override; + cfdp::TransmissionModes getTransmissionMode() const override; + bool getCrcFlag() const override; + bool getLargeFileFlag() const override; + cfdp::SegmentationControl getSegmentationControl() const override; + cfdp::WidthInBytes getLenEntityIds() const override; + cfdp::WidthInBytes getLenSeqNum() const override; + cfdp::SegmentMetadataFlag getSegmentMetadataFlag() const override; + bool hasSegmentMetadataFlag() const override; + + void getSourceId(cfdp::EntityId& sourceId) const override; + void getDestId(cfdp::EntityId& destId) const override; + void getTransactionSeqNum(cfdp::TransactionSeqNum& seqNum) const override; + + ReturnValue_t deserResult = HasReturnvaluesIF::RETURN_OK; + + /** + * Can also be used to reset the pointer to a nullptr, but the getter functions will not + * perform nullptr checks! + * @param dataPtr + * @param maxSize + * @param args + * @return + */ + ReturnValue_t setData(uint8_t* dataPtr, size_t maxSize, + void* args = nullptr) override; + + size_t getMaxSize() const; +protected: + PduHeaderFixedStruct* fixedHeader = nullptr; + const uint8_t* rawPtr = nullptr; + size_t maxSize = 0; + +private: + + void assignVarLenField(cfdp::VarLenField* field, cfdp::WidthInBytes width, + void* sourcePtr) const; + void* sourceIdRaw = nullptr; + void* seqNumRaw = nullptr; + void* destIdRaw = nullptr; +}; + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_HEADERDESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/HeaderSerializer.cpp b/src/fsfw/cfdp/pdu/HeaderSerializer.cpp new file mode 100644 index 00000000..a5163b29 --- /dev/null +++ b/src/fsfw/cfdp/pdu/HeaderSerializer.cpp @@ -0,0 +1,135 @@ +#include "HeaderSerializer.h" +#include "HeaderDeserializer.h" + +HeaderSerializer::HeaderSerializer(PduConfig& pduConf, cfdp::PduType pduType, + size_t initPduDataFieldLen, cfdp::SegmentMetadataFlag segmentMetadataFlag, + cfdp::SegmentationControl segCtrl): + pduType(pduType), segmentMetadataFlag(segmentMetadataFlag), segmentationCtrl(segCtrl), + pduDataFieldLen(initPduDataFieldLen), pduConf(pduConf) { +} + +ReturnValue_t HeaderSerializer::serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const { + if(buffer == nullptr or size == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if(maxSize < this->getSerializedSize()) { + return BUFFER_TOO_SHORT; + } + **buffer = cfdp::VERSION_BITS | this->pduType << 4 | pduConf.direction << 3 | + pduConf.mode << 2 | pduConf.crcFlag << 1 | pduConf.largeFile; + *buffer += 1; + **buffer = (pduDataFieldLen & 0xff00) >> 8; + *buffer += 1; + **buffer = pduDataFieldLen & 0x00ff; + *buffer += 1; + **buffer = segmentationCtrl << 7 | pduConf.sourceId.getWidth() << 4 | + segmentMetadataFlag << 3 | pduConf.seqNum.getWidth(); + *buffer += 1; + *size += 4; + ReturnValue_t result = pduConf.sourceId.serialize(buffer, size, maxSize, streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = pduConf.seqNum.serialize(buffer, size, maxSize, streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = pduConf.destId.serialize(buffer, size, maxSize, streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + + return HasReturnvaluesIF::RETURN_OK; +} + +size_t HeaderSerializer::getSerializedSize() const { + size_t shit = pduConf.seqNum.getWidth() + pduConf.sourceId.getWidth() * 2 + 4; + return shit; +} + +ReturnValue_t HeaderSerializer::deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) { + // We could implement this, but I prefer dedicated classes + return HasReturnvaluesIF::RETURN_FAILED; +} + +size_t HeaderSerializer::getWholePduSize() const { + // Return size of header plus the PDU data field length + return pduDataFieldLen + HeaderSerializer::getSerializedSize(); +} + +size_t HeaderSerializer::getPduDataFieldLen() const { + return pduDataFieldLen; +} + +void HeaderSerializer::setPduDataFieldLen(size_t pduDataFieldLen) { + this->pduDataFieldLen = pduDataFieldLen; +} + +void HeaderSerializer::setPduType(cfdp::PduType pduType) { + this->pduType = pduType; +} + +void HeaderSerializer::setSegmentMetadataFlag(cfdp::SegmentMetadataFlag segmentMetadataFlag) { + this->segmentMetadataFlag = segmentMetadataFlag; +} + +cfdp::PduType HeaderSerializer::getPduType() const { + return pduType; +} + +cfdp::Direction HeaderSerializer::getDirection() const { + return pduConf.direction; +} + +cfdp::TransmissionModes HeaderSerializer::getTransmissionMode() const { + return pduConf.mode; +} + +bool HeaderSerializer::getCrcFlag() const { + return pduConf.crcFlag; +} + +bool HeaderSerializer::getLargeFileFlag() const { + return pduConf.largeFile; +} + +cfdp::SegmentationControl HeaderSerializer::getSegmentationControl() const { + return segmentationCtrl; +} + +cfdp::WidthInBytes HeaderSerializer::getLenEntityIds() const { + return pduConf.sourceId.getWidth(); +} + +cfdp::WidthInBytes HeaderSerializer::getLenSeqNum() const { + return pduConf.seqNum.getWidth(); +} + +cfdp::SegmentMetadataFlag HeaderSerializer::getSegmentMetadataFlag() const { + return segmentMetadataFlag; +} + +void HeaderSerializer::getSourceId(cfdp::EntityId &sourceId) const { + sourceId = pduConf.sourceId; +} + +void HeaderSerializer::getDestId(cfdp::EntityId &destId) const { + destId = pduConf.destId; +} + +void HeaderSerializer::setSegmentationControl(cfdp::SegmentationControl segmentationControl) { + this->segmentationCtrl = segmentationControl; +} + +void HeaderSerializer::getTransactionSeqNum(cfdp::TransactionSeqNum &seqNum) const { + seqNum = pduConf.seqNum; +} + +bool HeaderSerializer::hasSegmentMetadataFlag() const { + if(this->segmentMetadataFlag == cfdp::SegmentMetadataFlag::PRESENT) { + return true; + } + return false; +} diff --git a/src/fsfw/cfdp/pdu/HeaderSerializer.h b/src/fsfw/cfdp/pdu/HeaderSerializer.h new file mode 100644 index 00000000..61e9d74a --- /dev/null +++ b/src/fsfw/cfdp/pdu/HeaderSerializer.h @@ -0,0 +1,64 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_HEADERSERIALIZER_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_HEADERSERIALIZER_H_ + +#include "PduHeaderIF.h" +#include "fsfw/serialize/SerializeIF.h" +#include "../definitions.h" +#include "PduConfig.h" + +class HeaderSerializer: public SerializeIF, public PduHeaderIF { +public: + + HeaderSerializer(PduConfig& pduConf, cfdp::PduType pduType, + size_t initPduDataFieldLen, + cfdp::SegmentMetadataFlag segmentMetadataFlag = cfdp::SegmentMetadataFlag::NOT_PRESENT, + cfdp::SegmentationControl segCtrl = + cfdp::SegmentationControl::NO_RECORD_BOUNDARIES_PRESERVATION); + + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; + + /** + * This only returns the length of the serialized hader. + * Use #getWholePduSize to get the length of the full packet, assuming that the PDU + * data field length was not properly. + * @return + */ + size_t getSerializedSize() const override; + + ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) override; + + void setPduDataFieldLen(size_t pduDataFieldLen); + void setPduType(cfdp::PduType pduType); + void setSegmentMetadataFlag(cfdp::SegmentMetadataFlag); + + size_t getPduDataFieldLen() const override; + size_t getWholePduSize() const override; + + cfdp::PduType getPduType() const override; + cfdp::Direction getDirection() const override; + cfdp::TransmissionModes getTransmissionMode() const override; + bool getCrcFlag() const override; + bool getLargeFileFlag() const override; + cfdp::SegmentationControl getSegmentationControl() const override; + cfdp::WidthInBytes getLenEntityIds() const override; + cfdp::WidthInBytes getLenSeqNum() const override; + cfdp::SegmentMetadataFlag getSegmentMetadataFlag() const override; + bool hasSegmentMetadataFlag() const; + void setSegmentationControl(cfdp::SegmentationControl); + + void getSourceId(cfdp::EntityId& sourceId) const override; + void getDestId(cfdp::EntityId& destId) const override; + void getTransactionSeqNum(cfdp::TransactionSeqNum& seqNum) const override; +private: + cfdp::PduType pduType; + cfdp::SegmentMetadataFlag segmentMetadataFlag; + cfdp::SegmentationControl segmentationCtrl; + size_t pduDataFieldLen; + + PduConfig& pduConf; +}; + + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_HEADERSERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/KeepAlivePduDeserializer.cpp b/src/fsfw/cfdp/pdu/KeepAlivePduDeserializer.cpp new file mode 100644 index 00000000..f8778224 --- /dev/null +++ b/src/fsfw/cfdp/pdu/KeepAlivePduDeserializer.cpp @@ -0,0 +1,20 @@ +#include "KeepAlivePduDeserializer.h" + +KeepAlivePduDeserializer::KeepAlivePduDeserializer(const uint8_t *pduBuf, size_t maxSize, + cfdp::FileSize &progress): FileDirectiveDeserializer(pduBuf, maxSize), progress(progress) { +} + +ReturnValue_t KeepAlivePduDeserializer::parseData() { + ReturnValue_t result = FileDirectiveDeserializer::parseData(); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + size_t currentIdx = FileDirectiveDeserializer::getHeaderSize(); + size_t remLen = FileDirectiveDeserializer::getWholePduSize() - currentIdx; + const uint8_t* buffer = rawPtr + currentIdx; + return progress.deSerialize(&buffer, &remLen, getEndianness()); +} + +cfdp::FileSize& KeepAlivePduDeserializer::getProgress() { + return progress; +} diff --git a/src/fsfw/cfdp/pdu/KeepAlivePduDeserializer.h b/src/fsfw/cfdp/pdu/KeepAlivePduDeserializer.h new file mode 100644 index 00000000..a7016166 --- /dev/null +++ b/src/fsfw/cfdp/pdu/KeepAlivePduDeserializer.h @@ -0,0 +1,18 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_KEEPALIVEPDUDESERIALIZER_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_KEEPALIVEPDUDESERIALIZER_H_ + +#include "fsfw/cfdp/FileSize.h" +#include "fsfw/cfdp/pdu/FileDirectiveDeserializer.h" + +class KeepAlivePduDeserializer: public FileDirectiveDeserializer { +public: + KeepAlivePduDeserializer(const uint8_t *pduBuf, size_t maxSize, cfdp::FileSize& progress); + + ReturnValue_t parseData() override; + + cfdp::FileSize& getProgress(); +private: + cfdp::FileSize& progress; +}; + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_KEEPALIVEPDUDESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/KeepAlivePduSerializer.cpp b/src/fsfw/cfdp/pdu/KeepAlivePduSerializer.cpp new file mode 100644 index 00000000..7882562b --- /dev/null +++ b/src/fsfw/cfdp/pdu/KeepAlivePduSerializer.cpp @@ -0,0 +1,26 @@ +#include "KeepAlivePduSerializer.h" + +KeepAlivePduSerializer::KeepAlivePduSerializer(PduConfig &conf, cfdp::FileSize& progress): + FileDirectiveSerializer(conf, cfdp::FileDirectives::KEEP_ALIVE, 4), progress(progress) { + updateDirectiveFieldLen(); +} + +size_t KeepAlivePduSerializer::getSerializedSize() const { + return FileDirectiveSerializer::getWholePduSize(); +} + +void KeepAlivePduSerializer::updateDirectiveFieldLen() { + if(this->getLargeFileFlag()) { + this->setDirectiveDataFieldLen(8); + } +} + +ReturnValue_t KeepAlivePduSerializer::serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const { + ReturnValue_t result = FileDirectiveSerializer::serialize(buffer, size, maxSize, + streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return progress.serialize(this->getLargeFileFlag(), buffer, size, maxSize, streamEndianness); +} diff --git a/src/fsfw/cfdp/pdu/KeepAlivePduSerializer.h b/src/fsfw/cfdp/pdu/KeepAlivePduSerializer.h new file mode 100644 index 00000000..57882d3f --- /dev/null +++ b/src/fsfw/cfdp/pdu/KeepAlivePduSerializer.h @@ -0,0 +1,21 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_KEEPALIVEPDUSERIALIZER_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_KEEPALIVEPDUSERIALIZER_H_ + +#include "fsfw/cfdp/FileSize.h" +#include "fsfw/cfdp/pdu/FileDirectiveSerializer.h" + +class KeepAlivePduSerializer: public FileDirectiveSerializer { +public: + KeepAlivePduSerializer(PduConfig& conf, cfdp::FileSize& progress); + + void updateDirectiveFieldLen(); + + size_t getSerializedSize() const override; + + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; +private: + cfdp::FileSize& progress; +}; + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_KEEPALIVEPDUSERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/MetadataInfo.cpp b/src/fsfw/cfdp/pdu/MetadataInfo.cpp new file mode 100644 index 00000000..04e0d6d1 --- /dev/null +++ b/src/fsfw/cfdp/pdu/MetadataInfo.cpp @@ -0,0 +1,115 @@ +#include "MetadataInfo.h" + +MetadataInfo::MetadataInfo(bool closureRequested, cfdp::ChecksumType checksumType, + cfdp::FileSize& fileSize, cfdp::Lv& sourceFileName, cfdp::Lv& destFileName): + closureRequested(closureRequested), checksumType(checksumType), fileSize(fileSize), + sourceFileName(sourceFileName), destFileName(destFileName) { +} + +void MetadataInfo::setOptionsArray(cfdp::Tlv** optionsArray, size_t* optionsLen, + size_t* maxOptionsLen) { + this->optionsArray = optionsArray; + if(maxOptionsLen != nullptr) { + this->maxOptionsLen = *maxOptionsLen; + } + if(optionsLen != nullptr) { + this->optionsLen = *optionsLen; + } +} + +cfdp::ChecksumType MetadataInfo::getChecksumType() const { + return checksumType; +} + +void MetadataInfo::setChecksumType(cfdp::ChecksumType checksumType) { + this->checksumType = checksumType; +} + +bool MetadataInfo::isClosureRequested() const { + return closureRequested; +} + +void MetadataInfo::setClosureRequested(bool closureRequested) { + this->closureRequested = closureRequested; +} + +cfdp::Lv& MetadataInfo::getDestFileName() { + return destFileName; +} + +cfdp::FileSize& MetadataInfo::getFileSize() { + return fileSize; +} + +ReturnValue_t MetadataInfo::getOptions(cfdp::Tlv*** optionsArray, size_t *optionsLen, + size_t* maxOptsLen) { + if(optionsArray == nullptr or this->optionsArray == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + *optionsArray = this->optionsArray; + if(optionsLen != nullptr) { + *optionsLen = this->optionsLen; + } + if(maxOptsLen != nullptr) { + *maxOptsLen = this->maxOptionsLen; + } + return HasReturnvaluesIF::RETURN_OK; +} + +bool MetadataInfo::hasOptions() const { + if (optionsArray != nullptr and optionsLen > 0) { + return true; + } + return false; +} + +bool MetadataInfo::canHoldOptions() const { + if (optionsArray != nullptr and maxOptionsLen > 0) { + return true; + } + return false; +} + +size_t MetadataInfo::getSerializedSize(bool fssLarge) { + // 1 byte + minimal FSS 4 bytes + size_t size = 5; + if(fssLarge) { + size += 4; + } + size += sourceFileName.getSerializedSize(); + size += destFileName.getSerializedSize(); + if(hasOptions()) { + for(size_t idx = 0; idx < optionsLen; idx++) { + size += optionsArray[idx]->getSerializedSize(); + } + } + return size; +} + +void MetadataInfo::setDestFileName(cfdp::Lv &destFileName) { + this->destFileName = destFileName; +} + +void MetadataInfo::setSourceFileName(cfdp::Lv &sourceFileName) { + this->sourceFileName = sourceFileName; +} + +size_t MetadataInfo::getMaxOptionsLen() const { + return maxOptionsLen; +} + +void MetadataInfo::setMaxOptionsLen(size_t maxOptionsLen) { + this->maxOptionsLen = maxOptionsLen; +} + +size_t MetadataInfo::getOptionsLen() const { + return optionsLen; +} + +void MetadataInfo::setOptionsLen(size_t optionsLen) { + this->optionsLen = optionsLen; +} + +cfdp::Lv& MetadataInfo::getSourceFileName() { + return sourceFileName; +} diff --git a/src/fsfw/cfdp/pdu/MetadataInfo.h b/src/fsfw/cfdp/pdu/MetadataInfo.h new file mode 100644 index 00000000..c5a9a0ef --- /dev/null +++ b/src/fsfw/cfdp/pdu/MetadataInfo.h @@ -0,0 +1,49 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_METADATAINFO_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_METADATAINFO_H_ + +#include "fsfw/cfdp/tlv/Tlv.h" +#include "fsfw/cfdp/tlv/Lv.h" +#include "fsfw/cfdp/FileSize.h" +#include "fsfw/cfdp/definitions.h" + +class MetadataInfo { +public: + MetadataInfo(bool closureRequested, cfdp::ChecksumType checksumType, cfdp::FileSize& fileSize, + cfdp::Lv& sourceFileName, cfdp::Lv& destFileName); + + size_t getSerializedSize(bool fssLarge = false); + + void setOptionsArray(cfdp::Tlv** optionsArray, size_t* optionsLen, size_t* maxOptionsLen); + cfdp::ChecksumType getChecksumType() const; + void setChecksumType(cfdp::ChecksumType checksumType); + bool isClosureRequested() const; + void setClosureRequested(bool closureRequested = false); + + void setDestFileName(cfdp::Lv& destFileName); + void setSourceFileName(cfdp::Lv& sourceFileName); + + cfdp::Lv& getDestFileName(); + cfdp::Lv& getSourceFileName(); + cfdp::FileSize& getFileSize(); + + bool hasOptions() const; + bool canHoldOptions() const; + ReturnValue_t getOptions(cfdp::Tlv*** optionsArray, size_t* optionsLen, size_t* maxOptsLen); + void setOptionsLen(size_t optionsLen); + size_t getOptionsLen() const; + void setMaxOptionsLen(size_t maxOptionsLen); + size_t getMaxOptionsLen() const; + +private: + bool closureRequested = false; + cfdp::ChecksumType checksumType; + cfdp::FileSize& fileSize; + cfdp::Lv& sourceFileName; + cfdp::Lv& destFileName; + + cfdp::Tlv** optionsArray = nullptr; + size_t optionsLen = 0; + size_t maxOptionsLen = 0; +}; + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_METADATAINFO_H_ */ diff --git a/src/fsfw/cfdp/pdu/MetadataPduDeserializer.cpp b/src/fsfw/cfdp/pdu/MetadataPduDeserializer.cpp new file mode 100644 index 00000000..ccfaf2c9 --- /dev/null +++ b/src/fsfw/cfdp/pdu/MetadataPduDeserializer.cpp @@ -0,0 +1,58 @@ +#include "MetadataPduDeserializer.h" + +MetadataPduDeserializer::MetadataPduDeserializer(const uint8_t *pduBuf, size_t maxSize, + MetadataInfo &info): FileDirectiveDeserializer(pduBuf, maxSize), info(info) { +} + +ReturnValue_t MetadataPduDeserializer::parseData() { + ReturnValue_t result = FileDirectiveDeserializer::parseData(); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + size_t currentIdx = FileDirectiveDeserializer::getHeaderSize(); + const uint8_t* buf = rawPtr + currentIdx; + size_t remSize = FileDirectiveDeserializer::getWholePduSize() - currentIdx; + if (remSize < 1) { + return SerializeIF::STREAM_TOO_SHORT; + } + info.setClosureRequested((*buf >> 6) & 0x01); + info.setChecksumType(static_cast(*buf & 0x0f)); + remSize -= 1; + buf += 1; + auto endianness = getEndianness(); + result = info.getFileSize().deSerialize(&buf, &remSize, endianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = info.getSourceFileName().deSerialize(&buf, &remSize, endianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = info.getDestFileName().deSerialize(&buf, &remSize, endianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + + info.setOptionsLen(0); + if (remSize > 0) { + if(not info.canHoldOptions()) { + return cfdp::METADATA_CANT_PARSE_OPTIONS; + } + cfdp::Tlv** optionsArray = nullptr; + size_t optsMaxLen = 0; + size_t optsIdx = 0; + info.getOptions(&optionsArray, nullptr, &optsMaxLen); + while(remSize > 0) { + if(optsIdx > optsMaxLen) { + return cfdp::METADATA_CANT_PARSE_OPTIONS; + } + result = optionsArray[optsIdx]->deSerialize(&buf, &remSize, endianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + optsIdx++; + } + info.setOptionsLen(optsIdx); + } + return result; +} diff --git a/src/fsfw/cfdp/pdu/MetadataPduDeserializer.h b/src/fsfw/cfdp/pdu/MetadataPduDeserializer.h new file mode 100644 index 00000000..a3b343b4 --- /dev/null +++ b/src/fsfw/cfdp/pdu/MetadataPduDeserializer.h @@ -0,0 +1,18 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_METADATAPDUDESERIALIZER_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_METADATAPDUDESERIALIZER_H_ + +#include "fsfw/cfdp/pdu/FileDirectiveDeserializer.h" +#include "fsfw/cfdp/pdu/MetadataInfo.h" + +class MetadataPduDeserializer: public FileDirectiveDeserializer { +public: + MetadataPduDeserializer(const uint8_t* pduBuf, size_t maxSize, MetadataInfo& info); + + ReturnValue_t parseData() override; +private: + MetadataInfo& info; +}; + + + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_METADATAPDUDESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/MetadataPduSerializer.cpp b/src/fsfw/cfdp/pdu/MetadataPduSerializer.cpp new file mode 100644 index 00000000..1d2d67c2 --- /dev/null +++ b/src/fsfw/cfdp/pdu/MetadataPduSerializer.cpp @@ -0,0 +1,54 @@ +#include "MetadataPduSerializer.h" + +MetadataPduSerializer::MetadataPduSerializer(PduConfig &conf, MetadataInfo &info): + FileDirectiveSerializer(conf, cfdp::FileDirectives::METADATA, 5), info(info) { + updateDirectiveFieldLen(); +} + +void MetadataPduSerializer::updateDirectiveFieldLen() { + setDirectiveDataFieldLen(info.getSerializedSize(getLargeFileFlag())); +} + +size_t MetadataPduSerializer::getSerializedSize() const { + return FileDirectiveSerializer::getWholePduSize(); +} + +ReturnValue_t MetadataPduSerializer::serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const { + ReturnValue_t result = FileDirectiveSerializer::serialize(buffer, size, maxSize, + streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if(*size + 1 >= maxSize) { + return SerializeIF::BUFFER_TOO_SHORT; + } + **buffer = info.isClosureRequested() << 6 | info.getChecksumType(); + *buffer += 1; + *size += 1; + result = info.getFileSize().serialize(buffer, size, maxSize, streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = info.getSourceFileName().serialize(buffer, size, maxSize, streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = info.getDestFileName().serialize(buffer, size, maxSize, streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + + if(info.hasOptions()) { + cfdp::Tlv** optsArray = nullptr; + size_t optsLen = 0; + info.getOptions(&optsArray, &optsLen, nullptr); + for(size_t idx = 0; idx < optsLen; idx++) { + result = optsArray[idx]->serialize(buffer, size, maxSize, streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + } + } + return result; +} diff --git a/src/fsfw/cfdp/pdu/MetadataPduSerializer.h b/src/fsfw/cfdp/pdu/MetadataPduSerializer.h new file mode 100644 index 00000000..6cbead49 --- /dev/null +++ b/src/fsfw/cfdp/pdu/MetadataPduSerializer.h @@ -0,0 +1,23 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_METADATAPDUSERIALIZER_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_METADATAPDUSERIALIZER_H_ + +#include "fsfw/cfdp/pdu/MetadataInfo.h" +#include "fsfw/cfdp/pdu/FileDirectiveSerializer.h" + +class MetadataPduSerializer: public FileDirectiveSerializer { +public: + MetadataPduSerializer(PduConfig &conf, MetadataInfo& info); + + void updateDirectiveFieldLen(); + + size_t getSerializedSize() const override; + + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; +private: + MetadataInfo& info; +}; + + + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_METADATAPDUSERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/NakInfo.cpp b/src/fsfw/cfdp/pdu/NakInfo.cpp new file mode 100644 index 00000000..d11aabc1 --- /dev/null +++ b/src/fsfw/cfdp/pdu/NakInfo.cpp @@ -0,0 +1,83 @@ +#include "NakInfo.h" + +NakInfo::NakInfo(cfdp::FileSize startOfScope, cfdp::FileSize endOfScope): + startOfScope(startOfScope), endOfScope(endOfScope) { +} + +size_t NakInfo::getSerializedSize(bool fssLarge) { + size_t size = 8; + if(fssLarge) { + size += 8; + } + if(hasSegmentRequests()) { + if(fssLarge) { + size += segmentRequestsLen * 16; + } else { + size += segmentRequestsLen * 8; + } + } + return size; +} + +bool NakInfo::hasSegmentRequests() const { + if(this->segmentRequests != nullptr and segmentRequestsLen > 0) { + return true; + } + return false; +} + +bool NakInfo::canHoldSegmentRequests() const { + if(this->segmentRequests != nullptr and maxSegmentRequestsLen > 0) { + return true; + } + return false; +} + +bool NakInfo::getSegmentRequests(SegmentRequest **segmentRequestPtr, + size_t *segmentRequestLen, size_t* maxSegmentRequestsLen) { + if(this->segmentRequests != nullptr) { + *segmentRequestPtr = this->segmentRequests; + } + if(segmentRequestLen != nullptr) { + *segmentRequestLen = this->segmentRequestsLen; + } + if(maxSegmentRequestsLen != nullptr) { + *maxSegmentRequestsLen = this->maxSegmentRequestsLen; + } + return true; +} + +void NakInfo::setSegmentRequests(SegmentRequest *segmentRequests, size_t* segmentRequestLen, + size_t* maxSegmentRequestLen) { + this->segmentRequests = segmentRequests; + if(segmentRequestLen != nullptr) { + this->segmentRequestsLen = *segmentRequestLen; + } + if(maxSegmentRequestLen != nullptr) { + this->maxSegmentRequestsLen = *maxSegmentRequestLen; + } +} + +cfdp::FileSize& NakInfo::getStartOfScope() { + return startOfScope; +} + +cfdp::FileSize& NakInfo::getEndOfScope() { + return endOfScope; +} + +size_t NakInfo::getSegmentRequestsLen() const { + return segmentRequestsLen; +} + +size_t NakInfo::getSegmentRequestsMaxLen() const { + return maxSegmentRequestsLen; +} + +void NakInfo::setSegmentRequestLen(size_t readLen) { + this->segmentRequestsLen = readLen; +} + +void NakInfo::setMaxSegmentRequestLen(size_t maxSize) { + this->maxSegmentRequestsLen = maxSize; +} diff --git a/src/fsfw/cfdp/pdu/NakInfo.h b/src/fsfw/cfdp/pdu/NakInfo.h new file mode 100644 index 00000000..839484be --- /dev/null +++ b/src/fsfw/cfdp/pdu/NakInfo.h @@ -0,0 +1,40 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_NAKINFO_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_NAKINFO_H_ + +#include "fsfw/cfdp/FileSize.h" +#include + +class NakInfo { +public: + using SegmentRequest = std::pair; + + NakInfo(cfdp::FileSize startOfScope, cfdp::FileSize endOfScope); + + void setSegmentRequests(SegmentRequest* segmentRequests, size_t* segmentRequestLen, + size_t* maxSegmentRequestLen); + + size_t getSerializedSize(bool fssLarge = false); + + cfdp::FileSize& getStartOfScope(); + cfdp::FileSize& getEndOfScope(); + + bool hasSegmentRequests() const; + bool canHoldSegmentRequests() const; + void setMaxSegmentRequestLen(size_t maxSize); + bool getSegmentRequests(SegmentRequest** segmentRequestPtr, size_t* segmentRequestLen, + size_t* maxSegmentRequestsLen); + size_t getSegmentRequestsLen() const; + size_t getSegmentRequestsMaxLen() const; + + //! This functions is more relevant for deserializers + void setSegmentRequestLen(size_t readLen); + +private: + cfdp::FileSize startOfScope; + cfdp::FileSize endOfScope; + SegmentRequest* segmentRequests = nullptr; + size_t segmentRequestsLen = 0; + size_t maxSegmentRequestsLen = 0; +}; + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_NAKINFO_H_ */ diff --git a/src/fsfw/cfdp/pdu/NakPduDeserializer.cpp b/src/fsfw/cfdp/pdu/NakPduDeserializer.cpp new file mode 100644 index 00000000..b2d02322 --- /dev/null +++ b/src/fsfw/cfdp/pdu/NakPduDeserializer.cpp @@ -0,0 +1,58 @@ +#include "NakPduDeserializer.h" + +NakPduDeserializer::NakPduDeserializer(const uint8_t *pduBuf, size_t maxSize, NakInfo &info): + FileDirectiveDeserializer(pduBuf, maxSize), nakInfo(info) { +} + +ReturnValue_t NakPduDeserializer::parseData() { + ReturnValue_t result = FileDirectiveDeserializer::parseData(); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + size_t currentIdx = FileDirectiveDeserializer::getHeaderSize(); + const uint8_t* buffer = rawPtr + currentIdx; + size_t remSize = FileDirectiveDeserializer::getWholePduSize() - currentIdx; + if (remSize < 1) { + return SerializeIF::STREAM_TOO_SHORT; + } + result = nakInfo.getStartOfScope().deSerialize(&buffer, &remSize, + SerializeIF::Endianness::NETWORK); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = nakInfo.getEndOfScope().deSerialize(&buffer, &remSize, + SerializeIF::Endianness::NETWORK); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + nakInfo.setSegmentRequestLen(0); + if(remSize > 0) { + if(not nakInfo.canHoldSegmentRequests()) { + return cfdp::NAK_CANT_PARSE_OPTIONS; + } + NakInfo::SegmentRequest* segReqs = nullptr; + size_t maxSegReqs = 0; + nakInfo.getSegmentRequests(&segReqs, nullptr, &maxSegReqs); + if(segReqs != nullptr) { + size_t idx = 0; + while(remSize > 0) { + if(idx == maxSegReqs) { + return cfdp::NAK_CANT_PARSE_OPTIONS; + } + result = segReqs[idx].first.deSerialize(&buffer, &remSize, + SerializeIF::Endianness::NETWORK); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = segReqs[idx].second.deSerialize(&buffer, &remSize, + SerializeIF::Endianness::NETWORK); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + idx++; + } + nakInfo.setSegmentRequestLen(idx); + } + } + return result; +} diff --git a/src/fsfw/cfdp/pdu/NakPduDeserializer.h b/src/fsfw/cfdp/pdu/NakPduDeserializer.h new file mode 100644 index 00000000..81726610 --- /dev/null +++ b/src/fsfw/cfdp/pdu/NakPduDeserializer.h @@ -0,0 +1,22 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_NAKPDUDESERIALIZER_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_NAKPDUDESERIALIZER_H_ + +#include "fsfw/cfdp/pdu/FileDirectiveDeserializer.h" +#include "fsfw/cfdp/pdu/NakInfo.h" + +class NakPduDeserializer: public FileDirectiveDeserializer { +public: + NakPduDeserializer(const uint8_t* pduBuf, size_t maxSize, NakInfo& info); + + /** + * This needs to be called before accessing the PDU fields to avoid segmentation faults. + * @return + */ + virtual ReturnValue_t parseData() override; +private: + NakInfo& nakInfo; +}; + + + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_NAKPDUDESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/NakPduSerializer.cpp b/src/fsfw/cfdp/pdu/NakPduSerializer.cpp new file mode 100644 index 00000000..9afb80cb --- /dev/null +++ b/src/fsfw/cfdp/pdu/NakPduSerializer.cpp @@ -0,0 +1,49 @@ +#include "NakPduSerializer.h" + +NakPduSerializer::NakPduSerializer(PduConfig& pduConf, NakInfo& nakInfo): + FileDirectiveSerializer(pduConf, cfdp::FileDirectives::NAK, 0), nakInfo(nakInfo) { + updateDirectiveFieldLen(); +} + +void NakPduSerializer::updateDirectiveFieldLen() { + this->setDirectiveDataFieldLen(nakInfo.getSerializedSize(getLargeFileFlag())); +} + +size_t NakPduSerializer::getSerializedSize() const { + return FileDirectiveSerializer::getWholePduSize(); +} + +ReturnValue_t NakPduSerializer::serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const { + ReturnValue_t result = FileDirectiveSerializer::serialize(buffer, size, maxSize, + streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = nakInfo.getStartOfScope().serialize(buffer, size, maxSize, streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = nakInfo.getEndOfScope().serialize(buffer, size, maxSize, streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if(nakInfo.hasSegmentRequests()) { + NakInfo::SegmentRequest *segmentRequests = nullptr; + size_t segmentRequestLen = 0; + nakInfo.getSegmentRequests(&segmentRequests, &segmentRequestLen, nullptr); + for(size_t idx = 0; idx < segmentRequestLen; idx++) { + result = segmentRequests[idx].first.serialize(buffer, size, maxSize, + streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = segmentRequests[idx].second.serialize(buffer, size, maxSize, + streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + } + } + return result; +} diff --git a/src/fsfw/cfdp/pdu/NakPduSerializer.h b/src/fsfw/cfdp/pdu/NakPduSerializer.h new file mode 100644 index 00000000..556f0037 --- /dev/null +++ b/src/fsfw/cfdp/pdu/NakPduSerializer.h @@ -0,0 +1,41 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_NAKPDUSERIALIZER_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_NAKPDUSERIALIZER_H_ + +#include "fsfw/cfdp/pdu/FileDirectiveSerializer.h" +#include "fsfw/cfdp/definitions.h" +#include "fsfw/cfdp/FileSize.h" +#include "NakInfo.h" + +#include + +class NakPduSerializer: public FileDirectiveSerializer { +public: + + /** + * + * @param PduConf + * @param startOfScope + * @param endOfScope + * @param [in] segmentRequests Pointer to the start of a list of segment requests + * @param segmentRequestLen Length of the segment request list to be serialized + */ + NakPduSerializer(PduConfig& PduConf, NakInfo& nakInfo); + + size_t getSerializedSize() const override; + + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; + + /** + * If you change the info struct, you might need to update the directive field length + * manually + */ + void updateDirectiveFieldLen(); +private: + NakInfo& nakInfo; + +}; + + + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_NAKPDUSERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/PduConfig.cpp b/src/fsfw/cfdp/pdu/PduConfig.cpp new file mode 100644 index 00000000..acf02f5b --- /dev/null +++ b/src/fsfw/cfdp/pdu/PduConfig.cpp @@ -0,0 +1,8 @@ +#include "PduConfig.h" + +PduConfig::PduConfig(cfdp::TransmissionModes mode, cfdp::TransactionSeqNum seqNum, + cfdp::EntityId sourceId, cfdp::EntityId destId, bool crcFlag, + bool largeFile, cfdp::Direction direction): + mode(mode), seqNum(seqNum), sourceId(sourceId), destId(destId), + crcFlag(crcFlag), largeFile(largeFile), direction(direction) { +} diff --git a/src/fsfw/cfdp/pdu/PduConfig.h b/src/fsfw/cfdp/pdu/PduConfig.h new file mode 100644 index 00000000..79d14a2e --- /dev/null +++ b/src/fsfw/cfdp/pdu/PduConfig.h @@ -0,0 +1,36 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_PDUCONFIG_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_PDUCONFIG_H_ + +#include "VarLenField.h" + +namespace cfdp { + +struct EntityId: public VarLenField { +public: + EntityId(): VarLenField() {} + EntityId(cfdp::WidthInBytes width, size_t entityId): VarLenField(width, entityId) {} +}; + +struct TransactionSeqNum: public VarLenField { +public: + TransactionSeqNum(): VarLenField() {} + TransactionSeqNum(cfdp::WidthInBytes width, size_t seqNum): VarLenField(width, seqNum) {} +}; + +} + +class PduConfig { +public: + PduConfig(cfdp::TransmissionModes mode, cfdp::TransactionSeqNum seqNum, + cfdp::EntityId sourceId, cfdp::EntityId destId, bool crcFlag = false, + bool largeFile = false, cfdp::Direction direction = cfdp::Direction::TOWARDS_RECEIVER); + cfdp::TransmissionModes mode; + cfdp::TransactionSeqNum seqNum; + cfdp::EntityId sourceId; + cfdp::EntityId destId; + bool crcFlag; + bool largeFile; + cfdp::Direction direction; +}; + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_PDUCONFIG_H_ */ diff --git a/src/fsfw/cfdp/pdu/PduHeaderIF.h b/src/fsfw/cfdp/pdu/PduHeaderIF.h new file mode 100644 index 00000000..0ea8b4fe --- /dev/null +++ b/src/fsfw/cfdp/pdu/PduHeaderIF.h @@ -0,0 +1,37 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_PDUHEADERIF_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_PDUHEADERIF_H_ + +#include "PduConfig.h" +#include "../definitions.h" +#include + +/** + * @brief Generic interface to access all fields of a PDU header + * @details + * See CCSDS 727.0-B-5 pp.75 for more information about these fields + */ +class PduHeaderIF { +public: + virtual~ PduHeaderIF() {}; + + virtual size_t getWholePduSize() const = 0; + virtual size_t getPduDataFieldLen() const = 0; + virtual cfdp::PduType getPduType() const = 0; + virtual cfdp::Direction getDirection() const = 0; + virtual cfdp::TransmissionModes getTransmissionMode() const = 0; + virtual bool getCrcFlag() const = 0; + virtual bool getLargeFileFlag() const = 0; + virtual cfdp::SegmentationControl getSegmentationControl() const = 0; + virtual cfdp::WidthInBytes getLenEntityIds() const = 0; + virtual cfdp::WidthInBytes getLenSeqNum() const = 0; + virtual cfdp::SegmentMetadataFlag getSegmentMetadataFlag() const = 0; + virtual bool hasSegmentMetadataFlag() const = 0; + virtual void getSourceId(cfdp::EntityId& sourceId) const = 0; + virtual void getDestId(cfdp::EntityId& destId) const = 0; + virtual void getTransactionSeqNum(cfdp::TransactionSeqNum& seqNum) const = 0; +private: +}; + + + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_PDUHEADERIF_H_ */ diff --git a/src/fsfw/cfdp/pdu/PromptPduDeserializer.cpp b/src/fsfw/cfdp/pdu/PromptPduDeserializer.cpp new file mode 100644 index 00000000..abff805e --- /dev/null +++ b/src/fsfw/cfdp/pdu/PromptPduDeserializer.cpp @@ -0,0 +1,22 @@ +#include "PromptPduDeserializer.h" + +PromptPduDeserializer::PromptPduDeserializer(const uint8_t *pduBuf, size_t maxSize): + FileDirectiveDeserializer(pduBuf, maxSize) { +} + +cfdp::PromptResponseRequired PromptPduDeserializer::getPromptResponseRequired() const { + return responseRequired; +} + +ReturnValue_t PromptPduDeserializer::parseData() { + ReturnValue_t result = FileDirectiveDeserializer::parseData(); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + size_t currentIdx = FileDirectiveDeserializer::getHeaderSize(); + if (FileDirectiveDeserializer::getWholePduSize() - currentIdx < 1) { + return SerializeIF::STREAM_TOO_SHORT; + } + responseRequired = static_cast((rawPtr[currentIdx] >> 7) & 0x01); + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/src/fsfw/cfdp/pdu/PromptPduDeserializer.h b/src/fsfw/cfdp/pdu/PromptPduDeserializer.h new file mode 100644 index 00000000..97762243 --- /dev/null +++ b/src/fsfw/cfdp/pdu/PromptPduDeserializer.h @@ -0,0 +1,18 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_PROMPTPDUDESERIALIZER_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_PROMPTPDUDESERIALIZER_H_ + +#include "fsfw/cfdp/pdu/FileDirectiveDeserializer.h" + +class PromptPduDeserializer: public FileDirectiveDeserializer { +public: + PromptPduDeserializer(const uint8_t *pduBuf, size_t maxSize); + + cfdp::PromptResponseRequired getPromptResponseRequired() const; + ReturnValue_t parseData() override; +private: + cfdp::PromptResponseRequired responseRequired = cfdp::PromptResponseRequired::PROMPT_NAK; +}; + + + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_PROMPTPDUDESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/PromptPduSerializer.cpp b/src/fsfw/cfdp/pdu/PromptPduSerializer.cpp new file mode 100644 index 00000000..599f8072 --- /dev/null +++ b/src/fsfw/cfdp/pdu/PromptPduSerializer.cpp @@ -0,0 +1,27 @@ +#include "PromptPduSerializer.h" + +PromptPduSerializer::PromptPduSerializer(PduConfig &conf, + cfdp::PromptResponseRequired responseRequired): + FileDirectiveSerializer(conf, cfdp::FileDirectives::PROMPT, 1), + responseRequired(responseRequired) { +} + +size_t PromptPduSerializer::getSerializedSize() const { + return FileDirectiveSerializer::getWholePduSize(); +} + +ReturnValue_t PromptPduSerializer::serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const { + ReturnValue_t result = FileDirectiveSerializer::serialize(buffer, size, maxSize, + streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if(*size + 1 > maxSize) { + return SerializeIF::BUFFER_TOO_SHORT; + } + **buffer = this->responseRequired << 7; + *buffer += 1; + *size += 1; + return result; +} diff --git a/src/fsfw/cfdp/pdu/PromptPduSerializer.h b/src/fsfw/cfdp/pdu/PromptPduSerializer.h new file mode 100644 index 00000000..79945fd7 --- /dev/null +++ b/src/fsfw/cfdp/pdu/PromptPduSerializer.h @@ -0,0 +1,18 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_PROMPTPDUSERIALIZER_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_PROMPTPDUSERIALIZER_H_ + +#include "fsfw/cfdp/pdu/FileDirectiveSerializer.h" + +class PromptPduSerializer: public FileDirectiveSerializer { +public: + PromptPduSerializer(PduConfig& conf, cfdp::PromptResponseRequired responseRequired); + + size_t getSerializedSize() const override; + + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; +private: + cfdp::PromptResponseRequired responseRequired; +}; + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_PROMPTPDUSERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/VarLenField.cpp b/src/fsfw/cfdp/pdu/VarLenField.cpp new file mode 100644 index 00000000..ac2410c8 --- /dev/null +++ b/src/fsfw/cfdp/pdu/VarLenField.cpp @@ -0,0 +1,127 @@ +#include "VarLenField.h" +#include "fsfw/FSFW.h" +#include "fsfw/serviceinterface.h" +#include "fsfw/serialize/SerializeAdapter.h" + +cfdp::VarLenField::VarLenField(cfdp::WidthInBytes width, size_t value): VarLenField() { + ReturnValue_t result = this->setValue(width, value); + if(result != HasReturnvaluesIF::RETURN_OK) { +#if FSFW_DISABLE_PRINTOUT == 0 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "cfdp::VarLenField: Setting value failed" << std::endl; +#else + sif::printWarning("cfdp::VarLenField: Setting value failed\n"); +#endif +#endif + } +} + +cfdp::VarLenField::VarLenField(): width(cfdp::WidthInBytes::ONE_BYTE) { + value.oneByte = 0; +} + +cfdp::WidthInBytes cfdp::VarLenField::getWidth() const { + return width; +} + +ReturnValue_t cfdp::VarLenField::setValue(cfdp::WidthInBytes widthInBytes, size_t value) { + switch(widthInBytes) { + case(cfdp::WidthInBytes::ONE_BYTE): { + if(value > UINT8_MAX) { + return HasReturnvaluesIF::RETURN_FAILED; + } + this->value.oneByte = value; + break; + } + case(cfdp::WidthInBytes::TWO_BYTES): { + if(value > UINT16_MAX) { + return HasReturnvaluesIF::RETURN_FAILED; + } + this->value.twoBytes = value; + break; + } + case(cfdp::WidthInBytes::FOUR_BYTES): { + if(value > UINT32_MAX) { + return HasReturnvaluesIF::RETURN_FAILED; + } + this->value.fourBytes = value; + break; + } + default: { + break; + } + } + this->width = widthInBytes; + return HasReturnvaluesIF::RETURN_OK; +} + +size_t cfdp::VarLenField::getValue() const { + switch(width) { + case(cfdp::WidthInBytes::ONE_BYTE): { + return value.oneByte; + } + case(cfdp::WidthInBytes::TWO_BYTES): { + return value.twoBytes; + } + case(cfdp::WidthInBytes::FOUR_BYTES): { + return value.fourBytes; + } + } + return 0; +} + +ReturnValue_t cfdp::VarLenField::serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const { + switch(width) { + case(cfdp::WidthInBytes::ONE_BYTE): { + if (*size + 1 > maxSize) { + return BUFFER_TOO_SHORT; + } + **buffer = value.oneByte; + *size += 1; + *buffer += 1; + return HasReturnvaluesIF::RETURN_OK; + } + case(cfdp::WidthInBytes::TWO_BYTES): { + return SerializeAdapter::serialize(&value.twoBytes, buffer, size, maxSize, + streamEndianness); + } + case(cfdp::WidthInBytes::FOUR_BYTES): { + return SerializeAdapter::serialize(&value.fourBytes, buffer, size, maxSize, + streamEndianness); + } + default: { + return HasReturnvaluesIF::RETURN_FAILED; + } + } +} + +size_t cfdp::VarLenField::getSerializedSize() const { + return width; +} + +ReturnValue_t cfdp::VarLenField::deSerialize(cfdp::WidthInBytes width, const uint8_t **buffer, + size_t *size, Endianness streamEndianness) { + this->width = width; + return deSerialize(buffer, size, streamEndianness); +} + +ReturnValue_t cfdp::VarLenField::deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) { + switch(width) { + case(cfdp::WidthInBytes::ONE_BYTE): { + value.oneByte = **buffer; + *size += 1; + return HasReturnvaluesIF::RETURN_OK; + } + case(cfdp::WidthInBytes::TWO_BYTES): { + return SerializeAdapter::deSerialize(&value.twoBytes, buffer, size, streamEndianness); + } + case(cfdp::WidthInBytes::FOUR_BYTES): { + return SerializeAdapter::deSerialize(&value.fourBytes, buffer, size, streamEndianness); + } + default: { + return HasReturnvaluesIF::RETURN_FAILED; + } + } +} diff --git a/src/fsfw/cfdp/pdu/VarLenField.h b/src/fsfw/cfdp/pdu/VarLenField.h new file mode 100644 index 00000000..01bcfaed --- /dev/null +++ b/src/fsfw/cfdp/pdu/VarLenField.h @@ -0,0 +1,45 @@ +#ifndef FSFW_SRC_FSFW_CFDP_PDU_VARLENFIELD_H_ +#define FSFW_SRC_FSFW_CFDP_PDU_VARLENFIELD_H_ + +#include "../definitions.h" +#include "fsfw/serialize/SerializeIF.h" +#include +#include + +namespace cfdp { + +class VarLenField: public SerializeIF { +public: + union LengthFieldLen { + uint8_t oneByte; + uint16_t twoBytes; + uint32_t fourBytes; + uint64_t eightBytes; + }; + + VarLenField(); + VarLenField(cfdp::WidthInBytes width, size_t value); + + ReturnValue_t setValue(cfdp::WidthInBytes, size_t value); + + ReturnValue_t serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const override; + + size_t getSerializedSize() const override; + + ReturnValue_t deSerialize(cfdp::WidthInBytes width, const uint8_t **buffer, size_t *size, + Endianness streamEndianness); + + cfdp::WidthInBytes getWidth() const; + size_t getValue() const; +private: + ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) override; + + cfdp::WidthInBytes width; + LengthFieldLen value; +}; + +} + +#endif /* FSFW_SRC_FSFW_CFDP_PDU_VARLENFIELD_H_ */ diff --git a/src/fsfw/cfdp/tlv/CMakeLists.txt b/src/fsfw/cfdp/tlv/CMakeLists.txt new file mode 100644 index 00000000..24459cf8 --- /dev/null +++ b/src/fsfw/cfdp/tlv/CMakeLists.txt @@ -0,0 +1,10 @@ +target_sources(${LIB_FSFW_NAME} PRIVATE + EntityIdTlv.cpp + FilestoreRequestTlv.cpp + FilestoreResponseTlv.cpp + Lv.cpp + Tlv.cpp + FlowLabelTlv.cpp + MessageToUserTlv.cpp + FaultHandlerOverrideTlv.cpp +) \ No newline at end of file diff --git a/src/fsfw/cfdp/tlv/EntityIdTlv.cpp b/src/fsfw/cfdp/tlv/EntityIdTlv.cpp new file mode 100644 index 00000000..98b1094e --- /dev/null +++ b/src/fsfw/cfdp/tlv/EntityIdTlv.cpp @@ -0,0 +1,68 @@ +#include "EntityIdTlv.h" +#include + +EntityIdTlv::EntityIdTlv(cfdp::EntityId& entityId): entityId(entityId) { +} + +EntityIdTlv::~EntityIdTlv() { +} + +ReturnValue_t EntityIdTlv::serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const { + if(maxSize < this->getSerializedSize()) { + return BUFFER_TOO_SHORT; + } + **buffer = cfdp::TlvTypes::ENTITY_ID; + *size += 1; + *buffer += 1; + size_t serLen = entityId.getSerializedSize(); + **buffer = serLen; + *size += 1; + *buffer += 1; + return entityId.serialize(buffer, size, maxSize, streamEndianness); +} + +size_t EntityIdTlv::getSerializedSize() const { + return getLengthField() + 1; +} + +ReturnValue_t EntityIdTlv::deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) { + if(*size < 3) { + return STREAM_TOO_SHORT; + } + cfdp::TlvTypes type = static_cast(**buffer); + if(type != cfdp::TlvTypes::ENTITY_ID) { + return cfdp::INVALID_TLV_TYPE; + } + *buffer += 1; + *size -= 1; + + cfdp::WidthInBytes width = static_cast(**buffer); + if (*size < static_cast(1 + width)) { + return STREAM_TOO_SHORT; + } + *buffer += 1; + *size -= 1; + + return entityId.deSerialize(width, buffer, size, streamEndianness); +} + +ReturnValue_t EntityIdTlv::deSerialize(cfdp::Tlv &tlv, Endianness endianness) { + const uint8_t* ptr = tlv.getValue() + 2; + size_t remSz = tlv.getSerializedSize() - 2; + cfdp::WidthInBytes width = static_cast(remSz); + return entityId.deSerialize(width, &ptr, &remSz, endianness); +} + +uint8_t EntityIdTlv::getLengthField() const { + return 1 + entityId.getSerializedSize(); +} + +cfdp::TlvTypes EntityIdTlv::getType() const { + return cfdp::TlvTypes::ENTITY_ID; +} + +cfdp::EntityId& EntityIdTlv::getEntityId() { + return entityId; +} diff --git a/src/fsfw/cfdp/tlv/EntityIdTlv.h b/src/fsfw/cfdp/tlv/EntityIdTlv.h new file mode 100644 index 00000000..5860ce05 --- /dev/null +++ b/src/fsfw/cfdp/tlv/EntityIdTlv.h @@ -0,0 +1,39 @@ +#ifndef FSFW_SRC_FSFW_CFDP_ENTITYIDTLV_H_ +#define FSFW_SRC_FSFW_CFDP_ENTITYIDTLV_H_ + +#include "fsfw/cfdp/tlv/Tlv.h" +#include "fsfw/cfdp/pdu/PduConfig.h" +#include "TlvIF.h" + +class EntityIdTlv: public TlvIF { +public: + EntityIdTlv(cfdp::EntityId& entityId); + virtual~ EntityIdTlv(); + + ReturnValue_t serialize(uint8_t **buffer, size_t *size, + size_t maxSize, Endianness streamEndianness) const override; + + size_t getSerializedSize() const override; + + /** + * Deserialize an entity ID from a raw TLV object + * @param tlv + * @param endianness + * @return + */ + ReturnValue_t deSerialize(cfdp::Tlv& tlv, Endianness endianness); + + ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) override; + + uint8_t getLengthField() const override; + cfdp::TlvTypes getType() const override; + + cfdp::EntityId& getEntityId(); +private: + cfdp::EntityId& entityId; +}; + + + +#endif /* FSFW_SRC_FSFW_CFDP_ENTITYIDTLV_H_ */ diff --git a/src/fsfw/cfdp/tlv/FaultHandlerOverrideTlv.cpp b/src/fsfw/cfdp/tlv/FaultHandlerOverrideTlv.cpp new file mode 100644 index 00000000..f5ef9311 --- /dev/null +++ b/src/fsfw/cfdp/tlv/FaultHandlerOverrideTlv.cpp @@ -0,0 +1,64 @@ +#include "FaultHandlerOverrideTlv.h" + +FaultHandlerOverrideTlv::FaultHandlerOverrideTlv(cfdp::ConditionCode conditionCode, + cfdp::FaultHandlerCode handlerCode): + conditionCode(conditionCode), handlerCode(handlerCode) { +} + +FaultHandlerOverrideTlv::FaultHandlerOverrideTlv() { +} + +uint8_t FaultHandlerOverrideTlv::getLengthField() const { + return 1; +} + + +ReturnValue_t FaultHandlerOverrideTlv::serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const { + if((maxSize < 3) or ((*size + 3) > maxSize)) { + return SerializeIF::BUFFER_TOO_SHORT; + } + **buffer = getType(); + *size += 1; + *buffer += 1; + **buffer = getLengthField(); + *size += 1; + *buffer += 1; + **buffer = this->conditionCode << 4 | this->handlerCode; + *buffer += 1; + *size += 1; + return HasReturnvaluesIF::RETURN_OK; +} + +size_t FaultHandlerOverrideTlv::getSerializedSize() const { + return getLengthField() + 2; +} + +ReturnValue_t FaultHandlerOverrideTlv::deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) { + if(*size < 3) { + return SerializeIF::STREAM_TOO_SHORT; + } + auto detectedType = static_cast(**buffer); + if(detectedType != cfdp::TlvTypes::FAULT_HANDLER) { + return cfdp::INVALID_TLV_TYPE; + } + *buffer += 1; + *size -= 1; + size_t detectedSize = **buffer; + if(detectedSize != getLengthField()) { + return HasReturnvaluesIF::RETURN_FAILED; + } + *buffer += 1; + *size += 1; + this->conditionCode = static_cast((**buffer >> 4) & 0x0f); + this->handlerCode = static_cast(**buffer & 0x0f); + *buffer += 1; + *size += 1; + return HasReturnvaluesIF::RETURN_OK; +} + + +cfdp::TlvTypes FaultHandlerOverrideTlv::getType() const { + return cfdp::TlvTypes::FAULT_HANDLER; +} diff --git a/src/fsfw/cfdp/tlv/FaultHandlerOverrideTlv.h b/src/fsfw/cfdp/tlv/FaultHandlerOverrideTlv.h new file mode 100644 index 00000000..7014ae0e --- /dev/null +++ b/src/fsfw/cfdp/tlv/FaultHandlerOverrideTlv.h @@ -0,0 +1,39 @@ +#ifndef FSFW_SRC_FSFW_CFDP_TLV_FAULTHANDLEROVERRIDETLV_H_ +#define FSFW_SRC_FSFW_CFDP_TLV_FAULTHANDLEROVERRIDETLV_H_ + +#include "TlvIF.h" + +namespace cfdp { + +enum FaultHandlerCode { + RESERVED = 0b0000, + NOTICE_OF_CANCELLATION = 0b0001, + NOTICE_OF_SUSPENSION = 0b0010, + IGNORE_ERROR = 0b0011, + ABANDON_TRANSACTION = 0b0100 +}; + +} + +class FaultHandlerOverrideTlv: public TlvIF { +public: + + FaultHandlerOverrideTlv(); + FaultHandlerOverrideTlv(cfdp::ConditionCode conditionCode, cfdp::FaultHandlerCode handlerCode); + + ReturnValue_t serialize(uint8_t **buffer, size_t *size, + size_t maxSize, Endianness streamEndianness) const override; + + size_t getSerializedSize() const override; + + ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) override; + uint8_t getLengthField() const override; + cfdp::TlvTypes getType() const override; + +private: + cfdp::ConditionCode conditionCode = cfdp::ConditionCode::NO_CONDITION_FIELD; + cfdp::FaultHandlerCode handlerCode = cfdp::FaultHandlerCode::RESERVED; +}; + +#endif /* FSFW_SRC_FSFW_CFDP_TLV_FAULTHANDLEROVERRIDETLV_H_ */ diff --git a/src/fsfw/cfdp/tlv/FilestoreRequestTlv.cpp b/src/fsfw/cfdp/tlv/FilestoreRequestTlv.cpp new file mode 100644 index 00000000..044c4e9a --- /dev/null +++ b/src/fsfw/cfdp/tlv/FilestoreRequestTlv.cpp @@ -0,0 +1,83 @@ +#include "fsfw/cfdp/tlv/FilestoreRequestTlv.h" +#include "fsfw/FSFW.h" + +FilestoreRequestTlv::FilestoreRequestTlv(cfdp::FilestoreActionCode actionCode, + cfdp::Lv& firstFileName): FilestoreTlvBase(actionCode, firstFileName) { +} + +FilestoreRequestTlv::FilestoreRequestTlv(cfdp::Lv &firstFileName): + FilestoreTlvBase(cfdp::FilestoreActionCode::INVALID, firstFileName) { +} + +void FilestoreRequestTlv::setSecondFileName(cfdp::Lv *secondFileName) { + this->secondFileName = secondFileName; +} + +ReturnValue_t FilestoreRequestTlv::serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const { + ReturnValue_t result = commonSerialize(buffer, size, maxSize, streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = firstFileName.serialize(buffer, size, maxSize, + streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if(requiresSecondFileName()) { + if(secondFileName == nullptr) { + secondFileNameMissing(); + return cfdp::FILESTORE_REQUIRES_SECOND_FILE; + } + secondFileName->serialize(buffer, size, maxSize, streamEndianness); + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t FilestoreRequestTlv::deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) { + ReturnValue_t result = commonDeserialize(buffer, size, streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return deSerializeFromValue(buffer, size, streamEndianness); +} + +ReturnValue_t FilestoreRequestTlv::deSerialize(cfdp::Tlv &tlv, + SerializeIF::Endianness endianness) { + const uint8_t* ptr = tlv.getValue(); + size_t remSz = tlv.getSerializedSize(); + + return deSerializeFromValue(&ptr, &remSz, endianness); +} + +uint8_t FilestoreRequestTlv::getLengthField() const { + size_t secondFileNameLen = 0; + if(secondFileName != nullptr and requiresSecondFileName()) { + secondFileNameLen = secondFileName->getSerializedSize(); + } + return 1 + firstFileName.getSerializedSize() + secondFileNameLen; +} + +ReturnValue_t FilestoreRequestTlv::deSerializeFromValue(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) { + this->actionCode = static_cast((**buffer >> 4) & 0x0f); + *buffer += 1; + *size -= 1; + ReturnValue_t result = firstFileName.deSerialize(buffer, size, streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if(requiresSecondFileName()) { + if(secondFileName == nullptr) { + secondFileNameMissing(); + return HasReturnvaluesIF::RETURN_FAILED; + } + result = secondFileName->deSerialize(buffer, size, streamEndianness); + } + return result; +} + +cfdp::TlvTypes FilestoreRequestTlv::getType() const { + return cfdp::TlvTypes::FILESTORE_REQUEST; +} diff --git a/src/fsfw/cfdp/tlv/FilestoreRequestTlv.h b/src/fsfw/cfdp/tlv/FilestoreRequestTlv.h new file mode 100644 index 00000000..d4cedbb2 --- /dev/null +++ b/src/fsfw/cfdp/tlv/FilestoreRequestTlv.h @@ -0,0 +1,45 @@ +#ifndef FSFW_SRC_FSFW_CFDP_FILESTOREREQUESTTLV_H_ +#define FSFW_SRC_FSFW_CFDP_FILESTOREREQUESTTLV_H_ + +#include "fsfw/cfdp/tlv/FilestoreTlvBase.h" +#include "fsfw/cfdp/tlv/Tlv.h" +#include "TlvIF.h" +#include "Lv.h" +#include "../definitions.h" + +class FilestoreRequestTlv: + public cfdp::FilestoreTlvBase { +public: + FilestoreRequestTlv(cfdp::FilestoreActionCode actionCode, cfdp::Lv& firstFileName); + + FilestoreRequestTlv(cfdp::Lv& firstFileName); + + void setSecondFileName(cfdp::Lv* secondFileName); + + ReturnValue_t serialize(uint8_t **buffer, size_t *size, + size_t maxSize, Endianness streamEndianness) const override; + + /** + * Deserialize a FS request from a raw TLV object + * @param tlv + * @param endianness + * @return + */ + ReturnValue_t deSerialize(cfdp::Tlv& tlv, Endianness endianness); + + ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) override; + + uint8_t getLengthField() const override; + cfdp::TlvTypes getType() const override; + +private: + cfdp::Lv* secondFileName = nullptr; + + ReturnValue_t deSerializeFromValue(const uint8_t **buffer, size_t *size, + Endianness streamEndianness); +}; + + + +#endif /* FSFW_SRC_FSFW_CFDP_FILESTOREREQUESTTLV_H_ */ diff --git a/src/fsfw/cfdp/tlv/FilestoreResponseTlv.cpp b/src/fsfw/cfdp/tlv/FilestoreResponseTlv.cpp new file mode 100644 index 00000000..ec57579a --- /dev/null +++ b/src/fsfw/cfdp/tlv/FilestoreResponseTlv.cpp @@ -0,0 +1,124 @@ +#include "FilestoreResponseTlv.h" + +FilestoreResponseTlv::FilestoreResponseTlv(cfdp::FilestoreActionCode actionCode, uint8_t statusCode, + cfdp::Lv& firstFileName, cfdp::Lv* fsMsg): FilestoreTlvBase(actionCode, firstFileName), + statusCode(statusCode), filestoreMsg(fsMsg) { +} + +FilestoreResponseTlv::FilestoreResponseTlv(cfdp::Lv &firstFileName, cfdp::Lv* fsMsg): + FilestoreTlvBase(firstFileName), statusCode(0), filestoreMsg(fsMsg) { +} + +uint8_t FilestoreResponseTlv::getLengthField() const { + size_t optFieldsLen = 0; + if(secondFileName != nullptr) { + optFieldsLen += secondFileName->getSerializedSize(); + } + if(filestoreMsg != nullptr) { + optFieldsLen += filestoreMsg->getSerializedSize(); + } else { + optFieldsLen += 1; + } + return 1 + firstFileName.getSerializedSize() + optFieldsLen; +} + +void FilestoreResponseTlv::setSecondFileName(cfdp::Lv *secondFileName) { + this->secondFileName = secondFileName; +} + +void FilestoreResponseTlv::setFilestoreMessage(cfdp::Lv *filestoreMsg) { + this->filestoreMsg = filestoreMsg; +} + +ReturnValue_t FilestoreResponseTlv::serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const { + ReturnValue_t result = commonSerialize(buffer, size, maxSize, streamEndianness, + true, this->statusCode); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = firstFileName.serialize(buffer, size, maxSize, streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if(requiresSecondFileName()) { + if(secondFileName == nullptr) { + secondFileNameMissing(); + return cfdp::FILESTORE_REQUIRES_SECOND_FILE; + } + } + if(filestoreMsg != nullptr) { + result = filestoreMsg->serialize(buffer, size, maxSize, streamEndianness); + } + else { + if(*size == maxSize) { + return SerializeIF::BUFFER_TOO_SHORT; + } + **buffer = 0; + *buffer += 1; + *size +=1; + } + return result; +} + +ReturnValue_t FilestoreResponseTlv::deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) { + ReturnValue_t result = commonDeserialize(buffer, size, streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return deSerializeFromValue(buffer, size, streamEndianness); +} + +ReturnValue_t FilestoreResponseTlv::deSerializeFromValue(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) { + + // The common function above checks whether at least one byte is remaining + this->actionCode = static_cast((**buffer >> 4) & 0x0f); + this->statusCode = **buffer & 0x0f; + *buffer += 1; + *size -= 1; + ReturnValue_t result = firstFileName.deSerialize(buffer, size, streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if(requiresSecondFileName()) { + if(secondFileName == nullptr) { + return cfdp::FILESTORE_REQUIRES_SECOND_FILE; + } + result = secondFileName->deSerialize(buffer, size, streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + } + // If the filestore message is not empty, the deserialization is only considered successfully + // if the filestore message can be parsed. Also, if data follows after the FS response, + // the FS msg needs to be set as well. + if(*size == 0 or (*size > 1 and filestoreMsg == nullptr)) { + // Filestore message missing or can't parse it + return cfdp::FILESTORE_RESPONSE_CANT_PARSE_FS_MESSAGE; + } + if(filestoreMsg == nullptr) { + *size -= 1; + *buffer += 1; + // Ignore empty filestore message + return HasReturnvaluesIF::RETURN_OK; + } + return filestoreMsg->deSerialize(buffer, size, streamEndianness); +} + +ReturnValue_t FilestoreResponseTlv::deSerialize(const cfdp::Tlv &tlv, Endianness endianness) { + const uint8_t* ptr = tlv.getValue(); + size_t remSz = tlv.getSerializedSize(); + + return deSerializeFromValue(&ptr, &remSz, endianness); +} + +uint8_t FilestoreResponseTlv::getStatusCode() const { + return statusCode; +} + + +cfdp::TlvTypes FilestoreResponseTlv::getType() const { + return cfdp::TlvTypes::FILESTORE_RESPONSE; +} diff --git a/src/fsfw/cfdp/tlv/FilestoreResponseTlv.h b/src/fsfw/cfdp/tlv/FilestoreResponseTlv.h new file mode 100644 index 00000000..1159fdca --- /dev/null +++ b/src/fsfw/cfdp/tlv/FilestoreResponseTlv.h @@ -0,0 +1,50 @@ +#ifndef FSFW_SRC_FSFW_CFDP_FILESTORERESPONSETLV_H_ +#define FSFW_SRC_FSFW_CFDP_FILESTORERESPONSETLV_H_ + +#include "fsfw/cfdp/tlv/FilestoreTlvBase.h" +#include "fsfw/cfdp/tlv/Tlv.h" +#include "TlvIF.h" +#include "Lv.h" + +class FilestoreResponseTlv: + public cfdp::FilestoreTlvBase { +public: + + FilestoreResponseTlv(cfdp::Lv& firstFileName, cfdp::Lv* fsMsg); + + FilestoreResponseTlv(cfdp::FilestoreActionCode actionCode, uint8_t statusCode, + cfdp::Lv& firstFileName, cfdp::Lv* fsMsg); + + uint8_t getStatusCode() const; + void setSecondFileName(cfdp::Lv* secondFileName); + void setFilestoreMessage(cfdp::Lv* filestoreMsg); + + ReturnValue_t serialize(uint8_t **buffer, size_t *size, + size_t maxSize, Endianness streamEndianness) const override; + + /** + * Deserialize a filestore response from a raw TLV object + * @param tlv + * @param endianness + * @return + */ + ReturnValue_t deSerialize(const cfdp::Tlv& tlv, Endianness endianness); + + ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) override; + + uint8_t getLengthField() const override; + cfdp::TlvTypes getType() const override; + +private: + uint8_t statusCode; + cfdp::Lv* secondFileName = nullptr; + cfdp::Lv* filestoreMsg = nullptr; + + ReturnValue_t deSerializeFromValue(const uint8_t **buffer, size_t *size, + Endianness streamEndianness); +}; + + + +#endif /* FSFW_SRC_FSFW_CFDP_FILESTORERESPONSETLV_H_ */ diff --git a/src/fsfw/cfdp/tlv/FilestoreTlvBase.h b/src/fsfw/cfdp/tlv/FilestoreTlvBase.h new file mode 100644 index 00000000..f81b8807 --- /dev/null +++ b/src/fsfw/cfdp/tlv/FilestoreTlvBase.h @@ -0,0 +1,176 @@ +#ifndef FSFW_SRC_FSFW_CFDP_FILESTOREREQUESTBASE_H_ +#define FSFW_SRC_FSFW_CFDP_FILESTOREREQUESTBASE_H_ + +#include +#include +#include +#include +#include +#include +#include + +namespace cfdp { + +enum FilestoreActionCode { + CREATE_FILE = 0b0000, + DELETE_FILE = 0b0001, + // Second file name present + RENAME_FILE = 0b0010, + // Second file name present + APPEND_FILE = 0b0011, + // Second file name present + REPLACE_FILE = 0b0100, + CREATE_DIRECTORY = 0b0101, + REMOVE_DIRECTORY = 0b0110, + // Delete file if present + DENY_FILE = 0b0111, + // Remove directory if present + DNEY_DIRECTORY = 0b1000, + INVALID = 0b1111 +}; + +// FSR = Filestore Response +static constexpr uint8_t FSR_SUCCESS = 0b0000; +static constexpr uint8_t FSR_NOT_PERFORMED = 0b1111; + +static constexpr uint8_t FSR_CREATE_NOT_ALLOWED = 0b0001; + +static constexpr uint8_t FSR_DEL_FILE_NOT_EXISTS = 0b0001; +static constexpr uint8_t FSR_DEL_NOT_ALLOWED = 0b0010; + +static constexpr uint8_t FSR_RENAME_OLD_FILE_NOT_EXISTS = 0b0001; +static constexpr uint8_t FSR_RENAME_NEW_FILE_ALREADY_EXISTS = 0b0010; +static constexpr uint8_t FSR_RENAME_NOT_ALLOWED = 0b0011; + +static constexpr uint8_t FSR_APPEND_FILE_1_NOT_EXISTS = 0b0001; +static constexpr uint8_t FSR_APPEND_FILE_2_NOT_EXISTS = 0b0010; +static constexpr uint8_t FSR_APPEND_NOT_ALLOWED = 0b0011; + +static constexpr uint8_t FSR_REPLACE_FILE_1_NOT_EXISTS = 0b0001; +static constexpr uint8_t FSR_REPLACE_FILE_2_NOT_EXISTS = 0b0010; +static constexpr uint8_t FSR_REPLACE_REPLACE_NOT_ALLOWED = 0b0011; + +static constexpr uint8_t FSR_CREATE_DIR_NOT_POSSIBLE = 0b0001; + +static constexpr uint8_t FSR_DELDIR_NOT_EXISTS = 0b0001; +static constexpr uint8_t FSR_DELDIR_NOT_ALLOWED = 0b0010; + +static constexpr uint8_t FSR_DENY_FILE_NOT_ALLOWED = 0b0010; + +static constexpr uint8_t FSR_DENY_DIR_NOT_ALLOWED = 0b0010; + +class FilestoreTlvBase: public TlvIF { +public: + + FilestoreTlvBase(cfdp::Lv& firstFileName): firstFileName(firstFileName) {}; + FilestoreTlvBase(FilestoreActionCode actionCode, cfdp::Lv& firstFileName): + actionCode(actionCode), firstFileName(firstFileName) {}; + + ReturnValue_t commonSerialize(uint8_t **buffer, size_t *size, + size_t maxSize, Endianness streamEndianness, + bool isResponse = false, uint8_t responseStatusCode = 0) const { + if(buffer == nullptr or size == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if(maxSize < 3) { + return SerializeIF::BUFFER_TOO_SHORT; + } + **buffer = getType(); + *buffer += 1; + *size += 1; + **buffer = getLengthField(); + *buffer += 1; + *size += 1; + **buffer = this->actionCode << 4; + if(isResponse) { + **buffer |= responseStatusCode; + } + *buffer += 1; + *size += 1; + return HasReturnvaluesIF::RETURN_OK; + } + + ReturnValue_t commonDeserialize(const uint8_t **buffer, size_t *size, + SerializeIF::Endianness streamEndianness) { + if(buffer == nullptr or size == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if(*size < 3) { + return SerializeIF::STREAM_TOO_SHORT; + } + cfdp::TlvTypes type = static_cast(**buffer); + if(type != getType()) { + return cfdp::INVALID_TLV_TYPE; + } + *size -= 1; + *buffer += 1; + + size_t remainingLength = **buffer; + *size -= 1; + *buffer += 1; + if(remainingLength == 0) { + return SerializeIF::STREAM_TOO_SHORT; + } + return HasReturnvaluesIF::RETURN_OK; + } + + bool requiresSecondFileName() const { + using namespace cfdp; + if(actionCode == FilestoreActionCode::RENAME_FILE or + actionCode == FilestoreActionCode::APPEND_FILE or + actionCode == FilestoreActionCode::REPLACE_FILE) { + return true; + } + return false; + } + + void secondFileNameMissing() const { +#if FSFW_VERBOSE_LEVEL >= 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "FilestoreRequestTlv::deSerialize: Second file name required" + " but TLV pointer not set" << std::endl; +#else + sif::printWarning("FilestoreRequestTlv::deSerialize: Second file name required" + " but TLV pointer not set\n"); +#endif +#endif + } + + FilestoreActionCode getActionCode() const { + return actionCode; + } + + void setActionCode(FilestoreActionCode actionCode) { + this->actionCode = actionCode; + } + + cfdp::Lv& getFirstFileName() { + return firstFileName; + } + + ReturnValue_t convertToTlv(cfdp::Tlv& tlv, uint8_t *buffer, size_t maxSize, + Endianness streamEndianness) { + size_t serSize = 0; + uint8_t* valueStart = buffer + 2; + ReturnValue_t result = this->serialize(&buffer, &serSize, maxSize, streamEndianness); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + tlv.setValue(valueStart, serSize - 2); + tlv.setType(getType()); + return result; + } + + size_t getSerializedSize() const override { + return getLengthField() + 2; + } +protected: + FilestoreActionCode actionCode = FilestoreActionCode::INVALID; + cfdp::Lv& firstFileName; +}; + +} + + + +#endif /* FSFW_SRC_FSFW_CFDP_FILESTOREREQUESTBASE_H_ */ diff --git a/src/fsfw/cfdp/tlv/FlowLabelTlv.cpp b/src/fsfw/cfdp/tlv/FlowLabelTlv.cpp new file mode 100644 index 00000000..c5835414 --- /dev/null +++ b/src/fsfw/cfdp/tlv/FlowLabelTlv.cpp @@ -0,0 +1,5 @@ +#include "FlowLabelTlv.h" + +FlowLabelTlv::FlowLabelTlv(uint8_t* value, size_t size): + Tlv(cfdp::TlvTypes::FLOW_LABEL, value, size) { +} diff --git a/src/fsfw/cfdp/tlv/FlowLabelTlv.h b/src/fsfw/cfdp/tlv/FlowLabelTlv.h new file mode 100644 index 00000000..3375c361 --- /dev/null +++ b/src/fsfw/cfdp/tlv/FlowLabelTlv.h @@ -0,0 +1,13 @@ +#ifndef FSFW_SRC_FSFW_CFDP_TLV_FLOWLABELTLV_H_ +#define FSFW_SRC_FSFW_CFDP_TLV_FLOWLABELTLV_H_ + +#include "Tlv.h" + +class FlowLabelTlv: public cfdp::Tlv { +public: + FlowLabelTlv(uint8_t* value, size_t size); +private: + +}; + +#endif /* FSFW_SRC_FSFW_CFDP_TLV_FLOWLABELTLV_H_ */ diff --git a/src/fsfw/cfdp/tlv/Lv.cpp b/src/fsfw/cfdp/tlv/Lv.cpp new file mode 100644 index 00000000..fa3b99e7 --- /dev/null +++ b/src/fsfw/cfdp/tlv/Lv.cpp @@ -0,0 +1,88 @@ +#include "Lv.h" + +cfdp::Lv::Lv(const uint8_t *value, size_t size): value(value, size, true) { + if(size > 0) { + zeroLen = false; + } +} + +cfdp::Lv::Lv(): value(static_cast(nullptr), 0, true) { +} + +cfdp::Lv::Lv(const Lv& other): + value(other.value.getConstBuffer(), other.value.getSerializedSize() - 1, true) { + if(other.value.getSerializedSize() - 1 > 0) { + zeroLen = false; + } +} + +cfdp::Lv& cfdp::Lv::operator =(const Lv& other) { + size_t otherSize = 0; + uint8_t* value = const_cast(other.getValue(&otherSize)); + if (value == nullptr or otherSize == 0) { + this->zeroLen = true; + } + this->value.setBuffer(value, otherSize); + return *this; +} + + +ReturnValue_t cfdp::Lv::serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const { + if(maxSize < 1) { + return BUFFER_TOO_SHORT; + } + if(buffer == nullptr or size == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if(zeroLen) { + **buffer = 0; + *size += 1; + *buffer += 1; + return HasReturnvaluesIF::RETURN_OK; + } + return value.serialize(buffer, size, maxSize, streamEndianness); +} + +size_t cfdp::Lv::getSerializedSize() const { + if(zeroLen) { + return 1; + } + else if(value.getConstBuffer() == nullptr) { + return 0; + } + return value.getSerializedSize(); +} + +ReturnValue_t cfdp::Lv::deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) { + if(buffer == nullptr or size == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if(*size < 1) { + return SerializeIF::STREAM_TOO_SHORT; + } + size_t lengthField = **buffer; + if(lengthField == 0) { + zeroLen = true; + *buffer += 1; + *size -= 1; + return HasReturnvaluesIF::RETURN_OK; + } else if(*size < lengthField + 1) { + return SerializeIF::STREAM_TOO_SHORT; + } + zeroLen = false; + // Zero-copy implementation + value.setBuffer(const_cast(*buffer + 1), lengthField); + *buffer += 1 + lengthField; + *size -= 1 + lengthField; + return HasReturnvaluesIF::RETURN_OK; +} + +const uint8_t* cfdp::Lv::getValue(size_t* size) const { + if(size != nullptr) { + // Length without length field + *size = value.getSerializedSize() - 1; + } + return value.getConstBuffer(); +} diff --git a/src/fsfw/cfdp/tlv/Lv.h b/src/fsfw/cfdp/tlv/Lv.h new file mode 100644 index 00000000..46d47819 --- /dev/null +++ b/src/fsfw/cfdp/tlv/Lv.h @@ -0,0 +1,53 @@ +#ifndef FSFW_SRC_FSFW_CFDP_LV_H_ +#define FSFW_SRC_FSFW_CFDP_LV_H_ + +#include "fsfw/serialize/SerialBufferAdapter.h" + +namespace cfdp { + +/** + * @brief Length-Value field implementation + * @details + * Thin abstraction layer around a serial buffer adapter + */ +class Lv: public SerializeIF { +public: + Lv(const uint8_t* value, size_t size); + Lv(); + + // Delete copy ctor and assingment ctor for now because this class contains a reference to + // data + Lv (const Lv&); + Lv& operator= (const Lv&); + + ReturnValue_t serialize(uint8_t **buffer, size_t *size, + size_t maxSize, Endianness streamEndianness) const override; + + size_t getSerializedSize() const override; + + /** + * @brief Deserialize a LV field from a raw buffer + * @param buffer Raw buffer including the size field + * @param size + * @param streamEndianness + * @return + */ + ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) override; + + /** + * Get value field and its size. + * @param size Optionally retrieve size. Size will be the size of the actual value field + * without the length field of the LV + * @return + */ + const uint8_t* getValue(size_t* size) const; +private: + + bool zeroLen = true; + SerialBufferAdapter value; +}; + +} + +#endif /* FSFW_SRC_FSFW_CFDP_LV_H_ */ diff --git a/src/fsfw/cfdp/tlv/MessageToUserTlv.cpp b/src/fsfw/cfdp/tlv/MessageToUserTlv.cpp new file mode 100644 index 00000000..f776f5ef --- /dev/null +++ b/src/fsfw/cfdp/tlv/MessageToUserTlv.cpp @@ -0,0 +1,8 @@ +#include "MessageToUserTlv.h" + +MessageToUserTlv::MessageToUserTlv(uint8_t *value, size_t size): + Tlv(cfdp::TlvTypes::MSG_TO_USER, value, size) { +} + +MessageToUserTlv::MessageToUserTlv(): Tlv() { +} diff --git a/src/fsfw/cfdp/tlv/MessageToUserTlv.h b/src/fsfw/cfdp/tlv/MessageToUserTlv.h new file mode 100644 index 00000000..7bbe3a40 --- /dev/null +++ b/src/fsfw/cfdp/tlv/MessageToUserTlv.h @@ -0,0 +1,13 @@ +#ifndef FSFW_SRC_FSFW_CFDP_TLV_MESSAGETOUSERTLV_H_ +#define FSFW_SRC_FSFW_CFDP_TLV_MESSAGETOUSERTLV_H_ + +#include "Tlv.h" + +class MessageToUserTlv: public cfdp::Tlv { +public: + MessageToUserTlv(); + MessageToUserTlv(uint8_t* value, size_t size); +private: +}; + +#endif /* FSFW_SRC_FSFW_CFDP_TLV_MESSAGETOUSERTLV_H_ */ diff --git a/src/fsfw/cfdp/tlv/Tlv.cpp b/src/fsfw/cfdp/tlv/Tlv.cpp new file mode 100644 index 00000000..71aa512d --- /dev/null +++ b/src/fsfw/cfdp/tlv/Tlv.cpp @@ -0,0 +1,114 @@ +#include "Tlv.h" + +cfdp::Tlv::Tlv(TlvTypes type, const uint8_t *value, size_t size): type(type), + value(value, size, true) { + if(size > 0) { + zeroLen = false; + } +} + +cfdp::Tlv::Tlv(): value(static_cast(nullptr), 0, true) { +} + +ReturnValue_t cfdp::Tlv::serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const { + if(buffer == nullptr or size == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if(*size + 2 > maxSize) { + return BUFFER_TOO_SHORT; + } + if(type == TlvTypes::INVALID_TLV) { + return INVALID_TLV_TYPE; + } + **buffer = type; + *size += 1; + *buffer += 1; + + if(zeroLen) { + **buffer = 0; + *size += 1; + *buffer += 1; + return HasReturnvaluesIF::RETURN_OK; + } + if(value.getConstBuffer() == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + return value.serialize(buffer, size, maxSize, streamEndianness); +} + +size_t cfdp::Tlv::getSerializedSize() const { + if(zeroLen) { + return 2; + } + else if (value.getConstBuffer() == nullptr) { + return 0; + } + return value.getSerializedSize() + 1; +} + +ReturnValue_t cfdp::Tlv::deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) { + if(buffer == nullptr or size == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if(*size < 2) { + return STREAM_TOO_SHORT; + } + + uint8_t rawType = **buffer; + if(not checkType(rawType)) { + return INVALID_TLV_TYPE; + } + + type = static_cast(rawType); + *buffer += 1; + *size -= 1; + + size_t lengthField = **buffer; + if(lengthField == 0) { + zeroLen = true; + *buffer += 1; + *size -= 1; + return HasReturnvaluesIF::RETURN_OK; + } + if(lengthField + 1 > *size) { + return SerializeIF::STREAM_TOO_SHORT; + } + zeroLen = false; + // Zero-copy implementation + value.setBuffer(const_cast(*buffer + 1), lengthField); + *buffer += 1 + lengthField; + *size -= 1 + lengthField; + return HasReturnvaluesIF::RETURN_OK; +} + +const uint8_t* cfdp::Tlv::getValue() const { + return value.getConstBuffer(); +} + +cfdp::TlvTypes cfdp::Tlv::getType() const { + return type; +} + +bool cfdp::Tlv::checkType(uint8_t rawType) { + if (rawType != 0x03 and rawType <= 6) { + return true; + } + return false; +} + +void cfdp::Tlv::setValue(uint8_t *value, size_t len) { + if(len > 0) { + zeroLen = false; + } + this->value.setBuffer(value, len); +} + +uint8_t cfdp::Tlv::getLengthField() const { + return this->value.getSerializedSize() - 1; +} + +void cfdp::Tlv::setType(TlvTypes type) { + this->type = type; +} diff --git a/src/fsfw/cfdp/tlv/Tlv.h b/src/fsfw/cfdp/tlv/Tlv.h new file mode 100644 index 00000000..65c6ca09 --- /dev/null +++ b/src/fsfw/cfdp/tlv/Tlv.h @@ -0,0 +1,64 @@ +#ifndef FSFW_SRC_FSFW_CFDP_TLV_H_ +#define FSFW_SRC_FSFW_CFDP_TLV_H_ + +#include "TlvIF.h" +#include "fsfw/serialize/SerialBufferAdapter.h" + +namespace cfdp { + +/** + * @brief Type-Length-Value field implementation + * @details + * Thin abstraction layer around a serial buffer adapter + */ +class Tlv: public TlvIF { +public: + Tlv(TlvTypes type, const uint8_t *value, size_t size); + Tlv(); + + /** + * Serialize a TLV into a given buffer + * @param buffer + * @param size + * @param maxSize + * @param streamEndianness + * @return + * - RETURN_OK on success + * - INVALID_TLV_TYPE + * - SerializeIF returncode on wrong serialization parameters + */ + virtual ReturnValue_t serialize(uint8_t **buffer, size_t *size, + size_t maxSize, Endianness streamEndianness) const override; + + virtual size_t getSerializedSize() const override; + + /** + * @brief Deserialize a LV field from a raw buffer. Zero-copy implementation + * @param buffer Raw buffer including the size field + * @param size + * @param streamEndianness + * - RETURN_OK on success + * - INVALID_TLV_TYPE + * - SerializeIF returncode on wrong deserialization parameters + */ + virtual ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) override; + + + void setValue(uint8_t *value, size_t len); + + const uint8_t* getValue() const; + void setType(TlvTypes type); + TlvTypes getType() const override; + uint8_t getLengthField() const override; +private: + bool checkType(uint8_t rawType); + + bool zeroLen = true; + TlvTypes type = TlvTypes::INVALID_TLV; + SerialBufferAdapter value; +}; + +} + +#endif /* FSFW_SRC_FSFW_CFDP_TLV_H_ */ diff --git a/src/fsfw/cfdp/tlv/TlvIF.h b/src/fsfw/cfdp/tlv/TlvIF.h new file mode 100644 index 00000000..885e7814 --- /dev/null +++ b/src/fsfw/cfdp/tlv/TlvIF.h @@ -0,0 +1,16 @@ +#ifndef FSFW_SRC_FSFW_CFDP_TLVIF_H_ +#define FSFW_SRC_FSFW_CFDP_TLVIF_H_ + +#include "../definitions.h" + +class TlvIF: public SerializeIF { +public: + virtual~ TlvIF() {}; + + virtual uint8_t getLengthField() const = 0; + virtual cfdp::TlvTypes getType() const = 0; +}; + + + +#endif /* FSFW_SRC_FSFW_CFDP_TLVIF_H_ */ diff --git a/src/fsfw/controller/ExtendedControllerBase.h b/src/fsfw/controller/ExtendedControllerBase.h index 4172e03e..abd48637 100644 --- a/src/fsfw/controller/ExtendedControllerBase.h +++ b/src/fsfw/controller/ExtendedControllerBase.h @@ -8,11 +8,10 @@ #include "fsfw/datapoollocal/LocalDataPoolManager.h" /** - * @brief Extendes the basic ControllerBase with the common components - * HasActionsIF for commandability and HasLocalDataPoolIF to keep - * a pool of local data pool variables. + * @brief Extends the basic ControllerBase with commonly used components * @details - * Default implementations required for the interfaces will be empty and have + * HasActionsIF for commandability and HasLocalDataPoolIF to keep a pool of local data pool + * variables. Default implementations required for the interfaces will be empty and have * to be implemented by child class. */ class ExtendedControllerBase: public ControllerBase, diff --git a/src/fsfw/devicehandlers/AssemblyBase.h b/src/fsfw/devicehandlers/AssemblyBase.h index 6cac81b4..7d54f14d 100644 --- a/src/fsfw/devicehandlers/AssemblyBase.h +++ b/src/fsfw/devicehandlers/AssemblyBase.h @@ -7,7 +7,7 @@ /** * @brief Base class to implement reconfiguration and failure handling for - * redundant devices by monitoring their modes health states. + * redundant devices by monitoring their modes and health states. * @details * Documentation: Dissertation Baetz p.156, 157. * diff --git a/src/fsfw/devicehandlers/DeviceCommunicationIF.h b/src/fsfw/devicehandlers/DeviceCommunicationIF.h index e0b473d3..527e4700 100644 --- a/src/fsfw/devicehandlers/DeviceCommunicationIF.h +++ b/src/fsfw/devicehandlers/DeviceCommunicationIF.h @@ -85,9 +85,10 @@ public: * Called by DHB in the GET_WRITE doGetWrite(). * Get send confirmation that the data in sendMessage() was sent successfully. * @param cookie - * @return - @c RETURN_OK if data was sent successfull - * - Everything else triggers falure event with - * returnvalue as parameter 1 + * @return + * - @c RETURN_OK if data was sent successfully but a reply is expected + * - NO_REPLY_EXPECTED if data was sent successfully and no reply is expected + * - Everything else to indicate failure */ virtual ReturnValue_t getSendSuccess(CookieIF *cookie) = 0; diff --git a/src/fsfw/devicehandlers/DeviceHandlerBase.h b/src/fsfw/devicehandlers/DeviceHandlerBase.h index b182b611..da609eed 100644 --- a/src/fsfw/devicehandlers/DeviceHandlerBase.h +++ b/src/fsfw/devicehandlers/DeviceHandlerBase.h @@ -78,15 +78,16 @@ class StorageManagerIF; * * @ingroup devices */ -class DeviceHandlerBase: public DeviceHandlerIF, -public HasReturnvaluesIF, -public ExecutableObjectIF, -public SystemObject, -public HasModesIF, -public HasHealthIF, -public HasActionsIF, -public ReceivesParameterMessagesIF, -public HasLocalDataPoolIF { +class DeviceHandlerBase: + public DeviceHandlerIF, + public HasReturnvaluesIF, + public ExecutableObjectIF, + public SystemObject, + public HasModesIF, + public HasHealthIF, + public HasActionsIF, + public ReceivesParameterMessagesIF, + public HasLocalDataPoolIF { friend void (Factory::setStaticFrameworkObjectIds)(); public: /** @@ -334,8 +335,7 @@ protected: * - @c RETURN_OK to send command after #rawPacket and #rawPacketLen * have been set. * - @c HasActionsIF::EXECUTION_COMPLETE to generate a finish reply immediately. This can - * be used if no reply is expected. Otherwise, the developer can call #actionHelper.finish - * to finish the command handling. + * be used if no reply is expected * - Anything else triggers an event with the return code as a parameter as well as a * step reply failed with the return code */ diff --git a/src/fsfw/devicehandlers/DeviceHandlerIF.h b/src/fsfw/devicehandlers/DeviceHandlerIF.h index 1933c571..1fc57c42 100644 --- a/src/fsfw/devicehandlers/DeviceHandlerIF.h +++ b/src/fsfw/devicehandlers/DeviceHandlerIF.h @@ -120,7 +120,8 @@ public: static const ReturnValue_t WRONG_MODE_FOR_COMMAND = MAKE_RETURN_CODE(0xA5); static const ReturnValue_t TIMEOUT = MAKE_RETURN_CODE(0xA6); static const ReturnValue_t BUSY = MAKE_RETURN_CODE(0xA7); - static const ReturnValue_t NO_REPLY_EXPECTED = MAKE_RETURN_CODE(0xA8); //!< Used to indicate that this is a command-only command. + //!< Used to indicate that this is a command-only command. + static const ReturnValue_t NO_REPLY_EXPECTED = MAKE_RETURN_CODE(0xA8); static const ReturnValue_t NON_OP_TEMPERATURE = MAKE_RETURN_CODE(0xA9); static const ReturnValue_t COMMAND_NOT_IMPLEMENTED = MAKE_RETURN_CODE(0xAA); diff --git a/src/fsfw/ipc/FwMessageTypes.h b/src/fsfw/ipc/FwMessageTypes.h index 8b49c122..22fe9d0d 100644 --- a/src/fsfw/ipc/FwMessageTypes.h +++ b/src/fsfw/ipc/FwMessageTypes.h @@ -9,6 +9,7 @@ enum FsfwMessageTypes { HEALTH_COMMAND, MODE_SEQUENCE, ACTION, + CFDP, TM_STORE, DEVICE_HANDLER_COMMAND, MONITORING, diff --git a/src/fsfw/objectmanager/frameworkObjects.h b/src/fsfw/objectmanager/frameworkObjects.h index 36010807..ff7d9341 100644 --- a/src/fsfw/objectmanager/frameworkObjects.h +++ b/src/fsfw/objectmanager/frameworkObjects.h @@ -19,6 +19,9 @@ enum framework_objects: object_id_t { PUS_SERVICE_200_MODE_MGMT = 0x53000200, PUS_SERVICE_201_HEALTH = 0x53000201, + /* CFDP Distributer */ + CFDP_PACKET_DISTRIBUTOR = 0x53001000, + //Generic IDs for IPC, modes, health, events HEALTH_TABLE = 0x53010000, // MODE_STORE = 0x53010100, diff --git a/src/fsfw/osal/linux/CMakeLists.txt b/src/fsfw/osal/linux/CMakeLists.txt index 41800764..63206cb2 100644 --- a/src/fsfw/osal/linux/CMakeLists.txt +++ b/src/fsfw/osal/linux/CMakeLists.txt @@ -15,6 +15,7 @@ target_sources(${LIB_FSFW_NAME} TaskFactory.cpp tcpipHelpers.cpp unixUtility.cpp + CommandExecutor.cpp ) find_package(Threads REQUIRED) diff --git a/src/fsfw/osal/linux/MessageQueue.cpp b/src/fsfw/osal/linux/MessageQueue.cpp index b068c04f..d028f9f7 100644 --- a/src/fsfw/osal/linux/MessageQueue.cpp +++ b/src/fsfw/osal/linux/MessageQueue.cpp @@ -285,10 +285,10 @@ ReturnValue_t MessageQueue::sendMessageFromMessageQueue(MessageQueueId_t sendTo, utility::printUnixErrorGeneric(CLASS_NAME, "sendMessageFromMessageQueue", "EBADF"); #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "mq_send to: " << sendTo << " sent from " - << sentFrom << "failed" << std::endl; + sif::warning << "mq_send to " << sendTo << " sent from " + << sentFrom << " failed" << std::endl; #else - sif::printWarning("mq_send to: %d sent from %d failed\n", sendTo, sentFrom); + sif::printWarning("mq_send to %d sent from %d failed\n", sendTo, sentFrom); #endif return DESTINATION_INVALID; } diff --git a/src/fsfw/returnvalues/FwClassIds.h b/src/fsfw/returnvalues/FwClassIds.h index 9fa0c9ae..96f96660 100644 --- a/src/fsfw/returnvalues/FwClassIds.h +++ b/src/fsfw/returnvalues/FwClassIds.h @@ -60,6 +60,7 @@ enum: uint8_t { HAS_ACTIONS_IF, //HF DEVICE_COMMUNICATION_IF, //DC BSP, //BSP + CFDP, //CFDP TIME_STAMPER_IF, //TSI SGP4PROPAGATOR_CLASS, //SGP4 MUTEX_IF, //MUX diff --git a/src/fsfw/serialize/SerialBufferAdapter.cpp b/src/fsfw/serialize/SerialBufferAdapter.cpp index 4f03658a..6db17d5e 100644 --- a/src/fsfw/serialize/SerialBufferAdapter.cpp +++ b/src/fsfw/serialize/SerialBufferAdapter.cpp @@ -105,7 +105,7 @@ uint8_t * SerialBufferAdapter::getBuffer() { } template -const uint8_t * SerialBufferAdapter::getConstBuffer() { +const uint8_t * SerialBufferAdapter::getConstBuffer() const { if(constBuffer == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 sif::error << "SerialBufferAdapter::getConstBuffer:" diff --git a/src/fsfw/serialize/SerialBufferAdapter.h b/src/fsfw/serialize/SerialBufferAdapter.h index 6c79cd03..48f5ce53 100644 --- a/src/fsfw/serialize/SerialBufferAdapter.h +++ b/src/fsfw/serialize/SerialBufferAdapter.h @@ -66,7 +66,7 @@ public: Endianness streamEndianness) override; uint8_t * getBuffer(); - const uint8_t * getConstBuffer(); + const uint8_t * getConstBuffer() const; void setBuffer(uint8_t* buffer, count_t bufferLength); private: bool serializeLength = false; diff --git a/src/fsfw/subsystem/SubsystemBase.h b/src/fsfw/subsystem/SubsystemBase.h index 6b2e9b5f..a1de077d 100644 --- a/src/fsfw/subsystem/SubsystemBase.h +++ b/src/fsfw/subsystem/SubsystemBase.h @@ -62,7 +62,8 @@ protected: struct ChildInfo { MessageQueueId_t commandQueue; Mode_t mode; - Submode_t submode;bool healthChanged; + Submode_t submode; + bool healthChanged; }; Mode_t mode; diff --git a/src/fsfw/tcdistribution/CCSDSDistributor.cpp b/src/fsfw/tcdistribution/CCSDSDistributor.cpp index ffceaecc..a040a5df 100644 --- a/src/fsfw/tcdistribution/CCSDSDistributor.cpp +++ b/src/fsfw/tcdistribution/CCSDSDistributor.cpp @@ -7,8 +7,8 @@ #define CCSDS_DISTRIBUTOR_DEBUGGING 0 CCSDSDistributor::CCSDSDistributor(uint16_t setDefaultApid, - object_id_t setObjectId): - TcDistributor(setObjectId), defaultApid( setDefaultApid ) { + object_id_t setObjectId): + TcDistributor(setObjectId), defaultApid( setDefaultApid ) { } CCSDSDistributor::~CCSDSDistributor() {} @@ -16,97 +16,97 @@ CCSDSDistributor::~CCSDSDistributor() {} TcDistributor::TcMqMapIter CCSDSDistributor::selectDestination() { #if CCSDS_DISTRIBUTOR_DEBUGGING == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "CCSDSDistributor::selectDestination received: " << - this->currentMessage.getStorageId().poolIndex << ", " << - this->currentMessage.getStorageId().packetIndex << std::endl; + sif::debug << "CCSDSDistributor::selectDestination received: " << + this->currentMessage.getStorageId().poolIndex << ", " << + this->currentMessage.getStorageId().packetIndex << std::endl; #else - sif::printDebug("CCSDSDistributor::selectDestination received: %d, %d\n", - currentMessage.getStorageId().poolIndex, currentMessage.getStorageId().packetIndex); + sif::printDebug("CCSDSDistributor::selectDestination received: %d, %d\n", + currentMessage.getStorageId().poolIndex, currentMessage.getStorageId().packetIndex); #endif #endif - const uint8_t* packet = nullptr; - size_t size = 0; - ReturnValue_t result = this->tcStore->getData(currentMessage.getStorageId(), - &packet, &size ); - if(result != HasReturnvaluesIF::RETURN_OK) { + const uint8_t* packet = nullptr; + size_t size = 0; + ReturnValue_t result = this->tcStore->getData(currentMessage.getStorageId(), + &packet, &size ); + if(result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "CCSDSDistributor::selectDestination: Getting data from" - " store failed!" << std::endl; + sif::error << "CCSDSDistributor::selectDestination: Getting data from" + " store failed!" << std::endl; #else - sif::printError("CCSDSDistributor::selectDestination: Getting data from" + sif::printError("CCSDSDistributor::selectDestination: Getting data from" " store failed!\n"); #endif #endif - } - SpacePacketBase currentPacket(packet); + } + SpacePacketBase currentPacket(packet); #if FSFW_CPP_OSTREAM_ENABLED == 1 && CCSDS_DISTRIBUTOR_DEBUGGING == 1 - sif::info << "CCSDSDistributor::selectDestination has packet with APID " << std::hex << - currentPacket.getAPID() << std::dec << std::endl; + sif::info << "CCSDSDistributor::selectDestination has packet with APID " << std::hex << + currentPacket.getAPID() << std::dec << std::endl; #endif - TcMqMapIter position = this->queueMap.find(currentPacket.getAPID()); - if ( position != this->queueMap.end() ) { - return position; - } else { - //The APID was not found. Forward packet to main SW-APID anyway to - // create acceptance failure report. - return this->queueMap.find( this->defaultApid ); - } + TcMqMapIter position = this->queueMap.find(currentPacket.getAPID()); + if ( position != this->queueMap.end() ) { + return position; + } else { + //The APID was not found. Forward packet to main SW-APID anyway to + // create acceptance failure report. + return this->queueMap.find( this->defaultApid ); + } } MessageQueueId_t CCSDSDistributor::getRequestQueue() { - return tcQueue->getId(); + return tcQueue->getId(); } ReturnValue_t CCSDSDistributor::registerApplication( - AcceptsTelecommandsIF* application) { - ReturnValue_t returnValue = RETURN_OK; - auto insertPair = this->queueMap.emplace(application->getIdentifier(), - application->getRequestQueue()); - if(not insertPair.second) { - returnValue = RETURN_FAILED; - } - return returnValue; + AcceptsTelecommandsIF* application) { + ReturnValue_t returnValue = RETURN_OK; + auto insertPair = this->queueMap.emplace(application->getIdentifier(), + application->getRequestQueue()); + if(not insertPair.second) { + returnValue = RETURN_FAILED; + } + return returnValue; } ReturnValue_t CCSDSDistributor::registerApplication(uint16_t apid, - MessageQueueId_t id) { - ReturnValue_t returnValue = RETURN_OK; - auto insertPair = this->queueMap.emplace(apid, id); - if(not insertPair.second) { - returnValue = RETURN_FAILED; - } - return returnValue; + MessageQueueId_t id) { + ReturnValue_t returnValue = RETURN_OK; + auto insertPair = this->queueMap.emplace(apid, id); + if(not insertPair.second) { + returnValue = RETURN_FAILED; + } + return returnValue; } uint16_t CCSDSDistributor::getIdentifier() { - return 0; + return 0; } ReturnValue_t CCSDSDistributor::initialize() { - ReturnValue_t status = this->TcDistributor::initialize(); - this->tcStore = ObjectManager::instance()->get( objects::TC_STORE ); - if (this->tcStore == nullptr) { + ReturnValue_t status = this->TcDistributor::initialize(); + this->tcStore = ObjectManager::instance()->get( objects::TC_STORE ); + if (this->tcStore == nullptr) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "CCSDSDistributor::initialize: Could not initialize" - " TC store!" << std::endl; + sif::error << "CCSDSDistributor::initialize: Could not initialize" + " TC store!" << std::endl; #else - sif::printError("CCSDSDistributor::initialize: Could not initialize" + sif::printError("CCSDSDistributor::initialize: Could not initialize" " TC store!\n"); #endif #endif - status = RETURN_FAILED; - } - return status; + status = RETURN_FAILED; + } + return status; } ReturnValue_t CCSDSDistributor::callbackAfterSending( - ReturnValue_t queueStatus) { - if (queueStatus != RETURN_OK) { - tcStore->deleteData(currentMessage.getStorageId()); - } - return RETURN_OK; + ReturnValue_t queueStatus) { + if (queueStatus != RETURN_OK) { + tcStore->deleteData(currentMessage.getStorageId()); + } + return RETURN_OK; } diff --git a/src/fsfw/tcdistribution/CCSDSDistributor.h b/src/fsfw/tcdistribution/CCSDSDistributor.h index e8d54c9c..f8995bc5 100644 --- a/src/fsfw/tcdistribution/CCSDSDistributor.h +++ b/src/fsfw/tcdistribution/CCSDSDistributor.h @@ -15,56 +15,57 @@ * The Secondary Header (with Service/Subservice) is ignored. * @ingroup tc_distribution */ -class CCSDSDistributor : public TcDistributor, - public CCSDSDistributorIF, - public AcceptsTelecommandsIF { +class CCSDSDistributor: + public TcDistributor, + public CCSDSDistributorIF, + public AcceptsTelecommandsIF { public: - /** - * @brief The constructor sets the default APID and calls the - * TcDistributor ctor with a certain object id. - * @details - * @c tcStore is set in the @c initialize method. - * @param setDefaultApid The default APID, where packets with unknown - * destination are sent to. - */ - CCSDSDistributor(uint16_t setDefaultApid, object_id_t setObjectId); - /** - * The destructor is empty. - */ - virtual ~CCSDSDistributor(); + /** + * @brief The constructor sets the default APID and calls the + * TcDistributor ctor with a certain object id. + * @details + * @c tcStore is set in the @c initialize method. + * @param setDefaultApid The default APID, where packets with unknown + * destination are sent to. + */ + CCSDSDistributor(uint16_t setDefaultApid, object_id_t setObjectId); + /** + * The destructor is empty. + */ + virtual ~CCSDSDistributor(); - MessageQueueId_t getRequestQueue() override; - ReturnValue_t registerApplication( uint16_t apid, - MessageQueueId_t id) override; - ReturnValue_t registerApplication( - AcceptsTelecommandsIF* application) override; - uint16_t getIdentifier() override; - ReturnValue_t initialize() override; + MessageQueueId_t getRequestQueue() override; + ReturnValue_t registerApplication( uint16_t apid, + MessageQueueId_t id) override; + ReturnValue_t registerApplication( + AcceptsTelecommandsIF* application) override; + uint16_t getIdentifier() override; + ReturnValue_t initialize() override; protected: - /** - * This implementation checks if an application with fitting APID has - * registered and forwards the packet to the according message queue. - * If the packet is not found, it returns the queue to @c defaultApid, - * where a Acceptance Failure message should be generated. - * @return Iterator to map entry of found APID or iterator to default APID. - */ - TcMqMapIter selectDestination() override; + /** + * This implementation checks if an application with fitting APID has + * registered and forwards the packet to the according message queue. + * If the packet is not found, it returns the queue to @c defaultApid, + * where a Acceptance Failure message should be generated. + * @return Iterator to map entry of found APID or iterator to default APID. + */ + TcMqMapIter selectDestination() override; /** * The callback here handles the generation of acceptance * success/failure messages. */ ReturnValue_t callbackAfterSending( ReturnValue_t queueStatus ) override; - /** - * The default APID, where packets with unknown APID are sent to. - */ - uint16_t defaultApid; - /** - * A reference to the TC storage must be maintained, as this class handles - * pure Space Packets and there exists no SpacePacketStored class. - */ - StorageManagerIF* tcStore = nullptr; + /** + * The default APID, where packets with unknown APID are sent to. + */ + uint16_t defaultApid; + /** + * A reference to the TC storage must be maintained, as this class handles + * pure Space Packets and there exists no SpacePacketStored class. + */ + StorageManagerIF* tcStore = nullptr; }; diff --git a/src/fsfw/tcdistribution/CCSDSDistributorIF.h b/src/fsfw/tcdistribution/CCSDSDistributorIF.h index 6334a35a..4e4c2a5b 100644 --- a/src/fsfw/tcdistribution/CCSDSDistributorIF.h +++ b/src/fsfw/tcdistribution/CCSDSDistributorIF.h @@ -13,31 +13,30 @@ */ class CCSDSDistributorIF { public: - /** - * With this call, a class implementing the CCSDSApplicationIF can register - * at the distributor. - * @param application A pointer to the Application to register. - * @return - @c RETURN_OK on success, - * - @c RETURN_FAILED on failure. - */ - virtual ReturnValue_t registerApplication( - AcceptsTelecommandsIF* application) = 0; - /** - * With this call, other Applications can register to the CCSDS distributor. - * This is done by passing an APID and a MessageQueueId to the method. - * @param apid The APID to register. - * @param id The MessageQueueId of the message queue to send the - * TC Packets to. - * @return - @c RETURN_OK on success, - * - @c RETURN_FAILED on failure. - */ - virtual ReturnValue_t registerApplication( uint16_t apid, - MessageQueueId_t id) = 0; - /** - * The empty virtual destructor. - */ - virtual ~CCSDSDistributorIF() { - } + /** + * With this call, a class implementing the CCSDSApplicationIF can register + * at the distributor. + * @param application A pointer to the Application to register. + * @return - @c RETURN_OK on success, + * - @c RETURN_FAILED on failure. + */ + virtual ReturnValue_t registerApplication( + AcceptsTelecommandsIF* application) = 0; + /** + * With this call, other Applications can register to the CCSDS distributor. + * This is done by passing an APID and a MessageQueueId to the method. + * @param apid The APID to register. + * @param id The MessageQueueId of the message queue to send the + * TC Packets to. + * @return - @c RETURN_OK on success, + * - @c RETURN_FAILED on failure. + */ + virtual ReturnValue_t registerApplication( uint16_t apid, + MessageQueueId_t id) = 0; + /** + * The empty virtual destructor. + */ + virtual ~CCSDSDistributorIF() {} }; diff --git a/src/fsfw/tcdistribution/CFDPDistributor.cpp b/src/fsfw/tcdistribution/CFDPDistributor.cpp new file mode 100644 index 00000000..f28a2998 --- /dev/null +++ b/src/fsfw/tcdistribution/CFDPDistributor.cpp @@ -0,0 +1,147 @@ +#include "fsfw/tcdistribution/CCSDSDistributorIF.h" +#include "fsfw/tcdistribution/CFDPDistributor.h" + +#include "fsfw/tmtcpacket/cfdp/CFDPPacketStored.h" + +#include "fsfw/objectmanager/ObjectManager.h" + +#ifndef FSFW_CFDP_DISTRIBUTOR_DEBUGGING +#define FSFW_CFDP_DISTRIBUTOR_DEBUGGING 1 +#endif + +CFDPDistributor::CFDPDistributor(uint16_t setApid, object_id_t setObjectId, + object_id_t setPacketSource): + TcDistributor(setObjectId), apid(setApid), checker(setApid), + tcStatus(RETURN_FAILED), packetSource(setPacketSource) { +} + +CFDPDistributor::~CFDPDistributor() {} + +CFDPDistributor::TcMqMapIter CFDPDistributor::selectDestination() { +#if FSFW_CFDP_DISTRIBUTOR_DEBUGGING == 1 + store_address_t storeId = this->currentMessage.getStorageId(); +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::debug << "CFDPDistributor::handlePacket received: " << storeId.poolIndex << ", " << + storeId.packetIndex << std::endl; +#else + sif::printDebug("CFDPDistributor::handlePacket received: %d, %d\n", storeId.poolIndex, + storeId.packetIndex); +#endif +#endif + TcMqMapIter queueMapIt = this->queueMap.end(); + if(this->currentPacket == nullptr) { + return queueMapIt; + } + this->currentPacket->setStoreAddress(this->currentMessage.getStorageId()); + if (currentPacket->getWholeData() != nullptr) { + tcStatus = checker.checkPacket(currentPacket); + if(tcStatus != HasReturnvaluesIF::RETURN_OK) { +#if FSFW_VERBOSE_LEVEL >= 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::debug << "CFDPDistributor::handlePacket: Packet format invalid, code " << + static_cast(tcStatus) << std::endl; +#else + sif::printDebug("CFDPDistributor::handlePacket: Packet format invalid, code %d\n", + static_cast(tcStatus)); +#endif +#endif + } + queueMapIt = this->queueMap.find(0); + } + else { + tcStatus = PACKET_LOST; + } + + if (queueMapIt == this->queueMap.end()) { + tcStatus = DESTINATION_NOT_FOUND; +#if FSFW_VERBOSE_LEVEL >= 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::debug << "CFDPDistributor::handlePacket: Destination not found" << std::endl; +#else + sif::printDebug("CFDPDistributor::handlePacket: Destination not found\n"); +#endif /* !FSFW_CPP_OSTREAM_ENABLED == 1 */ +#endif + } + + if (tcStatus != RETURN_OK) { + return this->queueMap.end(); + } + else { + return queueMapIt; + } + +} + + +ReturnValue_t CFDPDistributor::registerHandler(AcceptsTelecommandsIF* handler) { + uint16_t handlerId = handler->getIdentifier(); //should be 0, because CFDPHandler does not set a set a service-ID +#if FSFW_CFDP_DISTRIBUTOR_DEBUGGING == 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::info << "CFDPDistributor::registerHandler: Handler ID: " << static_cast(handlerId) << std::endl; +#else + sif::printInfo("CFDPDistributor::registerHandler: Handler ID: %d\n", static_cast(handlerId)); +#endif +#endif + MessageQueueId_t queue = handler->getRequestQueue(); + auto returnPair = queueMap.emplace(handlerId, queue); + if (not returnPair.second) { +#if FSFW_VERBOSE_LEVEL >= 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::error << "CFDPDistributor::registerHandler: Service ID already" + " exists in map" << std::endl; +#else + sif::printError("CFDPDistributor::registerHandler: Service ID already exists in map\n"); +#endif +#endif + return SERVICE_ID_ALREADY_EXISTS; + } + return HasReturnvaluesIF::RETURN_OK; +} + +MessageQueueId_t CFDPDistributor::getRequestQueue() { + return tcQueue->getId(); +} + +//ReturnValue_t CFDPDistributor::callbackAfterSending(ReturnValue_t queueStatus) { +// if (queueStatus != RETURN_OK) { +// tcStatus = queueStatus; +// } +// if (tcStatus != RETURN_OK) { +// this->verifyChannel.sendFailureReport(tc_verification::ACCEPTANCE_FAILURE, +// currentPacket, tcStatus); +// // A failed packet is deleted immediately after reporting, +// // otherwise it will block memory. +// currentPacket->deletePacket(); +// return RETURN_FAILED; +// } else { +// this->verifyChannel.sendSuccessReport(tc_verification::ACCEPTANCE_SUCCESS, +// currentPacket); +// return RETURN_OK; +// } +//} + +uint16_t CFDPDistributor::getIdentifier() { + return this->apid; +} + +ReturnValue_t CFDPDistributor::initialize() { + currentPacket = new CFDPPacketStored(); + if(currentPacket == nullptr) { + // Should not happen, memory allocation failed! + return ObjectManagerIF::CHILD_INIT_FAILED; + } + + CCSDSDistributorIF* ccsdsDistributor = ObjectManager::instance()->get( + packetSource); + if (ccsdsDistributor == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::error << "CFDPDistributor::initialize: Packet source invalid" << std::endl; + sif::error << " Make sure it exists and implements CCSDSDistributorIF!" << std::endl; +#else + sif::printError("CFDPDistributor::initialize: Packet source invalid\n"); + sif::printError("Make sure it exists and implements CCSDSDistributorIF\n"); +#endif + return RETURN_FAILED; + } + return ccsdsDistributor->registerApplication(this); +} diff --git a/src/fsfw/tcdistribution/CFDPDistributor.h b/src/fsfw/tcdistribution/CFDPDistributor.h new file mode 100644 index 00000000..5c7513b3 --- /dev/null +++ b/src/fsfw/tcdistribution/CFDPDistributor.h @@ -0,0 +1,72 @@ +#ifndef FSFW_TCDISTRIBUTION_CFDPDISTRIBUTOR_H_ +#define FSFW_TCDISTRIBUTION_CFDPDISTRIBUTOR_H_ + +#include +#include "CFDPDistributorIF.h" +#include "TcDistributor.h" +#include "../tmtcpacket/cfdp/CFDPPacketStored.h" +#include "../returnvalues/HasReturnvaluesIF.h" +#include "../tmtcservices/AcceptsTelecommandsIF.h" +#include "../tmtcservices/VerificationReporter.h" + +/** + * This class accepts CFDP Telecommands and forwards them to Application + * services. + * @ingroup tc_distribution + */ +class CFDPDistributor: + public TcDistributor, + public CFDPDistributorIF, + public AcceptsTelecommandsIF { +public: + /** + * The ctor passes @c set_apid to the checker class and calls the + * TcDistribution ctor with a certain object id. + * @param setApid The APID of this receiving Application. + * @param setObjectId Object ID of the distributor itself + * @param setPacketSource Object ID of the source of TC packets. + * Must implement CCSDSDistributorIF. + */ + CFDPDistributor(uint16_t setApid, object_id_t setObjectId, + object_id_t setPacketSource); + /** + * The destructor is empty. + */ + virtual ~CFDPDistributor(); + ReturnValue_t registerHandler(AcceptsTelecommandsIF* handler) override; + MessageQueueId_t getRequestQueue() override; + ReturnValue_t initialize() override; + uint16_t getIdentifier() override; + +protected: + uint16_t apid; + /** + * The currently handled packet is stored here. + */ + CFDPPacketStored* currentPacket = nullptr; + TcPacketCheckCFDP checker; + /** + * With this variable, the current check status is stored to generate + * acceptance messages later. + */ + ReturnValue_t tcStatus; + + const object_id_t packetSource; + + /** + * This method reads the packet service, checks if such a service is + * registered and forwards the packet to the destination. + * It also initiates the formal packet check and sending of verification + * messages. + * @return Iterator to map entry of found service id + * or iterator to @c map.end(). + */ + TcMqMapIter selectDestination() override; + /** + * The callback here handles the generation of acceptance + * success/failure messages. + */ + //ReturnValue_t callbackAfterSending(ReturnValue_t queueStatus) override; +}; + +#endif /* FSFW_TCDISTRIBUTION_CFDPDISTRIBUTOR_H_ */ diff --git a/src/fsfw/tcdistribution/CFDPDistributorIF.h b/src/fsfw/tcdistribution/CFDPDistributorIF.h new file mode 100644 index 00000000..f1c85772 --- /dev/null +++ b/src/fsfw/tcdistribution/CFDPDistributorIF.h @@ -0,0 +1,27 @@ +#ifndef FSFW_TCDISTRIBUTION_CFDPDISTRIBUTORIF_H_ +#define FSFW_TCDISTRIBUTION_CFDPDISTRIBUTORIF_H_ + +#include "../tmtcservices/AcceptsTelecommandsIF.h" +#include "../ipc/MessageQueueSenderIF.h" + +/** + * This interface allows CFDP Services to register themselves at a CFDP Distributor. + * @ingroup tc_distribution + */ +class CFDPDistributorIF { +public: + /** + * The empty virtual destructor. + */ + virtual ~CFDPDistributorIF() { + } + /** + * With this method, Handlers can register themselves at the CFDP Distributor. + * @param handler A pointer to the registering Handler. + * @return - @c RETURN_OK on success, + * - @c RETURN_FAILED on failure. + */ + virtual ReturnValue_t registerHandler(AcceptsTelecommandsIF* handler) = 0; +}; + +#endif /* FSFW_TCDISTRIBUTION_CFDPDISTRIBUTORIF_H_ */ diff --git a/src/fsfw/tcdistribution/CMakeLists.txt b/src/fsfw/tcdistribution/CMakeLists.txt index 6f237076..7118c38c 100644 --- a/src/fsfw/tcdistribution/CMakeLists.txt +++ b/src/fsfw/tcdistribution/CMakeLists.txt @@ -2,5 +2,8 @@ target_sources(${LIB_FSFW_NAME} PRIVATE CCSDSDistributor.cpp PUSDistributor.cpp TcDistributor.cpp - TcPacketCheck.cpp + TcPacketCheckPUS.cpp + TcPacketCheckCFDP.cpp + CFDPDistributor.cpp ) + diff --git a/src/fsfw/tcdistribution/PUSDistributor.cpp b/src/fsfw/tcdistribution/PUSDistributor.cpp index adab58c8..aafd1244 100644 --- a/src/fsfw/tcdistribution/PUSDistributor.cpp +++ b/src/fsfw/tcdistribution/PUSDistributor.cpp @@ -24,25 +24,25 @@ PUSDistributor::TcMqMapIter PUSDistributor::selectDestination() { if(this->currentPacket == nullptr) { return queueMapIt; } - this->currentPacket->setStoreAddress(this->currentMessage.getStorageId()); + this->currentPacket->setStoreAddress(this->currentMessage.getStorageId(), currentPacket); if (currentPacket->getWholeData() != nullptr) { tcStatus = checker.checkPacket(currentPacket); if(tcStatus != HasReturnvaluesIF::RETURN_OK) { #if FSFW_VERBOSE_LEVEL >= 1 const char* keyword = "unnamed error"; - if(tcStatus == TcPacketCheck::INCORRECT_CHECKSUM) { + if(tcStatus == TcPacketCheckPUS::INCORRECT_CHECKSUM) { keyword = "checksum"; } - else if(tcStatus == TcPacketCheck::INCORRECT_PRIMARY_HEADER) { + else if(tcStatus == TcPacketCheckPUS::INCORRECT_PRIMARY_HEADER) { keyword = "incorrect primary header"; } - else if(tcStatus == TcPacketCheck::ILLEGAL_APID) { + else if(tcStatus == TcPacketCheckPUS::ILLEGAL_APID) { keyword = "illegal APID"; } - else if(tcStatus == TcPacketCheck::INCORRECT_SECONDARY_HEADER) { + else if(tcStatus == TcPacketCheckPUS::INCORRECT_SECONDARY_HEADER) { keyword = "incorrect secondary header"; } - else if(tcStatus == TcPacketCheck::INCOMPLETE_PACKET) { + else if(tcStatus == TcPacketCheckPUS::INCOMPLETE_PACKET) { keyword = "incomplete packet"; } #if FSFW_CPP_OSTREAM_ENABLED == 1 diff --git a/src/fsfw/tcdistribution/PUSDistributor.h b/src/fsfw/tcdistribution/PUSDistributor.h index 53a996ca..b010125c 100644 --- a/src/fsfw/tcdistribution/PUSDistributor.h +++ b/src/fsfw/tcdistribution/PUSDistributor.h @@ -3,7 +3,7 @@ #include "PUSDistributorIF.h" #include "TcDistributor.h" -#include "TcPacketCheck.h" +#include "TcPacketCheckPUS.h" #include "fsfw/tmtcpacket/pus/tc.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" @@ -17,65 +17,65 @@ * @ingroup tc_distribution */ class PUSDistributor: public TcDistributor, - public PUSDistributorIF, - public AcceptsTelecommandsIF { +public PUSDistributorIF, +public AcceptsTelecommandsIF { public: - /** - * The ctor passes @c set_apid to the checker class and calls the - * TcDistribution ctor with a certain object id. - * @param setApid The APID of this receiving Application. - * @param setObjectId Object ID of the distributor itself - * @param setPacketSource Object ID of the source of TC packets. - * Must implement CCSDSDistributorIF. - */ - PUSDistributor(uint16_t setApid, object_id_t setObjectId, - object_id_t setPacketSource); - /** - * The destructor is empty. - */ - virtual ~PUSDistributor(); - ReturnValue_t registerService(AcceptsTelecommandsIF* service) override; - MessageQueueId_t getRequestQueue() override; - ReturnValue_t initialize() override; - uint16_t getIdentifier() override; + /** + * The ctor passes @c set_apid to the checker class and calls the + * TcDistribution ctor with a certain object id. + * @param setApid The APID of this receiving Application. + * @param setObjectId Object ID of the distributor itself + * @param setPacketSource Object ID of the source of TC packets. + * Must implement CCSDSDistributorIF. + */ + PUSDistributor(uint16_t setApid, object_id_t setObjectId, + object_id_t setPacketSource); + /** + * The destructor is empty. + */ + virtual ~PUSDistributor(); + ReturnValue_t registerService(AcceptsTelecommandsIF* service) override; + MessageQueueId_t getRequestQueue() override; + ReturnValue_t initialize() override; + uint16_t getIdentifier() override; protected: - /** - * This attribute contains the class, that performs a formal packet check. - */ - TcPacketCheck checker; - /** - * With this class, verification messages are sent to the - * TC Verification service. - */ - VerificationReporter verifyChannel; - /** - * The currently handled packet is stored here. - */ - TcPacketStoredPus* currentPacket = nullptr; + /** + * This attribute contains the class, that performs a formal packet check. + */ + TcPacketCheckPUS checker; + /** + * With this class, verification messages are sent to the + * TC Verification service. + */ + VerificationReporter verifyChannel; + /** + * The currently handled packet is stored here. + */ + TcPacketStoredPus* currentPacket = nullptr; - /** - * With this variable, the current check status is stored to generate - * acceptance messages later. - */ - ReturnValue_t tcStatus; + /** + * With this variable, the current check status is stored to generate + * acceptance messages later. + */ + ReturnValue_t tcStatus; - const object_id_t packetSource; + const object_id_t packetSource; - /** - * This method reads the packet service, checks if such a service is - * registered and forwards the packet to the destination. - * It also initiates the formal packet check and sending of verification - * messages. - * @return Iterator to map entry of found service id - * or iterator to @c map.end(). - */ - TcMqMapIter selectDestination() override; - /** - * The callback here handles the generation of acceptance - * success/failure messages. - */ - ReturnValue_t callbackAfterSending(ReturnValue_t queueStatus) override; + /** + * This method reads the packet service, checks if such a service is + * registered and forwards the packet to the destination. + * It also initiates the formal packet check and sending of verification + * messages. + * @return Iterator to map entry of found service id + * or iterator to @c map.end(). + */ + TcMqMapIter selectDestination() override; + /** + * The callback here handles the generation of acceptance + * success/failure messages. + */ + ReturnValue_t callbackAfterSending(ReturnValue_t queueStatus) override; }; #endif /* FSFW_TCDISTRIBUTION_PUSDISTRIBUTOR_H_ */ diff --git a/src/fsfw/tcdistribution/PUSDistributorIF.h b/src/fsfw/tcdistribution/PUSDistributorIF.h index 0125c08f..e4a66758 100644 --- a/src/fsfw/tcdistribution/PUSDistributorIF.h +++ b/src/fsfw/tcdistribution/PUSDistributorIF.h @@ -10,18 +10,18 @@ */ class PUSDistributorIF { public: - /** - * The empty virtual destructor. - */ - virtual ~PUSDistributorIF() { - } -/** - * With this method, Services can register themselves at the PUS Distributor. - * @param service A pointer to the registering Service. - * @return - @c RETURN_OK on success, - * - @c RETURN_FAILED on failure. - */ - virtual ReturnValue_t registerService( AcceptsTelecommandsIF* service ) = 0; + /** + * The empty virtual destructor. + */ + virtual ~PUSDistributorIF() { + } + /** + * With this method, Services can register themselves at the PUS Distributor. + * @param service A pointer to the registering Service. + * @return - @c RETURN_OK on success, + * - @c RETURN_FAILED on failure. + */ + virtual ReturnValue_t registerService( AcceptsTelecommandsIF* service ) = 0; }; #endif /* FSFW_TCDISTRIBUTION_PUSDISTRIBUTORIF_H_ */ diff --git a/src/fsfw/tcdistribution/TcPacketCheckCFDP.cpp b/src/fsfw/tcdistribution/TcPacketCheckCFDP.cpp new file mode 100644 index 00000000..43e5511b --- /dev/null +++ b/src/fsfw/tcdistribution/TcPacketCheckCFDP.cpp @@ -0,0 +1,13 @@ +#include "fsfw/tcdistribution/TcPacketCheckCFDP.h" +#include "fsfw/tmtcpacket/cfdp/CFDPPacketStored.h" + +TcPacketCheckCFDP::TcPacketCheckCFDP(uint16_t setApid): apid(setApid) { +} + +ReturnValue_t TcPacketCheckCFDP::checkPacket(SpacePacketBase* currentPacket) { + return RETURN_OK; +} + +uint16_t TcPacketCheckCFDP::getApid() const { + return apid; +} diff --git a/src/fsfw/tcdistribution/TcPacketCheckCFDP.h b/src/fsfw/tcdistribution/TcPacketCheckCFDP.h new file mode 100644 index 00000000..8205fe4b --- /dev/null +++ b/src/fsfw/tcdistribution/TcPacketCheckCFDP.h @@ -0,0 +1,35 @@ +#ifndef FSFW_TCDISTRIBUTION_TCPACKETCHECKCFDP_H_ +#define FSFW_TCDISTRIBUTION_TCPACKETCHECKCFDP_H_ + +#include "TcPacketCheckIF.h" + +#include "fsfw/FSFW.h" + +class CFDPPacketStored; + +/** + * This class performs a formal packet check for incoming CFDP Packets. + * @ingroup tc_distribution + */ +class TcPacketCheckCFDP : + public TcPacketCheckIF, + public HasReturnvaluesIF { +protected: + /** + * The packet id each correct packet should have. + * It is composed of the APID and some static fields. + */ + uint16_t apid; +public: + /** + * The constructor only sets the APID attribute. + * @param set_apid The APID to set. + */ + TcPacketCheckCFDP(uint16_t setApid); + + ReturnValue_t checkPacket(SpacePacketBase* currentPacket) override; + + uint16_t getApid() const; +}; + +#endif /* FSFW_TCDISTRIBUTION_TCPACKETCHECKCFDP_H_ */ diff --git a/src/fsfw/tcdistribution/TcPacketCheckIF.h b/src/fsfw/tcdistribution/TcPacketCheckIF.h new file mode 100644 index 00000000..ac1dfef9 --- /dev/null +++ b/src/fsfw/tcdistribution/TcPacketCheckIF.h @@ -0,0 +1,31 @@ +#ifndef FSFW_TCDISTRIBUTION_TCPACKETCHECKIF_H_ +#define FSFW_TCDISTRIBUTION_TCPACKETCHECKIF_H_ + +#include "../returnvalues/HasReturnvaluesIF.h" + +class SpacePacketBase; + +/** + * This interface is used by PacketCheckers for PUS packets and CFDP packets . + * @ingroup tc_distribution + */ +class TcPacketCheckIF { +public: + /** + * The empty virtual destructor. + */ + virtual ~TcPacketCheckIF() { + } + + /** + * This is the actual method to formally check a certain Packet. + * The packet's Application Data can not be checked here. + * @param current_packet The packet to check + * @return - @c RETURN_OK on success. + * - @c INCORRECT_CHECKSUM if checksum is invalid. + * - @c ILLEGAL_APID if APID does not match. + */ + virtual ReturnValue_t checkPacket(SpacePacketBase* currentPacket) = 0; +}; + +#endif /* FSFW_TCDISTRIBUTION_TCPACKETCHECKIF_H_ */ diff --git a/src/fsfw/tcdistribution/TcPacketCheck.cpp b/src/fsfw/tcdistribution/TcPacketCheckPUS.cpp similarity index 65% rename from src/fsfw/tcdistribution/TcPacketCheck.cpp rename to src/fsfw/tcdistribution/TcPacketCheckPUS.cpp index 44501c58..d106a455 100644 --- a/src/fsfw/tcdistribution/TcPacketCheck.cpp +++ b/src/fsfw/tcdistribution/TcPacketCheckPUS.cpp @@ -1,18 +1,20 @@ -#include "fsfw/tcdistribution/TcPacketCheck.h" +#include "fsfw/tcdistribution/TcPacketCheckPUS.h" #include "fsfw/globalfunctions/CRC.h" -#include "fsfw/tmtcpacket/pus/tc/TcPacketBase.h" +#include "fsfw/tmtcpacket/pus/tc/TcPacketStoredPus.h" +#include "fsfw/tmtcpacket/pus/tc/TcPacketPusBase.h" #include "fsfw/tmtcpacket/pus/tc/TcPacketStoredBase.h" #include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/storagemanager/StorageManagerIF.h" #include "fsfw/tmtcservices/VerificationCodes.h" -TcPacketCheck::TcPacketCheck(uint16_t setApid): apid(setApid) { +TcPacketCheckPUS::TcPacketCheckPUS(uint16_t setApid): apid(setApid) { } -ReturnValue_t TcPacketCheck::checkPacket(TcPacketStoredBase* currentPacket) { - TcPacketBase* tcPacketBase = currentPacket->getPacketBase(); - if(tcPacketBase == nullptr) { +ReturnValue_t TcPacketCheckPUS::checkPacket(SpacePacketBase* currentPacket) { + TcPacketStoredBase* storedPacket = dynamic_cast(currentPacket); + TcPacketPusBase* tcPacketBase = dynamic_cast(currentPacket); + if(tcPacketBase == nullptr or storedPacket == nullptr) { return RETURN_FAILED; } uint16_t calculated_crc = CRC::crc16ccitt(tcPacketBase->getWholeData(), @@ -29,7 +31,7 @@ ReturnValue_t TcPacketCheck::checkPacket(TcPacketStoredBase* currentPacket) { if (tcPacketBase->getAPID() != this->apid) return ILLEGAL_APID; - if (not currentPacket->isSizeCorrect()) { + if (not storedPacket->isSizeCorrect()) { return INCOMPLETE_PACKET; } @@ -41,6 +43,6 @@ ReturnValue_t TcPacketCheck::checkPacket(TcPacketStoredBase* currentPacket) { return RETURN_OK; } -uint16_t TcPacketCheck::getApid() const { +uint16_t TcPacketCheckPUS::getApid() const { return apid; } diff --git a/src/fsfw/tcdistribution/TcPacketCheck.h b/src/fsfw/tcdistribution/TcPacketCheckPUS.h similarity index 73% rename from src/fsfw/tcdistribution/TcPacketCheck.h rename to src/fsfw/tcdistribution/TcPacketCheckPUS.h index 519943c7..ae4c7789 100644 --- a/src/fsfw/tcdistribution/TcPacketCheck.h +++ b/src/fsfw/tcdistribution/TcPacketCheckPUS.h @@ -1,5 +1,7 @@ -#ifndef FSFW_TCDISTRIBUTION_TCPACKETCHECK_H_ -#define FSFW_TCDISTRIBUTION_TCPACKETCHECK_H_ +#ifndef FSFW_TCDISTRIBUTION_TCPACKETCHECKPUS_H_ +#define FSFW_TCDISTRIBUTION_TCPACKETCHECKPUS_H_ + +#include "TcPacketCheckIF.h" #include "fsfw/FSFW.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" @@ -12,7 +14,9 @@ class TcPacketStoredBase; * Currently, it only checks if the APID and CRC are correct. * @ingroup tc_distribution */ -class TcPacketCheck : public HasReturnvaluesIF { +class TcPacketCheckPUS : + public TcPacketCheckIF, + public HasReturnvaluesIF { protected: /** * Describes the version number a packet must have to pass. @@ -49,18 +53,11 @@ public: * The constructor only sets the APID attribute. * @param set_apid The APID to set. */ - TcPacketCheck(uint16_t setApid); - /** - * This is the actual method to formally check a certain Telecommand Packet. - * The packet's Application Data can not be checked here. - * @param current_packet The packt to check - * @return - @c RETURN_OK on success. - * - @c INCORRECT_CHECKSUM if checksum is invalid. - * - @c ILLEGAL_APID if APID does not match. - */ - ReturnValue_t checkPacket(TcPacketStoredBase* currentPacket); + TcPacketCheckPUS(uint16_t setApid); + + ReturnValue_t checkPacket(SpacePacketBase* currentPacket) override; uint16_t getApid() const; }; -#endif /* FSFW_TCDISTRIBUTION_TCPACKETCHECK_H_ */ +#endif /* FSFW_TCDISTRIBUTION_TCPACKETCHECKPUS_H_ */ diff --git a/src/fsfw/tmtcpacket/CMakeLists.txt b/src/fsfw/tmtcpacket/CMakeLists.txt index fdc884ec..e1deaba9 100644 --- a/src/fsfw/tmtcpacket/CMakeLists.txt +++ b/src/fsfw/tmtcpacket/CMakeLists.txt @@ -3,5 +3,6 @@ target_sources(${LIB_FSFW_NAME} PRIVATE SpacePacketBase.cpp ) +add_subdirectory(cfdp) add_subdirectory(packetmatcher) add_subdirectory(pus) \ No newline at end of file diff --git a/src/fsfw/tmtcpacket/RedirectableDataPointerIF.h b/src/fsfw/tmtcpacket/RedirectableDataPointerIF.h new file mode 100644 index 00000000..63a760ec --- /dev/null +++ b/src/fsfw/tmtcpacket/RedirectableDataPointerIF.h @@ -0,0 +1,34 @@ +#ifndef TMTCPACKET_PUS_TC_SETTABLEDATAPOINTERIF_H_ +#define TMTCPACKET_PUS_TC_SETTABLEDATAPOINTERIF_H_ + +#include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include + +/** + * @brief This interface can be used for classes which store a reference to data. It allows + * the implementing class to redirect the data it refers too. + */ +class RedirectableDataPointerIF { +public: + virtual ~RedirectableDataPointerIF() {}; + + /** + * Redirect the data pointer, but allow an implementation to change the data. + * The default implementation also sets a read-only pointer where applicable. + * @param dataPtr + * @param maxSize Maximum allowed size in buffer which holds the data. Can be used for size + * checks if a struct is cast directly onto the data pointer to ensure that the buffer is + * large enough + * @param args Any additional user arguments required to set the data pointer + * @return + * - RETURN_OK if the pointer was set successfully + * - RETURN_FAILED on general error of if the maximum size is too small + */ + virtual ReturnValue_t setData(uint8_t* dataPtr, size_t maxSize, void* args = nullptr) = 0; + +private: +}; + + + +#endif /* FSFW_SRC_FSFW_TMTCPACKET_PUS_TC_SETTABLEDATAPOINTERIF_H_ */ diff --git a/src/fsfw/tmtcpacket/SpacePacket.cpp b/src/fsfw/tmtcpacket/SpacePacket.cpp index cbf82e0d..5284eb5c 100644 --- a/src/fsfw/tmtcpacket/SpacePacket.cpp +++ b/src/fsfw/tmtcpacket/SpacePacket.cpp @@ -5,23 +5,23 @@ SpacePacket::SpacePacket(uint16_t packetDataLength, bool isTelecommand, uint16_t apid, uint16_t sequenceCount): SpacePacketBase( (uint8_t*)&this->localData ) { - initSpacePacketHeader(isTelecommand, false, apid, sequenceCount); - this->setPacketSequenceCount(sequenceCount); - if ( packetDataLength <= sizeof(this->localData.fields.buffer) ) { - this->setPacketDataLength(packetDataLength); - } else { - this->setPacketDataLength( sizeof(this->localData.fields.buffer) ); - } + initSpacePacketHeader(isTelecommand, false, apid, sequenceCount); + this->setPacketSequenceCount(sequenceCount); + if ( packetDataLength <= sizeof(this->localData.fields.buffer) ) { + this->setPacketDataLength(packetDataLength); + } else { + this->setPacketDataLength( sizeof(this->localData.fields.buffer) ); + } } SpacePacket::~SpacePacket( void ) { } bool SpacePacket::addWholeData( const uint8_t* p_Data, uint32_t packet_size ) { - if ( packet_size <= sizeof(this->data) ) { - memcpy( &this->localData.byteStream, p_Data, packet_size ); - return true; - } else { - return false; - } + if ( packet_size <= sizeof(this->data) ) { + memcpy( &this->localData.byteStream, p_Data, packet_size ); + return true; + } else { + return false; + } } diff --git a/src/fsfw/tmtcpacket/SpacePacket.h b/src/fsfw/tmtcpacket/SpacePacket.h index a092712c..d9e51f35 100644 --- a/src/fsfw/tmtcpacket/SpacePacket.h +++ b/src/fsfw/tmtcpacket/SpacePacket.h @@ -26,7 +26,7 @@ public: * @param sequenceCount ets the packet's Source Sequence Count field. */ SpacePacket(uint16_t packetDataLength, bool isTelecommand = false, - uint16_t apid = APID_IDLE_PACKET, uint16_t sequenceCount = 0); + uint16_t apid = APID_IDLE_PACKET, uint16_t sequenceCount = 0); /** * The class's default destructor. */ diff --git a/src/fsfw/tmtcpacket/SpacePacketBase.cpp b/src/fsfw/tmtcpacket/SpacePacketBase.cpp index 16883d7f..58f4feea 100644 --- a/src/fsfw/tmtcpacket/SpacePacketBase.cpp +++ b/src/fsfw/tmtcpacket/SpacePacketBase.cpp @@ -110,10 +110,6 @@ uint8_t* SpacePacketBase::getWholeData() { return (uint8_t*)this->data; } -void SpacePacketBase::setData( const uint8_t* p_Data ) { - this->data = (SpacePacketPointer*)p_Data; -} - uint32_t SpacePacketBase::getApidAndSequenceCount() const { return (getAPID() << 16) + getPacketSequenceCount(); } @@ -121,3 +117,11 @@ uint32_t SpacePacketBase::getApidAndSequenceCount() const { uint8_t* SpacePacketBase::getPacketData() { return &(data->packet_data); } + +ReturnValue_t SpacePacketBase::setData(uint8_t *pData, size_t maxSize, void *args) { + if(maxSize < 6) { + return HasReturnvaluesIF::RETURN_FAILED; + } + this->data = reinterpret_cast(const_cast(pData)); + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/src/fsfw/tmtcpacket/SpacePacketBase.h b/src/fsfw/tmtcpacket/SpacePacketBase.h index 1ebc484f..dfc808e3 100644 --- a/src/fsfw/tmtcpacket/SpacePacketBase.h +++ b/src/fsfw/tmtcpacket/SpacePacketBase.h @@ -1,6 +1,7 @@ #ifndef FSFW_TMTCPACKET_SPACEPACKETBASE_H_ #define FSFW_TMTCPACKET_SPACEPACKETBASE_H_ +#include #include "ccsds_header.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" @@ -37,7 +38,7 @@ struct SpacePacketPointer { * the most significant bit (from left). * @ingroup tmtcpackets */ -class SpacePacketBase { +class SpacePacketBase: virtual public RedirectableDataPointerIF { protected: /** * A pointer to a structure which defines the data structure of @@ -70,8 +71,7 @@ public: */ virtual ~SpacePacketBase(); - //CCSDS Methods - + //CCSDS Methods: /** * Getter for the packet version number field. * @return Returns the highest three bit of the packet in one byte. @@ -163,7 +163,7 @@ public: */ void setPacketDataLength( uint16_t setLength ); - // Helper methods + //Helper methods: /** * This method returns a raw uint8_t pointer to the packet. * @return A \c uint8_t pointer to the first byte of the CCSDS primary header. @@ -171,12 +171,14 @@ public: virtual uint8_t* getWholeData( void ); uint8_t* getPacketData(); + /** * With this method, the packet data pointer can be redirected to another * location. * @param p_Data A pointer to another raw Space Packet. */ - virtual void setData( const uint8_t* p_Data ); + virtual ReturnValue_t setData(uint8_t* p_Data , size_t maxSize, + void* args = nullptr) override; /** * This method returns the full raw packet size. * @return The full size of the packet in bytes. diff --git a/src/fsfw/tmtcpacket/cfdp/CFDPPacket.cpp b/src/fsfw/tmtcpacket/cfdp/CFDPPacket.cpp new file mode 100644 index 00000000..6172201e --- /dev/null +++ b/src/fsfw/tmtcpacket/cfdp/CFDPPacket.cpp @@ -0,0 +1,20 @@ +#include "fsfw/tmtcpacket/cfdp/CFDPPacket.h" + +#include "fsfw/globalfunctions/CRC.h" +#include "fsfw/globalfunctions/arrayprinter.h" +#include "fsfw/serviceinterface/ServiceInterface.h" + +#include + +CFDPPacket::CFDPPacket(const uint8_t* setData): SpacePacketBase(setData) {} + +CFDPPacket::~CFDPPacket() {} + +void CFDPPacket::print() { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::info << "CFDPPacket::print:" << std::endl; +#else + sif::printInfo("CFDPPacket::print:\n"); +#endif + arrayprinter::print(getWholeData(), getFullSize()); +} diff --git a/src/fsfw/tmtcpacket/cfdp/CFDPPacket.h b/src/fsfw/tmtcpacket/cfdp/CFDPPacket.h new file mode 100644 index 00000000..f288a8ae --- /dev/null +++ b/src/fsfw/tmtcpacket/cfdp/CFDPPacket.h @@ -0,0 +1,27 @@ +#ifndef FSFW_INC_FSFW_TMTCPACKET_CFDP_CFDPPACKET_H_ +#define FSFW_INC_FSFW_TMTCPACKET_CFDP_CFDPPACKET_H_ + +#include "fsfw/tmtcpacket/SpacePacketBase.h" + +class CFDPPacket : public SpacePacketBase { +public: + /** + * This is the default constructor. + * It sets its internal data pointer to the address passed and also + * forwards the data pointer to the parent SpacePacketBase class. + * @param setData The position where the packet data lies. + */ + CFDPPacket( const uint8_t* setData ); + /** + * This is the empty default destructor. + */ + virtual ~CFDPPacket(); + + /** + * This is a debugging helper method that prints the whole packet content + * to the screen. + */ + void print(); +}; + +#endif /* FSFW_INC_FSFW_TMTCPACKET_CFDP_CFDPPACKET_H_ */ diff --git a/src/fsfw/tmtcpacket/cfdp/CFDPPacketStored.cpp b/src/fsfw/tmtcpacket/cfdp/CFDPPacketStored.cpp new file mode 100644 index 00000000..568d8981 --- /dev/null +++ b/src/fsfw/tmtcpacket/cfdp/CFDPPacketStored.cpp @@ -0,0 +1,97 @@ +#include "fsfw/tmtcpacket/cfdp/CFDPPacketStored.h" +#include "fsfw/objectmanager/ObjectManager.h" + +StorageManagerIF* CFDPPacketStored::store = nullptr; + +CFDPPacketStored::CFDPPacketStored(): CFDPPacket(nullptr) { +} + +CFDPPacketStored::CFDPPacketStored(store_address_t setAddress): CFDPPacket(nullptr) { + this->setStoreAddress(setAddress); +} + +CFDPPacketStored::CFDPPacketStored(const uint8_t* data, size_t size): CFDPPacket(data) { + if (this->getFullSize() != size) { + return; + } + if (this->checkAndSetStore()) { + ReturnValue_t status = store->addData(&storeAddress, data, size); + if (status != HasReturnvaluesIF::RETURN_OK) { + this->setData(nullptr, -1); + } + const uint8_t* storePtr = nullptr; + // Repoint base data pointer to the data in the store. + store->getData(storeAddress, &storePtr, &size); + this->setData(const_cast(storePtr), size); + } +} + +ReturnValue_t CFDPPacketStored::deletePacket() { + ReturnValue_t result = this->store->deleteData(this->storeAddress); + this->storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; + // To circumvent size checks + this->setData(nullptr, -1); + return result; +} + +//CFDPPacket* CFDPPacketStored::getPacketBase() { +// return this; +//} +void CFDPPacketStored::setStoreAddress(store_address_t setAddress) { + this->storeAddress = setAddress; + const uint8_t* tempData = nullptr; + size_t tempSize; + ReturnValue_t status = StorageManagerIF::RETURN_FAILED; + if (this->checkAndSetStore()) { + status = this->store->getData(this->storeAddress, &tempData, &tempSize); + } + if (status == StorageManagerIF::RETURN_OK) { + this->setData(const_cast(tempData), tempSize); + } else { + // To circumvent size checks + this->setData(nullptr, -1); + this->storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; + } +} + +store_address_t CFDPPacketStored::getStoreAddress() { + return this->storeAddress; +} + +CFDPPacketStored::~CFDPPacketStored() { +} + +ReturnValue_t CFDPPacketStored::getData(const uint8_t **dataPtr, size_t *dataSize) { + return HasReturnvaluesIF::RETURN_OK; +} + +//ReturnValue_t CFDPPacketStored::setData(const uint8_t *data) { +// return HasReturnvaluesIF::RETURN_OK; +//} + +bool CFDPPacketStored::checkAndSetStore() { + if (this->store == nullptr) { + this->store = ObjectManager::instance()->get(objects::TC_STORE); + if (this->store == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::error << "CFDPPacketStored::CFDPPacketStored: TC Store not found!" + << std::endl; +#endif + return false; + } + } + return true; +} + +bool CFDPPacketStored::isSizeCorrect() { + const uint8_t* temp_data = nullptr; + size_t temp_size; + ReturnValue_t status = this->store->getData(this->storeAddress, &temp_data, + &temp_size); + if (status == StorageManagerIF::RETURN_OK) { + if (this->getFullSize() == temp_size) { + return true; + } + } + return false; +} diff --git a/src/fsfw/tmtcpacket/cfdp/CFDPPacketStored.h b/src/fsfw/tmtcpacket/cfdp/CFDPPacketStored.h new file mode 100644 index 00000000..2c03439b --- /dev/null +++ b/src/fsfw/tmtcpacket/cfdp/CFDPPacketStored.h @@ -0,0 +1,67 @@ +#ifndef FSFW_INC_FSFW_TMTCPACKET_CFDP_CFDPPACKETSTORED_H_ +#define FSFW_INC_FSFW_TMTCPACKET_CFDP_CFDPPACKETSTORED_H_ + +#include "../pus/tc/TcPacketStoredBase.h" +#include "CFDPPacket.h" + +class CFDPPacketStored: + public CFDPPacket, + public TcPacketStoredBase { +public: + /** + * Create stored packet with existing data. + * @param data + * @param size + */ + CFDPPacketStored(const uint8_t* data, size_t size); + /** + * Create stored packet from existing packet in store + * @param setAddress + */ + CFDPPacketStored(store_address_t setAddress); + CFDPPacketStored(); + + virtual ~CFDPPacketStored(); + + /** + * Getter function for the raw data. + * @param dataPtr [out] Pointer to the data pointer to set + * @param dataSize [out] Address of size to set. + * @return -@c RETURN_OK if data was retrieved successfully. + */ + ReturnValue_t getData(const uint8_t ** dataPtr, size_t* dataSize); + + void setStoreAddress(store_address_t setAddress); + + store_address_t getStoreAddress(); + + ReturnValue_t deletePacket(); + +private: + + bool isSizeCorrect(); +protected: + /** + * This is a pointer to the store all instances of the class use. + * If the store is not yet set (i.e. @c store is NULL), every constructor + * call tries to set it and throws an error message in case of failures. + * The default store is objects::TC_STORE. + */ + static StorageManagerIF* store; + /** + * The address where the packet data of the object instance is stored. + */ + store_address_t storeAddress; + /** + * A helper method to check if a store is assigned to the class. + * If not, the method tries to retrieve the store from the global + * ObjectManager. + * @return @li @c true if the store is linked or could be created. + * @li @c false otherwise. + */ + bool checkAndSetStore(); +}; + + + +#endif /* FSFW_INC_FSFW_TMTCPACKET_CFDP_CFDPPACKETSTORED_H_ */ diff --git a/src/fsfw/tmtcpacket/cfdp/CMakeLists.txt b/src/fsfw/tmtcpacket/cfdp/CMakeLists.txt new file mode 100644 index 00000000..0b7ab18a --- /dev/null +++ b/src/fsfw/tmtcpacket/cfdp/CMakeLists.txt @@ -0,0 +1,4 @@ +target_sources(${LIB_FSFW_NAME} PRIVATE + CFDPPacket.cpp + CFDPPacketStored.cpp +) diff --git a/src/fsfw/tmtcpacket/pus/tc/CMakeLists.txt b/src/fsfw/tmtcpacket/pus/tc/CMakeLists.txt index 723b7943..dc611263 100644 --- a/src/fsfw/tmtcpacket/pus/tc/CMakeLists.txt +++ b/src/fsfw/tmtcpacket/pus/tc/CMakeLists.txt @@ -1,5 +1,5 @@ target_sources(${LIB_FSFW_NAME} PRIVATE - TcPacketBase.cpp + TcPacketPusBase.cpp TcPacketPus.cpp TcPacketStoredBase.cpp TcPacketStoredPus.cpp diff --git a/src/fsfw/tmtcpacket/pus/tc/TcPacketPus.cpp b/src/fsfw/tmtcpacket/pus/tc/TcPacketPus.cpp index 2b97b0d2..dc1eb4bf 100644 --- a/src/fsfw/tmtcpacket/pus/tc/TcPacketPus.cpp +++ b/src/fsfw/tmtcpacket/pus/tc/TcPacketPus.cpp @@ -3,7 +3,7 @@ #include -TcPacketPus::TcPacketPus(const uint8_t *setData): TcPacketBase(setData) { +TcPacketPus::TcPacketPus(const uint8_t *setData): TcPacketPusBase(setData) { tcData = reinterpret_cast(const_cast(setData)); } @@ -59,13 +59,6 @@ void TcPacketPus::setErrorControl() { (&tcData->appData)[size + 1] = (crc) & 0X00FF; // CRCL } -void TcPacketPus::setData(const uint8_t* pData) { - SpacePacketBase::setData(pData); - // This function is const-correct, but it was decided to keep the pointer non-const - // for convenience. Therefore, cast aways constness here and then cast to packet type. - tcData = reinterpret_cast(const_cast(pData)); -} - uint8_t TcPacketPus::getSecondaryHeaderFlag() const { #if FSFW_USE_PUS_C_TELECOMMANDS == 1 // Does not exist for PUS C @@ -93,5 +86,20 @@ uint16_t TcPacketPus::getSourceId() const { size_t TcPacketPus::calculateFullPacketLength(size_t appDataLen) const { return sizeof(CCSDSPrimaryHeader) + sizeof(PUSTcDataFieldHeader) + - appDataLen + TcPacketBase::CRC_SIZE; + appDataLen + TcPacketPusBase::CRC_SIZE; } + +ReturnValue_t TcPacketPus::setData(uint8_t *dataPtr, size_t maxSize, void *args) { + ReturnValue_t result = SpacePacketBase::setData(dataPtr, maxSize); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if(maxSize < sizeof(TcPacketPointer)) { + return HasReturnvaluesIF::RETURN_FAILED; + } + // This function is const-correct, but it was decided to keep the pointer non-const + // for convenience. Therefore, cast away constness here and then cast to packet type. + tcData = reinterpret_cast(const_cast(dataPtr)); + return HasReturnvaluesIF::RETURN_OK; +} + diff --git a/src/fsfw/tmtcpacket/pus/tc/TcPacketPus.h b/src/fsfw/tmtcpacket/pus/tc/TcPacketPus.h index 1bacc3a7..1b0facaf 100644 --- a/src/fsfw/tmtcpacket/pus/tc/TcPacketPus.h +++ b/src/fsfw/tmtcpacket/pus/tc/TcPacketPus.h @@ -4,7 +4,7 @@ #include "fsfw/FSFW.h" #include "../definitions.h" #include "fsfw/tmtcpacket/ccsds_header.h" -#include "TcPacketBase.h" +#include "TcPacketPusBase.h" #include @@ -38,7 +38,7 @@ struct TcPacketPointer { }; -class TcPacketPus: public TcPacketBase { +class TcPacketPus: public TcPacketPusBase { public: static const uint16_t TC_PACKET_MIN_SIZE = (sizeof(CCSDSPrimaryHeader) + sizeof(PUSTcDataFieldHeader) + 2); @@ -65,7 +65,8 @@ public: protected: - void setData(const uint8_t* pData) override; + ReturnValue_t setData(uint8_t* dataPtr, size_t maxSize, + void* args = nullptr) override; /** * Initializes the Tc Packet header. diff --git a/src/fsfw/tmtcpacket/pus/tc/TcPacketBase.cpp b/src/fsfw/tmtcpacket/pus/tc/TcPacketPusBase.cpp similarity index 65% rename from src/fsfw/tmtcpacket/pus/tc/TcPacketBase.cpp rename to src/fsfw/tmtcpacket/pus/tc/TcPacketPusBase.cpp index 0c7a4183..1a8850b1 100644 --- a/src/fsfw/tmtcpacket/pus/tc/TcPacketBase.cpp +++ b/src/fsfw/tmtcpacket/pus/tc/TcPacketPusBase.cpp @@ -1,4 +1,4 @@ -#include "fsfw/tmtcpacket/pus/tc/TcPacketBase.h" +#include "TcPacketPusBase.h" #include "fsfw/globalfunctions/CRC.h" #include "fsfw/globalfunctions/arrayprinter.h" @@ -6,11 +6,11 @@ #include -TcPacketBase::TcPacketBase(const uint8_t* setData): SpacePacketBase(setData) {} +TcPacketPusBase::TcPacketPusBase(const uint8_t* setData): SpacePacketBase(setData) {} -TcPacketBase::~TcPacketBase() {} +TcPacketPusBase::~TcPacketPusBase() {} -void TcPacketBase::print() { +void TcPacketPusBase::print() { #if FSFW_CPP_OSTREAM_ENABLED == 1 sif::info << "TcPacketBase::print:" << std::endl; #else diff --git a/src/fsfw/tmtcpacket/pus/tc/TcPacketBase.h b/src/fsfw/tmtcpacket/pus/tc/TcPacketPusBase.h similarity index 93% rename from src/fsfw/tmtcpacket/pus/tc/TcPacketBase.h rename to src/fsfw/tmtcpacket/pus/tc/TcPacketPusBase.h index 14356c8c..b65ca0fb 100644 --- a/src/fsfw/tmtcpacket/pus/tc/TcPacketBase.h +++ b/src/fsfw/tmtcpacket/pus/tc/TcPacketPusBase.h @@ -1,6 +1,7 @@ #ifndef TMTCPACKET_PUS_TCPACKETBASE_H_ #define TMTCPACKET_PUS_TCPACKETBASE_H_ +#include #include "fsfw/tmtcpacket/SpacePacketBase.h" #include @@ -15,7 +16,8 @@ * check can be performed by making use of the getWholeData method. * @ingroup tmtcpackets */ -class TcPacketBase : public SpacePacketBase { +class TcPacketPusBase : public SpacePacketBase, + virtual public RedirectableDataPointerIF { friend class TcPacketStoredBase; public: @@ -41,11 +43,11 @@ public: * forwards the data pointer to the parent SpacePacketBase class. * @param setData The position where the packet data lies. */ - TcPacketBase( const uint8_t* setData ); + TcPacketPusBase( const uint8_t* setData ); /** * This is the empty default destructor. */ - virtual ~TcPacketBase(); + virtual ~TcPacketPusBase(); /** * This command returns the CCSDS Secondary Header Flag. @@ -133,6 +135,7 @@ public: * to the screen. */ void print(); + protected: /** @@ -143,7 +146,8 @@ protected: * * @param p_data A pointer to another PUS Telecommand Packet. */ - void setData( const uint8_t* pData ) = 0; + virtual ReturnValue_t setData(uint8_t* pData, size_t maxSize, + void* args = nullptr) override = 0; }; diff --git a/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredBase.cpp b/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredBase.cpp index 98ce1725..35bfdfeb 100644 --- a/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredBase.cpp +++ b/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredBase.cpp @@ -46,7 +46,8 @@ bool TcPacketStoredBase::checkAndSetStore() { return true; } -void TcPacketStoredBase::setStoreAddress(store_address_t setAddress) { +void TcPacketStoredBase::setStoreAddress(store_address_t setAddress, + RedirectableDataPointerIF* packet) { this->storeAddress = setAddress; const uint8_t* tempData = nullptr; size_t tempSize; @@ -54,15 +55,12 @@ void TcPacketStoredBase::setStoreAddress(store_address_t setAddress) { if (this->checkAndSetStore()) { status = this->store->getData(this->storeAddress, &tempData, &tempSize); } - TcPacketBase* tcPacketBase = this->getPacketBase(); - if(tcPacketBase == nullptr) { - return; - } + if (status == StorageManagerIF::RETURN_OK) { - tcPacketBase->setData(tempData); + packet->setData(const_cast(tempData), tempSize); } else { - tcPacketBase->setData(nullptr); + packet->setData(nullptr, -1); this->storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; } } diff --git a/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredBase.h b/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredBase.h index 1e1681f6..045d40d8 100644 --- a/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredBase.h +++ b/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredBase.h @@ -2,16 +2,10 @@ #define TMTCPACKET_PUS_TCPACKETSTORED_H_ #include "TcPacketStoredIF.h" -#include "../../../storagemanager/StorageManagerIF.h" +#include "fsfw/storagemanager/StorageManagerIF.h" /** - * This class generates a ECSS PUS Telecommand packet within a given - * intermediate storage. - * As most packets are passed between tasks with the help of a storage - * anyway, it seems logical to create a Packet-In-Storage access class - * which saves the user almost all storage handling operation. - * Packets can both be newly created with the class and be "linked" to - * packets in a store with the help of a storeAddress. + * Base class for telecommand packets like CFDP or PUS packets. * @ingroup tmtcpackets */ class TcPacketStoredBase: public TcPacketStoredIF { @@ -44,7 +38,7 @@ public: */ ReturnValue_t getData(const uint8_t ** dataPtr, size_t* dataSize) override; - void setStoreAddress(store_address_t setAddress) override; + void setStoreAddress(store_address_t setAddress, RedirectableDataPointerIF* packet) override; store_address_t getStoreAddress() override; /** diff --git a/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredIF.h b/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredIF.h index 3d356725..4beafedc 100644 --- a/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredIF.h +++ b/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredIF.h @@ -1,9 +1,10 @@ #ifndef FSFW_TMTCPACKET_PUS_TCPACKETSTOREDIF_H_ #define FSFW_TMTCPACKET_PUS_TCPACKETSTOREDIF_H_ -#include "TcPacketBase.h" -#include "../../../storagemanager/storeAddress.h" -#include "../../../returnvalues/HasReturnvaluesIF.h" +#include +#include "TcPacketPusBase.h" +#include "fsfw/storagemanager/storeAddress.h" +#include "fsfw/returnvalues/HasReturnvaluesIF.h" class TcPacketStoredIF { public: @@ -14,7 +15,7 @@ public: * if the packet is a class member and used for more than one packet. * @param setAddress The new packet id to link to. */ - virtual void setStoreAddress(store_address_t setAddress) = 0; + virtual void setStoreAddress(store_address_t setAddress, RedirectableDataPointerIF* packet) = 0; virtual store_address_t getStoreAddress() = 0; @@ -25,12 +26,6 @@ public: * @return -@c RETURN_OK if data was retrieved successfully. */ virtual ReturnValue_t getData(const uint8_t ** dataPtr, size_t* dataSize) = 0; - - /** - * Get packet base pointer which can be used to get access to PUS packet fields - * @return - */ - virtual TcPacketBase* getPacketBase() = 0; }; diff --git a/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredPus.cpp b/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredPus.cpp index 7f8f4ac8..f1ad13e1 100644 --- a/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredPus.cpp +++ b/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredPus.cpp @@ -22,7 +22,7 @@ TcPacketStoredPus::TcPacketStoredPus(uint16_t apid, uint8_t service, #endif return; } - this->setData(pData); + this->setData(pData, TC_PACKET_MIN_SIZE + size); #if FSFW_USE_PUS_C_TELECOMMANDS == 1 pus::PusVersion pusVersion = pus::PusVersion::PUS_C_VERSION; #else @@ -39,7 +39,7 @@ TcPacketStoredPus::TcPacketStoredPus(): TcPacketStoredBase(), TcPacketPus(nullpt } TcPacketStoredPus::TcPacketStoredPus(store_address_t setAddress): TcPacketPus(nullptr) { - TcPacketStoredBase::setStoreAddress(setAddress); + TcPacketStoredBase::setStoreAddress(setAddress, this); } TcPacketStoredPus::TcPacketStoredPus(const uint8_t* data, size_t size): TcPacketPus(data) { @@ -49,23 +49,24 @@ TcPacketStoredPus::TcPacketStoredPus(const uint8_t* data, size_t size): TcPacket if (this->checkAndSetStore()) { ReturnValue_t status = store->addData(&storeAddress, data, size); if (status != HasReturnvaluesIF::RETURN_OK) { - this->setData(nullptr); + this->setData(nullptr, size); } const uint8_t* storePtr = nullptr; // Repoint base data pointer to the data in the store. store->getData(storeAddress, &storePtr, &size); - this->setData(storePtr); + this->setData(const_cast(storePtr), size); } } ReturnValue_t TcPacketStoredPus::deletePacket() { ReturnValue_t result = this->store->deleteData(this->storeAddress); this->storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; - this->setData(nullptr); + // To circumvent size checks + this->setData(nullptr, -1); return result; } -TcPacketBase* TcPacketStoredPus::getPacketBase() { +TcPacketPusBase* TcPacketStoredPus::getPacketBase() { return this; } diff --git a/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredPus.h b/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredPus.h index 8b318733..f0434b33 100644 --- a/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredPus.h +++ b/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredPus.h @@ -26,7 +26,7 @@ public: */ TcPacketStoredPus(uint16_t apid, uint8_t service, uint8_t subservice, uint8_t sequence_count = 0, const uint8_t* data = nullptr, - size_t size = 0, uint8_t ack = TcPacketBase::ACK_ALL); + size_t size = 0, uint8_t ack = TcPacketPusBase::ACK_ALL); /** * Create stored packet with existing data. * @param data @@ -41,7 +41,7 @@ public: TcPacketStoredPus(); ReturnValue_t deletePacket() override; - TcPacketBase* getPacketBase() override; + TcPacketPusBase* getPacketBase(); private: diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketPusA.cpp b/src/fsfw/tmtcpacket/pus/tm/TmPacketPusA.cpp index ccf5a8ac..933a6b4c 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketPusA.cpp +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketPusA.cpp @@ -36,9 +36,13 @@ uint16_t TmPacketPusA::getSourceDataSize() { - CRC_SIZE + 1; } -void TmPacketPusA::setData(const uint8_t* p_Data) { - SpacePacketBase::setData(p_Data); - tmData = (TmPacketPointerPusA*) p_Data; +ReturnValue_t TmPacketPusA::setData(uint8_t* p_Data, size_t maxSize, void* args) { + ReturnValue_t result = SpacePacketBase::setData(p_Data, maxSize); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + tmData = reinterpret_cast(const_cast(p_Data)); + return HasReturnvaluesIF::RETURN_OK; } diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketPusA.h b/src/fsfw/tmtcpacket/pus/tm/TmPacketPusA.h index 3856c779..9bb01890 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketPusA.h +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketPusA.h @@ -110,7 +110,8 @@ protected: * * @param p_data A pointer to another PUS Telemetry Packet. */ - void setData( const uint8_t* pData ); + ReturnValue_t setData(uint8_t* pData, size_t maxSize, + void* args = nullptr) override; /** * In case data was filled manually (almost never the case). diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketPusC.cpp b/src/fsfw/tmtcpacket/pus/tm/TmPacketPusC.cpp index 003d565e..f33a896a 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketPusC.cpp +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketPusC.cpp @@ -35,9 +35,16 @@ uint16_t TmPacketPusC::getSourceDataSize() { return getPacketDataLength() - sizeof(tmData->dataField) - CRC_SIZE + 1; } -void TmPacketPusC::setData(const uint8_t* p_Data) { - SpacePacketBase::setData(p_Data); - tmData = (TmPacketPointerPusC*) p_Data; +ReturnValue_t TmPacketPusC::setData(uint8_t* p_Data, size_t maxSize, void* args) { + ReturnValue_t result = SpacePacketBase::setData(p_Data, maxSize); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if(maxSize < sizeof(TmPacketPointerPusC)) { + return HasReturnvaluesIF::RETURN_OK; + } + tmData = reinterpret_cast(const_cast(p_Data)); + return HasReturnvaluesIF::RETURN_OK; } diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketPusC.h b/src/fsfw/tmtcpacket/pus/tm/TmPacketPusC.h index 3a9be132..b3780183 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketPusC.h +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketPusC.h @@ -110,9 +110,9 @@ protected: * This call overwrites the parent's setData method to set both its * @c tc_data pointer and the parent's @c data pointer. * - * @param p_data A pointer to another PUS Telemetry Packet. + * @param pData A pointer to another PUS Telemetry Packet. */ - void setData( const uint8_t* pData ); + ReturnValue_t setData(uint8_t* pData, size_t maxSize, void* args = nullptr) override; /** * In case data was filled manually (almost never the case). diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredBase.cpp b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredBase.cpp index 523fb619..f2cc5a67 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredBase.cpp +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredBase.cpp @@ -27,7 +27,7 @@ store_address_t TmPacketStoredBase::getStoreAddress() { void TmPacketStoredBase::deletePacket() { store->deleteData(storeAddress); storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; - setDataPointer(nullptr); + setData(nullptr, -1); } void TmPacketStoredBase::setStoreAddress(store_address_t setAddress) { @@ -39,9 +39,9 @@ void TmPacketStoredBase::setStoreAddress(store_address_t setAddress) { } ReturnValue_t status = store->getData(storeAddress, &tempData, &tempSize); if (status == StorageManagerIF::RETURN_OK) { - setDataPointer(tempData); + setData(const_cast(tempData), tempSize); } else { - setDataPointer(nullptr); + setData(nullptr, -1); storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; } } diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredBase.h b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredBase.h index 91ca2f93..372b1e63 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredBase.h +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredBase.h @@ -21,7 +21,7 @@ * packets in a store with the help of a storeAddress. * @ingroup tmtcpackets */ -class TmPacketStoredBase { +class TmPacketStoredBase: virtual public RedirectableDataPointerIF { public: /** * This is a default constructor which does not set the data pointer. @@ -33,7 +33,6 @@ public: virtual ~TmPacketStoredBase(); virtual uint8_t* getAllTmData() = 0; - virtual void setDataPointer(const uint8_t* newPointer) = 0; /** * This is a getter for the current store address of the packet. diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusA.cpp b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusA.cpp index 4ffacce4..b4b396b5 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusA.cpp +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusA.cpp @@ -26,7 +26,7 @@ TmPacketStoredPusA::TmPacketStoredPusA(uint16_t apid, uint8_t service, handleStoreFailure("A", returnValue, sizeToReserve); return; } - setData(pData); + setData(pData, sizeToReserve); initializeTmPacket(apid, service, subservice, packetSubcounter); memcpy(getSourceData(), headerData, headerSize); memcpy(getSourceData() + headerSize, data, size); @@ -56,7 +56,7 @@ TmPacketStoredPusA::TmPacketStoredPusA(uint16_t apid, uint8_t service, handleStoreFailure("A", returnValue, sizeToReserve); return; } - setData(pData); + setData(pData, sizeToReserve); initializeTmPacket(apid, service, subservice, packetSubcounter); uint8_t *putDataHere = getSourceData(); size_t size = 0; @@ -75,6 +75,6 @@ uint8_t* TmPacketStoredPusA::getAllTmData() { return getWholeData(); } -void TmPacketStoredPusA::setDataPointer(const uint8_t *newPointer) { - setData(newPointer); +ReturnValue_t TmPacketStoredPusA::setData(uint8_t *newPointer, size_t maxSize, void* args) { + return TmPacketPusA::setData(newPointer, maxSize); } diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusA.h b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusA.h index 6a338cd5..6fa80949 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusA.h +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusA.h @@ -57,7 +57,17 @@ public: SerializeIF* header = nullptr); uint8_t* getAllTmData() override; - void setDataPointer(const uint8_t* newPointer) override; + +private: + + /** + * Implementation required by base class + * @param newPointer + * @param maxSize + * @param args + * @return + */ + ReturnValue_t setData(uint8_t* newPointer, size_t maxSize, void* args = nullptr) override; }; diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusC.cpp b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusC.cpp index ee574299..8d7dd9eb 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusC.cpp +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusC.cpp @@ -27,7 +27,7 @@ TmPacketStoredPusC::TmPacketStoredPusC(uint16_t apid, uint8_t service, handleStoreFailure("C", returnValue, sizeToReserve); return; } - setData(pData); + setData(pData, sizeToReserve); initializeTmPacket(apid, service, subservice, packetSubcounter, destinationId, timeRefField); memcpy(getSourceData(), headerData, headerSize); memcpy(getSourceData() + headerSize, data, size); @@ -56,7 +56,7 @@ TmPacketStoredPusC::TmPacketStoredPusC(uint16_t apid, uint8_t service, handleStoreFailure("C", returnValue, sizeToReserve); return; } - setData(pData); + TmPacketPusC::setData(pData, sizeToReserve); initializeTmPacket(apid, service, subservice, packetSubcounter, destinationId, timeRefField); uint8_t *putDataHere = getSourceData(); size_t size = 0; @@ -76,6 +76,7 @@ uint8_t* TmPacketStoredPusC::getAllTmData() { return getWholeData(); } -void TmPacketStoredPusC::setDataPointer(const uint8_t *newPointer) { - setData(newPointer); +ReturnValue_t TmPacketStoredPusC::setData(uint8_t *newPointer, size_t maxSize, + void* args) { + return TmPacketPusC::setData(newPointer, maxSize); } diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusC.h b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusC.h index 35c66083..cbf62b1b 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusC.h +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusC.h @@ -59,7 +59,17 @@ public: SerializeIF* header = nullptr, uint16_t destinationId = 0, uint8_t timeRefField = 0); uint8_t* getAllTmData() override; - void setDataPointer(const uint8_t* newPointer) override; + +private: + + /** + * Implementation required by base class + * @param newPointer + * @param maxSize + * @param args + * @return + */ + ReturnValue_t setData(uint8_t* newPointer, size_t maxSize, void* args = nullptr) override; }; diff --git a/src/fsfw/tmtcservices/CommandingServiceBase.cpp b/src/fsfw/tmtcservices/CommandingServiceBase.cpp index 10805b47..00fed415 100644 --- a/src/fsfw/tmtcservices/CommandingServiceBase.cpp +++ b/src/fsfw/tmtcservices/CommandingServiceBase.cpp @@ -13,300 +13,300 @@ object_id_t CommandingServiceBase::defaultPacketSource = objects::NO_OBJECT; object_id_t CommandingServiceBase::defaultPacketDestination = objects::NO_OBJECT; CommandingServiceBase::CommandingServiceBase(object_id_t setObjectId, - uint16_t apid, uint8_t service, uint8_t numberOfParallelCommands, - uint16_t commandTimeoutSeconds, size_t queueDepth) : - SystemObject(setObjectId), apid(apid), service(service), - timeoutSeconds(commandTimeoutSeconds), - commandMap(numberOfParallelCommands) { - commandQueue = QueueFactory::instance()->createMessageQueue(queueDepth); - requestQueue = QueueFactory::instance()->createMessageQueue(queueDepth); + uint16_t apid, uint8_t service, uint8_t numberOfParallelCommands, + uint16_t commandTimeoutSeconds, size_t queueDepth) : + SystemObject(setObjectId), apid(apid), service(service), + timeoutSeconds(commandTimeoutSeconds), + commandMap(numberOfParallelCommands) { + commandQueue = QueueFactory::instance()->createMessageQueue(queueDepth); + requestQueue = QueueFactory::instance()->createMessageQueue(queueDepth); } void CommandingServiceBase::setPacketSource(object_id_t packetSource) { - this->packetSource = packetSource; + this->packetSource = packetSource; } void CommandingServiceBase::setPacketDestination( - object_id_t packetDestination) { - this->packetDestination = packetDestination; + object_id_t packetDestination) { + this->packetDestination = packetDestination; } CommandingServiceBase::~CommandingServiceBase() { - QueueFactory::instance()->deleteMessageQueue(commandQueue); - QueueFactory::instance()->deleteMessageQueue(requestQueue); + QueueFactory::instance()->deleteMessageQueue(commandQueue); + QueueFactory::instance()->deleteMessageQueue(requestQueue); } ReturnValue_t CommandingServiceBase::performOperation(uint8_t opCode) { - handleCommandQueue(); - handleRequestQueue(); - checkTimeout(); - doPeriodicOperation(); - return RETURN_OK; + handleCommandQueue(); + handleRequestQueue(); + checkTimeout(); + doPeriodicOperation(); + return RETURN_OK; } uint16_t CommandingServiceBase::getIdentifier() { - return service; + return service; } MessageQueueId_t CommandingServiceBase::getRequestQueue() { - return requestQueue->getId(); + return requestQueue->getId(); } ReturnValue_t CommandingServiceBase::initialize() { - ReturnValue_t result = SystemObject::initialize(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + ReturnValue_t result = SystemObject::initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - if(packetDestination == objects::NO_OBJECT) { - packetDestination = defaultPacketDestination; - } - AcceptsTelemetryIF* packetForwarding = - ObjectManager::instance()->get(packetDestination); + if(packetDestination == objects::NO_OBJECT) { + packetDestination = defaultPacketDestination; + } + AcceptsTelemetryIF* packetForwarding = + ObjectManager::instance()->get(packetDestination); - if(packetSource == objects::NO_OBJECT) { - packetSource = defaultPacketSource; - } - PUSDistributorIF* distributor = ObjectManager::instance()->get( - packetSource); + if(packetSource == objects::NO_OBJECT) { + packetSource = defaultPacketSource; + } + PUSDistributorIF* distributor = ObjectManager::instance()->get( + packetSource); - if (packetForwarding == nullptr or distributor == nullptr) { + if (packetForwarding == nullptr or distributor == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "CommandingServiceBase::intialize: Packet source or " - "packet destination invalid!" << std::endl; + sif::error << "CommandingServiceBase::intialize: Packet source or " + "packet destination invalid!" << std::endl; #endif - return ObjectManagerIF::CHILD_INIT_FAILED; - } + return ObjectManagerIF::CHILD_INIT_FAILED; + } - distributor->registerService(this); - requestQueue->setDefaultDestination( - packetForwarding->getReportReceptionQueue()); + distributor->registerService(this); + requestQueue->setDefaultDestination( + packetForwarding->getReportReceptionQueue()); - IPCStore = ObjectManager::instance()->get(objects::IPC_STORE); - TCStore = ObjectManager::instance()->get(objects::TC_STORE); + IPCStore = ObjectManager::instance()->get(objects::IPC_STORE); + TCStore = ObjectManager::instance()->get(objects::TC_STORE); - if (IPCStore == nullptr or TCStore == nullptr) { + if (IPCStore == nullptr or TCStore == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "CommandingServiceBase::intialize: IPC store or TC store " - "not initialized yet!" << std::endl; + sif::error << "CommandingServiceBase::intialize: IPC store or TC store " + "not initialized yet!" << std::endl; #endif - return ObjectManagerIF::CHILD_INIT_FAILED; - } + return ObjectManagerIF::CHILD_INIT_FAILED; + } - return RETURN_OK; + return RETURN_OK; } void CommandingServiceBase::handleCommandQueue() { - CommandMessage reply; - ReturnValue_t result = RETURN_FAILED; - while(true) { - result = commandQueue->receiveMessage(&reply); - if (result == HasReturnvaluesIF::RETURN_OK) { - handleCommandMessage(&reply); - continue; - } - else if(result == MessageQueueIF::EMPTY) { - break; - } - else { + CommandMessage reply; + ReturnValue_t result = RETURN_FAILED; + while(true) { + result = commandQueue->receiveMessage(&reply); + if (result == HasReturnvaluesIF::RETURN_OK) { + handleCommandMessage(&reply); + continue; + } + else if(result == MessageQueueIF::EMPTY) { + break; + } + else { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "CommandingServiceBase::handleCommandQueue: Receiving message failed" - "with code" << result << std::endl; + sif::warning << "CommandingServiceBase::handleCommandQueue: Receiving message failed" + "with code" << result << std::endl; #else - sif::printWarning("CommandingServiceBase::handleCommandQueue: Receiving message " - "failed with code %d\n", result); + sif::printWarning("CommandingServiceBase::handleCommandQueue: Receiving message " + "failed with code %d\n", result); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - break; - } - } + break; + } + } } void CommandingServiceBase::handleCommandMessage(CommandMessage* reply) { - bool isStep = false; - CommandMessage nextCommand; - CommandMapIter iter = commandMap.find(reply->getSender()); + bool isStep = false; + CommandMessage nextCommand; + CommandMapIter iter = commandMap.find(reply->getSender()); - // handle unrequested reply first - if (reply->getSender() == MessageQueueIF::NO_QUEUE or - iter == commandMap.end()) { - handleUnrequestedReply(reply); - return; - } - nextCommand.setCommand(CommandMessage::CMD_NONE); + // handle unrequested reply first + if (reply->getSender() == MessageQueueIF::NO_QUEUE or + iter == commandMap.end()) { + handleUnrequestedReply(reply); + return; + } + nextCommand.setCommand(CommandMessage::CMD_NONE); - // Implemented by child class, specifies what to do with reply. - ReturnValue_t result = handleReply(reply, iter->second.command, &iter->second.state, - &nextCommand, iter->second.objectId, &isStep); + // Implemented by child class, specifies what to do with reply. + ReturnValue_t result = handleReply(reply, iter->second.command, &iter->second.state, + &nextCommand, iter->second.objectId, &isStep); - /* If the child implementation does not implement special handling for - * rejected replies (RETURN_FAILED or INVALID_REPLY is returned), a - * failure verification will be generated with the reason as the - * return code and the initial command as failure parameter 1 */ - if((reply->getCommand() == CommandMessage::REPLY_REJECTED) and - (result == RETURN_FAILED or result == INVALID_REPLY)) { - result = reply->getReplyRejectedReason(); - failureParameter1 = iter->second.command; - } + /* If the child implementation does not implement special handling for + * rejected replies (RETURN_FAILED or INVALID_REPLY is returned), a + * failure verification will be generated with the reason as the + * return code and the initial command as failure parameter 1 */ + if((reply->getCommand() == CommandMessage::REPLY_REJECTED) and + (result == RETURN_FAILED or result == INVALID_REPLY)) { + result = reply->getReplyRejectedReason(); + failureParameter1 = iter->second.command; + } - switch (result) { - case EXECUTION_COMPLETE: - case RETURN_OK: - case NO_STEP_MESSAGE: - // handle result of reply handler implemented by developer. - handleReplyHandlerResult(result, iter, &nextCommand, reply, isStep); - break; - case INVALID_REPLY: - //might be just an unrequested reply at a bad moment - handleUnrequestedReply(reply); - break; - default: - if (isStep) { - verificationReporter.sendFailureReport( - tc_verification::PROGRESS_FAILURE, iter->second.tcInfo.ackFlags, - iter->second.tcInfo.tcPacketId, iter->second.tcInfo.tcSequenceControl, - result, ++iter->second.step, failureParameter1, - failureParameter2); - } else { - verificationReporter.sendFailureReport( - tc_verification::COMPLETION_FAILURE, iter->second.tcInfo.ackFlags, - iter->second.tcInfo.tcPacketId, iter->second.tcInfo.tcSequenceControl, - result, 0, failureParameter1, failureParameter2); - } - failureParameter1 = 0; - failureParameter2 = 0; - checkAndExecuteFifo(iter); - break; - } + switch (result) { + case EXECUTION_COMPLETE: + case RETURN_OK: + case NO_STEP_MESSAGE: + // handle result of reply handler implemented by developer. + handleReplyHandlerResult(result, iter, &nextCommand, reply, isStep); + break; + case INVALID_REPLY: + //might be just an unrequested reply at a bad moment + handleUnrequestedReply(reply); + break; + default: + if (isStep) { + verificationReporter.sendFailureReport( + tc_verification::PROGRESS_FAILURE, iter->second.tcInfo.ackFlags, + iter->second.tcInfo.tcPacketId, iter->second.tcInfo.tcSequenceControl, + result, ++iter->second.step, failureParameter1, + failureParameter2); + } else { + verificationReporter.sendFailureReport( + tc_verification::COMPLETION_FAILURE, iter->second.tcInfo.ackFlags, + iter->second.tcInfo.tcPacketId, iter->second.tcInfo.tcSequenceControl, + result, 0, failureParameter1, failureParameter2); + } + failureParameter1 = 0; + failureParameter2 = 0; + checkAndExecuteFifo(iter); + break; + } } void CommandingServiceBase::handleReplyHandlerResult(ReturnValue_t result, - CommandMapIter iter, CommandMessage* nextCommand, - CommandMessage* reply, bool& isStep) { - iter->second.command = nextCommand->getCommand(); + CommandMapIter iter, CommandMessage* nextCommand, + CommandMessage* reply, bool& isStep) { + iter->second.command = nextCommand->getCommand(); - // In case a new command is to be sent immediately, this is performed here. - // If no new command is sent, only analyse reply result by initializing - // sendResult as RETURN_OK - ReturnValue_t sendResult = RETURN_OK; - if (nextCommand->getCommand() != CommandMessage::CMD_NONE) { - sendResult = commandQueue->sendMessage(reply->getSender(), - nextCommand); - } + // In case a new command is to be sent immediately, this is performed here. + // If no new command is sent, only analyse reply result by initializing + // sendResult as RETURN_OK + ReturnValue_t sendResult = RETURN_OK; + if (nextCommand->getCommand() != CommandMessage::CMD_NONE) { + sendResult = commandQueue->sendMessage(reply->getSender(), + nextCommand); + } - if (sendResult == RETURN_OK) { - if (isStep and result != NO_STEP_MESSAGE) { - verificationReporter.sendSuccessReport( - tc_verification::PROGRESS_SUCCESS, - iter->second.tcInfo.ackFlags, iter->second.tcInfo.tcPacketId, - iter->second.tcInfo.tcSequenceControl, ++iter->second.step); - } - else { - verificationReporter.sendSuccessReport( - tc_verification::COMPLETION_SUCCESS, - iter->second.tcInfo.ackFlags, iter->second.tcInfo.tcPacketId, - iter->second.tcInfo.tcSequenceControl, 0); - checkAndExecuteFifo(iter); - } - } - else { - if (isStep) { - nextCommand->clearCommandMessage(); - verificationReporter.sendFailureReport( - tc_verification::PROGRESS_FAILURE, iter->second.tcInfo.ackFlags, - iter->second.tcInfo.tcPacketId, - iter->second.tcInfo.tcSequenceControl, sendResult, - ++iter->second.step, failureParameter1, failureParameter2); - } else { - nextCommand->clearCommandMessage(); - verificationReporter.sendFailureReport( - tc_verification::COMPLETION_FAILURE, - iter->second.tcInfo.ackFlags, iter->second.tcInfo.tcPacketId, - iter->second.tcInfo.tcSequenceControl, sendResult, 0, - failureParameter1, failureParameter2); - } - failureParameter1 = 0; - failureParameter2 = 0; - checkAndExecuteFifo(iter); - } + if (sendResult == RETURN_OK) { + if (isStep and result != NO_STEP_MESSAGE) { + verificationReporter.sendSuccessReport( + tc_verification::PROGRESS_SUCCESS, + iter->second.tcInfo.ackFlags, iter->second.tcInfo.tcPacketId, + iter->second.tcInfo.tcSequenceControl, ++iter->second.step); + } + else { + verificationReporter.sendSuccessReport( + tc_verification::COMPLETION_SUCCESS, + iter->second.tcInfo.ackFlags, iter->second.tcInfo.tcPacketId, + iter->second.tcInfo.tcSequenceControl, 0); + checkAndExecuteFifo(iter); + } + } + else { + if (isStep) { + nextCommand->clearCommandMessage(); + verificationReporter.sendFailureReport( + tc_verification::PROGRESS_FAILURE, iter->second.tcInfo.ackFlags, + iter->second.tcInfo.tcPacketId, + iter->second.tcInfo.tcSequenceControl, sendResult, + ++iter->second.step, failureParameter1, failureParameter2); + } else { + nextCommand->clearCommandMessage(); + verificationReporter.sendFailureReport( + tc_verification::COMPLETION_FAILURE, + iter->second.tcInfo.ackFlags, iter->second.tcInfo.tcPacketId, + iter->second.tcInfo.tcSequenceControl, sendResult, 0, + failureParameter1, failureParameter2); + } + failureParameter1 = 0; + failureParameter2 = 0; + checkAndExecuteFifo(iter); + } } void CommandingServiceBase::handleRequestQueue() { - TmTcMessage message; - ReturnValue_t result; - store_address_t address; - TcPacketStoredPus packet; - MessageQueueId_t queue; - object_id_t objectId; - for (result = requestQueue->receiveMessage(&message); result == RETURN_OK; - result = requestQueue->receiveMessage(&message)) { - address = message.getStorageId(); - packet.setStoreAddress(address); + TmTcMessage message; + ReturnValue_t result; + store_address_t address; + TcPacketStoredPus packet; + MessageQueueId_t queue; + object_id_t objectId; + for (result = requestQueue->receiveMessage(&message); result == RETURN_OK; + result = requestQueue->receiveMessage(&message)) { + address = message.getStorageId(); + packet.setStoreAddress(address, &packet); - if ((packet.getSubService() == 0) - or (isValidSubservice(packet.getSubService()) != RETURN_OK)) { - rejectPacket(tc_verification::START_FAILURE, &packet, INVALID_SUBSERVICE); - continue; - } + if ((packet.getSubService() == 0) + or (isValidSubservice(packet.getSubService()) != RETURN_OK)) { + rejectPacket(tc_verification::START_FAILURE, &packet, INVALID_SUBSERVICE); + continue; + } - result = getMessageQueueAndObject(packet.getSubService(), - packet.getApplicationData(), packet.getApplicationDataSize(), - &queue, &objectId); - if (result != HasReturnvaluesIF::RETURN_OK) { - rejectPacket(tc_verification::START_FAILURE, &packet, result); - continue; - } + result = getMessageQueueAndObject(packet.getSubService(), + packet.getApplicationData(), packet.getApplicationDataSize(), + &queue, &objectId); + if (result != HasReturnvaluesIF::RETURN_OK) { + rejectPacket(tc_verification::START_FAILURE, &packet, result); + continue; + } - //Is a command already active for the target object? - CommandMapIter iter; - iter = commandMap.find(queue); + //Is a command already active for the target object? + CommandMapIter iter; + iter = commandMap.find(queue); - if (iter != commandMap.end()) { - result = iter->second.fifo.insert(address); - if (result != RETURN_OK) { - rejectPacket(tc_verification::START_FAILURE, &packet, OBJECT_BUSY); - } - } else { - CommandInfo newInfo; //Info will be set by startExecution if neccessary - newInfo.objectId = objectId; - result = commandMap.insert(queue, newInfo, &iter); - if (result != RETURN_OK) { - rejectPacket(tc_verification::START_FAILURE, &packet, BUSY); - } else { - startExecution(&packet, iter); - } - } + if (iter != commandMap.end()) { + result = iter->second.fifo.insert(address); + if (result != RETURN_OK) { + rejectPacket(tc_verification::START_FAILURE, &packet, OBJECT_BUSY); + } + } else { + CommandInfo newInfo; //Info will be set by startExecution if neccessary + newInfo.objectId = objectId; + result = commandMap.insert(queue, newInfo, &iter); + if (result != RETURN_OK) { + rejectPacket(tc_verification::START_FAILURE, &packet, BUSY); + } else { + startExecution(&packet, iter); + } + } - } + } } ReturnValue_t CommandingServiceBase::sendTmPacket(uint8_t subservice, - const uint8_t* data, size_t dataLen, const uint8_t* headerData, - size_t headerSize) { + const uint8_t* data, size_t dataLen, const uint8_t* headerData, + size_t headerSize) { #if FSFW_USE_PUS_C_TELEMETRY == 0 - TmPacketStoredPusA tmPacketStored(this->apid, this->service, subservice, - this->tmPacketCounter, data, dataLen, headerData, headerSize); + TmPacketStoredPusA tmPacketStored(this->apid, this->service, subservice, + this->tmPacketCounter, data, dataLen, headerData, headerSize); #else - TmPacketStoredPusC tmPacketStored(this->apid, this->service, subservice, + TmPacketStoredPusC tmPacketStored(this->apid, this->service, subservice, this->tmPacketCounter, data, dataLen, headerData, headerSize); #endif - ReturnValue_t result = tmPacketStored.sendPacket( - requestQueue->getDefaultDestination(), requestQueue->getId()); - if (result == HasReturnvaluesIF::RETURN_OK) { - this->tmPacketCounter++; - } - return result; + ReturnValue_t result = tmPacketStored.sendPacket( + requestQueue->getDefaultDestination(), requestQueue->getId()); + if (result == HasReturnvaluesIF::RETURN_OK) { + this->tmPacketCounter++; + } + return result; } @@ -316,7 +316,7 @@ ReturnValue_t CommandingServiceBase::sendTmPacket(uint8_t subservice, uint8_t* pBuffer = buffer; size_t size = 0; SerializeAdapter::serialize(&objectId, &pBuffer, &size, - sizeof(object_id_t), SerializeIF::Endianness::BIG); + sizeof(object_id_t), SerializeIF::Endianness::BIG); #if FSFW_USE_PUS_C_TELEMETRY == 0 TmPacketStoredPusA tmPacketStored(this->apid, this->service, subservice, this->tmPacketCounter, data, dataLen, buffer, size); @@ -351,95 +351,96 @@ ReturnValue_t CommandingServiceBase::sendTmPacket(uint8_t subservice, } -void CommandingServiceBase::startExecution(TcPacketStoredBase *storedPacket, +void CommandingServiceBase::startExecution(TcPacketStoredPus* storedPacket, CommandMapIter iter) { ReturnValue_t result = RETURN_OK; CommandMessage command; - TcPacketBase* tcPacketBase = storedPacket->getPacketBase(); - if(tcPacketBase == nullptr) { + //TcPacketPusBase* tcPacketBase = storedPacket->getPacketBase(); + if(storedPacket == nullptr) { return; } - iter->second.subservice = tcPacketBase->getSubService(); + iter->second.subservice = storedPacket->getSubService(); result = prepareCommand(&command, iter->second.subservice, - tcPacketBase->getApplicationData(), - tcPacketBase->getApplicationDataSize(), &iter->second.state, + storedPacket->getApplicationData(), + storedPacket->getApplicationDataSize(), &iter->second.state, iter->second.objectId); ReturnValue_t sendResult = RETURN_OK; - switch (result) { - case RETURN_OK: - if (command.getCommand() != CommandMessage::CMD_NONE) { - sendResult = commandQueue->sendMessage(iter.value->first, - &command); - } - if (sendResult == RETURN_OK) { - Clock::getUptime(&iter->second.uptimeOfStart); - iter->second.step = 0; - iter->second.subservice = tcPacketBase->getSubService(); - iter->second.command = command.getCommand(); - iter->second.tcInfo.ackFlags = tcPacketBase->getAcknowledgeFlags(); - iter->second.tcInfo.tcPacketId = tcPacketBase->getPacketId(); - iter->second.tcInfo.tcSequenceControl = - tcPacketBase->getPacketSequenceControl(); - acceptPacket(tc_verification::START_SUCCESS, storedPacket); - } else { - command.clearCommandMessage(); - rejectPacket(tc_verification::START_FAILURE, storedPacket, sendResult); - checkAndExecuteFifo(iter); - } - break; - case EXECUTION_COMPLETE: - if (command.getCommand() != CommandMessage::CMD_NONE) { - //Fire-and-forget command. - sendResult = commandQueue->sendMessage(iter.value->first, - &command); - } - if (sendResult == RETURN_OK) { - verificationReporter.sendSuccessReport(tc_verification::START_SUCCESS, - storedPacket->getPacketBase()); - acceptPacket(tc_verification::COMPLETION_SUCCESS, storedPacket); - checkAndExecuteFifo(iter); - } else { - command.clearCommandMessage(); - rejectPacket(tc_verification::START_FAILURE, storedPacket, sendResult); - checkAndExecuteFifo(iter); - } - break; - default: - rejectPacket(tc_verification::START_FAILURE, storedPacket, result); - checkAndExecuteFifo(iter); - break; - } + switch (result) { + case RETURN_OK: + if (command.getCommand() != CommandMessage::CMD_NONE) { + sendResult = commandQueue->sendMessage(iter.value->first, + &command); + } + if (sendResult == RETURN_OK) { + Clock::getUptime(&iter->second.uptimeOfStart); + iter->second.step = 0; + iter->second.subservice = storedPacket->getSubService(); + iter->second.command = command.getCommand(); + iter->second.tcInfo.ackFlags = storedPacket->getAcknowledgeFlags(); + iter->second.tcInfo.tcPacketId = storedPacket->getPacketId(); + iter->second.tcInfo.tcSequenceControl = + storedPacket->getPacketSequenceControl(); + acceptPacket(tc_verification::START_SUCCESS, storedPacket); + } else { + command.clearCommandMessage(); + rejectPacket(tc_verification::START_FAILURE, storedPacket, sendResult); + checkAndExecuteFifo(iter); + } + break; + case EXECUTION_COMPLETE: + if (command.getCommand() != CommandMessage::CMD_NONE) { + //Fire-and-forget command. + sendResult = commandQueue->sendMessage(iter.value->first, + &command); + } + if (sendResult == RETURN_OK) { + verificationReporter.sendSuccessReport(tc_verification::START_SUCCESS, + storedPacket->getPacketBase()); + acceptPacket(tc_verification::COMPLETION_SUCCESS, storedPacket); + checkAndExecuteFifo(iter); + } else { + command.clearCommandMessage(); + rejectPacket(tc_verification::START_FAILURE, storedPacket, sendResult); + checkAndExecuteFifo(iter); + } + break; + default: + rejectPacket(tc_verification::START_FAILURE, storedPacket, result); + checkAndExecuteFifo(iter); + break; + } } void CommandingServiceBase::rejectPacket(uint8_t reportId, - TcPacketStoredBase* packet, ReturnValue_t errorCode) { - verificationReporter.sendFailureReport(reportId, packet->getPacketBase(), errorCode); - packet->deletePacket(); + TcPacketStoredPus* packet, ReturnValue_t errorCode) { + verificationReporter.sendFailureReport(reportId, dynamic_cast(packet), + errorCode); + packet->deletePacket(); } void CommandingServiceBase::acceptPacket(uint8_t reportId, - TcPacketStoredBase* packet) { - verificationReporter.sendSuccessReport(reportId, packet->getPacketBase()); - packet->deletePacket(); + TcPacketStoredPus* packet) { + verificationReporter.sendSuccessReport(reportId, dynamic_cast(packet)); + packet->deletePacket(); } void CommandingServiceBase::checkAndExecuteFifo(CommandMapIter& iter) { - store_address_t address; - if (iter->second.fifo.retrieve(&address) != RETURN_OK) { - commandMap.erase(&iter); - } else { - TcPacketStoredPus newPacket(address); - startExecution(&newPacket, iter); - } + store_address_t address; + if (iter->second.fifo.retrieve(&address) != RETURN_OK) { + commandMap.erase(&iter); + } else { + TcPacketStoredPus newPacket(address); + startExecution(&newPacket, iter); + } } void CommandingServiceBase::handleUnrequestedReply(CommandMessage* reply) { - reply->clearCommandMessage(); + reply->clearCommandMessage(); } @@ -447,22 +448,22 @@ inline void CommandingServiceBase::doPeriodicOperation() { } MessageQueueId_t CommandingServiceBase::getCommandQueue() { - return commandQueue->getId(); + return commandQueue->getId(); } void CommandingServiceBase::checkTimeout() { - uint32_t uptime; - Clock::getUptime(&uptime); - CommandMapIter iter; - for (iter = commandMap.begin(); iter != commandMap.end(); ++iter) { - if ((iter->second.uptimeOfStart + (timeoutSeconds * 1000)) < uptime) { - verificationReporter.sendFailureReport( - tc_verification::COMPLETION_FAILURE, iter->second.tcInfo.ackFlags, - iter->second.tcInfo.tcPacketId, iter->second.tcInfo.tcSequenceControl, - TIMEOUT); - checkAndExecuteFifo(iter); - } - } + uint32_t uptime; + Clock::getUptime(&uptime); + CommandMapIter iter; + for (iter = commandMap.begin(); iter != commandMap.end(); ++iter) { + if ((iter->second.uptimeOfStart + (timeoutSeconds * 1000)) < uptime) { + verificationReporter.sendFailureReport( + tc_verification::COMPLETION_FAILURE, iter->second.tcInfo.ackFlags, + iter->second.tcInfo.tcPacketId, iter->second.tcInfo.tcSequenceControl, + TIMEOUT); + checkAndExecuteFifo(iter); + } + } } void CommandingServiceBase::setTaskIF(PeriodicTaskIF* task_) { diff --git a/src/fsfw/tmtcservices/CommandingServiceBase.h b/src/fsfw/tmtcservices/CommandingServiceBase.h index b6709693..d9b1b5ef 100644 --- a/src/fsfw/tmtcservices/CommandingServiceBase.h +++ b/src/fsfw/tmtcservices/CommandingServiceBase.h @@ -14,8 +14,8 @@ #include "fsfw/container/FIFO.h" #include "fsfw/serialize/SerializeIF.h" -class TcPacketStored; class TcPacketStoredBase; +class TcPacketStoredPus; namespace Factory{ void setStaticFrameworkObjectIds(); @@ -36,333 +36,333 @@ void setStaticFrameworkObjectIds(); * @ingroup pus_services */ class CommandingServiceBase: public SystemObject, - public AcceptsTelecommandsIF, - public ExecutableObjectIF, - public HasReturnvaluesIF { - friend void (Factory::setStaticFrameworkObjectIds)(); +public AcceptsTelecommandsIF, +public ExecutableObjectIF, +public HasReturnvaluesIF { + friend void (Factory::setStaticFrameworkObjectIds)(); public: - // We could make this configurable via preprocessor and the FSFWConfig file. - static constexpr uint8_t COMMAND_INFO_FIFO_DEPTH = - fsfwconfig::FSFW_CSB_FIFO_DEPTH; + // We could make this configurable via preprocessor and the FSFWConfig file. + static constexpr uint8_t COMMAND_INFO_FIFO_DEPTH = + fsfwconfig::FSFW_CSB_FIFO_DEPTH; - static const uint8_t INTERFACE_ID = CLASS_ID::COMMAND_SERVICE_BASE; + static const uint8_t INTERFACE_ID = CLASS_ID::COMMAND_SERVICE_BASE; - static const ReturnValue_t EXECUTION_COMPLETE = MAKE_RETURN_CODE(1); - static const ReturnValue_t NO_STEP_MESSAGE = MAKE_RETURN_CODE(2); - static const ReturnValue_t OBJECT_BUSY = MAKE_RETURN_CODE(3); - static const ReturnValue_t BUSY = MAKE_RETURN_CODE(4); - static const ReturnValue_t INVALID_TC = MAKE_RETURN_CODE(5); - static const ReturnValue_t INVALID_OBJECT = MAKE_RETURN_CODE(6); - static const ReturnValue_t INVALID_REPLY = MAKE_RETURN_CODE(7); + static const ReturnValue_t EXECUTION_COMPLETE = MAKE_RETURN_CODE(1); + static const ReturnValue_t NO_STEP_MESSAGE = MAKE_RETURN_CODE(2); + static const ReturnValue_t OBJECT_BUSY = MAKE_RETURN_CODE(3); + static const ReturnValue_t BUSY = MAKE_RETURN_CODE(4); + static const ReturnValue_t INVALID_TC = MAKE_RETURN_CODE(5); + static const ReturnValue_t INVALID_OBJECT = MAKE_RETURN_CODE(6); + static const ReturnValue_t INVALID_REPLY = MAKE_RETURN_CODE(7); - /** - * Class constructor. Initializes two important MessageQueues: - * commandQueue for command reception and requestQueue for device reception - * @param setObjectId - * @param apid - * @param service - * @param numberOfParallelCommands - * @param commandTimeout_seconds - * @param setPacketSource - * @param setPacketDestination - * @param queueDepth - */ - CommandingServiceBase(object_id_t setObjectId, uint16_t apid, - uint8_t service, uint8_t numberOfParallelCommands, - uint16_t commandTimeoutSeconds, size_t queueDepth = 20); - virtual ~CommandingServiceBase(); + /** + * Class constructor. Initializes two important MessageQueues: + * commandQueue for command reception and requestQueue for device reception + * @param setObjectId + * @param apid + * @param service + * @param numberOfParallelCommands + * @param commandTimeout_seconds + * @param setPacketSource + * @param setPacketDestination + * @param queueDepth + */ + CommandingServiceBase(object_id_t setObjectId, uint16_t apid, + uint8_t service, uint8_t numberOfParallelCommands, + uint16_t commandTimeoutSeconds, size_t queueDepth = 20); + virtual ~CommandingServiceBase(); - /** - * This setter can be used to set the packet source individually instead - * of using the default static framework ID set in the factory. - * This should be called at object initialization and not during run-time! - * @param packetSource - */ - void setPacketSource(object_id_t packetSource); - /** - * This setter can be used to set the packet destination individually - * instead of using the default static framework ID set in the factory. - * This should be called at object initialization and not during run-time! - * @param packetDestination - */ - void setPacketDestination(object_id_t packetDestination); + /** + * This setter can be used to set the packet source individually instead + * of using the default static framework ID set in the factory. + * This should be called at object initialization and not during run-time! + * @param packetSource + */ + void setPacketSource(object_id_t packetSource); + /** + * This setter can be used to set the packet destination individually + * instead of using the default static framework ID set in the factory. + * This should be called at object initialization and not during run-time! + * @param packetDestination + */ + void setPacketDestination(object_id_t packetDestination); - /*** - * This is the periodically called function. - * Handle request queue for external commands. - * Handle command Queue for internal commands. - * @param opCode is unused here at the moment - * @return RETURN_OK - */ - virtual ReturnValue_t performOperation(uint8_t opCode) override; + /*** + * This is the periodically called function. + * Handle request queue for external commands. + * Handle command Queue for internal commands. + * @param opCode is unused here at the moment + * @return RETURN_OK + */ + virtual ReturnValue_t performOperation(uint8_t opCode) override; - virtual uint16_t getIdentifier(); + virtual uint16_t getIdentifier(); - /** - * Returns the requestQueue MessageQueueId_t - * - * The requestQueue is the queue for external commands (TC) - * - * @return requestQueue messageQueueId_t - */ - virtual MessageQueueId_t getRequestQueue(); + /** + * Returns the requestQueue MessageQueueId_t + * + * The requestQueue is the queue for external commands (TC) + * + * @return requestQueue messageQueueId_t + */ + virtual MessageQueueId_t getRequestQueue(); - /** - * Returns the commandQueue MessageQueueId_t - * - * Remember the CommandQueue is the queue for internal communication - * @return commandQueue messageQueueId_t - */ - virtual MessageQueueId_t getCommandQueue(); + /** + * Returns the commandQueue MessageQueueId_t + * + * Remember the CommandQueue is the queue for internal communication + * @return commandQueue messageQueueId_t + */ + virtual MessageQueueId_t getCommandQueue(); - virtual ReturnValue_t initialize() override; + virtual ReturnValue_t initialize() override; - /** - * Implementation of ExecutableObjectIF function - * - * Used to setup the reference of the task, that executes this component - * @param task Pointer to the taskIF of this task - */ - virtual void setTaskIF(PeriodicTaskIF* task) override; + /** + * Implementation of ExecutableObjectIF function + * + * Used to setup the reference of the task, that executes this component + * @param task Pointer to the taskIF of this task + */ + virtual void setTaskIF(PeriodicTaskIF* task) override; protected: - /** - * Check the target subservice - * @param subservice[in] - * @return - * -@c RETURN_OK Subservice valid, continue message handling + /** + * Check the target subservice + * @param subservice[in] + * @return + * -@c RETURN_OK Subservice valid, continue message handling * -@c INVALID_SUBSERVICE if service is not known, rejects packet. - */ - virtual ReturnValue_t isValidSubservice(uint8_t subservice) = 0; + */ + virtual ReturnValue_t isValidSubservice(uint8_t subservice) = 0; - /** - * Once a TC Request is valid, the existence of the destination and its - * target interface is checked and retrieved. The target message queue ID - * can then be acquired by using the target interface. - * @param subservice - * @param tcData Application Data of TC Packet - * @param tcDataLen - * @param id MessageQueue ID is stored here - * @param objectId Object ID is extracted and stored here - * @return - * - @c RETURN_OK Cotinue message handling - * - @c RETURN_FAILED Reject the packet and generates a start failure - * verification - */ - virtual ReturnValue_t getMessageQueueAndObject(uint8_t subservice, - const uint8_t *tcData, size_t tcDataLen, MessageQueueId_t *id, - object_id_t *objectId) = 0; + /** + * Once a TC Request is valid, the existence of the destination and its + * target interface is checked and retrieved. The target message queue ID + * can then be acquired by using the target interface. + * @param subservice + * @param tcData Application Data of TC Packet + * @param tcDataLen + * @param id MessageQueue ID is stored here + * @param objectId Object ID is extracted and stored here + * @return + * - @c RETURN_OK Cotinue message handling + * - @c RETURN_FAILED Reject the packet and generates a start failure + * verification + */ + virtual ReturnValue_t getMessageQueueAndObject(uint8_t subservice, + const uint8_t *tcData, size_t tcDataLen, MessageQueueId_t *id, + object_id_t *objectId) = 0; - /** - * After the Message Queue and Object ID are determined, the command is - * prepared by using an implementation specific CommandMessage type - * which is sent to the target object. It contains all necessary information - * for the device to execute telecommands. - * @param message [out] message which can be set and is sent to the object - * @param subservice Subservice of the current communication - * @param tcData Application data of command - * @param tcDataLen Application data length - * @param state [out/in] Setable state of the communication. - * communication - * @param objectId Target object ID - * @return - * - @c RETURN_OK to generate a verification start message - * - @c EXECUTION_COMPELTE Fire-and-forget command. Generate a completion - * verification message. - * - @c Anything else rejects the packets and generates a start failure - * verification. - */ - virtual ReturnValue_t prepareCommand(CommandMessage* message, - uint8_t subservice, const uint8_t *tcData, size_t tcDataLen, - uint32_t *state, object_id_t objectId) = 0; + /** + * After the Message Queue and Object ID are determined, the command is + * prepared by using an implementation specific CommandMessage type + * which is sent to the target object. It contains all necessary information + * for the device to execute telecommands. + * @param message [out] message which can be set and is sent to the object + * @param subservice Subservice of the current communication + * @param tcData Application data of command + * @param tcDataLen Application data length + * @param state [out/in] Setable state of the communication. + * communication + * @param objectId Target object ID + * @return + * - @c RETURN_OK to generate a verification start message + * - @c EXECUTION_COMPELTE Fire-and-forget command. Generate a completion + * verification message. + * - @c Anything else rejects the packets and generates a start failure + * verification. + */ + virtual ReturnValue_t prepareCommand(CommandMessage* message, + uint8_t subservice, const uint8_t *tcData, size_t tcDataLen, + uint32_t *state, object_id_t objectId) = 0; - /** - * This function is implemented by child services to specify how replies - * to a command from another software component are handled. - * @param reply - * This is the reply in form of a generic read-only command message. - * @param previousCommand - * Command_t of related command - * @param state [out/in] - * Additional parameter which can be used to pass state information. - * State of the communication - * @param optionalNextCommand [out] - * An optional next command which can be set in this function - * @param objectId Source object ID - * @param isStep Flag value to mark steps of command execution - * @return - * - @c RETURN_OK, @c EXECUTION_COMPLETE or @c NO_STEP_MESSAGE to - * generate TC verification success - * - @c INVALID_REPLY Calls handleUnrequestedReply - * - Anything else triggers a TC verification failure. If RETURN_FAILED or - * INVALID_REPLY is returned and the command ID is - * CommandMessage::REPLY_REJECTED, a failure verification message with - * the reason as the error parameter and the initial command as - * failure parameter 1 is generated. - */ - virtual ReturnValue_t handleReply(const CommandMessage* reply, - Command_t previousCommand, uint32_t *state, - CommandMessage* optionalNextCommand, object_id_t objectId, - bool *isStep) = 0; + /** + * This function is implemented by child services to specify how replies + * to a command from another software component are handled. + * @param reply + * This is the reply in form of a generic read-only command message. + * @param previousCommand + * Command_t of related command + * @param state [out/in] + * Additional parameter which can be used to pass state information. + * State of the communication + * @param optionalNextCommand [out] + * An optional next command which can be set in this function + * @param objectId Source object ID + * @param isStep Flag value to mark steps of command execution + * @return + * - @c RETURN_OK, @c EXECUTION_COMPLETE or @c NO_STEP_MESSAGE to + * generate TC verification success + * - @c INVALID_REPLY Calls handleUnrequestedReply + * - Anything else triggers a TC verification failure. If RETURN_FAILED or + * INVALID_REPLY is returned and the command ID is + * CommandMessage::REPLY_REJECTED, a failure verification message with + * the reason as the error parameter and the initial command as + * failure parameter 1 is generated. + */ + virtual ReturnValue_t handleReply(const CommandMessage* reply, + Command_t previousCommand, uint32_t *state, + CommandMessage* optionalNextCommand, object_id_t objectId, + bool *isStep) = 0; - /** - * This function can be overidden to handle unrequested reply, - * when the reply sender ID is unknown or is not found is the command map. - * The default implementation will clear the command message and all - * its contents. - * @param reply - * Reply which is non-const so the default implementation can clear the - * message. - */ - virtual void handleUnrequestedReply(CommandMessage* reply); + /** + * This function can be overidden to handle unrequested reply, + * when the reply sender ID is unknown or is not found is the command map. + * The default implementation will clear the command message and all + * its contents. + * @param reply + * Reply which is non-const so the default implementation can clear the + * message. + */ + virtual void handleUnrequestedReply(CommandMessage* reply); - virtual void doPeriodicOperation(); + virtual void doPeriodicOperation(); - struct CommandInfo: public SerializeIF{ - struct tcInfo { - uint8_t ackFlags; - uint16_t tcPacketId; - uint16_t tcSequenceControl; - } tcInfo; - uint32_t uptimeOfStart; - uint8_t step; - uint8_t subservice; - uint32_t state; - Command_t command; - object_id_t objectId; - FIFO fifo; + struct CommandInfo: public SerializeIF{ + struct tcInfo { + uint8_t ackFlags; + uint16_t tcPacketId; + uint16_t tcSequenceControl; + } tcInfo; + uint32_t uptimeOfStart; + uint8_t step; + uint8_t subservice; + uint32_t state; + Command_t command; + object_id_t objectId; + FIFO fifo; - virtual ReturnValue_t serialize(uint8_t **buffer, size_t *size, - size_t maxSize, Endianness streamEndianness) const override{ - return HasReturnvaluesIF::RETURN_FAILED; - }; + virtual ReturnValue_t serialize(uint8_t **buffer, size_t *size, + size_t maxSize, Endianness streamEndianness) const override{ + return HasReturnvaluesIF::RETURN_FAILED; + }; - virtual size_t getSerializedSize() const override { - return 0; - }; + virtual size_t getSerializedSize() const override { + return 0; + }; - virtual ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) override { - return HasReturnvaluesIF::RETURN_FAILED; - }; - }; + virtual ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) override { + return HasReturnvaluesIF::RETURN_FAILED; + }; + }; - using CommandMapIter = FixedMap::Iterator; + using CommandMapIter = FixedMap::Iterator; - const uint16_t apid; + const uint16_t apid; - const uint8_t service; + const uint8_t service; - const uint16_t timeoutSeconds; + const uint16_t timeoutSeconds; - uint8_t tmPacketCounter = 0; + uint8_t tmPacketCounter = 0; - StorageManagerIF *IPCStore = nullptr; + StorageManagerIF *IPCStore = nullptr; - StorageManagerIF *TCStore = nullptr; + StorageManagerIF *TCStore = nullptr; - MessageQueueIF* commandQueue = nullptr; + MessageQueueIF* commandQueue = nullptr; - MessageQueueIF* requestQueue = nullptr; + MessageQueueIF* requestQueue = nullptr; - VerificationReporter verificationReporter; + VerificationReporter verificationReporter; - FixedMap commandMap; + FixedMap commandMap; - /* May be set be children to return a more precise failure condition. */ - uint32_t failureParameter1 = 0; - uint32_t failureParameter2 = 0; + /* May be set be children to return a more precise failure condition. */ + uint32_t failureParameter1 = 0; + uint32_t failureParameter2 = 0; - static object_id_t defaultPacketSource; - object_id_t packetSource = objects::NO_OBJECT; - static object_id_t defaultPacketDestination; - object_id_t packetDestination = objects::NO_OBJECT; + static object_id_t defaultPacketSource; + object_id_t packetSource = objects::NO_OBJECT; + static object_id_t defaultPacketDestination; + object_id_t packetDestination = objects::NO_OBJECT; - /** - * Pointer to the task which executes this component, - * is invalid before setTaskIF was called. - */ - PeriodicTaskIF* executingTask = nullptr; + /** + * Pointer to the task which executes this component, + * is invalid before setTaskIF was called. + */ + PeriodicTaskIF* executingTask = nullptr; - /** - * @brief Send TM data from pointer to data. - * If a header is supplied it is added before data - * @param subservice Number of subservice - * @param data Pointer to the data in the Packet - * @param dataLen Lenght of data in the Packet - * @param headerData HeaderData will be placed before data - * @param headerSize Size of HeaderData - */ - ReturnValue_t sendTmPacket(uint8_t subservice, const uint8_t *data, - size_t dataLen, const uint8_t* headerData = nullptr, - size_t headerSize = 0); + /** + * @brief Send TM data from pointer to data. + * If a header is supplied it is added before data + * @param subservice Number of subservice + * @param data Pointer to the data in the Packet + * @param dataLen Lenght of data in the Packet + * @param headerData HeaderData will be placed before data + * @param headerSize Size of HeaderData + */ + ReturnValue_t sendTmPacket(uint8_t subservice, const uint8_t *data, + size_t dataLen, const uint8_t* headerData = nullptr, + size_t headerSize = 0); - /** - * @brief To send TM packets of objects that still need to be serialized - * and consist of an object ID with appended data. - * @param subservice Number of subservice - * @param objectId ObjectId is placed before data - * @param data Data to append to the packet - * @param dataLen Length of Data - */ - ReturnValue_t sendTmPacket(uint8_t subservice, object_id_t objectId, - const uint8_t *data, size_t dataLen); + /** + * @brief To send TM packets of objects that still need to be serialized + * and consist of an object ID with appended data. + * @param subservice Number of subservice + * @param objectId ObjectId is placed before data + * @param data Data to append to the packet + * @param dataLen Length of Data + */ + ReturnValue_t sendTmPacket(uint8_t subservice, object_id_t objectId, + const uint8_t *data, size_t dataLen); - /** - * @brief To send packets which are contained inside a class implementing - * SerializeIF. - * @param subservice Number of subservice - * @param content This is a pointer to the serialized packet - * @param header Serialize IF header which will be placed before content - */ - ReturnValue_t sendTmPacket(uint8_t subservice, SerializeIF* content, - SerializeIF* header = nullptr); + /** + * @brief To send packets which are contained inside a class implementing + * SerializeIF. + * @param subservice Number of subservice + * @param content This is a pointer to the serialized packet + * @param header Serialize IF header which will be placed before content + */ + ReturnValue_t sendTmPacket(uint8_t subservice, SerializeIF* content, + SerializeIF* header = nullptr); - void checkAndExecuteFifo(CommandMapIter& iter); + void checkAndExecuteFifo(CommandMapIter& iter); -private: - /** - * This method handles internal execution of a command, - * once it has been started by @sa{startExecution()} in the request - * queue handler. - * It handles replies generated by the devices and relayed by the specific - * service implementation. This means that it determines further course of - * action depending on the return values specified in the service - * implementation. - * This includes the generation of TC verification messages. Note that - * the static framework object ID @c VerificationReporter::messageReceiver - * needs to be set. - * - TM[1,5] Step Successs - * - TM[1,6] Step Failure - * - TM[1,7] Completion Success - * - TM[1,8] Completion Failure - */ - void handleCommandQueue(); + private: + /** + * This method handles internal execution of a command, + * once it has been started by @sa{startExecution()} in the request + * queue handler. + * It handles replies generated by the devices and relayed by the specific + * service implementation. This means that it determines further course of + * action depending on the return values specified in the service + * implementation. + * This includes the generation of TC verification messages. Note that + * the static framework object ID @c VerificationReporter::messageReceiver + * needs to be set. + * - TM[1,5] Step Successs + * - TM[1,6] Step Failure + * - TM[1,7] Completion Success + * - TM[1,8] Completion Failure + */ + void handleCommandQueue(); - /** - * @brief Handler function for request queue - * @details - * Sequence of request queue handling: - * isValidSubservice -> getMessageQueueAndObject -> startExecution - * Generates a Start Success Reports TM[1,3] in subfunction - * @sa{startExecution()} or a Start Failure Report TM[1,4] by using the - * TC Verification Service. - */ - void handleRequestQueue(); + /** + * @brief Handler function for request queue + * @details + * Sequence of request queue handling: + * isValidSubservice -> getMessageQueueAndObject -> startExecution + * Generates a Start Success Reports TM[1,3] in subfunction + * @sa{startExecution()} or a Start Failure Report TM[1,4] by using the + * TC Verification Service. + */ + void handleRequestQueue(); - void rejectPacket(uint8_t reportId, TcPacketStoredBase* packet, - ReturnValue_t errorCode); + void rejectPacket(uint8_t reportId, TcPacketStoredPus* packet, + ReturnValue_t errorCode); - void acceptPacket(uint8_t reportId, TcPacketStoredBase* packet); + void acceptPacket(uint8_t reportId, TcPacketStoredPus* packet); - void startExecution(TcPacketStoredBase *storedPacket, CommandMapIter iter); + void startExecution(TcPacketStoredPus* storedPacket, CommandMapIter iter); - void handleCommandMessage(CommandMessage* reply); - void handleReplyHandlerResult(ReturnValue_t result, CommandMapIter iter, - CommandMessage* nextCommand, CommandMessage* reply, bool& isStep); + void handleCommandMessage(CommandMessage* reply); + void handleReplyHandlerResult(ReturnValue_t result, CommandMapIter iter, + CommandMessage* nextCommand, CommandMessage* reply, bool& isStep); - void checkTimeout(); + void checkTimeout(); }; #endif /* FSFW_TMTCSERVICES_COMMANDINGSERVICEBASE_H_ */ diff --git a/src/fsfw/tmtcservices/PusServiceBase.cpp b/src/fsfw/tmtcservices/PusServiceBase.cpp index 866e0844..191acd9c 100644 --- a/src/fsfw/tmtcservices/PusServiceBase.cpp +++ b/src/fsfw/tmtcservices/PusServiceBase.cpp @@ -12,28 +12,28 @@ object_id_t PusServiceBase::packetSource = 0; object_id_t PusServiceBase::packetDestination = 0; PusServiceBase::PusServiceBase(object_id_t setObjectId, uint16_t setApid, - uint8_t setServiceId) : - SystemObject(setObjectId), apid(setApid), serviceId(setServiceId) { - requestQueue = QueueFactory::instance()-> - createMessageQueue(PUS_SERVICE_MAX_RECEPTION); + uint8_t setServiceId): + SystemObject(setObjectId), apid(setApid), serviceId(setServiceId) { + requestQueue = QueueFactory::instance()-> + createMessageQueue(PUS_SERVICE_MAX_RECEPTION); } PusServiceBase::~PusServiceBase() { - QueueFactory::instance()->deleteMessageQueue(requestQueue); + QueueFactory::instance()->deleteMessageQueue(requestQueue); } ReturnValue_t PusServiceBase::performOperation(uint8_t opCode) { - handleRequestQueue(); - ReturnValue_t result = this->performService(); - if (result != RETURN_OK) { + handleRequestQueue(); + ReturnValue_t result = this->performService(); + if (result != RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "PusService " << (uint16_t) this->serviceId - << ": performService returned with " << (int16_t) result - << std::endl; + sif::error << "PusService " << (uint16_t) this->serviceId + << ": performService returned with " << (int16_t) result + << std::endl; #endif - return RETURN_FAILED; - } - return RETURN_OK; + return RETURN_FAILED; + } + return RETURN_OK; } void PusServiceBase::setTaskIF(PeriodicTaskIF* taskHandle) { @@ -41,88 +41,88 @@ void PusServiceBase::setTaskIF(PeriodicTaskIF* taskHandle) { } void PusServiceBase::handleRequestQueue() { - TmTcMessage message; - ReturnValue_t result = RETURN_FAILED; - for (uint8_t count = 0; count < PUS_SERVICE_MAX_RECEPTION; count++) { - ReturnValue_t status = this->requestQueue->receiveMessage(&message); -// if(status != MessageQueueIF::EMPTY) { + TmTcMessage message; + ReturnValue_t result = RETURN_FAILED; + for (uint8_t count = 0; count < PUS_SERVICE_MAX_RECEPTION; count++) { + ReturnValue_t status = this->requestQueue->receiveMessage(&message); + // if(status != MessageQueueIF::EMPTY) { #if FSFW_CPP_OSTREAM_ENABLED == 1 -// sif::debug << "PusServiceBase::performOperation: Receiving from " -// << "MQ ID: " << std::hex << "0x" << std::setw(8) -// << std::setfill('0') << this->requestQueue->getId() -// << std::dec << " returned: " << status << std::setfill(' ') -// << std::endl; + // sif::debug << "PusServiceBase::performOperation: Receiving from " + // << "MQ ID: " << std::hex << "0x" << std::setw(8) + // << std::setfill('0') << this->requestQueue->getId() + // << std::dec << " returned: " << status << std::setfill(' ') + // << std::endl; #endif -// } + // } - if (status == RETURN_OK) { - this->currentPacket.setStoreAddress(message.getStorageId()); - //info << "Service " << (uint16_t) this->serviceId << - // ": new packet!" << std::endl; + if (status == RETURN_OK) { + this->currentPacket.setStoreAddress(message.getStorageId(), ¤tPacket); + //info << "Service " << (uint16_t) this->serviceId << + // ": new packet!" << std::endl; - result = this->handleRequest(currentPacket.getSubService()); + result = this->handleRequest(currentPacket.getSubService()); - // debug << "Service " << (uint16_t)this->serviceId << - // ": handleRequest returned: " << (int)return_code << std::endl; - if (result == RETURN_OK) { - this->verifyReporter.sendSuccessReport( - tc_verification::COMPLETION_SUCCESS, &this->currentPacket); - } - else { - this->verifyReporter.sendFailureReport( - tc_verification::COMPLETION_FAILURE, &this->currentPacket, - result, 0, errorParameter1, errorParameter2); - } - this->currentPacket.deletePacket(); - errorParameter1 = 0; - errorParameter2 = 0; - } - else if (status == MessageQueueIF::EMPTY) { - status = RETURN_OK; - // debug << "PusService " << (uint16_t)this->serviceId << - // ": no new packet." << std::endl; - break; - } - else { + // debug << "Service " << (uint16_t)this->serviceId << + // ": handleRequest returned: " << (int)return_code << std::endl; + if (result == RETURN_OK) { + this->verifyReporter.sendSuccessReport( + tc_verification::COMPLETION_SUCCESS, &this->currentPacket); + } + else { + this->verifyReporter.sendFailureReport( + tc_verification::COMPLETION_FAILURE, &this->currentPacket, + result, 0, errorParameter1, errorParameter2); + } + this->currentPacket.deletePacket(); + errorParameter1 = 0; + errorParameter2 = 0; + } + else if (status == MessageQueueIF::EMPTY) { + status = RETURN_OK; + // debug << "PusService " << (uint16_t)this->serviceId << + // ": no new packet." << std::endl; + break; + } + else { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "PusServiceBase::performOperation: Service " - << this->serviceId << ": Error receiving packet. Code: " - << std::hex << status << std::dec << std::endl; + sif::error << "PusServiceBase::performOperation: Service " + << this->serviceId << ": Error receiving packet. Code: " + << std::hex << status << std::dec << std::endl; #endif - } - } + } + } } uint16_t PusServiceBase::getIdentifier() { - return this->serviceId; + return this->serviceId; } MessageQueueId_t PusServiceBase::getRequestQueue() { - return this->requestQueue->getId(); + return this->requestQueue->getId(); } ReturnValue_t PusServiceBase::initialize() { - ReturnValue_t result = SystemObject::initialize(); - if (result != RETURN_OK) { - return result; - } - AcceptsTelemetryIF* destService = ObjectManager::instance()->get( - packetDestination); - PUSDistributorIF* distributor = ObjectManager::instance()->get( - packetSource); - if (destService == nullptr or distributor == nullptr) { + ReturnValue_t result = SystemObject::initialize(); + if (result != RETURN_OK) { + return result; + } + AcceptsTelemetryIF* destService = ObjectManager::instance()->get( + packetDestination); + PUSDistributorIF* distributor = ObjectManager::instance()->get( + packetSource); + if (destService == nullptr or distributor == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "PusServiceBase::PusServiceBase: Service " - << this->serviceId << ": Configuration error. Make sure " - << "packetSource and packetDestination are defined correctly" - << std::endl; + sif::error << "PusServiceBase::PusServiceBase: Service " + << this->serviceId << ": Configuration error. Make sure " + << "packetSource and packetDestination are defined correctly" + << std::endl; #endif - return ObjectManagerIF::CHILD_INIT_FAILED; - } - this->requestQueue->setDefaultDestination( - destService->getReportReceptionQueue()); - distributor->registerService(this); - return HasReturnvaluesIF::RETURN_OK; + return ObjectManagerIF::CHILD_INIT_FAILED; + } + this->requestQueue->setDefaultDestination( + destService->getReportReceptionQueue()); + distributor->registerService(this); + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t PusServiceBase::initializeAfterTaskCreation() { diff --git a/src/fsfw/tmtcservices/PusServiceBase.h b/src/fsfw/tmtcservices/PusServiceBase.h index ea4147fe..ec338331 100644 --- a/src/fsfw/tmtcservices/PusServiceBase.h +++ b/src/fsfw/tmtcservices/PusServiceBase.h @@ -35,126 +35,126 @@ void setStaticFrameworkObjectIds(); * @ingroup pus_services */ class PusServiceBase : public ExecutableObjectIF, - public AcceptsTelecommandsIF, - public SystemObject, - public HasReturnvaluesIF { - friend void (Factory::setStaticFrameworkObjectIds)(); +public AcceptsTelecommandsIF, +public SystemObject, +public HasReturnvaluesIF { + friend void (Factory::setStaticFrameworkObjectIds)(); public: - /** - * @brief The passed values are set, but inter-object initialization is - * done in the initialize method. - * @param setObjectId - * The system object identifier of this Service instance. - * @param setApid - * The APID the Service is instantiated for. - * @param setServiceId - * The Service Identifier as specified in ECSS PUS. - */ - PusServiceBase( object_id_t setObjectId, uint16_t setApid, - uint8_t setServiceId); - /** - * The destructor is empty. - */ - virtual ~PusServiceBase(); - /** - * @brief The handleRequest method shall handle any kind of Telecommand - * Request immediately. - * @details - * Implemetations can take the Telecommand in currentPacket and perform - * any kind of operation. - * They may send additional "Start Success (1,3)" messages with the - * verifyReporter, but Completion Success or Failure Reports are generated - * automatically after execution of this method. - * - * If a Telecommand can not be executed within one call cycle, - * this Base class is not the right parent. - * - * The child class may add additional error information by setting - * #errorParameters which aren attached to the generated verification - * message. - * - * Subservice checking should be implemented in this method. - * - * @return The returned status_code is directly taken as main error code - * in the Verification Report. - * On success, RETURN_OK shall be returned. - */ - virtual ReturnValue_t handleRequest(uint8_t subservice) = 0; - /** - * In performService, implementations can handle periodic, - * non-TC-triggered activities. - * The performService method is always called. - * @return Currently, everything other that RETURN_OK only triggers - * diagnostic output. - */ - virtual ReturnValue_t performService() = 0; - /** - * This method implements the typical activity of a simple PUS Service. - * It checks for new requests, and, if found, calls handleRequest, sends - * completion verification messages and deletes - * the TC requests afterwards. - * performService is always executed afterwards. - * @return @c RETURN_OK if the periodic performService was successful. - * @c RETURN_FAILED else. - */ - ReturnValue_t performOperation(uint8_t opCode) override; - virtual uint16_t getIdentifier() override; - MessageQueueId_t getRequestQueue() override; - virtual ReturnValue_t initialize() override; + /** + * @brief The passed values are set, but inter-object initialization is + * done in the initialize method. + * @param setObjectId + * The system object identifier of this Service instance. + * @param setApid + * The APID the Service is instantiated for. + * @param setServiceId + * The Service Identifier as specified in ECSS PUS. + */ + PusServiceBase( object_id_t setObjectId, uint16_t setApid, + uint8_t setServiceId); + /** + * The destructor is empty. + */ + virtual ~PusServiceBase(); + /** + * @brief The handleRequest method shall handle any kind of Telecommand + * Request immediately. + * @details + * Implemetations can take the Telecommand in currentPacket and perform + * any kind of operation. + * They may send additional "Start Success (1,3)" messages with the + * verifyReporter, but Completion Success or Failure Reports are generated + * automatically after execution of this method. + * + * If a Telecommand can not be executed within one call cycle, + * this Base class is not the right parent. + * + * The child class may add additional error information by setting + * #errorParameters which aren attached to the generated verification + * message. + * + * Subservice checking should be implemented in this method. + * + * @return The returned status_code is directly taken as main error code + * in the Verification Report. + * On success, RETURN_OK shall be returned. + */ + virtual ReturnValue_t handleRequest(uint8_t subservice) = 0; + /** + * In performService, implementations can handle periodic, + * non-TC-triggered activities. + * The performService method is always called. + * @return Currently, everything other that RETURN_OK only triggers + * diagnostic output. + */ + virtual ReturnValue_t performService() = 0; + /** + * This method implements the typical activity of a simple PUS Service. + * It checks for new requests, and, if found, calls handleRequest, sends + * completion verification messages and deletes + * the TC requests afterwards. + * performService is always executed afterwards. + * @return @c RETURN_OK if the periodic performService was successful. + * @c RETURN_FAILED else. + */ + ReturnValue_t performOperation(uint8_t opCode) override; + virtual uint16_t getIdentifier() override; + MessageQueueId_t getRequestQueue() override; + virtual ReturnValue_t initialize() override; - virtual void setTaskIF(PeriodicTaskIF* taskHandle) override; - virtual ReturnValue_t initializeAfterTaskCreation() override; + virtual void setTaskIF(PeriodicTaskIF* taskHandle) override; + virtual ReturnValue_t initializeAfterTaskCreation() override; protected: - /** - * @brief Handle to the underlying task - * @details - * Will be set by setTaskIF(), which is called on task creation. - */ - PeriodicTaskIF* taskHandle = nullptr; - /** - * The APID of this instance of the Service. - */ - uint16_t apid; - /** - * The Service Identifier. - */ - uint8_t serviceId; - /** - * One of two error parameters for additional error information. - */ - uint32_t errorParameter1 = 0; - /** - * One of two error parameters for additional error information. - */ - uint32_t errorParameter2 = 0; - /** - * This is a complete instance of the telecommand reception queue - * of the class. It is initialized on construction of the class. - */ - MessageQueueIF* requestQueue = nullptr; - /** - * An instance of the VerificationReporter class, that simplifies - * sending any kind of verification message to the TC Verification Service. - */ - VerificationReporter verifyReporter; - /** - * The current Telecommand to be processed. - * It is deleted after handleRequest was executed. - */ - TcPacketStoredPus currentPacket; + /** + * @brief Handle to the underlying task + * @details + * Will be set by setTaskIF(), which is called on task creation. + */ + PeriodicTaskIF* taskHandle = nullptr; + /** + * The APID of this instance of the Service. + */ + uint16_t apid; + /** + * The Service Identifier. + */ + uint8_t serviceId; + /** + * One of two error parameters for additional error information. + */ + uint32_t errorParameter1 = 0; + /** + * One of two error parameters for additional error information. + */ + uint32_t errorParameter2 = 0; + /** + * This is a complete instance of the telecommand reception queue + * of the class. It is initialized on construction of the class. + */ + MessageQueueIF* requestQueue = nullptr; + /** + * An instance of the VerificationReporter class, that simplifies + * sending any kind of verification message to the TC Verification Service. + */ + VerificationReporter verifyReporter; + /** + * The current Telecommand to be processed. + * It is deleted after handleRequest was executed. + */ + TcPacketStoredPus currentPacket; - static object_id_t packetSource; + static object_id_t packetSource; - static object_id_t packetDestination; + static object_id_t packetDestination; private: - /** - * This constant sets the maximum number of packets accepted per call. - * Remember that one packet must be completely handled in one - * #handleRequest call. - */ - static const uint8_t PUS_SERVICE_MAX_RECEPTION = 10; + /** + * This constant sets the maximum number of packets accepted per call. + * Remember that one packet must be completely handled in one + * #handleRequest call. + */ + static const uint8_t PUS_SERVICE_MAX_RECEPTION = 10; - void handleRequestQueue(); + void handleRequestQueue(); }; #endif /* FSFW_TMTCSERVICES_PUSSERVICEBASE_H_ */ diff --git a/src/fsfw/tmtcservices/PusVerificationReport.h b/src/fsfw/tmtcservices/PusVerificationReport.h index c22ba535..bc9793d9 100644 --- a/src/fsfw/tmtcservices/PusVerificationReport.h +++ b/src/fsfw/tmtcservices/PusVerificationReport.h @@ -4,7 +4,7 @@ #include "VerificationCodes.h" #include "fsfw/ipc/MessageQueueMessage.h" -#include "fsfw/tmtcpacket/pus/tc/TcPacketBase.h" +#include "fsfw/tmtcpacket/pus/tc/TcPacketPusBase.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" class PusVerificationMessage: public MessageQueueMessage { diff --git a/src/fsfw/tmtcservices/VerificationReporter.cpp b/src/fsfw/tmtcservices/VerificationReporter.cpp index 2b371d1e..b885cccf 100644 --- a/src/fsfw/tmtcservices/VerificationReporter.cpp +++ b/src/fsfw/tmtcservices/VerificationReporter.cpp @@ -17,7 +17,7 @@ VerificationReporter::VerificationReporter() : VerificationReporter::~VerificationReporter() {} void VerificationReporter::sendSuccessReport(uint8_t set_report_id, - TcPacketBase* currentPacket, uint8_t set_step) { + TcPacketPusBase* currentPacket, uint8_t set_step) { if (acknowledgeQueue == MessageQueueIF::NO_QUEUE) { this->initialize(); } @@ -59,7 +59,7 @@ void VerificationReporter::sendSuccessReport(uint8_t set_report_id, } void VerificationReporter::sendFailureReport(uint8_t report_id, - TcPacketBase* currentPacket, ReturnValue_t error_code, uint8_t step, + TcPacketPusBase* currentPacket, ReturnValue_t error_code, uint8_t step, uint32_t parameter1, uint32_t parameter2) { if (acknowledgeQueue == MessageQueueIF::NO_QUEUE) { this->initialize(); diff --git a/src/fsfw/tmtcservices/VerificationReporter.h b/src/fsfw/tmtcservices/VerificationReporter.h index 4a64d3df..d57cc791 100644 --- a/src/fsfw/tmtcservices/VerificationReporter.h +++ b/src/fsfw/tmtcservices/VerificationReporter.h @@ -25,13 +25,13 @@ public: VerificationReporter(); virtual ~VerificationReporter(); - void sendSuccessReport( uint8_t set_report_id, TcPacketBase* current_packet, + void sendSuccessReport( uint8_t set_report_id, TcPacketPusBase* current_packet, uint8_t set_step = 0 ); void sendSuccessReport(uint8_t set_report_id, uint8_t ackFlags, uint16_t tcPacketId, uint16_t tcSequenceControl, uint8_t set_step = 0); - void sendFailureReport( uint8_t report_id, TcPacketBase* current_packet, + void sendFailureReport( uint8_t report_id, TcPacketPusBase* current_packet, ReturnValue_t error_code = 0, uint8_t step = 0, uint32_t parameter1 = 0, uint32_t parameter2 = 0 ); diff --git a/tests/src/fsfw_tests/unit/CMakeLists.txt b/tests/src/fsfw_tests/unit/CMakeLists.txt index 164e3bde..ce0d313c 100644 --- a/tests/src/fsfw_tests/unit/CMakeLists.txt +++ b/tests/src/fsfw_tests/unit/CMakeLists.txt @@ -21,3 +21,4 @@ add_subdirectory(storagemanager) add_subdirectory(globalfunctions) add_subdirectory(timemanager) add_subdirectory(tmtcpacket) +add_subdirectory(cfdp) diff --git a/tests/src/fsfw_tests/unit/cfdp/CMakeLists.txt b/tests/src/fsfw_tests/unit/cfdp/CMakeLists.txt new file mode 100644 index 00000000..8e18cd3b --- /dev/null +++ b/tests/src/fsfw_tests/unit/cfdp/CMakeLists.txt @@ -0,0 +1,12 @@ +target_sources(${FSFW_TEST_TGT} PRIVATE + testCfdp.cpp + testTlvsLvs.cpp + testAckPdu.cpp + testEofPdu.cpp + testNakPdu.cpp + testFinishedPdu.cpp + testPromptPdu.cpp + testKeepAlivePdu.cpp + testMetadataPdu.cpp + testFileData.cpp +) diff --git a/tests/src/fsfw_tests/unit/cfdp/testAckPdu.cpp b/tests/src/fsfw_tests/unit/cfdp/testAckPdu.cpp new file mode 100644 index 00000000..70576543 --- /dev/null +++ b/tests/src/fsfw_tests/unit/cfdp/testAckPdu.cpp @@ -0,0 +1,101 @@ +#include + +#include "fsfw/cfdp/pdu/AckPduDeserializer.h" +#include "fsfw/cfdp/pdu/AckPduSerializer.h" +#include "fsfw/globalfunctions/arrayprinter.h" + +#include + +TEST_CASE( "ACK PDU" , "[AckPdu]") { + + using namespace cfdp; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + std::array buf = {}; + uint8_t* bufptr = buf.data(); + size_t maxsz = buf.size(); + size_t sz = 0; + auto seqNum = TransactionSeqNum(WidthInBytes::TWO_BYTES, 15); + auto sourceId = EntityId(WidthInBytes::TWO_BYTES, 1); + auto destId = EntityId(WidthInBytes::TWO_BYTES, 2); + auto pduConf = PduConfig(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); + AckInfo ackInfo(FileDirectives::EOF_DIRECTIVE, ConditionCode::NO_ERROR, AckTransactionStatus::ACTIVE); + auto ackSerializer = AckPduSerializer(ackInfo, pduConf); + result = ackSerializer.serialize(&bufptr, &sz, maxsz, SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + SECTION("Serialize") { + REQUIRE(buf.data()[sz - 3] == cfdp::FileDirectives::ACK); + REQUIRE((buf.data()[sz - 2] >> 4) == FileDirectives::EOF_DIRECTIVE); + REQUIRE((buf.data()[sz - 2] & 0x0f) == 0); + REQUIRE(buf.data()[sz - 1] == AckTransactionStatus::ACTIVE); + ackInfo.setAckedDirective(FileDirectives::FINISH); + ackInfo.setAckedConditionCode(ConditionCode::FILESTORE_REJECTION); + ackInfo.setTransactionStatus(AckTransactionStatus::TERMINATED); + auto ackSerializer2 = AckPduSerializer(ackInfo, pduConf); + bufptr = buf.data(); + sz = 0; + result = ackSerializer2.serialize(&bufptr, &sz, maxsz, SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(buf.data()[sz - 3] == cfdp::FileDirectives::ACK); + REQUIRE((buf.data()[sz - 2] >> 4) == FileDirectives::FINISH); + REQUIRE((buf.data()[sz - 2] & 0x0f) == 0b0001); + REQUIRE((buf.data()[sz - 1] >> 4) == ConditionCode::FILESTORE_REJECTION); + REQUIRE((buf.data()[sz - 1] & 0b11) == AckTransactionStatus::TERMINATED); + + bufptr = buf.data(); + sz = 0; + ackInfo.setAckedDirective(FileDirectives::KEEP_ALIVE); + auto ackSerializer3 = AckPduSerializer(ackInfo, pduConf); + result = ackSerializer3.serialize(&bufptr, &sz, maxsz, SerializeIF::Endianness::NETWORK); + // Invalid file directive + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + + ackInfo.setAckedDirective(FileDirectives::FINISH); + // buffer too small + result = ackSerializer.serialize(&bufptr, &sz, 8, SerializeIF::Endianness::NETWORK); + REQUIRE(result == SerializeIF::BUFFER_TOO_SHORT); + } + + SECTION("Deserialize") { + AckInfo ackInfo; + auto reader = AckPduDeserializer(buf.data(), sz, ackInfo); + result = reader.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(ackInfo.getAckedDirective() == FileDirectives::EOF_DIRECTIVE); + REQUIRE(ackInfo.getAckedConditionCode() == ConditionCode::NO_ERROR); + REQUIRE(ackInfo.getDirectiveSubtypeCode() == 0); + REQUIRE(ackInfo.getTransactionStatus() == AckTransactionStatus::ACTIVE); + + AckInfo newInfo = AckInfo(FileDirectives::FINISH, + ConditionCode::FILESTORE_REJECTION, AckTransactionStatus::TERMINATED); + auto ackSerializer2 = AckPduSerializer(newInfo, pduConf); + bufptr = buf.data(); + sz = 0; + result = ackSerializer2.serialize(&bufptr, &sz, maxsz, SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + auto reader2 = AckPduDeserializer(buf.data(), sz, ackInfo); + result = reader2.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(ackInfo.getAckedDirective() == FileDirectives::FINISH); + REQUIRE(ackInfo.getAckedConditionCode() == ConditionCode::FILESTORE_REJECTION); + REQUIRE(ackInfo.getDirectiveSubtypeCode() == 0b0001); + REQUIRE(ackInfo.getTransactionStatus() == AckTransactionStatus::TERMINATED); + + uint8_t prevVal = buf[sz - 2]; + buf[sz - 2] = FileDirectives::INVALID_DIRECTIVE << 4; + result = reader2.parseData(); + REQUIRE(result == cfdp::INVALID_ACK_DIRECTIVE_FIELDS); + buf[sz - 2] = FileDirectives::FINISH << 4 | 0b1111; + result = reader2.parseData(); + REQUIRE(result == cfdp::INVALID_ACK_DIRECTIVE_FIELDS); + buf[sz - 2] = prevVal; + buf[sz - 3] = cfdp::FileDirectives::INVALID_DIRECTIVE; + result = reader2.parseData(); + REQUIRE(result == cfdp::INVALID_DIRECTIVE_FIELDS); + buf[sz - 3] = cfdp::FileDirectives::ACK; + auto maxSizeTooSmall = AckPduDeserializer(buf.data(), sz - 2, ackInfo); + result = maxSizeTooSmall.parseData(); + REQUIRE(result == SerializeIF::STREAM_TOO_SHORT); + } +} diff --git a/tests/src/fsfw_tests/unit/cfdp/testCfdp.cpp b/tests/src/fsfw_tests/unit/cfdp/testCfdp.cpp new file mode 100644 index 00000000..7db3800d --- /dev/null +++ b/tests/src/fsfw_tests/unit/cfdp/testCfdp.cpp @@ -0,0 +1,372 @@ +#include +#include "fsfw/cfdp/pdu/FileDirectiveDeserializer.h" +#include "fsfw/cfdp/pdu/FileDirectiveSerializer.h" +#include "fsfw/cfdp/pdu/HeaderDeserializer.h" +#include "fsfw_tests/unit/CatchDefinitions.h" +#include "fsfw/cfdp/FileSize.h" +#include "fsfw/globalfunctions/arrayprinter.h" +#include "fsfw/cfdp/pdu/HeaderSerializer.h" +#include "fsfw/serialize/SerializeAdapter.h" + +#include +#include + +TEST_CASE( "CFDP Base" , "[CfdpBase]") { + using namespace cfdp; + std::array serBuf; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + cfdp::TransactionSeqNum seqNum = TransactionSeqNum(cfdp::WidthInBytes::ONE_BYTE, 2); + cfdp::EntityId sourceId = EntityId(cfdp::WidthInBytes::ONE_BYTE, 0); + cfdp::EntityId destId = EntityId(cfdp::WidthInBytes::ONE_BYTE, 1); + PduConfig pduConf = PduConfig(cfdp::TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, + destId, false); + uint8_t* serTarget = serBuf.data(); + const uint8_t* deserTarget = serTarget; + size_t serSize = 0; + + SECTION("Header Serialization") { + auto headerSerializer = HeaderSerializer(pduConf, cfdp::PduType::FILE_DIRECTIVE, 0); + const uint8_t** dummyPtr = nullptr; + ReturnValue_t deserResult = headerSerializer.deSerialize(dummyPtr, &serSize, + SerializeIF::Endianness::NETWORK); + REQUIRE(deserResult == retval::CATCH_FAILED); + deserResult = headerSerializer.serialize(nullptr, &serSize, serBuf.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(deserResult == retval::CATCH_FAILED); + REQUIRE(seqNum.getSerializedSize() == 1); + + REQUIRE(headerSerializer.getPduDataFieldLen() == 0); + REQUIRE(headerSerializer.getSerializedSize() == 7); + REQUIRE(headerSerializer.getWholePduSize() == 7); + REQUIRE(headerSerializer.getCrcFlag() == false); + REQUIRE(headerSerializer.getDirection() == cfdp::Direction::TOWARDS_RECEIVER); + REQUIRE(headerSerializer.getLargeFileFlag() == false); + REQUIRE(headerSerializer.getLenEntityIds() == 1); + REQUIRE(headerSerializer.getLenSeqNum() == 1); + REQUIRE(headerSerializer.getPduType() == cfdp::PduType::FILE_DIRECTIVE); + REQUIRE(headerSerializer.getSegmentMetadataFlag() == cfdp::SegmentMetadataFlag::NOT_PRESENT); + REQUIRE(headerSerializer.getSegmentationControl() == false); + REQUIRE(headerSerializer.getTransmissionMode() == cfdp::TransmissionModes::ACKNOWLEDGED); + + cfdp::TransactionSeqNum seqNumLocal; + headerSerializer.getTransactionSeqNum(seqNumLocal); + REQUIRE(seqNumLocal.getWidth() == cfdp::WidthInBytes::ONE_BYTE); + REQUIRE(seqNumLocal.getValue() == 2); + cfdp::EntityId sourceDestId; + headerSerializer.getSourceId(sourceDestId); + REQUIRE(sourceDestId.getWidth() == cfdp::WidthInBytes::ONE_BYTE); + REQUIRE(sourceDestId.getValue() == 0); + headerSerializer.getDestId(sourceDestId); + REQUIRE(sourceDestId.getWidth() == cfdp::WidthInBytes::ONE_BYTE); + REQUIRE(sourceDestId.getValue() == 1); + + result = headerSerializer.serialize(&serTarget, &serSize, + serBuf.size(), SerializeIF::Endianness::BIG); + REQUIRE(result == retval::CATCH_OK); + REQUIRE(serSize == 7); + // Only version bits are set + REQUIRE(serBuf[0] == 0b00100000); + // PDU data field length is 0 + REQUIRE(serBuf[1] == 0); + REQUIRE(serBuf[2] == 0); + // Entity and Transaction Sequence number are 1 byte large + REQUIRE(serBuf[3] == 0b00010001); + // Source ID + REQUIRE(serBuf[4] == 0); + // Transaction Seq Number + REQUIRE(serBuf[5] == 2); + // Dest ID + REQUIRE(serBuf[6] == 1); + + for(uint8_t idx = 0; idx < 7; idx++) { + ReturnValue_t result = headerSerializer.serialize(&serTarget, &serSize, + idx, SerializeIF::Endianness::BIG); + REQUIRE(result == static_cast(SerializeIF::BUFFER_TOO_SHORT)); + } + + // Set PDU data field len + headerSerializer.setPduDataFieldLen(0x0ff0); + REQUIRE(headerSerializer.getPduDataFieldLen() == 0x0ff0); + REQUIRE(headerSerializer.getSerializedSize() == 7); + REQUIRE(headerSerializer.getWholePduSize() == 7 + 0x0ff0); + serTarget = serBuf.data(); + serSize = 0; + result = headerSerializer.serialize(&serTarget, &serSize, + serBuf.size(), SerializeIF::Endianness::BIG); + REQUIRE(serBuf[1] == 0x0f); + REQUIRE(serBuf[2] == 0xf0); + + pduConf.crcFlag = true; + pduConf.largeFile = true; + pduConf.direction = cfdp::Direction::TOWARDS_SENDER; + pduConf.mode = cfdp::TransmissionModes::UNACKNOWLEDGED; + headerSerializer.setSegmentationControl( + cfdp::SegmentationControl::RECORD_BOUNDARIES_PRESERVATION); + headerSerializer.setPduType(cfdp::PduType::FILE_DATA); + headerSerializer.setSegmentMetadataFlag(cfdp::SegmentMetadataFlag::PRESENT); + serTarget = serBuf.data(); + serSize = 0; + result = headerSerializer.serialize(&serTarget, &serSize, + serBuf.size(), SerializeIF::Endianness::BIG); + + // Everything except version bit flipped to one now + REQUIRE(serBuf[0] == 0x3f); + REQUIRE(serBuf[3] == 0x99); + pduConf.seqNum.setValue(cfdp::WidthInBytes::TWO_BYTES, 0x0fff); + pduConf.sourceId.setValue(cfdp::WidthInBytes::FOUR_BYTES, 0xff00ff00); + pduConf.destId.setValue(cfdp::WidthInBytes::FOUR_BYTES, 0x00ff00ff); + REQUIRE(pduConf.sourceId.getSerializedSize() == 4); + REQUIRE(headerSerializer.getSerializedSize() == 14); + serTarget = serBuf.data(); + serSize = 0; + result = headerSerializer.serialize(&serTarget, &serSize, + serBuf.size(), SerializeIF::Endianness::BIG); + + for(uint8_t idx = 0; idx < 14; idx++) { + ReturnValue_t result = headerSerializer.serialize(&serTarget, &serSize, + idx, SerializeIF::Endianness::BIG); + REQUIRE(result == static_cast(SerializeIF::BUFFER_TOO_SHORT)); + } + REQUIRE(headerSerializer.getCrcFlag() == true); + REQUIRE(headerSerializer.getDirection() == cfdp::Direction::TOWARDS_SENDER); + REQUIRE(headerSerializer.getLargeFileFlag() == true); + REQUIRE(headerSerializer.getLenEntityIds() == 4); + REQUIRE(headerSerializer.getLenSeqNum() == 2); + REQUIRE(headerSerializer.getPduType() == cfdp::PduType::FILE_DATA); + REQUIRE(headerSerializer.getSegmentMetadataFlag() == cfdp::SegmentMetadataFlag::PRESENT); + REQUIRE(headerSerializer.getTransmissionMode() == cfdp::TransmissionModes::UNACKNOWLEDGED); + REQUIRE(headerSerializer.getSegmentationControl() == true); + // Last three bits are 2 now (length of seq number) and bit 1 to bit 3 is 4 (len entity IDs) + REQUIRE(serBuf[3] == 0b11001010); + uint32_t entityId = 0; + size_t deSerSize = 0; + SerializeAdapter::deSerialize(&entityId, serBuf.data() + 4, &deSerSize, + SerializeIF::Endianness::NETWORK); + REQUIRE(deSerSize == 4); + REQUIRE(entityId == 0xff00ff00); + uint16_t seqNum = 0; + SerializeAdapter::deSerialize(&seqNum, serBuf.data() + 8, &deSerSize, + SerializeIF::Endianness::NETWORK); + REQUIRE(deSerSize == 2); + REQUIRE(seqNum == 0x0fff); + SerializeAdapter::deSerialize(&entityId, serBuf.data() + 10, &deSerSize, + SerializeIF::Endianness::NETWORK); + REQUIRE(deSerSize == 4); + REQUIRE(entityId == 0x00ff00ff); + + result = pduConf.sourceId.setValue(cfdp::WidthInBytes::ONE_BYTE, 0xfff); + REQUIRE(result == retval::CATCH_FAILED); + result = pduConf.sourceId.setValue(cfdp::WidthInBytes::TWO_BYTES, 0xfffff); + REQUIRE(result == retval::CATCH_FAILED); + result = pduConf.sourceId.setValue(cfdp::WidthInBytes::FOUR_BYTES, 0xfffffffff); + REQUIRE(result == retval::CATCH_FAILED); + uint8_t oneByteSourceId = 32; + serTarget = &oneByteSourceId; + size_t deserLen = 1; + pduConf.sourceId.deSerialize(cfdp::WidthInBytes::ONE_BYTE, + const_cast(&serTarget), &deserLen, + SerializeIF::Endianness::MACHINE); + REQUIRE(pduConf.sourceId.getValue() == 32); + + uint16_t twoByteSourceId = 0xf0f0; + serTarget = reinterpret_cast(&twoByteSourceId); + deserLen = 2; + pduConf.sourceId.deSerialize(cfdp::WidthInBytes::TWO_BYTES, + const_cast(&serTarget), &deserLen, + SerializeIF::Endianness::MACHINE); + REQUIRE(pduConf.sourceId.getValue() == 0xf0f0); + + uint32_t fourByteSourceId = 0xf0f0f0f0; + serTarget = reinterpret_cast(&fourByteSourceId); + deserLen = 4; + pduConf.sourceId.deSerialize(cfdp::WidthInBytes::FOUR_BYTES, + const_cast(&serTarget), &deserLen, + SerializeIF::Endianness::MACHINE); + REQUIRE(pduConf.sourceId.getValue() == 0xf0f0f0f0); + + pduConf.sourceId.setValue(cfdp::WidthInBytes::ONE_BYTE, 1); + serTarget = serBuf.data(); + serSize = 1; + result = pduConf.sourceId.serialize(&serTarget, &serSize, 1, + SerializeIF::Endianness::MACHINE); + REQUIRE(result == static_cast(SerializeIF::BUFFER_TOO_SHORT)); + } + + SECTION( "Header Deserialization" ) { + // We unittested the serializer before, so we can use it now to generate valid raw CFDP + // data + auto headerSerializer = HeaderSerializer(pduConf, cfdp::PduType::FILE_DIRECTIVE, 0); + ReturnValue_t result = headerSerializer.serialize(&serTarget, &serSize, + serBuf.size(), SerializeIF::Endianness::BIG); + REQUIRE(result == retval::CATCH_OK); + REQUIRE(serBuf[1] == 0); + REQUIRE(serBuf[2] == 0); + // Entity and Transaction Sequence number are 1 byte large + REQUIRE(serBuf[3] == 0b00010001); + REQUIRE(serSize == 7); + // Deser call not strictly necessary + auto headerDeser = HeaderDeserializer(serBuf.data(), serBuf.size()); + + ReturnValue_t serResult = headerDeser.parseData(); + REQUIRE(serResult == retval::CATCH_OK); + REQUIRE(headerDeser.getPduDataFieldLen() == 0); + REQUIRE(headerDeser.getHeaderSize() == 7); + REQUIRE(headerDeser.getWholePduSize() == 7); + REQUIRE(headerDeser.getCrcFlag() == false); + REQUIRE(headerDeser.getDirection() == cfdp::Direction::TOWARDS_RECEIVER); + REQUIRE(headerDeser.getLargeFileFlag() == false); + REQUIRE(headerDeser.getLenEntityIds() == 1); + REQUIRE(headerDeser.getLenSeqNum() == 1); + REQUIRE(headerDeser.getPduType() == cfdp::PduType::FILE_DIRECTIVE); + REQUIRE(headerDeser.getSegmentMetadataFlag() == cfdp::SegmentMetadataFlag::NOT_PRESENT); + REQUIRE(headerDeser.getSegmentationControl() == false); + REQUIRE(headerDeser.getTransmissionMode() == cfdp::TransmissionModes::ACKNOWLEDGED); + + pduConf.crcFlag = true; + pduConf.largeFile = true; + pduConf.direction = cfdp::Direction::TOWARDS_SENDER; + pduConf.mode = cfdp::TransmissionModes::UNACKNOWLEDGED; + headerSerializer.setSegmentationControl( + cfdp::SegmentationControl::RECORD_BOUNDARIES_PRESERVATION); + headerSerializer.setPduType(cfdp::PduType::FILE_DATA); + headerSerializer.setSegmentMetadataFlag(cfdp::SegmentMetadataFlag::PRESENT); + result = pduConf.seqNum.setValue(cfdp::WidthInBytes::TWO_BYTES, 0x0fff); + REQUIRE(result == retval::CATCH_OK); + result = pduConf.sourceId.setValue(cfdp::WidthInBytes::FOUR_BYTES, 0xff00ff00); + REQUIRE(result == retval::CATCH_OK); + result = pduConf.destId.setValue(cfdp::WidthInBytes::FOUR_BYTES, 0x00ff00ff); + REQUIRE(result == retval::CATCH_OK); + serTarget = serBuf.data(); + serSize = 0; + result = headerSerializer.serialize(&serTarget, &serSize, + serBuf.size(), SerializeIF::Endianness::BIG); + headerDeser = HeaderDeserializer(serBuf.data(), serBuf.size()); + + result = headerDeser.parseData(); + REQUIRE(result == retval::CATCH_OK); + // Everything except version bit flipped to one now + REQUIRE(serBuf[0] == 0x3f); + REQUIRE(serBuf[3] == 0b11001010); + REQUIRE(headerDeser.getWholePduSize() == 14); + + REQUIRE(headerDeser.getCrcFlag() == true); + REQUIRE(headerDeser.getDirection() == cfdp::Direction::TOWARDS_SENDER); + REQUIRE(headerDeser.getLargeFileFlag() == true); + REQUIRE(headerDeser.getLenEntityIds() == 4); + REQUIRE(headerDeser.getLenSeqNum() == 2); + REQUIRE(headerDeser.getPduType() == cfdp::PduType::FILE_DATA); + REQUIRE(headerDeser.getSegmentMetadataFlag() == cfdp::SegmentMetadataFlag::PRESENT); + REQUIRE(headerDeser.getSegmentationControl() == true); + REQUIRE(headerDeser.getTransmissionMode() == cfdp::TransmissionModes::UNACKNOWLEDGED); + + cfdp::TransactionSeqNum seqNumLocal; + headerDeser.getTransactionSeqNum(seqNumLocal); + REQUIRE(seqNumLocal.getWidth() == cfdp::WidthInBytes::TWO_BYTES); + REQUIRE(seqNumLocal.getValue() == 0x0fff); + cfdp::EntityId sourceDestId; + headerDeser.getSourceId(sourceDestId); + REQUIRE(sourceDestId.getWidth() == cfdp::WidthInBytes::FOUR_BYTES); + REQUIRE(sourceDestId.getValue() == 0xff00ff00); + headerDeser.getDestId(sourceDestId); + REQUIRE(sourceDestId.getWidth() == cfdp::WidthInBytes::FOUR_BYTES); + REQUIRE(sourceDestId.getValue() == 0x00ff00ff); + + size_t deSerSize = headerDeser.getWholePduSize(); + serTarget = serBuf.data(); + const uint8_t** serTargetConst = const_cast(&serTarget); + result = headerDeser.parseData(); + REQUIRE(result == retval::CATCH_OK); + + headerDeser.setData(nullptr, -1); + REQUIRE(headerDeser.getHeaderSize() == 0); + headerDeser.setData(serBuf.data(), serBuf.size()); + + serTarget = serBuf.data(); + serSize = 0; + pduConf.sourceId.setValue(cfdp::WidthInBytes::ONE_BYTE, 22); + pduConf.destId.setValue(cfdp::WidthInBytes::ONE_BYTE, 48); + result = headerSerializer.serialize(&serTarget, &serSize, + serBuf.size(), SerializeIF::Endianness::BIG); + REQUIRE(result == retval::CATCH_OK); + REQUIRE(headerDeser.getWholePduSize() == 8); + headerDeser.setData(serBuf.data(), serBuf.size()); + + headerDeser.getSourceId(sourceDestId); + REQUIRE(sourceDestId.getWidth() == cfdp::WidthInBytes::ONE_BYTE); + REQUIRE(sourceDestId.getValue() == 22); + } + + SECTION("File Directive") { + auto fdSer = FileDirectiveSerializer(pduConf, FileDirectives::ACK, 4); + REQUIRE(fdSer.getSerializedSize() == 8); + serTarget = serBuf.data(); + serSize = 0; + result = fdSer.serialize(&serTarget, &serSize, serBuf.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + // Only version bits are set + REQUIRE(serBuf[0] == 0b00100000); + // PDU data field length is 5 (4 + Directive code octet) + REQUIRE(serBuf[1] == 0); + REQUIRE(serBuf[2] == 5); + // Entity and Transaction Sequence number are 1 byte large + REQUIRE(serBuf[3] == 0b00010001); + // Source ID + REQUIRE(serBuf[4] == 0); + // Transaction Seq Number + REQUIRE(serBuf[5] == 2); + // Dest ID + REQUIRE(serBuf[6] == 1); + REQUIRE(serBuf[7] == FileDirectives::ACK); + + serTarget = serBuf.data(); + size_t deserSize = 20; + serSize = 0; + REQUIRE(fdSer.deSerialize(&deserTarget, &deserSize, SerializeIF::Endianness::NETWORK) == + HasReturnvaluesIF::RETURN_FAILED); + REQUIRE(fdSer.serialize(nullptr, nullptr, 85, SerializeIF::Endianness::NETWORK) == + HasReturnvaluesIF::RETURN_FAILED); + for(uint8_t idx = 0; idx < 8; idx++) { + serTarget = serBuf.data(); + serSize = 0; + REQUIRE(fdSer.serialize(&serTarget, &serSize, idx, SerializeIF::Endianness::NETWORK) == + SerializeIF::BUFFER_TOO_SHORT); + } + + deserTarget = serBuf.data(); + deserSize = 0; + auto fdDeser = FileDirectiveDeserializer(deserTarget, serBuf.size()); + REQUIRE(fdDeser.getEndianness() == SerializeIF::Endianness::NETWORK); + fdDeser.setEndianness(SerializeIF::Endianness::MACHINE); + REQUIRE(fdDeser.getEndianness() == SerializeIF::Endianness::MACHINE); + fdDeser.setEndianness(SerializeIF::Endianness::NETWORK); + REQUIRE(fdDeser.parseData() == HasReturnvaluesIF::RETURN_OK); + REQUIRE(fdDeser.getFileDirective() == FileDirectives::ACK); + REQUIRE(fdDeser.getPduDataFieldLen() == 5); + REQUIRE(fdDeser.getHeaderSize() == 8); + REQUIRE(fdDeser.getPduType() == cfdp::PduType::FILE_DIRECTIVE); + + serBuf[7] = 0xff; + // Invalid file directive + REQUIRE(fdDeser.parseData() == cfdp::INVALID_DIRECTIVE_FIELDS); + } + + SECTION("FileSize") { + std::array fssBuf = {}; + uint8_t* buffer = fssBuf.data(); + size_t size = 0; + cfdp::FileSize fss; + REQUIRE(fss.getSize() == 0); + fss.setFileSize(0x20, false); + ReturnValue_t result = fss.serialize(&buffer, &size, fssBuf.size(), + SerializeIF::Endianness::MACHINE); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + uint32_t fileSize = 0; + result = SerializeAdapter::deSerialize(&fileSize, fssBuf.data(), nullptr, + SerializeIF::Endianness::MACHINE); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(fileSize == 0x20); + + } +} + diff --git a/tests/src/fsfw_tests/unit/cfdp/testEofPdu.cpp b/tests/src/fsfw_tests/unit/cfdp/testEofPdu.cpp new file mode 100644 index 00000000..9edaf572 --- /dev/null +++ b/tests/src/fsfw_tests/unit/cfdp/testEofPdu.cpp @@ -0,0 +1,124 @@ +#include + +#include "fsfw/cfdp/pdu/EofPduDeserializer.h" +#include "fsfw/cfdp/pdu/EofPduSerializer.h" +#include "fsfw/globalfunctions/arrayprinter.h" + +#include + +TEST_CASE( "EOF PDU" , "[EofPdu]") { + using namespace cfdp; + + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + std::array buf = {}; + uint8_t* bufPtr = buf.data(); + size_t sz = 0; + EntityId destId(WidthInBytes::TWO_BYTES, 2); + EntityIdTlv faultLoc(destId); + FileSize fileSize(12); + // We can already set the fault location, it will be ignored + EofInfo eofInfo(cfdp::ConditionCode::NO_ERROR, 5, fileSize, &faultLoc); + TransactionSeqNum seqNum(WidthInBytes::TWO_BYTES, 15); + EntityId sourceId(WidthInBytes::TWO_BYTES, 1); + + PduConfig pduConf(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); + + auto eofSerializer = EofPduSerializer(pduConf, eofInfo); + SECTION("Serialize") { + result = eofSerializer.serialize(&bufPtr, &sz, buf.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(((buf[1] << 8) | buf[2]) == 10); + uint32_t checksum = 0; + result = SerializeAdapter::deSerialize(&checksum, buf.data() + sz - 8, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(checksum == 5); + uint32_t fileSizeVal = 0; + result = SerializeAdapter::deSerialize(&fileSizeVal, buf.data() + sz - 4, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(fileSizeVal == 12); + REQUIRE(buf[sz - 10] == cfdp::FileDirectives::EOF_DIRECTIVE); + REQUIRE(buf[sz - 9] == 0x00); + REQUIRE(sz == 20); + + eofInfo.setConditionCode(cfdp::ConditionCode::FILESTORE_REJECTION); + eofInfo.setFileSize(0x10ffffff10, true); + pduConf.largeFile = true; + // Should serialize with fault location now + auto serializeWithFaultLocation = EofPduSerializer(pduConf, eofInfo); + bufPtr = buf.data(); + sz = 0; + result = serializeWithFaultLocation.serialize(&bufPtr, &sz, buf.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(sz == 28); + REQUIRE(buf[10] == cfdp::FileDirectives::EOF_DIRECTIVE); + REQUIRE(buf[11] >> 4 == cfdp::ConditionCode::FILESTORE_REJECTION); + uint64_t fileSizeLarge = 0; + result = SerializeAdapter::deSerialize(&fileSizeLarge, buf.data() + 16, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(fileSizeLarge == 0x10ffffff10); + REQUIRE(buf[sz - 4] == cfdp::TlvTypes::ENTITY_ID); + // width of entity ID is 2 + REQUIRE(buf[sz - 3] == 2); + uint16_t entityIdRaw = 0; + result = SerializeAdapter::deSerialize(&entityIdRaw, buf.data() + sz - 2, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(entityIdRaw == 2); + bufPtr = buf.data(); + sz = 0; + for(size_t idx = 0; idx < 27; idx++) { + result = serializeWithFaultLocation.serialize(&bufPtr, &sz, idx, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == SerializeIF::BUFFER_TOO_SHORT); + bufPtr = buf.data(); + sz = 0; + } + eofInfo.setChecksum(16); + eofInfo.setFaultLoc(nullptr); + } + + SECTION("Deserialize") { + result = eofSerializer.serialize(&bufPtr, &sz, buf.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + EntityIdTlv tlv(destId); + EofInfo emptyInfo(&tlv); + auto deserializer = EofPduDeserializer(buf.data(), buf.size(), emptyInfo); + result = deserializer.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(emptyInfo.getConditionCode() == cfdp::ConditionCode::NO_ERROR); + REQUIRE(emptyInfo.getChecksum() == 5); + REQUIRE(emptyInfo.getFileSize().getSize() == 12); + + eofInfo.setConditionCode(cfdp::ConditionCode::FILESTORE_REJECTION); + eofInfo.setFileSize(0x10ffffff10, true); + pduConf.largeFile = true; + // Should serialize with fault location now + auto serializeWithFaultLocation = EofPduSerializer(pduConf, eofInfo); + bufPtr = buf.data(); + sz = 0; + result = serializeWithFaultLocation.serialize(&bufPtr, &sz, buf.size(), + SerializeIF::Endianness::NETWORK); + auto deserializer2 = EofPduDeserializer(buf.data(), buf.size(), emptyInfo); + result = deserializer2.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(emptyInfo.getConditionCode() == cfdp::ConditionCode::FILESTORE_REJECTION); + REQUIRE(emptyInfo.getChecksum() == 5); + REQUIRE(emptyInfo.getFileSize().getSize() == 0x10ffffff10); + REQUIRE(emptyInfo.getFaultLoc()->getType() == cfdp::TlvTypes::ENTITY_ID); + REQUIRE(emptyInfo.getFaultLoc()->getSerializedSize() == 4); + uint16_t destId = emptyInfo.getFaultLoc()->getEntityId().getValue(); + REQUIRE(destId == 2); + for(size_t maxSz = 0; maxSz < deserializer2.getWholePduSize() - 1; maxSz++) { + auto invalidDeser = EofPduDeserializer(buf.data(), maxSz, emptyInfo); + result = invalidDeser.parseData(); + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + } + } + +} + + diff --git a/tests/src/fsfw_tests/unit/cfdp/testFileData.cpp b/tests/src/fsfw_tests/unit/cfdp/testFileData.cpp new file mode 100644 index 00000000..8a84a2a3 --- /dev/null +++ b/tests/src/fsfw_tests/unit/cfdp/testFileData.cpp @@ -0,0 +1,175 @@ +#include + +#include "fsfw/cfdp/pdu/FileDataDeserializer.h" +#include "fsfw/cfdp/pdu/FileDataSerializer.h" +#include "fsfw/globalfunctions/arrayprinter.h" +#include "fsfw/serviceinterface.h" + +#include + +TEST_CASE( "File Data PDU" , "[FileDataPdu]") { + using namespace cfdp; + + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + std::array fileBuffer = {}; + std::array fileDataBuffer = {}; + uint8_t* buffer = fileDataBuffer.data(); + size_t sz = 0; + EntityId destId(WidthInBytes::TWO_BYTES, 2); + TransactionSeqNum seqNum(WidthInBytes::TWO_BYTES, 15); + EntityId sourceId(WidthInBytes::TWO_BYTES, 1); + PduConfig pduConf(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); + + for(uint8_t idx = 0; idx < 10; idx++) { + fileBuffer[idx] = idx; + } + FileSize offset(50); + FileDataInfo info(offset, fileBuffer.data(), 10); + + SECTION("Serialization") { + FileDataSerializer serializer(pduConf, info); + result = serializer.serialize(&buffer, &sz, fileDataBuffer.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(sz == 24); + // 10 file bytes plus 4 byte offset + REQUIRE(((fileDataBuffer[1] << 8) | fileDataBuffer[2]) == 14); + // File Data -> Fourth bit is one + REQUIRE(fileDataBuffer[0] == 0b00110000); + uint32_t offsetRaw = 0; + buffer = fileDataBuffer.data(); + result = SerializeAdapter::deSerialize(&offsetRaw, buffer + 10, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(offsetRaw == 50); + buffer = fileDataBuffer.data() + 14; + for(size_t idx = 0; idx < 10; idx++) { + REQUIRE(buffer[idx] == idx); + } + + REQUIRE(info.hasSegmentMetadata() == false); + info.addSegmentMetadataInfo(cfdp::RecordContinuationState::CONTAINS_START_AND_END, + fileBuffer.data(), 10); + REQUIRE(info.hasSegmentMetadata() == true); + REQUIRE(info.getSegmentationControl() == + cfdp::SegmentationControl::NO_RECORD_BOUNDARIES_PRESERVATION); + info.setSegmentationControl(cfdp::SegmentationControl::RECORD_BOUNDARIES_PRESERVATION); + serializer.update(); + REQUIRE(serializer.getSegmentationControl() == + cfdp::SegmentationControl::RECORD_BOUNDARIES_PRESERVATION); + buffer = fileDataBuffer.data(); + sz = 0; + serializer.setSegmentationControl(cfdp::SegmentationControl::RECORD_BOUNDARIES_PRESERVATION); + + result = serializer.serialize(&buffer, &sz, fileDataBuffer.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(((fileDataBuffer[1] << 8) | fileDataBuffer[2]) == 25); + // First bit: Seg Ctrl is set + // Bits 1 to 3 length of enitity IDs is 2 + // Bit 4: Segment metadata flag is set + // Bit 5 to seven: length of transaction seq num is 2 + REQUIRE(fileDataBuffer[3] == 0b10101010); + REQUIRE((fileDataBuffer[10] >> 6) & 0b11 == + cfdp::RecordContinuationState::CONTAINS_START_AND_END); + // Segment metadata length + REQUIRE((fileDataBuffer[10] & 0x3f) == 10); + buffer = fileDataBuffer.data() + 11; + // Check segment metadata + for(size_t idx = 0; idx < 10; idx++) { + REQUIRE(buffer[idx] == idx); + } + // Check filedata + buffer = fileDataBuffer.data() + 25; + for(size_t idx = 0; idx < 10; idx++) { + REQUIRE(buffer[idx] == idx); + } + + for(size_t invalidStartSz = 1; invalidStartSz < sz; invalidStartSz ++) { + buffer = fileDataBuffer.data(); + sz = 0; + result = serializer.serialize(&buffer, &invalidStartSz, sz, + SerializeIF::Endianness::NETWORK); + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + } + + info.setSegmentMetadataFlag(true); + REQUIRE(info.getSegmentMetadataFlag() == cfdp::SegmentMetadataFlag::PRESENT); + info.setSegmentMetadataFlag(false); + REQUIRE(info.getSegmentMetadataFlag() == cfdp::SegmentMetadataFlag::NOT_PRESENT); + info.setRecordContinuationState(cfdp::RecordContinuationState::CONTAINS_END_NO_START); + info.setSegmentMetadataLen(10); + info.setSegmentMetadata(nullptr); + info.setFileData(nullptr, 0); + } + + SECTION("Deserialization") { + FileDataSerializer serializer(pduConf, info); + result = serializer.serialize(&buffer, &sz, fileDataBuffer.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + FileSize emptyOffset; + FileDataInfo emptyInfo(emptyOffset); + FileDataDeserializer deserializer(fileDataBuffer.data(), fileDataBuffer.size(), emptyInfo); + result = deserializer.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(deserializer.getWholePduSize() == 24); + REQUIRE(deserializer.getPduDataFieldLen() == 14); + REQUIRE(deserializer.getSegmentationControl() == + cfdp::SegmentationControl::NO_RECORD_BOUNDARIES_PRESERVATION); + REQUIRE(deserializer.getSegmentMetadataFlag() == + cfdp::SegmentMetadataFlag::NOT_PRESENT); + + REQUIRE(emptyInfo.getOffset().getSize() == 50); + REQUIRE(emptyInfo.hasSegmentMetadata() == false); + size_t emptyFileSize = 0; + const uint8_t* fileData = emptyInfo.getFileData(&emptyFileSize); + REQUIRE(emptyFileSize == 10); + for(size_t idx = 0; idx < 10; idx++) { + REQUIRE(fileData[idx] == idx); + } + + deserializer.setEndianness(SerializeIF::Endianness::NETWORK); + + info.addSegmentMetadataInfo(cfdp::RecordContinuationState::CONTAINS_START_AND_END, + fileBuffer.data(), 10); + serializer.update(); + buffer = fileDataBuffer.data(); + sz = 0; + result = serializer.serialize(&buffer, &sz, fileDataBuffer.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + result = deserializer.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + REQUIRE(emptyInfo.getOffset().getSize() == 50); + REQUIRE(emptyInfo.hasSegmentMetadata() == true); + REQUIRE(emptyInfo.getRecordContinuationState() == + cfdp::RecordContinuationState::CONTAINS_START_AND_END); + emptyFileSize = 0; + fileData = emptyInfo.getFileData(&emptyFileSize); + REQUIRE(emptyFileSize == 10); + for(size_t idx = 0; idx < 10; idx++) { + REQUIRE(fileData[idx] == idx); + } + size_t segmentMetadataLen = 0; + fileData = emptyInfo.getSegmentMetadata(&segmentMetadataLen); + REQUIRE(segmentMetadataLen == 10); + for(size_t idx = 0; idx < 10; idx++) { + REQUIRE(fileData[idx] == idx); + } + for(size_t invalidPduField = 0; invalidPduField < 24; invalidPduField++) { + fileDataBuffer[1] = (invalidPduField >> 8) & 0xff; + fileDataBuffer[2] = invalidPduField & 0xff; + result = deserializer.parseData(); + // Starting at 15, the file data is parsed. There is not leading file data length + // field to the parser can't check whether the remaining length is valid + if(invalidPduField < 15) { + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + } + } + + } +} diff --git a/tests/src/fsfw_tests/unit/cfdp/testFinishedPdu.cpp b/tests/src/fsfw_tests/unit/cfdp/testFinishedPdu.cpp new file mode 100644 index 00000000..718750de --- /dev/null +++ b/tests/src/fsfw_tests/unit/cfdp/testFinishedPdu.cpp @@ -0,0 +1,196 @@ +#include + +#include "fsfw/globalfunctions/arrayprinter.h" +#include "fsfw/cfdp/pdu/FinishedPduDeserializer.h" +#include "fsfw/cfdp/pdu/FinishedPduSerializer.h" + +#include + +TEST_CASE( "Finished PDU" , "[FinishedPdu]") { + using namespace cfdp; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + std::array fnBuffer = {}; + uint8_t* buffer = fnBuffer.data(); + size_t sz = 0; + EntityId destId(WidthInBytes::TWO_BYTES, 2); + TransactionSeqNum seqNum(WidthInBytes::TWO_BYTES, 15); + EntityId sourceId(WidthInBytes::TWO_BYTES, 1); + PduConfig pduConf(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); + + cfdp::Lv emptyFsMsg; + FinishedInfo info(cfdp::ConditionCode::INACTIVITY_DETECTED, + cfdp::FinishedDeliveryCode::DATA_INCOMPLETE, + cfdp::FinishedFileStatus::DISCARDED_DELIBERATELY); + + SECTION("Serialize") { + FinishPduSerializer serializer(pduConf, info); + result = serializer.serialize(&buffer, &sz, fnBuffer.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(serializer.getSerializedSize() == 12); + REQUIRE(((fnBuffer[1] << 8) | fnBuffer[2]) == 2); + REQUIRE(fnBuffer[10] == cfdp::FileDirectives::FINISH); + REQUIRE(((fnBuffer[sz - 1] >> 4) & 0x0f) == cfdp::ConditionCode::INACTIVITY_DETECTED); + REQUIRE(((fnBuffer[sz - 1] >> 2) & 0x01) == cfdp::FinishedDeliveryCode::DATA_INCOMPLETE); + REQUIRE((fnBuffer[sz - 1] & 0b11) == cfdp::FinishedFileStatus::DISCARDED_DELIBERATELY); + REQUIRE(sz == 12); + + // Add a filestore response + std::string firstName = "hello.txt"; + cfdp::Lv firstNameLv(reinterpret_cast(firstName.data()), firstName.size()); + FilestoreResponseTlv response(cfdp::FilestoreActionCode::DELETE_FILE, + cfdp::FSR_APPEND_FILE_1_NOT_EXISTS, firstNameLv, nullptr); + FilestoreResponseTlv* responsePtr = &response; + REQUIRE(response.getSerializedSize() == 14); + size_t len = 1; + info.setFilestoreResponsesArray(&responsePtr, &len, &len); + serializer.updateDirectiveFieldLen(); + REQUIRE(serializer.getSerializedSize() == 12 + 14); + sz = 0; + buffer = fnBuffer.data(); + result = serializer.serialize(&buffer, &sz, fnBuffer.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(serializer.getSerializedSize() == 12 + 14); + REQUIRE(serializer.getPduDataFieldLen() == 16); + + // Add two filestore responses and a fault location parameter + std::string secondName = "hello2.txt"; + cfdp::Lv secondNameLv(reinterpret_cast(secondName.data()), secondName.size()); + FilestoreResponseTlv response2(cfdp::FilestoreActionCode::DENY_FILE , + cfdp::FSR_SUCCESS, secondNameLv, nullptr); + REQUIRE(response2.getSerializedSize() == 15); + len = 2; + std::array responses {&response, &response2}; + info.setFilestoreResponsesArray(responses.data(), &len, &len); + serializer.updateDirectiveFieldLen(); + + EntityIdTlv faultLoc(destId); + REQUIRE(faultLoc.getSerializedSize() == 4); + info.setFaultLocation(&faultLoc); + serializer.updateDirectiveFieldLen(); + sz = 0; + buffer = fnBuffer.data(); + result = serializer.serialize(&buffer, &sz, fnBuffer.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + info.setConditionCode(cfdp::ConditionCode::FILESTORE_REJECTION); + REQUIRE(serializer.getSerializedSize() == 12 + 14 + 15 + 4); + REQUIRE(sz == 12 + 14 + 15 + 4); + info.setFileStatus(cfdp::FinishedFileStatus::DISCARDED_FILESTORE_REJECTION); + REQUIRE(info.getFileStatus() == cfdp::FinishedFileStatus::DISCARDED_FILESTORE_REJECTION); + info.setDeliveryCode(cfdp::FinishedDeliveryCode::DATA_INCOMPLETE); + REQUIRE(info.getDeliveryCode() == cfdp::FinishedDeliveryCode::DATA_INCOMPLETE); + for(size_t maxSz = 0; maxSz < 45; maxSz++) { + sz = 0; + buffer = fnBuffer.data(); + result = serializer.serialize(&buffer, &sz, maxSz, SerializeIF::Endianness::NETWORK); + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + } + } + + SECTION("Deserialize") { + FinishedInfo emptyInfo; + FinishPduSerializer serializer(pduConf, info); + result = serializer.serialize(&buffer, &sz, fnBuffer.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + FinishPduDeserializer deserializer(fnBuffer.data(), fnBuffer.size(), emptyInfo); + result = deserializer.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(emptyInfo.getFileStatus() == cfdp::FinishedFileStatus::DISCARDED_DELIBERATELY); + REQUIRE(emptyInfo.getConditionCode() == cfdp::ConditionCode::INACTIVITY_DETECTED); + REQUIRE(emptyInfo.getDeliveryCode() == cfdp::FinishedDeliveryCode::DATA_INCOMPLETE); + + // Add a filestore response + sz = 0; + buffer = fnBuffer.data(); + std::string firstName = "hello.txt"; + cfdp::Lv firstNameLv(reinterpret_cast(firstName.data()), firstName.size()); + FilestoreResponseTlv response(cfdp::FilestoreActionCode::DELETE_FILE, + cfdp::FSR_NOT_PERFORMED, firstNameLv, nullptr); + FilestoreResponseTlv* responsePtr = &response; + size_t len = 1; + info.setFilestoreResponsesArray(&responsePtr, &len, &len); + serializer.updateDirectiveFieldLen(); + REQUIRE(serializer.getPduDataFieldLen() == 16); + result = serializer.serialize(&buffer, &sz, fnBuffer.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + FilestoreResponseTlv emptyResponse(firstNameLv, nullptr); + responsePtr = &emptyResponse; + emptyInfo.setFilestoreResponsesArray(&responsePtr, nullptr, &len); + FinishPduDeserializer deserializer2(fnBuffer.data(), fnBuffer.size(), emptyInfo); + result = deserializer2.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(emptyInfo.getFsResponsesLen() == 1); + FilestoreResponseTlv** responseArray = nullptr; + emptyInfo.getFilestoreResonses(&responseArray, nullptr, nullptr); + REQUIRE(responseArray[0]->getActionCode() == cfdp::FilestoreActionCode::DELETE_FILE); + REQUIRE(responseArray[0]->getStatusCode() == cfdp::FSR_NOT_PERFORMED); + auto& fileNameRef = responseArray[0]->getFirstFileName(); + size_t stringSize = 0; + const char* string = reinterpret_cast(fileNameRef.getValue(&stringSize)); + std::string firstFileName(string, stringSize); + REQUIRE(firstFileName == "hello.txt"); + + // Add two filestore responses and a fault location parameter + std::string secondName = "hello2.txt"; + cfdp::Lv secondNameLv(reinterpret_cast(secondName.data()), secondName.size()); + FilestoreResponseTlv response2(cfdp::FilestoreActionCode::DENY_FILE , + cfdp::FSR_SUCCESS, secondNameLv, nullptr); + REQUIRE(response2.getSerializedSize() == 15); + len = 2; + std::array responses {&response, &response2}; + info.setFilestoreResponsesArray(responses.data(), &len, &len); + serializer.updateDirectiveFieldLen(); + + EntityIdTlv faultLoc(destId); + info.setFaultLocation(&faultLoc); + serializer.updateDirectiveFieldLen(); + sz = 0; + buffer = fnBuffer.data(); + result = serializer.serialize(&buffer, &sz, fnBuffer.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + EntityId emptyId; + EntityIdTlv emptyFaultLoc(emptyId); + emptyInfo.setFaultLocation(&emptyFaultLoc); + response.setFilestoreMessage(&emptyFsMsg); + emptyInfo.setFilestoreResponsesArray(responses.data(), &len, &len); + response2.setFilestoreMessage(&emptyFsMsg); + FinishPduDeserializer deserializer3(fnBuffer.data(), fnBuffer.size(), emptyInfo); + result = deserializer3.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + auto& infoRef = deserializer3.getInfo(); + REQUIRE(deserializer3.getWholePduSize() == 45); + + size_t invalidMaxLen = 1; + emptyInfo.setFilestoreResponsesArray(responses.data(), &len, &invalidMaxLen); + result = deserializer3.parseData(); + REQUIRE(result == cfdp::FINISHED_CANT_PARSE_FS_RESPONSES); + emptyInfo.setFilestoreResponsesArray(nullptr, nullptr, nullptr); + result = deserializer3.parseData(); + REQUIRE(result == cfdp::FINISHED_CANT_PARSE_FS_RESPONSES); + + // Clear condition code + auto tmp = fnBuffer[11]; + fnBuffer[11] = fnBuffer[11] & ~0xf0; + fnBuffer[11] = fnBuffer[11] | (cfdp::ConditionCode::NO_ERROR << 4); + emptyInfo.setFilestoreResponsesArray(responses.data(), &len, &len); + result = deserializer3.parseData(); + REQUIRE(result == cfdp::INVALID_TLV_TYPE); + + fnBuffer[11] = tmp; + // Invalid TLV type, should be entity ID + fnBuffer[sz - 4] = cfdp::TlvTypes::FILESTORE_REQUEST; + result = deserializer3.parseData(); + REQUIRE(result == cfdp::INVALID_TLV_TYPE); + + for(size_t maxSz = 0; maxSz < 45; maxSz++) { + FinishPduDeserializer faultyDeser(fnBuffer.data(), maxSz, emptyInfo); + result = faultyDeser.parseData(); + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + } + } +} diff --git a/tests/src/fsfw_tests/unit/cfdp/testKeepAlivePdu.cpp b/tests/src/fsfw_tests/unit/cfdp/testKeepAlivePdu.cpp new file mode 100644 index 00000000..09008650 --- /dev/null +++ b/tests/src/fsfw_tests/unit/cfdp/testKeepAlivePdu.cpp @@ -0,0 +1,84 @@ +#include + +#include "fsfw/cfdp/pdu/KeepAlivePduDeserializer.h" +#include "fsfw/cfdp/pdu/KeepAlivePduSerializer.h" +#include "fsfw/globalfunctions/arrayprinter.h" + +#include + +TEST_CASE( "Keep Alive PDU" , "[KeepAlivePdu]") { + using namespace cfdp; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + std::array kaBuffer = {}; + uint8_t* buffer = kaBuffer.data(); + size_t sz = 0; + EntityId destId(WidthInBytes::TWO_BYTES, 2); + TransactionSeqNum seqNum(WidthInBytes::TWO_BYTES, 15); + EntityId sourceId(WidthInBytes::TWO_BYTES, 1); + PduConfig pduConf(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); + + FileSize progress(0x50); + + SECTION("Serialize") { + KeepAlivePduSerializer serializer(pduConf, progress); + result = serializer.serialize(&buffer, &sz, kaBuffer.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(kaBuffer[10] == cfdp::FileDirectives::KEEP_ALIVE); + uint32_t fsRaw = 0; + result = SerializeAdapter::deSerialize(&fsRaw, kaBuffer.data() + 11, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(fsRaw == 0x50); + REQUIRE(sz == 15); + REQUIRE(serializer.getWholePduSize() == 15); + REQUIRE(serializer.getPduDataFieldLen() == 5); + + pduConf.largeFile = true; + serializer.updateDirectiveFieldLen(); + buffer = kaBuffer.data(); + sz = 0; + result = serializer.serialize(&buffer, &sz, kaBuffer.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(serializer.getWholePduSize() == 19); + REQUIRE(serializer.getPduDataFieldLen() == 9); + uint64_t fsRawLarge = 0; + result = SerializeAdapter::deSerialize(&fsRawLarge, kaBuffer.data() + 11, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(fsRawLarge == 0x50); + + for(size_t invalidMaxSz = 0; invalidMaxSz < sz; invalidMaxSz++) { + buffer = kaBuffer.data(); + sz = 0; + result = serializer.serialize(&buffer, &sz, invalidMaxSz, + SerializeIF::Endianness::NETWORK); + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + } + } + + SECTION("Deserialize") { + KeepAlivePduSerializer serializer(pduConf, progress); + result = serializer.serialize(&buffer, &sz, kaBuffer.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + // Set another file size + progress.setFileSize(200, false); + KeepAlivePduDeserializer deserializer(kaBuffer.data(), kaBuffer.size(), progress); + result = deserializer.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + auto& progRef = deserializer.getProgress(); + // Should have been overwritten + REQUIRE(progRef.getSize() == 0x50); + sz = deserializer.getWholePduSize(); + + // invalid max size + for(size_t invalidMaxSz = 0; invalidMaxSz < sz; invalidMaxSz++) { + deserializer.setData(kaBuffer.data(), invalidMaxSz); + result = deserializer.parseData(); + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + } + } +} diff --git a/tests/src/fsfw_tests/unit/cfdp/testMetadataPdu.cpp b/tests/src/fsfw_tests/unit/cfdp/testMetadataPdu.cpp new file mode 100644 index 00000000..50dae9e9 --- /dev/null +++ b/tests/src/fsfw_tests/unit/cfdp/testMetadataPdu.cpp @@ -0,0 +1,185 @@ +#include +#include + +#include "fsfw/cfdp/tlv/FilestoreResponseTlv.h" +#include "fsfw/cfdp/pdu/MetadataPduDeserializer.h" +#include "fsfw/cfdp/pdu/MetadataPduSerializer.h" +#include "fsfw/globalfunctions/arrayprinter.h" + +#include + +TEST_CASE( "Metadata PDU" , "[MetadataPdu]") { + using namespace cfdp; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + std::array mdBuffer = {}; + uint8_t* buffer = mdBuffer.data(); + size_t sz = 0; + EntityId destId(WidthInBytes::TWO_BYTES, 2); + TransactionSeqNum seqNum(WidthInBytes::TWO_BYTES, 15); + EntityId sourceId(WidthInBytes::TWO_BYTES, 1); + PduConfig pduConf(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); + + std::string firstFileName = "hello.txt"; + cfdp::Lv sourceFileName(reinterpret_cast(firstFileName.data()), + firstFileName.size()); + cfdp::Lv destFileName(nullptr, 0); + FileSize fileSize(35); + MetadataInfo info(false, ChecksumType::MODULAR, fileSize, sourceFileName, destFileName); + + FilestoreResponseTlv response(FilestoreActionCode::CREATE_DIRECTORY, FSR_CREATE_NOT_ALLOWED, + sourceFileName, nullptr); + std::array msg = {0x41, 0x42, 0x43}; + cfdp::Tlv responseTlv; + std::array responseBuf = {}; + uint8_t* responseBufPtr = responseBuf.data(); + response.convertToTlv(responseTlv, buffer, responseBuf.size(), + SerializeIF::Endianness::MACHINE); + MessageToUserTlv msgToUser(msg.data(), msg.size()); + std::array options {&responseTlv, &msgToUser}; + REQUIRE(options[0]->getSerializedSize() == 2 + 1 + 10 + 1); + REQUIRE(options[1]->getSerializedSize() == 5); + + SECTION("Serialize") { + MetadataPduSerializer serializer(pduConf, info); + result = serializer.serialize(&buffer, &sz, mdBuffer.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(serializer.getWholePduSize() == 27); + REQUIRE(info.getSourceFileName().getSerializedSize() == 10); + REQUIRE(info.getDestFileName().getSerializedSize() == 1); + REQUIRE(info.getSerializedSize() == 16); + REQUIRE((mdBuffer[1] << 8 | mdBuffer[2]) == 17); + REQUIRE(mdBuffer[10] == FileDirectives::METADATA); + // no closure requested and checksum type is modular => 0x00 + REQUIRE(mdBuffer[11] == 0x00); + uint32_t fileSizeRaw = 0; + result = SerializeAdapter::deSerialize(&fileSizeRaw, mdBuffer.data() + 12, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(fileSizeRaw == 35); + REQUIRE(mdBuffer[16] == 9); + REQUIRE(mdBuffer[17] == 'h'); + REQUIRE(mdBuffer[18] == 'e'); + REQUIRE(mdBuffer[19] == 'l'); + REQUIRE(mdBuffer[20] == 'l'); + REQUIRE(mdBuffer[21] == 'o'); + REQUIRE(mdBuffer[22] == '.'); + REQUIRE(mdBuffer[23] == 't'); + REQUIRE(mdBuffer[24] == 'x'); + REQUIRE(mdBuffer[25] == 't'); + REQUIRE(mdBuffer[26] == 0); + + std::string otherFileName = "hello2.txt"; + cfdp::Lv otherFileNameLv(reinterpret_cast(otherFileName.data()), + otherFileName.size()); + info.setSourceFileName(otherFileNameLv); + size_t sizeOfOptions = options.size(); + info.setOptionsArray(options.data(), &sizeOfOptions, &sizeOfOptions); + REQUIRE(info.getMaxOptionsLen() == 2); + info.setMaxOptionsLen(3); + REQUIRE(info.getMaxOptionsLen() == 3); + info.setChecksumType(cfdp::ChecksumType::CRC_32C); + info.setClosureRequested(true); + uint8_t* buffer = mdBuffer.data(); + size_t sz = 0; + serializer.updateDirectiveFieldLen(); + + result = serializer.serialize(&buffer, &sz, mdBuffer.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE((mdBuffer[1] << 8 | mdBuffer[2]) == 37); + auto checksumType = static_cast(mdBuffer[11] & 0x0f); + REQUIRE(checksumType == cfdp::ChecksumType::CRC_32C); + bool closureRequested = mdBuffer[11] >> 6 & 0x01; + REQUIRE(closureRequested == true); + // The size of the two options is 19. Summing up: + // - 11 bytes of source file name + // - 1 byte for dest file name + // - 4 for FSS + // - 1 leading byte. + // - 1 byte for PDU type + // PDU header has 10 bytes. + // I am not going to check the options raw content, those are part of the dedicated + // TLV unittests + REQUIRE(sz == 10 + 37); + for(size_t maxSz = 0; maxSz < sz; maxSz++) { + uint8_t* buffer = mdBuffer.data(); + size_t sz = 0; + result = serializer.serialize(&buffer, &sz, maxSz, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == SerializeIF::BUFFER_TOO_SHORT); + } + for(size_t initSz = 1; initSz < 47; initSz++) { + uint8_t* buffer = mdBuffer.data(); + size_t sz = initSz; + result = serializer.serialize(&buffer, &sz, 46, SerializeIF::Endianness::NETWORK); + REQUIRE(result == SerializeIF::BUFFER_TOO_SHORT); + } + info.setDestFileName(destFileName); + } + + SECTION("Deserialize") { + MetadataPduSerializer serializer(pduConf, info); + result = serializer.serialize(&buffer, &sz, mdBuffer.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + MetadataPduDeserializer deserializer(mdBuffer.data(), mdBuffer.size(), info); + result = deserializer.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + size_t fullSize = deserializer.getWholePduSize(); + for(size_t maxSz = 0; maxSz < fullSize; maxSz++) { + MetadataPduDeserializer invalidSzDeser(mdBuffer.data(), maxSz, info); + result = invalidSzDeser.parseData(); + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + } + size_t sizeOfOptions = options.size(); + size_t maxSize = 4; + info.setOptionsArray(options.data(), &sizeOfOptions, &maxSize); + REQUIRE(info.getOptionsLen() == 2); + info.setChecksumType(cfdp::ChecksumType::CRC_32C); + info.setClosureRequested(true); + uint8_t* buffer = mdBuffer.data(); + size_t sz = 0; + serializer.updateDirectiveFieldLen(); + + info.setSourceFileName(sourceFileName); + result = serializer.serialize(&buffer, &sz, mdBuffer.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + MetadataPduDeserializer deserializer2(mdBuffer.data(), mdBuffer.size(), info); + result = deserializer2.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(options[0]->getType() == cfdp::TlvTypes::FILESTORE_RESPONSE); + REQUIRE(options[0]->getSerializedSize() == 14); + REQUIRE(options[1]->getType() == cfdp::TlvTypes::MSG_TO_USER); + REQUIRE(options[1]->getSerializedSize() == 5); + + for(size_t invalidFieldLen = 0; invalidFieldLen < 36; invalidFieldLen++) { + mdBuffer[1] = (invalidFieldLen >> 8) & 0xff; + mdBuffer[2] = invalidFieldLen & 0xff; + result = deserializer2.parseData(); + if(invalidFieldLen == 17) { + REQUIRE(info.getOptionsLen() == 0); + } + if(invalidFieldLen == 31) { + REQUIRE(info.getOptionsLen() == 1); + } + // This is the precise length where there are no options or one option + if(invalidFieldLen != 17 and invalidFieldLen != 31) { + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + } + } + mdBuffer[1] = (36 >> 8) & 0xff; + mdBuffer[2] = 36 & 0xff; + info.setOptionsArray(nullptr, nullptr, nullptr); + REQUIRE(deserializer2.parseData() == cfdp::METADATA_CANT_PARSE_OPTIONS); + info.setOptionsArray(options.data(), &sizeOfOptions, nullptr); + for(size_t maxSz = 0; maxSz < 46; maxSz++) { + MetadataPduDeserializer invalidSzDeser(mdBuffer.data(), maxSz, info); + result = invalidSzDeser.parseData(); + REQUIRE(result == SerializeIF::STREAM_TOO_SHORT); + } + } +} diff --git a/tests/src/fsfw_tests/unit/cfdp/testNakPdu.cpp b/tests/src/fsfw_tests/unit/cfdp/testNakPdu.cpp new file mode 100644 index 00000000..57ec5140 --- /dev/null +++ b/tests/src/fsfw_tests/unit/cfdp/testNakPdu.cpp @@ -0,0 +1,160 @@ +#include + +#include "fsfw/cfdp/pdu/PduConfig.h" +#include "fsfw/cfdp/pdu/NakPduDeserializer.h" +#include "fsfw/cfdp/pdu/NakPduSerializer.h" +#include "fsfw/globalfunctions/arrayprinter.h" + +#include + +TEST_CASE( "NAK PDU" , "[NakPdu]") { + using namespace cfdp; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + std::array nakBuffer = {}; + uint8_t* buffer = nakBuffer.data(); + size_t sz = 0; + EntityId destId(WidthInBytes::TWO_BYTES, 2); + TransactionSeqNum seqNum(WidthInBytes::TWO_BYTES, 15); + EntityId sourceId(WidthInBytes::TWO_BYTES, 1); + PduConfig pduConf(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); + + FileSize startOfScope(50); + FileSize endOfScope(1050); + NakInfo info(startOfScope, endOfScope); + SECTION("Serializer") { + NakPduSerializer serializer(pduConf, info); + result = serializer.serialize(&buffer, &sz, nakBuffer.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(serializer.getSerializedSize() == 19); + REQUIRE(serializer.FileDirectiveSerializer::getSerializedSize() == 11); + REQUIRE(sz == 19); + REQUIRE(serializer.getPduDataFieldLen() == 9); + REQUIRE(((nakBuffer[1] << 8) | nakBuffer[2]) == 0x09); + REQUIRE(nakBuffer[10] == cfdp::FileDirectives::NAK); + uint32_t scope = 0; + result = SerializeAdapter::deSerialize(&scope, nakBuffer.data() + 11, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(scope == 50); + result = SerializeAdapter::deSerialize(&scope, nakBuffer.data() + 15, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(scope == 1050); + + NakInfo::SegmentRequest segReq0(cfdp::FileSize(2020), cfdp::FileSize(2520)); + NakInfo::SegmentRequest segReq1(cfdp::FileSize(2932), cfdp::FileSize(3021)); + // Now add 2 segment requests to NAK info and serialize them as well + std::array segReqs = { segReq0, segReq1 }; + size_t segReqsLen = segReqs.size(); + info.setSegmentRequests(segReqs.data(), &segReqsLen , &segReqsLen); + uint8_t* buffer = nakBuffer.data(); + size_t sz = 0; + serializer.updateDirectiveFieldLen(); + result = serializer.serialize(&buffer, &sz, nakBuffer.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(serializer.getSerializedSize() == 35); + REQUIRE(serializer.getPduDataFieldLen() == 25); + REQUIRE(((nakBuffer[1] << 8) | nakBuffer[2]) == 25); + uint32_t segReqScopes = 0; + result = SerializeAdapter::deSerialize(&segReqScopes, nakBuffer.data() + 19, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(segReqScopes == 2020); + result = SerializeAdapter::deSerialize(&segReqScopes, nakBuffer.data() + 23, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(segReqScopes == 2520); + result = SerializeAdapter::deSerialize(&segReqScopes, nakBuffer.data() + 27, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(segReqScopes == 2932); + result = SerializeAdapter::deSerialize(&segReqScopes, nakBuffer.data() + 31, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(segReqScopes == 3021); + + for(size_t maxSz = 0; maxSz < 35; maxSz++) { + uint8_t* buffer = nakBuffer.data(); + size_t sz = 0; + result = serializer.serialize(&buffer, &sz, maxSz, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == SerializeIF::BUFFER_TOO_SHORT); + } + for(size_t sz = 35; sz > 0; sz--) { + uint8_t* buffer = nakBuffer.data(); + size_t locSize = sz; + result = serializer.serialize(&buffer, &locSize, 35, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == SerializeIF::BUFFER_TOO_SHORT); + } + } + + SECTION("Deserializer") { + NakPduSerializer serializer(pduConf, info); + result = serializer.serialize(&buffer, &sz, nakBuffer.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + info.getStartOfScope().setFileSize(0, false); + info.getEndOfScope().setFileSize(0, false); + NakPduDeserializer deserializer(nakBuffer.data(), nakBuffer.size(), info); + result = deserializer.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(deserializer.getWholePduSize() == 19); + REQUIRE(info.getStartOfScope().getSize() == 50); + REQUIRE(info.getEndOfScope().getSize() == 1050); + + NakInfo::SegmentRequest segReq0(cfdp::FileSize(2020), cfdp::FileSize(2520)); + NakInfo::SegmentRequest segReq1(cfdp::FileSize(2932), cfdp::FileSize(3021)); + // Now add 2 segment requests to NAK info and serialize them as well + std::array segReqs = { segReq0, segReq1 }; + size_t segReqsLen = segReqs.size(); + info.setSegmentRequests(segReqs.data(), &segReqsLen, &segReqsLen); + uint8_t* buffer = nakBuffer.data(); + size_t sz = 0; + serializer.updateDirectiveFieldLen(); + result = serializer.serialize(&buffer, &sz, nakBuffer.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + NakPduDeserializer deserializeWithSegReqs(nakBuffer.data(), nakBuffer.size(), info); + result = deserializeWithSegReqs.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + NakInfo::SegmentRequest* segReqsPtr = nullptr; + size_t readSegReqs = 0; + info.getSegmentRequests(&segReqsPtr, &readSegReqs, nullptr); + REQUIRE(readSegReqs == 2); + REQUIRE(segReqsPtr[0].first.getSize() == 2020); + REQUIRE(segReqsPtr[0].second.getSize() == 2520); + REQUIRE(segReqsPtr[1].first.getSize() == 2932); + REQUIRE(segReqsPtr[1].second.getSize() == 3021); + REQUIRE(deserializeWithSegReqs.getPduDataFieldLen() == 25); + REQUIRE(info.getSegmentRequestsLen() == 2); + for(size_t idx = 0; idx < 34; idx ++) { + NakPduDeserializer faultyDeserializer(nakBuffer.data(), idx, info); + result = faultyDeserializer.parseData(); + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + } + for(size_t pduFieldLen = 0; pduFieldLen < 25; pduFieldLen++) { + nakBuffer[1] = (pduFieldLen >> 8) & 0xff; + nakBuffer[2] = pduFieldLen & 0xff; + NakPduDeserializer faultyDeserializer(nakBuffer.data(), nakBuffer.size(), info); + result = faultyDeserializer.parseData(); + if(pduFieldLen == 9) { + REQUIRE(info.getSegmentRequestsLen() == 0); + } else if(pduFieldLen == 17) { + REQUIRE(info.getSegmentRequestsLen() == 1); + } else if(pduFieldLen == 25) { + REQUIRE(info.getSegmentRequestsLen() == 2); + } + if(pduFieldLen != 9 and pduFieldLen != 17 and pduFieldLen != 25) { + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + } + } + info.setMaxSegmentRequestLen(5); + REQUIRE(info.getSegmentRequestsMaxLen() == 5); + } +} + diff --git a/tests/src/fsfw_tests/unit/cfdp/testPromptPdu.cpp b/tests/src/fsfw_tests/unit/cfdp/testPromptPdu.cpp new file mode 100644 index 00000000..64589e46 --- /dev/null +++ b/tests/src/fsfw_tests/unit/cfdp/testPromptPdu.cpp @@ -0,0 +1,71 @@ +#include + +#include "fsfw/cfdp/pdu/PromptPduDeserializer.h" +#include "fsfw/cfdp/pdu/PromptPduSerializer.h" +#include "fsfw/globalfunctions/arrayprinter.h" + +#include + +TEST_CASE( "Prompt PDU" , "[PromptPdu]") { + using namespace cfdp; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + std::array rawBuf = {}; + uint8_t* buffer = rawBuf.data(); + size_t sz = 0; + EntityId destId(WidthInBytes::TWO_BYTES, 2); + TransactionSeqNum seqNum(WidthInBytes::TWO_BYTES, 15); + EntityId sourceId(WidthInBytes::TWO_BYTES, 1); + PduConfig pduConf(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); + + SECTION("Serialize") { + PromptPduSerializer serializer(pduConf, cfdp::PromptResponseRequired::PROMPT_KEEP_ALIVE); + result = serializer.serialize(&buffer, &sz, rawBuf.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(serializer.getWholePduSize() == 12); + REQUIRE(sz == 12); + REQUIRE(serializer.getPduDataFieldLen() == 2); + REQUIRE(rawBuf[10] == FileDirectives::PROMPT); + REQUIRE((rawBuf[sz - 1] >> 7) & 0x01 == cfdp::PromptResponseRequired::PROMPT_KEEP_ALIVE); + + for(size_t invalidMaxSz = 0; invalidMaxSz < sz; invalidMaxSz++) { + uint8_t* buffer = rawBuf.data(); + size_t sz = 0; + result = serializer.serialize(&buffer, &sz, invalidMaxSz, + SerializeIF::Endianness::NETWORK); + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + } + for(size_t invalidSz = 1; invalidSz < sz; invalidSz++) { + size_t locSz = invalidSz; + uint8_t* buffer = rawBuf.data(); + result = serializer.serialize(&buffer, &locSz, sz, + SerializeIF::Endianness::NETWORK); + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + } + } + + SECTION("Deserialize") { + PromptPduSerializer serializer(pduConf, cfdp::PromptResponseRequired::PROMPT_KEEP_ALIVE); + result = serializer.serialize(&buffer, &sz, rawBuf.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + PromptPduDeserializer deserializer(rawBuf.data(), rawBuf.size()); + result = deserializer.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(deserializer.getPromptResponseRequired() == + cfdp::PromptResponseRequired::PROMPT_KEEP_ALIVE); + sz = deserializer.getWholePduSize(); + rawBuf[2] = 1; + result = deserializer.parseData(); + REQUIRE(result == SerializeIF::STREAM_TOO_SHORT); + rawBuf[2] = 2; + + for(size_t invalidMaxSz = 0; invalidMaxSz < sz; invalidMaxSz++) { + deserializer.setData(rawBuf.data(), invalidMaxSz); + result = deserializer.parseData(); + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + } + } +} + diff --git a/tests/src/fsfw_tests/unit/cfdp/testTlvsLvs.cpp b/tests/src/fsfw_tests/unit/cfdp/testTlvsLvs.cpp new file mode 100644 index 00000000..15e94ebb --- /dev/null +++ b/tests/src/fsfw_tests/unit/cfdp/testTlvsLvs.cpp @@ -0,0 +1,334 @@ +#include "fsfw/cfdp/pdu/PduConfig.h" +#include "fsfw/cfdp/tlv/Tlv.h" +#include "fsfw/cfdp/tlv/Lv.h" + +#include +#include +#include +#include + +#include "fsfw/globalfunctions/arrayprinter.h" +#include +#include +#include + +#include +#include + +TEST_CASE( "CFDP TLV LV" , "[CfdpTlvLv]") { + using namespace cfdp; + int result = HasReturnvaluesIF::RETURN_OK; + std::array rawBuf; + uint8_t* serPtr = rawBuf.data(); + const uint8_t* deserPtr = rawBuf.data(); + size_t deserSize = 0; + cfdp::EntityId sourceId = EntityId(cfdp::WidthInBytes::TWO_BYTES, 0x0ff0); + + SECTION("TLV Serialization") { + std::array tlvRawBuf; + serPtr = tlvRawBuf.data(); + result = sourceId.serialize(&serPtr, &deserSize, tlvRawBuf.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(deserSize == 2); + auto tlv = Tlv(TlvTypes::ENTITY_ID, tlvRawBuf.data(), deserSize); + REQUIRE(tlv.getSerializedSize() == 4); + REQUIRE(tlv.getLengthField() == 2); + serPtr = rawBuf.data(); + deserSize = 0; + result = tlv.serialize(&serPtr, &deserSize, rawBuf.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(deserSize == 4); + REQUIRE(rawBuf[0] == TlvTypes::ENTITY_ID); + REQUIRE(rawBuf[1] == 2); + uint16_t entityId = 0; + SerializeAdapter::deSerialize(&entityId, rawBuf.data() + 2, &deserSize, + SerializeIF::Endianness::NETWORK); + REQUIRE(entityId == 0x0ff0); + + // Set new value + sourceId.setValue(cfdp::WidthInBytes::FOUR_BYTES, 12); + serPtr = tlvRawBuf.data(); + deserSize = 0; + result = sourceId.serialize(&serPtr, &deserSize, tlvRawBuf.size(), + SerializeIF::Endianness::NETWORK); + tlv.setValue(tlvRawBuf.data(), cfdp::WidthInBytes::FOUR_BYTES); + serPtr = rawBuf.data(); + deserSize = 0; + result = tlv.serialize(&serPtr, &deserSize, rawBuf.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(rawBuf[0] == TlvTypes::ENTITY_ID); + REQUIRE(rawBuf[1] == 4); + + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + serPtr = rawBuf.data(); + deserSize = 0; + auto tlvInvalid = Tlv(cfdp::TlvTypes::INVALID_TLV, tlvRawBuf.data(), 0); + REQUIRE(tlvInvalid.serialize(&serPtr, &deserSize, rawBuf.size(), + SerializeIF::Endianness::NETWORK) != HasReturnvaluesIF::RETURN_OK); + tlvInvalid = Tlv(cfdp::TlvTypes::ENTITY_ID, nullptr, 3); + REQUIRE(tlvInvalid.serialize(&serPtr, &deserSize, rawBuf.size(), + SerializeIF::Endianness::NETWORK) != HasReturnvaluesIF::RETURN_OK); + REQUIRE(tlvInvalid.serialize(&serPtr, &deserSize, 0, + SerializeIF::Endianness::NETWORK) != HasReturnvaluesIF::RETURN_OK); + REQUIRE(tlvInvalid.getSerializedSize() == 0); + REQUIRE(tlvInvalid.serialize(nullptr, nullptr, 0, + SerializeIF::Endianness::NETWORK) != HasReturnvaluesIF::RETURN_OK); + + Tlv zeroLenField(TlvTypes::FAULT_HANDLER, nullptr, 0); + REQUIRE(zeroLenField.getSerializedSize() == 2); + serPtr = rawBuf.data(); + deserSize = 0; + REQUIRE(zeroLenField.serialize(&serPtr, &deserSize, rawBuf.size(), + SerializeIF::Endianness::NETWORK) == HasReturnvaluesIF::RETURN_OK); + REQUIRE(rawBuf[0] == TlvTypes::FAULT_HANDLER); + REQUIRE(rawBuf[1] == 0); + } + + SECTION("TLV Deserialization") { + // Serialization was tested before, generate raw data now + std::array tlvRawBuf; + serPtr = tlvRawBuf.data(); + result = sourceId.serialize(&serPtr, &deserSize, tlvRawBuf.size(), + SerializeIF::Endianness::NETWORK); + auto tlvSerialization = Tlv(TlvTypes::ENTITY_ID, tlvRawBuf.data(), deserSize); + serPtr = rawBuf.data(); + deserSize = 0; + result = tlvSerialization.serialize(&serPtr, &deserSize, rawBuf.size(), + SerializeIF::Endianness::NETWORK); + Tlv tlv; + deserPtr = rawBuf.data(); + result = tlv.deSerialize(&deserPtr, &deserSize, SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(tlv.getSerializedSize() == 4); + REQUIRE(tlv.getType() == TlvTypes::ENTITY_ID); + deserPtr = tlv.getValue(); + uint16_t entityId = 0; + deserSize = 0; + SerializeAdapter::deSerialize(&entityId, deserPtr, &deserSize, + SerializeIF::Endianness::NETWORK); + REQUIRE(entityId == 0x0ff0); + + REQUIRE(tlv.deSerialize(nullptr, nullptr, SerializeIF::Endianness::NETWORK) != + HasReturnvaluesIF::RETURN_OK); + deserPtr = rawBuf.data(); + deserSize = 0; + REQUIRE(tlv.deSerialize(&deserPtr, &deserSize, SerializeIF::Endianness::NETWORK) == + SerializeIF::STREAM_TOO_SHORT); + // Set invalid TLV + rawBuf[0] = TlvTypes::INVALID_TLV; + deserSize = 4; + REQUIRE(tlv.deSerialize(&deserPtr, &deserSize, SerializeIF::Endianness::NETWORK) != + HasReturnvaluesIF::RETURN_OK); + + Tlv zeroLenField(TlvTypes::FAULT_HANDLER, nullptr, 0); + serPtr = rawBuf.data(); + deserSize = 0; + REQUIRE(zeroLenField.serialize(&serPtr, &deserSize, rawBuf.size(), + SerializeIF::Endianness::NETWORK) == HasReturnvaluesIF::RETURN_OK); + deserPtr = rawBuf.data(); + result = zeroLenField.deSerialize(&deserPtr, &deserSize, SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(zeroLenField.getSerializedSize() == 2); + REQUIRE(deserSize == 0); + } + + SECTION("LV Serialization") { + std::array lvRawBuf; + serPtr = lvRawBuf.data(); + result = sourceId.serialize(&serPtr, &deserSize, lvRawBuf.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(deserSize == 2); + auto lv = cfdp::Lv(lvRawBuf.data(), 2); + auto lvCopy = cfdp::Lv(lv); + REQUIRE(lv.getSerializedSize() == 3); + REQUIRE(lvCopy.getSerializedSize() == 3); + REQUIRE(lv.getValue(nullptr) == lvCopy.getValue(nullptr)); + serPtr = rawBuf.data(); + deserSize = 0; + result = lv.serialize(&serPtr, &deserSize, rawBuf.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(deserSize == 3); + REQUIRE(rawBuf[0] == 2); + uint16_t sourceId = 0; + result = SerializeAdapter::deSerialize(&sourceId, rawBuf.data() + 1, &deserSize, + SerializeIF::Endianness::BIG); + REQUIRE(sourceId == 0x0ff0); + + auto lvEmpty = Lv(nullptr, 0); + REQUIRE(lvEmpty.getSerializedSize() == 1); + serPtr = rawBuf.data(); + deserSize = 0; + result = lvEmpty.serialize(&serPtr, &deserSize, rawBuf.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(deserSize == 1); + } + + SECTION("LV Deserialization") { + std::array lvRawBuf; + serPtr = lvRawBuf.data(); + result = sourceId.serialize(&serPtr, &deserSize, lvRawBuf.size(), + SerializeIF::Endianness::NETWORK); + auto lv = cfdp::Lv(lvRawBuf.data(), 2); + serPtr = rawBuf.data(); + deserSize = 0; + result = lv.serialize(&serPtr, &deserSize, rawBuf.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + Lv uninitLv; + deserPtr = rawBuf.data(); + deserSize = 3; + result = uninitLv.deSerialize(&deserPtr, &deserSize, SerializeIF::Endianness::BIG); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(uninitLv.getSerializedSize() == 3); + const uint8_t* storedValue = uninitLv.getValue(nullptr); + uint16_t sourceId = 0; + result = SerializeAdapter::deSerialize(&sourceId, storedValue, &deserSize, + SerializeIF::Endianness::BIG); + REQUIRE(sourceId == 0x0ff0); + + auto lvEmpty = Lv(nullptr, 0); + REQUIRE(lvEmpty.getSerializedSize() == 1); + serPtr = rawBuf.data(); + deserSize = 0; + result = lvEmpty.serialize(&serPtr, &deserSize, rawBuf.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(deserSize == 1); + deserPtr = rawBuf.data(); + result = uninitLv.deSerialize(&deserPtr, &deserSize, SerializeIF::Endianness::BIG); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(uninitLv.getSerializedSize() == 1); + + REQUIRE(uninitLv.deSerialize(nullptr, nullptr, SerializeIF::Endianness::BIG) == + HasReturnvaluesIF::RETURN_FAILED); + serPtr = rawBuf.data(); + deserSize = 0; + REQUIRE(uninitLv.serialize(&serPtr, &deserSize, 0, SerializeIF::Endianness::BIG) == + SerializeIF::BUFFER_TOO_SHORT); + REQUIRE(uninitLv.serialize(nullptr, nullptr, 12, SerializeIF::Endianness::BIG)); + deserSize = 0; + REQUIRE(uninitLv.deSerialize(&deserPtr, &deserSize, SerializeIF::Endianness::BIG) == + SerializeIF::STREAM_TOO_SHORT); + } + + SECTION("Filestore Response TLV") { + std::string name = "hello.txt"; + cfdp::Lv firstName(reinterpret_cast(name.data()), name.size()); + std::string name2 = "hello2.txt"; + cfdp::Lv secondName(reinterpret_cast(name2.data()), name2.size()); + std::string msg = "12345"; + cfdp::Lv fsMsg(reinterpret_cast(msg.data()), msg.size()); + FilestoreResponseTlv response(cfdp::FilestoreActionCode::APPEND_FILE, cfdp::FSR_SUCCESS, + firstName, &fsMsg); + response.setSecondFileName(&secondName); + REQUIRE(response.getLengthField() == 10 + 11 + 6 + 1); + REQUIRE(response.getSerializedSize() == response.getLengthField() + 2); + + cfdp::Tlv rawResponse; + std::array serBuf = {}; + result = response.convertToTlv(rawResponse, serBuf.data(), serBuf.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(rawResponse.getType() == cfdp::TlvTypes::FILESTORE_RESPONSE); + cfdp::Lv emptyMsg; + cfdp::Lv emptySecondName; + FilestoreResponseTlv emptyTlv(firstName, &emptyMsg); + emptyTlv.setSecondFileName(&emptySecondName); + result = emptyTlv.deSerialize(rawResponse, SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(emptyTlv.getActionCode() == cfdp::FilestoreActionCode::APPEND_FILE); + REQUIRE(emptyTlv.getStatusCode() == cfdp::FSR_SUCCESS); + size_t firstNameLen = 0; + const char* firstNamePtr = reinterpret_cast( + emptyTlv.getFirstFileName().getValue(&firstNameLen)); + auto helloString = std::string(firstNamePtr, firstNameLen); + REQUIRE(helloString == "hello.txt"); + } + + SECTION("Filestore Request TLV") { + std::string name = "hello.txt"; + cfdp::Lv firstName(reinterpret_cast(name.data()), name.size()); + std::string name2 = "hello2.txt"; + cfdp::Lv secondName(reinterpret_cast(name2.data()), name2.size()); + FilestoreRequestTlv request(cfdp::FilestoreActionCode::APPEND_FILE, firstName); + + // second name not set yet + REQUIRE(request.getLengthField() == 10 + 1); + REQUIRE(request.getSerializedSize() == request.getLengthField() + 2); + + std::array serBuf = {}; + uint8_t* ptr = serBuf.data(); + size_t sz = 0; + result = request.serialize(&ptr, &sz, serBuf.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == cfdp::FILESTORE_REQUIRES_SECOND_FILE); + + ptr = serBuf.data(); + sz = 0; + request.setSecondFileName(&secondName); + size_t expectedSz = request.getLengthField(); + REQUIRE(expectedSz == 10 + 11 + 1); + REQUIRE(request.getSerializedSize() == expectedSz + 2); + result = request.serialize(&ptr, &sz, serBuf.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(sz == expectedSz + 2); + + FilestoreRequestTlv emptyRequest(firstName); + emptyRequest.setSecondFileName(&secondName); + const uint8_t* constptr = serBuf.data(); + result = emptyRequest.deSerialize(&constptr, &sz, SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + cfdp::Tlv rawRequest; + ptr = serBuf.data(); + sz = 0; + result = request.convertToTlv(rawRequest, serBuf.data(), serBuf.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(rawRequest.getType() == cfdp::TlvTypes::FILESTORE_REQUEST); + + emptyRequest.setActionCode(cfdp::FilestoreActionCode::DELETE_FILE); + result = emptyRequest.deSerialize(rawRequest, SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(emptyRequest.getType() == cfdp::TlvTypes::FILESTORE_REQUEST); + REQUIRE(emptyRequest.getActionCode() == cfdp::FilestoreActionCode::APPEND_FILE); + } + + SECTION("Other") { + MessageToUserTlv emptyTlv; + uint8_t flowLabel = 1; + FlowLabelTlv flowLabelTlv(&flowLabel, 1); + + FaultHandlerOverrideTlv faultOverrideTlv(cfdp::ConditionCode::FILESTORE_REJECTION, + cfdp::FaultHandlerCode::NOTICE_OF_CANCELLATION); + size_t sz = 0; + ReturnValue_t result = faultOverrideTlv.serialize(&serPtr, &sz, rawBuf.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(faultOverrideTlv.getSerializedSize() == 3); + REQUIRE(sz == 3); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + FaultHandlerOverrideTlv emptyOverrideTlv; + result = emptyOverrideTlv.deSerialize(&deserPtr, &sz, SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + EntityId entId(cfdp::WidthInBytes::TWO_BYTES, 0x42); + EntityId emptyId; + EntityIdTlv idTlv(emptyId); + serPtr = rawBuf.data(); + result = idTlv.serialize(&serPtr, &deserSize, rawBuf.size(), + SerializeIF::Endianness::NETWORK); + cfdp::Tlv rawTlv(cfdp::TlvTypes::ENTITY_ID, rawBuf.data() + 2, 2); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + deserPtr = rawBuf.data(); + result = idTlv.deSerialize(rawTlv, SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + } +} From 7a84dff7d65211aea06eb7f44c706a3c273220b9 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 6 Dec 2021 16:23:09 +0100 Subject: [PATCH 02/56] maybe this fixes the build error? --- tests/src/fsfw_tests/unit/cfdp/testFinishedPdu.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/tests/src/fsfw_tests/unit/cfdp/testFinishedPdu.cpp b/tests/src/fsfw_tests/unit/cfdp/testFinishedPdu.cpp index 718750de..72c3f932 100644 --- a/tests/src/fsfw_tests/unit/cfdp/testFinishedPdu.cpp +++ b/tests/src/fsfw_tests/unit/cfdp/testFinishedPdu.cpp @@ -37,7 +37,7 @@ TEST_CASE( "Finished PDU" , "[FinishedPdu]") { // Add a filestore response std::string firstName = "hello.txt"; - cfdp::Lv firstNameLv(reinterpret_cast(firstName.data()), firstName.size()); + cfdp::Lv firstNameLv(reinterpret_cast(firstName.data()), firstName.size()); FilestoreResponseTlv response(cfdp::FilestoreActionCode::DELETE_FILE, cfdp::FSR_APPEND_FILE_1_NOT_EXISTS, firstNameLv, nullptr); FilestoreResponseTlv* responsePtr = &response; @@ -56,7 +56,7 @@ TEST_CASE( "Finished PDU" , "[FinishedPdu]") { // Add two filestore responses and a fault location parameter std::string secondName = "hello2.txt"; - cfdp::Lv secondNameLv(reinterpret_cast(secondName.data()), secondName.size()); + cfdp::Lv secondNameLv(reinterpret_cast(secondName.data()), secondName.size()); FilestoreResponseTlv response2(cfdp::FilestoreActionCode::DENY_FILE , cfdp::FSR_SUCCESS, secondNameLv, nullptr); REQUIRE(response2.getSerializedSize() == 15); @@ -106,7 +106,7 @@ TEST_CASE( "Finished PDU" , "[FinishedPdu]") { sz = 0; buffer = fnBuffer.data(); std::string firstName = "hello.txt"; - cfdp::Lv firstNameLv(reinterpret_cast(firstName.data()), firstName.size()); + cfdp::Lv firstNameLv(reinterpret_cast(firstName.data()), firstName.size()); FilestoreResponseTlv response(cfdp::FilestoreActionCode::DELETE_FILE, cfdp::FSR_NOT_PERFORMED, firstNameLv, nullptr); FilestoreResponseTlv* responsePtr = &response; @@ -136,7 +136,7 @@ TEST_CASE( "Finished PDU" , "[FinishedPdu]") { // Add two filestore responses and a fault location parameter std::string secondName = "hello2.txt"; - cfdp::Lv secondNameLv(reinterpret_cast(secondName.data()), secondName.size()); + cfdp::Lv secondNameLv(reinterpret_cast(secondName.data()), secondName.size()); FilestoreResponseTlv response2(cfdp::FilestoreActionCode::DENY_FILE , cfdp::FSR_SUCCESS, secondNameLv, nullptr); REQUIRE(response2.getSerializedSize() == 15); From d39e0c8bb6a7140ca604d4935df9da619ed38826 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 7 Dec 2021 14:08:26 +0100 Subject: [PATCH 03/56] renamed test folder --- automation/Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/automation/Jenkinsfile b/automation/Jenkinsfile index d4a8e2ab..ba3f5afb 100644 --- a/automation/Jenkinsfile +++ b/automation/Jenkinsfile @@ -1,7 +1,7 @@ pipeline { agent any environment { - BUILDDIR = 'build-unittests' + BUILDDIR = 'build-tests' } stages { stage('Create Docker') { From 78ddce249cf7340eb77b40731238fb943c478954 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 18 Jan 2022 18:29:54 +0100 Subject: [PATCH 04/56] try an optimization --- CMakeLists.txt | 9 ++------- src/CMakeLists.txt | 9 --------- 2 files changed, 2 insertions(+), 16 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index bb3d48b8..04aab3e3 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -152,13 +152,8 @@ else() set(OS_FSFW "host") endif() -if(FSFW_BUILD_UNITTESTS OR FSFW_BUILD_DOCS) - configure_file(src/fsfw/FSFW.h.in fsfw/FSFW.h) - configure_file(src/fsfw/FSFWVersion.h.in fsfw/FSFWVersion.h) -else() - configure_file(src/fsfw/FSFW.h.in FSFW.h) - configure_file(src/fsfw/FSFWVersion.h.in FSFWVersion.h) -endif() +configure_file(src/fsfw/FSFW.h.in fsfw/FSFW.h) +configure_file(src/fsfw/FSFWVersion.h.in fsfw/FSFWVersion.h) message(STATUS "Compiling FSFW for the ${FSFW_OS_NAME} operating system.") diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index e4670807..ed2f2522 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -7,12 +7,3 @@ target_include_directories(${LIB_FSFW_NAME} INTERFACE ) add_subdirectory(fsfw) - -# Configure File - -target_include_directories(${LIB_FSFW_NAME} PRIVATE - ${CMAKE_CURRENT_BINARY_DIR} -) -target_include_directories(${LIB_FSFW_NAME} INTERFACE - ${CMAKE_CURRENT_BINARY_DIR} -) From 6c63d82f5c77566a569756b79304c5e0790b53f2 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 18 Jan 2022 18:47:29 +0100 Subject: [PATCH 05/56] better comment --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 04aab3e3..1b3e9d53 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -90,7 +90,7 @@ set(FSFW_CORE_INC_PATH "inc") set_property(CACHE FSFW_OSAL PROPERTY STRINGS host linux rtems freertos) -# Configure Files +# For configure files target_include_directories(${LIB_FSFW_NAME} PRIVATE ${CMAKE_CURRENT_BINARY_DIR} ) From 371ff931bfb1284960b6a13716fdd34251ab8ed8 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 26 Jan 2022 12:11:52 +0100 Subject: [PATCH 06/56] Linux CommandExecutor The CommandExecutor helper class can execute shell commands in blocking and non-blocking mode This class is able to execute processes by using the Linux popen call. It also has the capability of writing the read output of a process into a provided ring buffer. The executor works by first loading the command which should be executed and specifying whether it should be executed blocking or non-blocking. After that, execution can be started with the execute call. Using non-blocking mode allows to execute commands which might take a longer time in the background, and allowing the user thread to check completion status with the check function Moved to HAL like requested in code review and unit tested with failing commands as well. Also, Linux HAL components are compiled by default now unless explicitely disabled. --- hal/CMakeLists.txt | 8 +- hal/src/fsfw_hal/CMakeLists.txt | 2 +- hal/src/fsfw_hal/linux/CMakeLists.txt | 11 +- hal/src/fsfw_hal/linux/CommandExecutor.cpp | 213 ++++++++++++++++++ hal/src/fsfw_hal/linux/CommandExecutor.h | 135 +++++++++++ hal/src/fsfw_hal/linux/gpio/CMakeLists.txt | 20 +- hal/src/fsfw_hal/linux/i2c/I2cComIF.cpp | 32 ++- hal/src/fsfw_hal/linux/uart/UartComIF.cpp | 46 +++- hal/src/fsfw_hal/linux/uart/UartCookie.cpp | 4 +- scripts/helper.py | 4 +- src/fsfw/FSFW.h.in | 4 + src/fsfw/container/SimpleRingBuffer.h | 15 +- src/fsfw/devicehandlers/AssemblyBase.h | 2 +- .../devicehandlers/DeviceCommunicationIF.h | 7 +- src/fsfw/devicehandlers/DeviceHandlerBase.h | 3 +- src/fsfw/devicehandlers/DeviceHandlerIF.h | 3 +- src/fsfw/osal/linux/CMakeLists.txt | 33 ++- src/fsfw/osal/linux/MessageQueue.cpp | 6 +- src/fsfw/subsystem/SubsystemBase.h | 3 +- tests/src/fsfw_tests/unit/CMakeLists.txt | 1 + tests/src/fsfw_tests/unit/hal/CMakeLists.txt | 3 + .../unit/hal/testCommandExecutor.cpp | 110 +++++++++ 22 files changed, 608 insertions(+), 57 deletions(-) create mode 100644 hal/src/fsfw_hal/linux/CommandExecutor.cpp create mode 100644 hal/src/fsfw_hal/linux/CommandExecutor.h create mode 100644 tests/src/fsfw_tests/unit/hal/CMakeLists.txt create mode 100644 tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp diff --git a/hal/CMakeLists.txt b/hal/CMakeLists.txt index 7a9a0ffa..424a012d 100644 --- a/hal/CMakeLists.txt +++ b/hal/CMakeLists.txt @@ -3,7 +3,13 @@ cmake_minimum_required(VERSION 3.13) # Can also be changed by upper CMakeLists.txt file find_library(LIB_FSFW_NAME fsfw REQUIRED) -option(FSFW_HAL_ADD_LINUX "Add the Linux HAL to the sources. Required gpiod library" OFF) +option(FSFW_HAL_ADD_LINUX "Add the Linux HAL to the sources. Requires gpiod library" OFF) +# On by default for now because I did not have an issue including and compiling those files +# and libraries on a Desktop Linux system and the primary target of the FSFW is still embedded +# Linux. The only exception from this is the gpiod library which requires a dedicated installation, +# but CMake is able to determine whether this library is installed with find_library. +option(FSFW_HAL_LINUX_ADD_PERIPHERAL_DRIVERS "Add peripheral drivers for embedded Linux" ON) + option(FSFW_HAL_ADD_RASPBERRY_PI "Add Raspberry Pi specific code to the sources" OFF) option(FSFW_HAL_ADD_STM32H7 "Add the STM32H7 HAL to the sources" OFF) option(FSFW_HAL_WARNING_SHADOW_LOCAL_GCC "Enable -Wshadow=local warning in GCC" ON) diff --git a/hal/src/fsfw_hal/CMakeLists.txt b/hal/src/fsfw_hal/CMakeLists.txt index f5901e91..b7559d4b 100644 --- a/hal/src/fsfw_hal/CMakeLists.txt +++ b/hal/src/fsfw_hal/CMakeLists.txt @@ -1,7 +1,7 @@ add_subdirectory(devicehandlers) add_subdirectory(common) -if(FSFW_HAL_ADD_LINUX) +if(UNIX) add_subdirectory(linux) endif() diff --git a/hal/src/fsfw_hal/linux/CMakeLists.txt b/hal/src/fsfw_hal/linux/CMakeLists.txt index 5944b0e5..5ec8af06 100644 --- a/hal/src/fsfw_hal/linux/CMakeLists.txt +++ b/hal/src/fsfw_hal/linux/CMakeLists.txt @@ -4,10 +4,13 @@ endif() target_sources(${LIB_FSFW_NAME} PRIVATE UnixFileGuard.cpp + CommandExecutor.cpp utility.cpp ) -add_subdirectory(gpio) -add_subdirectory(spi) -add_subdirectory(i2c) -add_subdirectory(uart) \ No newline at end of file +if(FSFW_HAL_LINUX_ADD_PERIPHERAL_DRIVERS) + add_subdirectory(gpio) + add_subdirectory(spi) + add_subdirectory(i2c) + add_subdirectory(uart) +endif() diff --git a/hal/src/fsfw_hal/linux/CommandExecutor.cpp b/hal/src/fsfw_hal/linux/CommandExecutor.cpp new file mode 100644 index 00000000..016217e1 --- /dev/null +++ b/hal/src/fsfw_hal/linux/CommandExecutor.cpp @@ -0,0 +1,213 @@ +#include "CommandExecutor.h" + +#include "fsfw/serviceinterface.h" +#include "fsfw/container/SimpleRingBuffer.h" +#include "fsfw/container/DynamicFIFO.h" + +#include + +#include + +CommandExecutor::CommandExecutor(const size_t maxSize): +readVec(maxSize) { + waiter.events = POLLIN; +} + +ReturnValue_t CommandExecutor::load(std::string command, bool blocking, bool printOutput) { + if(state == States::PENDING) { + return COMMAND_PENDING; + } + + currentCmd = command; + this->blocking = blocking; + this->printOutput = printOutput; + if(state == States::IDLE) { + state = States::COMMAND_LOADED; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t CommandExecutor::execute() { + if(state == States::IDLE) { + return NO_COMMAND_LOADED_OR_PENDING; + } + else if(state == States::PENDING) { + return COMMAND_PENDING; + } + currentCmdFile = popen(currentCmd.c_str(), "r"); + if(currentCmdFile == nullptr) { + lastError = errno; + return HasReturnvaluesIF::RETURN_FAILED; + } + if(blocking) { + ReturnValue_t result = executeBlocking(); + state = States::IDLE; + return result; + } + else { + currentFd = fileno(currentCmdFile); + waiter.fd = currentFd; + } + state = States::PENDING; + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t CommandExecutor::close() { + if(state == States::PENDING) { + // Attempt to close process, irrespective of if it is running or not + if(currentCmdFile != nullptr) { + pclose(currentCmdFile); + } + } + return HasReturnvaluesIF::RETURN_OK; +} + +void CommandExecutor::printLastError(std::string funcName) const { + if(lastError != 0) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << funcName << " pclose failed with code " << lastError << ": " << + strerror(lastError) << std::endl; +#else + sif::printError("%s pclose failed with code %d: %s\n", + funcName, lastError, strerror(lastError)); +#endif + } +} + +void CommandExecutor::setRingBuffer(SimpleRingBuffer *ringBuffer, + DynamicFIFO* sizesFifo) { + this->ringBuffer = ringBuffer; + this->sizesFifo = sizesFifo; +} + +ReturnValue_t CommandExecutor::check(bool& replyReceived) { + if(blocking) { + return HasReturnvaluesIF::RETURN_OK; + } + switch(state) { + case(States::IDLE): + case(States::COMMAND_LOADED): { + return NO_COMMAND_LOADED_OR_PENDING; + } + case(States::PENDING): { + break; + } + } + + int result = poll(&waiter, 1, 0); + switch(result) { + case(0): { + return HasReturnvaluesIF::RETURN_OK; + break; + } + case(1): { + if (waiter.revents & POLLIN) { + ssize_t readBytes = read(currentFd, readVec.data(), readVec.size()); + if(readBytes == 0) { + // Should not happen +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "CommandExecutor::check: No bytes read " + "after poll event.." << std::endl; +#else + sif::printWarning("CommandExecutor::check: No bytes read after poll event..\n"); +#endif + break; + } + else if(readBytes > 0) { + replyReceived = true; + if(printOutput) { + // It is assumed the command output is line terminated +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::info << currentCmd << " | " << readVec.data(); +#else + sif::printInfo("%s | %s", currentCmd, readVec.data()); +#endif + } + if(ringBuffer != nullptr) { + ringBuffer->writeData(reinterpret_cast( + readVec.data()), readBytes); + } + if(sizesFifo != nullptr) { + if(not sizesFifo->full()) { + sizesFifo->insert(readBytes); + } + } + } + else { + // Should also not happen +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "CommandExecutor::check: Error " << errno << ": " << + strerror(errno) << std::endl; +#else + sif::printWarning("CommandExecutor::check: Error %d: %s\n", errno, strerror(errno)); +#endif + } + } + if(waiter.revents & POLLERR) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "CommandExecuter::check: Poll error" << std::endl; +#else + sif::printWarning("CommandExecuter::check: Poll error\n"); +#endif + return COMMAND_ERROR; + } + if(waiter.revents & POLLHUP) { + result = pclose(currentCmdFile); + ReturnValue_t retval = EXECUTION_FINISHED; + if(result != 0) { + lastError = result; + retval = HasReturnvaluesIF::RETURN_FAILED; + } + state = States::IDLE; + currentCmdFile = nullptr; + currentFd = 0; + return retval; + } + break; + } + } + return HasReturnvaluesIF::RETURN_OK; +} + +void CommandExecutor::reset() { + CommandExecutor::close(); + currentCmdFile = nullptr; + currentFd = 0; + state = States::IDLE; +} + +int CommandExecutor::getLastError() const { + // See: https://stackoverflow.com/questions/808541/any-benefit-in-using-wexitstatus-macro-in-c-over-division-by-256-on-exit-statu + return WEXITSTATUS(this->lastError); +} + +CommandExecutor::States CommandExecutor::getCurrentState() const { + return state; +} + +ReturnValue_t CommandExecutor::executeBlocking() { + while(fgets(readVec.data(), readVec.size(), currentCmdFile) != nullptr) { + std::string output(readVec.data()); + if(printOutput) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::info << currentCmd << " | " << output; +#else + sif::printInfo("%s | %s", currentCmd, output); +#endif + } + if(ringBuffer != nullptr) { + ringBuffer->writeData(reinterpret_cast(output.data()), output.size()); + } + if(sizesFifo != nullptr) { + if(not sizesFifo->full()) { + sizesFifo->insert(output.size()); + } + } + } + int result = pclose(currentCmdFile); + if(result != 0) { + lastError = result; + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/hal/src/fsfw_hal/linux/CommandExecutor.h b/hal/src/fsfw_hal/linux/CommandExecutor.h new file mode 100644 index 00000000..895bd943 --- /dev/null +++ b/hal/src/fsfw_hal/linux/CommandExecutor.h @@ -0,0 +1,135 @@ +#ifndef FSFW_SRC_FSFW_OSAL_LINUX_COMMANDEXECUTOR_H_ +#define FSFW_SRC_FSFW_OSAL_LINUX_COMMANDEXECUTOR_H_ + +#include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "fsfw/returnvalues/FwClassIds.h" + +#include + +#include +#include + +class SimpleRingBuffer; +template class DynamicFIFO; + +/** + * @brief Helper class to execute shell commands in blocking and non-blocking mode + * @details + * This class is able to execute processes by using the Linux popen call. It also has the + * capability of writing the read output of a process into a provided ring buffer. + * + * The executor works by first loading the command which should be executed and specifying + * whether it should be executed blocking or non-blocking. After that, execution can be started + * with the execute command. In blocking mode, the execute command will block until the command + * has finished + */ +class CommandExecutor { +public: + enum class States { + IDLE, + COMMAND_LOADED, + PENDING + }; + + static constexpr uint8_t CLASS_ID = CLASS_ID::LINUX_OSAL; + + //! [EXPORT] : [COMMENT] Execution of the current command has finished + static constexpr ReturnValue_t EXECUTION_FINISHED = + HasReturnvaluesIF::makeReturnCode(CLASS_ID, 0); + + //! [EXPORT] : [COMMENT] Command is pending. This will also be returned if the user tries + //! to load another command but a command is still pending + static constexpr ReturnValue_t COMMAND_PENDING = + HasReturnvaluesIF::makeReturnCode(CLASS_ID, 1); + //! [EXPORT] : [COMMENT] Some bytes have been read from the executing process + static constexpr ReturnValue_t BYTES_READ = + HasReturnvaluesIF::makeReturnCode(CLASS_ID, 2); + //! [EXPORT] : [COMMENT] Command execution failed + static constexpr ReturnValue_t COMMAND_ERROR = + HasReturnvaluesIF::makeReturnCode(CLASS_ID, 3); + //! [EXPORT] : [COMMENT] + static constexpr ReturnValue_t NO_COMMAND_LOADED_OR_PENDING = + HasReturnvaluesIF::makeReturnCode(CLASS_ID, 4); + static constexpr ReturnValue_t PCLOSE_CALL_ERROR = + HasReturnvaluesIF::makeReturnCode(CLASS_ID, 6); + + /** + * Constructor. Is initialized with maximum size of internal buffer to read data from the + * executed process. + * @param maxSize + */ + CommandExecutor(const size_t maxSize); + + /** + * Load a new command which should be executed + * @param command + * @param blocking + * @param printOutput + * @return + */ + ReturnValue_t load(std::string command, bool blocking, bool printOutput = true); + /** + * Execute the loaded command. + * @return + * - In blocking mode, it will return RETURN_FAILED if + * the result of the system call was not 0. The error value can be accessed using + * getLastError + * - In non-blocking mode, this call will start + * the execution and then return RETURN_OK + */ + ReturnValue_t execute(); + /** + * Only used in non-blocking mode. Checks the currently running command. + * @param bytesRead Will be set to the number of bytes read, if bytes have been read + * @return + * - BYTES_READ if bytes have been read from the executing process. It is recommended to call + * check again after this + * - RETURN_OK execution is pending, but no bytes have been read from the executing process + * - RETURN_FAILED if execution has failed, error value can be accessed using getLastError + * - EXECUTION_FINISHED if the process was executed successfully + * - NO_COMMAND_LOADED_OR_PENDING self-explanatory + * - COMMAND_ERROR internal poll error + */ + ReturnValue_t check(bool& replyReceived); + /** + * Abort the current command. Should normally not be necessary, check can be used to find + * out whether command execution was successful + * @return RETURN_OK + */ + ReturnValue_t close(); + + States getCurrentState() const; + int getLastError() const; + void printLastError(std::string funcName) const; + + /** + * Assign a ring buffer and a FIFO which will be filled by the executor with the output + * read from the started process + * @param ringBuffer + * @param sizesFifo + */ + void setRingBuffer(SimpleRingBuffer* ringBuffer, DynamicFIFO* sizesFifo); + + /** + * Reset the executor. This calls close internally and then reset the state machine so new + * commands can be loaded and executed + */ + void reset(); +private: + std::string currentCmd; + bool blocking = true; + FILE* currentCmdFile = nullptr; + int currentFd = 0; + bool printOutput = true; + std::vector readVec; + struct pollfd waiter {}; + SimpleRingBuffer* ringBuffer = nullptr; + DynamicFIFO* sizesFifo = nullptr; + + States state = States::IDLE; + int lastError = 0; + + ReturnValue_t executeBlocking(); +}; + +#endif /* FSFW_SRC_FSFW_OSAL_LINUX_COMMANDEXECUTOR_H_ */ diff --git a/hal/src/fsfw_hal/linux/gpio/CMakeLists.txt b/hal/src/fsfw_hal/linux/gpio/CMakeLists.txt index 7083f70d..b1609850 100644 --- a/hal/src/fsfw_hal/linux/gpio/CMakeLists.txt +++ b/hal/src/fsfw_hal/linux/gpio/CMakeLists.txt @@ -1,12 +1,16 @@ -target_sources(${LIB_FSFW_NAME} PRIVATE - LinuxLibgpioIF.cpp -) - # This abstraction layer requires the gpiod library. You can install this library # with "sudo apt-get install -y libgpiod-dev". If you are cross-compiling, you need # to install the package before syncing the sysroot to your host computer. -find_library(LIB_GPIO gpiod REQUIRED) +find_library(LIB_GPIO gpiod) + +if(${LIB_GPIO} MATCHES LIB_GPIO-NOTFOUND) + message(STATUS "gpiod library not found, not linking against it") +else() + target_sources(${LIB_FSFW_NAME} PRIVATE + LinuxLibgpioIF.cpp + ) + target_link_libraries(${LIB_FSFW_NAME} PRIVATE + ${LIB_GPIO} + ) +endif() -target_link_libraries(${LIB_FSFW_NAME} PRIVATE - ${LIB_GPIO} -) \ No newline at end of file diff --git a/hal/src/fsfw_hal/linux/i2c/I2cComIF.cpp b/hal/src/fsfw_hal/linux/i2c/I2cComIF.cpp index 98d9a510..fd5e8454 100644 --- a/hal/src/fsfw_hal/linux/i2c/I2cComIF.cpp +++ b/hal/src/fsfw_hal/linux/i2c/I2cComIF.cpp @@ -1,8 +1,10 @@ +#include "fsfw/FSFW.h" + #include "fsfw_hal/linux/i2c/I2cComIF.h" #include "fsfw_hal/linux/utility.h" #include "fsfw_hal/linux/UnixFileGuard.h" -#include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/serviceinterface.h" #include #include @@ -24,12 +26,16 @@ ReturnValue_t I2cComIF::initializeInterface(CookieIF* cookie) { std::string deviceFile; if(cookie == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::error << "I2cComIF::initializeInterface: Invalid cookie!" << std::endl; +#endif return NULLPOINTER; } I2cCookie* i2cCookie = dynamic_cast(cookie); if(i2cCookie == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::error << "I2cComIF::initializeInterface: Invalid I2C cookie!" << std::endl; +#endif return NULLPOINTER; } @@ -41,15 +47,19 @@ ReturnValue_t I2cComIF::initializeInterface(CookieIF* cookie) { I2cInstance i2cInstance = {std::vector(maxReplyLen), 0}; auto statusPair = i2cDeviceMap.emplace(i2cAddress, i2cInstance); if (not statusPair.second) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::error << "I2cComIF::initializeInterface: Failed to insert device with address " << i2cAddress << "to I2C device " << "map" << std::endl; +#endif return HasReturnvaluesIF::RETURN_FAILED; } return HasReturnvaluesIF::RETURN_OK; } +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::error << "I2cComIF::initializeInterface: Device with address " << i2cAddress << "already in use" << std::endl; +#endif return HasReturnvaluesIF::RETURN_FAILED; } @@ -61,8 +71,10 @@ ReturnValue_t I2cComIF::sendMessage(CookieIF *cookie, std::string deviceFile; if(sendData == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::error << "I2cComIF::sendMessage: Send Data is nullptr" << std::endl; +#endif return HasReturnvaluesIF::RETURN_FAILED; } @@ -72,15 +84,19 @@ ReturnValue_t I2cComIF::sendMessage(CookieIF *cookie, I2cCookie* i2cCookie = dynamic_cast(cookie); if(i2cCookie == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::error << "I2cComIF::sendMessage: Invalid I2C Cookie!" << std::endl; +#endif return NULLPOINTER; } address_t i2cAddress = i2cCookie->getAddress(); i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); if (i2cDeviceMapIter == i2cDeviceMap.end()) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::error << "I2cComIF::sendMessage: i2cAddress of Cookie not " << "registered in i2cDeviceMap" << std::endl; +#endif return HasReturnvaluesIF::RETURN_FAILED; } @@ -94,10 +110,12 @@ ReturnValue_t I2cComIF::sendMessage(CookieIF *cookie, return result; } - if (write(fd, sendData, sendLen) != (int)sendLen) { + if (write(fd, sendData, sendLen) != static_cast(sendLen)) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::error << "I2cComIF::sendMessage: Failed to send data to I2C " "device with error code " << errno << ". Error description: " << strerror(errno) << std::endl; +#endif return HasReturnvaluesIF::RETURN_FAILED; } return HasReturnvaluesIF::RETURN_OK; @@ -119,7 +137,9 @@ ReturnValue_t I2cComIF::requestReceiveMessage(CookieIF *cookie, I2cCookie* i2cCookie = dynamic_cast(cookie); if(i2cCookie == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::error << "I2cComIF::requestReceiveMessage: Invalid I2C Cookie!" << std::endl; +#endif i2cDeviceMapIter->second.replyLen = 0; return NULLPOINTER; } @@ -127,8 +147,10 @@ ReturnValue_t I2cComIF::requestReceiveMessage(CookieIF *cookie, address_t i2cAddress = i2cCookie->getAddress(); i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); if (i2cDeviceMapIter == i2cDeviceMap.end()) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::error << "I2cComIF::requestReceiveMessage: i2cAddress of Cookie not " << "registered in i2cDeviceMap" << std::endl; +#endif i2cDeviceMapIter->second.replyLen = 0; return HasReturnvaluesIF::RETURN_FAILED; } @@ -156,7 +178,9 @@ ReturnValue_t I2cComIF::requestReceiveMessage(CookieIF *cookie, << requestLen << " bytes" << std::endl; #endif i2cDeviceMapIter->second.replyLen = 0; +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::debug << "I2cComIF::requestReceiveMessage: Read " << readLen << " of " << requestLen << " bytes" << std::endl; +#endif return HasReturnvaluesIF::RETURN_FAILED; } @@ -168,15 +192,19 @@ ReturnValue_t I2cComIF::readReceivedMessage(CookieIF *cookie, uint8_t **buffer, size_t* size) { I2cCookie* i2cCookie = dynamic_cast(cookie); if(i2cCookie == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::error << "I2cComIF::readReceivedMessage: Invalid I2C Cookie!" << std::endl; +#endif return NULLPOINTER; } address_t i2cAddress = i2cCookie->getAddress(); i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); if (i2cDeviceMapIter == i2cDeviceMap.end()) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::error << "I2cComIF::readReceivedMessage: i2cAddress of Cookie not " << "found in i2cDeviceMap" << std::endl; +#endif return HasReturnvaluesIF::RETURN_FAILED; } *buffer = i2cDeviceMapIter->second.replyBuffer.data(); diff --git a/hal/src/fsfw_hal/linux/uart/UartComIF.cpp b/hal/src/fsfw_hal/linux/uart/UartComIF.cpp index f5754c6e..08ec9aa0 100644 --- a/hal/src/fsfw_hal/linux/uart/UartComIF.cpp +++ b/hal/src/fsfw_hal/linux/uart/UartComIF.cpp @@ -1,8 +1,8 @@ #include "UartComIF.h" -#include "OBSWConfig.h" +#include "fsfw/FSFW.h" #include "fsfw_hal/linux/utility.h" -#include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/serviceinterface.h" #include #include @@ -26,7 +26,9 @@ ReturnValue_t UartComIF::initializeInterface(CookieIF* cookie) { UartCookie* uartCookie = dynamic_cast(cookie); if (uartCookie == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::error << "UartComIF::initializeInterface: Invalid UART Cookie!" << std::endl; +#endif return NULLPOINTER; } @@ -42,14 +44,18 @@ ReturnValue_t UartComIF::initializeInterface(CookieIF* cookie) { UartElements uartElements = {fileDescriptor, std::vector(maxReplyLen), 0}; auto status = uartDeviceMap.emplace(deviceFile, uartElements); if (status.second == false) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::warning << "UartComIF::initializeInterface: Failed to insert device " << deviceFile << "to UART device map" << std::endl; +#endif return RETURN_FAILED; } } else { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::warning << "UartComIF::initializeInterface: UART device " << deviceFile << " already in use" << std::endl; +#endif return RETURN_FAILED; } @@ -70,15 +76,19 @@ int UartComIF::configureUartPort(UartCookie* uartCookie) { int fd = open(deviceFile.c_str(), flags); if (fd < 0) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::warning << "UartComIF::configureUartPort: Failed to open uart " << deviceFile << "with error code " << errno << strerror(errno) << std::endl; +#endif return fd; } /* Read in existing settings */ if(tcgetattr(fd, &options) != 0) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::warning << "UartComIF::configureUartPort: Error " << errno << "from tcgetattr: " << strerror(errno) << std::endl; +#endif return fd; } @@ -99,8 +109,10 @@ int UartComIF::configureUartPort(UartCookie* uartCookie) { /* Save option settings */ if (tcsetattr(fd, TCSANOW, &options) != 0) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::warning << "UartComIF::configureUartPort: Failed to set options with error " << errno << ": " << strerror(errno); +#endif return fd; } return fd; @@ -152,7 +164,9 @@ void UartComIF::setDatasizeOptions(struct termios* options, UartCookie* uartCook options->c_cflag |= CS8; break; default: +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::warning << "UartComIF::setDatasizeOptions: Invalid size specified" << std::endl; +#endif break; } } @@ -259,7 +273,9 @@ void UartComIF::configureBaudrate(struct termios* options, UartCookie* uartCooki cfsetospeed(options, B460800); break; default: +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::warning << "UartComIF::configureBaudrate: Baudrate not supported" << std::endl; +#endif break; } } @@ -275,29 +291,37 @@ ReturnValue_t UartComIF::sendMessage(CookieIF *cookie, } if(sendData == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::warning << "UartComIF::sendMessage: Send data is nullptr" << std::endl; +#endif return RETURN_FAILED; } UartCookie* uartCookie = dynamic_cast(cookie); if(uartCookie == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::warning << "UartComIF::sendMessasge: Invalid UART Cookie!" << std::endl; +#endif return NULLPOINTER; } deviceFile = uartCookie->getDeviceFile(); uartDeviceMapIter = uartDeviceMap.find(deviceFile); if (uartDeviceMapIter == uartDeviceMap.end()) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::debug << "UartComIF::sendMessage: Device file " << deviceFile << "not in UART map" << std::endl; +#endif return RETURN_FAILED; } fd = uartDeviceMapIter->second.fileDescriptor; - if (write(fd, sendData, sendLen) != (int)sendLen) { + if (write(fd, sendData, sendLen) != static_cast(sendLen)) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::error << "UartComIF::sendMessage: Failed to send data with error code " << errno << ": Error description: " << strerror(errno) << std::endl; +#endif return RETURN_FAILED; } @@ -314,7 +338,9 @@ ReturnValue_t UartComIF::requestReceiveMessage(CookieIF *cookie, size_t requestL UartCookie* uartCookie = dynamic_cast(cookie); if(uartCookie == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::debug << "UartComIF::requestReceiveMessage: Invalid Uart Cookie!" << std::endl; +#endif return NULLPOINTER; } @@ -327,8 +353,10 @@ ReturnValue_t UartComIF::requestReceiveMessage(CookieIF *cookie, size_t requestL } if (uartDeviceMapIter == uartDeviceMap.end()) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::debug << "UartComIF::requestReceiveMessage: Device file " << deviceFile << " not in uart map" << std::endl; +#endif return RETURN_FAILED; } @@ -425,8 +453,10 @@ ReturnValue_t UartComIF::handleNoncanonicalRead(UartCookie &uartCookie, UartDevi } else if (bytesRead != static_cast(requestLen)) { if(uartCookie.isReplySizeFixed()) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::warning << "UartComIF::requestReceiveMessage: Only read " << bytesRead << " of " << requestLen << " bytes" << std::endl; +#endif return RETURN_FAILED; } } @@ -442,15 +472,19 @@ ReturnValue_t UartComIF::readReceivedMessage(CookieIF *cookie, UartCookie* uartCookie = dynamic_cast(cookie); if(uartCookie == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::debug << "UartComIF::readReceivedMessage: Invalid uart cookie!" << std::endl; +#endif return NULLPOINTER; } deviceFile = uartCookie->getDeviceFile(); uartDeviceMapIter = uartDeviceMap.find(deviceFile); if (uartDeviceMapIter == uartDeviceMap.end()) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::debug << "UartComIF::readReceivedMessage: Device file " << deviceFile << " not in uart map" << std::endl; +#endif return RETURN_FAILED; } @@ -468,7 +502,9 @@ ReturnValue_t UartComIF::flushUartRxBuffer(CookieIF *cookie) { UartDeviceMapIter uartDeviceMapIter; UartCookie* uartCookie = dynamic_cast(cookie); if(uartCookie == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::warning << "UartComIF::flushUartRxBuffer: Invalid uart cookie!" << std::endl; +#endif return NULLPOINTER; } deviceFile = uartCookie->getDeviceFile(); @@ -486,7 +522,9 @@ ReturnValue_t UartComIF::flushUartTxBuffer(CookieIF *cookie) { UartDeviceMapIter uartDeviceMapIter; UartCookie* uartCookie = dynamic_cast(cookie); if(uartCookie == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::warning << "UartComIF::flushUartTxBuffer: Invalid uart cookie!" << std::endl; +#endif return NULLPOINTER; } deviceFile = uartCookie->getDeviceFile(); @@ -504,7 +542,9 @@ ReturnValue_t UartComIF::flushUartTxAndRxBuf(CookieIF *cookie) { UartDeviceMapIter uartDeviceMapIter; UartCookie* uartCookie = dynamic_cast(cookie); if(uartCookie == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::warning << "UartComIF::flushUartTxAndRxBuf: Invalid uart cookie!" << std::endl; +#endif return NULLPOINTER; } deviceFile = uartCookie->getDeviceFile(); diff --git a/hal/src/fsfw_hal/linux/uart/UartCookie.cpp b/hal/src/fsfw_hal/linux/uart/UartCookie.cpp index 1c52e9cd..140b1992 100644 --- a/hal/src/fsfw_hal/linux/uart/UartCookie.cpp +++ b/hal/src/fsfw_hal/linux/uart/UartCookie.cpp @@ -1,6 +1,6 @@ #include "fsfw_hal/linux/uart/UartCookie.h" -#include +#include UartCookie::UartCookie(object_id_t handlerId, std::string deviceFile, UartModes uartMode, uint32_t baudrate, size_t maxReplyLen): @@ -42,7 +42,9 @@ void UartCookie::setBitsPerWord(uint8_t bitsPerWord_) { case 8: break; default: +#if FSFW_CPP_OSTREAM_ENABLED == 1 sif::debug << "UartCookie::setBitsPerWord: Invalid bits per word specified" << std::endl; +#endif return; } bitsPerWord = bitsPerWord_; diff --git a/scripts/helper.py b/scripts/helper.py index 0bb430ee..1234a943 100755 --- a/scripts/helper.py +++ b/scripts/helper.py @@ -132,7 +132,9 @@ def handle_tests_type(args, build_dir_list: list): def create_tests_build_cfg(): os.mkdir(UNITTEST_FOLDER_NAME) os.chdir(UNITTEST_FOLDER_NAME) - os.system('cmake -DFSFW_OSAL=host -DFSFW_BUILD_UNITTESTS=ON ..') + cmake_cmd = "cmake -DFSFW_OSAL=host -DFSFW_BUILD_UNITTESTS=ON .." + print(f"Executing CMake command {cmake_cmd}") + os.system(cmake_cmd) os.chdir('..') diff --git a/src/fsfw/FSFW.h.in b/src/fsfw/FSFW.h.in index 7e52b646..a4982369 100644 --- a/src/fsfw/FSFW.h.in +++ b/src/fsfw/FSFW.h.in @@ -18,6 +18,10 @@ // FSFW core defines +#ifndef FSFW_TCP_RECV_WIRETAPPING_ENABLED +#define FSFW_TCP_RECV_WIRETAPPING_ENABLED 0 +#endif + #ifndef FSFW_CPP_OSTREAM_ENABLED #define FSFW_CPP_OSTREAM_ENABLED 1 #endif /* FSFW_CPP_OSTREAM_ENABLED */ diff --git a/src/fsfw/container/SimpleRingBuffer.h b/src/fsfw/container/SimpleRingBuffer.h index 6f31c5fb..dc0aeba8 100644 --- a/src/fsfw/container/SimpleRingBuffer.h +++ b/src/fsfw/container/SimpleRingBuffer.h @@ -5,8 +5,7 @@ #include /** - * @brief Circular buffer implementation, useful for buffering - * into data streams. + * @brief Circular buffer implementation, useful for buffering into data streams. * @details * Note that the deleteData() has to be called to increment the read pointer. * This class allocated dynamically, so @@ -20,8 +19,8 @@ public: * @param size * @param overwriteOld If the ring buffer is overflowing at a write * operation, the oldest data will be overwritten. - * @param maxExcessBytes These additional bytes will be allocated in addtion - * to the specified size to accomodate contiguous write operations + * @param maxExcessBytes These additional bytes will be allocated in addition + * to the specified size to accommodate continuous write operations * with getFreeElement. * */ @@ -32,10 +31,10 @@ public: * @param buffer * @param size * @param overwriteOld - * If the ring buffer is overflowing at a write operartion, the oldest data + * If the ring buffer is overflowing at a write operation, the oldest data * will be overwritten. * @param maxExcessBytes - * If the buffer can accomodate additional bytes for contigous write + * If the buffer can accommodate additional bytes for contiguous write * operations with getFreeElement, this is the maximum allowed additional * size */ @@ -48,7 +47,7 @@ public: * Write to circular buffer and increment write pointer by amount. * @param data * @param amount - * @return -@c RETURN_OK if write operation was successfull + * @return -@c RETURN_OK if write operation was successful * -@c RETURN_FAILED if */ ReturnValue_t writeData(const uint8_t* data, size_t amount); @@ -108,7 +107,7 @@ public: * Delete data by incrementing read pointer. * @param amount * @param deleteRemaining - * If the amount specified is larger than the remaing size to read and this + * If the amount specified is larger than the remaining size to read and this * is set to true, the remaining amount will be deleted as well * @param trueAmount [out] * If deleteRemaining was set to true, the amount deleted will be assigned diff --git a/src/fsfw/devicehandlers/AssemblyBase.h b/src/fsfw/devicehandlers/AssemblyBase.h index 6cac81b4..7d54f14d 100644 --- a/src/fsfw/devicehandlers/AssemblyBase.h +++ b/src/fsfw/devicehandlers/AssemblyBase.h @@ -7,7 +7,7 @@ /** * @brief Base class to implement reconfiguration and failure handling for - * redundant devices by monitoring their modes health states. + * redundant devices by monitoring their modes and health states. * @details * Documentation: Dissertation Baetz p.156, 157. * diff --git a/src/fsfw/devicehandlers/DeviceCommunicationIF.h b/src/fsfw/devicehandlers/DeviceCommunicationIF.h index e0b473d3..527e4700 100644 --- a/src/fsfw/devicehandlers/DeviceCommunicationIF.h +++ b/src/fsfw/devicehandlers/DeviceCommunicationIF.h @@ -85,9 +85,10 @@ public: * Called by DHB in the GET_WRITE doGetWrite(). * Get send confirmation that the data in sendMessage() was sent successfully. * @param cookie - * @return - @c RETURN_OK if data was sent successfull - * - Everything else triggers falure event with - * returnvalue as parameter 1 + * @return + * - @c RETURN_OK if data was sent successfully but a reply is expected + * - NO_REPLY_EXPECTED if data was sent successfully and no reply is expected + * - Everything else to indicate failure */ virtual ReturnValue_t getSendSuccess(CookieIF *cookie) = 0; diff --git a/src/fsfw/devicehandlers/DeviceHandlerBase.h b/src/fsfw/devicehandlers/DeviceHandlerBase.h index b182b611..4bc54ac4 100644 --- a/src/fsfw/devicehandlers/DeviceHandlerBase.h +++ b/src/fsfw/devicehandlers/DeviceHandlerBase.h @@ -334,8 +334,7 @@ protected: * - @c RETURN_OK to send command after #rawPacket and #rawPacketLen * have been set. * - @c HasActionsIF::EXECUTION_COMPLETE to generate a finish reply immediately. This can - * be used if no reply is expected. Otherwise, the developer can call #actionHelper.finish - * to finish the command handling. + * be used if no reply is expected * - Anything else triggers an event with the return code as a parameter as well as a * step reply failed with the return code */ diff --git a/src/fsfw/devicehandlers/DeviceHandlerIF.h b/src/fsfw/devicehandlers/DeviceHandlerIF.h index 1933c571..1fc57c42 100644 --- a/src/fsfw/devicehandlers/DeviceHandlerIF.h +++ b/src/fsfw/devicehandlers/DeviceHandlerIF.h @@ -120,7 +120,8 @@ public: static const ReturnValue_t WRONG_MODE_FOR_COMMAND = MAKE_RETURN_CODE(0xA5); static const ReturnValue_t TIMEOUT = MAKE_RETURN_CODE(0xA6); static const ReturnValue_t BUSY = MAKE_RETURN_CODE(0xA7); - static const ReturnValue_t NO_REPLY_EXPECTED = MAKE_RETURN_CODE(0xA8); //!< Used to indicate that this is a command-only command. + //!< Used to indicate that this is a command-only command. + static const ReturnValue_t NO_REPLY_EXPECTED = MAKE_RETURN_CODE(0xA8); static const ReturnValue_t NON_OP_TEMPERATURE = MAKE_RETURN_CODE(0xA9); static const ReturnValue_t COMMAND_NOT_IMPLEMENTED = MAKE_RETURN_CODE(0xAA); diff --git a/src/fsfw/osal/linux/CMakeLists.txt b/src/fsfw/osal/linux/CMakeLists.txt index 41800764..dcdade67 100644 --- a/src/fsfw/osal/linux/CMakeLists.txt +++ b/src/fsfw/osal/linux/CMakeLists.txt @@ -1,20 +1,19 @@ -target_sources(${LIB_FSFW_NAME} - PRIVATE - Clock.cpp - BinarySemaphore.cpp - CountingSemaphore.cpp - FixedTimeslotTask.cpp - InternalErrorCodes.cpp - MessageQueue.cpp - Mutex.cpp - MutexFactory.cpp - PeriodicPosixTask.cpp - PosixThread.cpp - QueueFactory.cpp - SemaphoreFactory.cpp - TaskFactory.cpp - tcpipHelpers.cpp - unixUtility.cpp +target_sources(${LIB_FSFW_NAME} PRIVATE + Clock.cpp + BinarySemaphore.cpp + CountingSemaphore.cpp + FixedTimeslotTask.cpp + InternalErrorCodes.cpp + MessageQueue.cpp + Mutex.cpp + MutexFactory.cpp + PeriodicPosixTask.cpp + PosixThread.cpp + QueueFactory.cpp + SemaphoreFactory.cpp + TaskFactory.cpp + tcpipHelpers.cpp + unixUtility.cpp ) find_package(Threads REQUIRED) diff --git a/src/fsfw/osal/linux/MessageQueue.cpp b/src/fsfw/osal/linux/MessageQueue.cpp index b068c04f..d028f9f7 100644 --- a/src/fsfw/osal/linux/MessageQueue.cpp +++ b/src/fsfw/osal/linux/MessageQueue.cpp @@ -285,10 +285,10 @@ ReturnValue_t MessageQueue::sendMessageFromMessageQueue(MessageQueueId_t sendTo, utility::printUnixErrorGeneric(CLASS_NAME, "sendMessageFromMessageQueue", "EBADF"); #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "mq_send to: " << sendTo << " sent from " - << sentFrom << "failed" << std::endl; + sif::warning << "mq_send to " << sendTo << " sent from " + << sentFrom << " failed" << std::endl; #else - sif::printWarning("mq_send to: %d sent from %d failed\n", sendTo, sentFrom); + sif::printWarning("mq_send to %d sent from %d failed\n", sendTo, sentFrom); #endif return DESTINATION_INVALID; } diff --git a/src/fsfw/subsystem/SubsystemBase.h b/src/fsfw/subsystem/SubsystemBase.h index 6b2e9b5f..a1de077d 100644 --- a/src/fsfw/subsystem/SubsystemBase.h +++ b/src/fsfw/subsystem/SubsystemBase.h @@ -62,7 +62,8 @@ protected: struct ChildInfo { MessageQueueId_t commandQueue; Mode_t mode; - Submode_t submode;bool healthChanged; + Submode_t submode; + bool healthChanged; }; Mode_t mode; diff --git a/tests/src/fsfw_tests/unit/CMakeLists.txt b/tests/src/fsfw_tests/unit/CMakeLists.txt index 164e3bde..7d5fbd43 100644 --- a/tests/src/fsfw_tests/unit/CMakeLists.txt +++ b/tests/src/fsfw_tests/unit/CMakeLists.txt @@ -21,3 +21,4 @@ add_subdirectory(storagemanager) add_subdirectory(globalfunctions) add_subdirectory(timemanager) add_subdirectory(tmtcpacket) +add_subdirectory(hal) diff --git a/tests/src/fsfw_tests/unit/hal/CMakeLists.txt b/tests/src/fsfw_tests/unit/hal/CMakeLists.txt new file mode 100644 index 00000000..ee14a3aa --- /dev/null +++ b/tests/src/fsfw_tests/unit/hal/CMakeLists.txt @@ -0,0 +1,3 @@ +target_sources(${FSFW_TEST_TGT} PRIVATE + testCommandExecutor.cpp +) diff --git a/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp b/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp new file mode 100644 index 00000000..0c825389 --- /dev/null +++ b/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp @@ -0,0 +1,110 @@ +#include + +#include "fsfw/serviceinterface.h" + +#include "fsfw/container/SimpleRingBuffer.h" +#include "fsfw/container/DynamicFIFO.h" + +#include "fsfw_hal/linux/CommandExecutor.h" +#include "fsfw/platform.h" + +#include +#include + +#ifdef PLATFORM_UNIX + +static const char TEST_FILE_NAME[] = "/tmp/fsfw-unittest-test.txt"; + +TEST_CASE( "Command Executor" , "[cmd-exec]") { + // Check blocking mode first + CommandExecutor cmdExecutor(1024); + std::string cmd = "echo \"test\" >> " + std::string(TEST_FILE_NAME); + REQUIRE(cmdExecutor.getCurrentState() == CommandExecutor::States::IDLE); + ReturnValue_t result = cmdExecutor.load(cmd, true, true); + REQUIRE(cmdExecutor.getCurrentState() == CommandExecutor::States::COMMAND_LOADED); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(cmdExecutor.execute() == HasReturnvaluesIF::RETURN_OK); + // Check that file exists with contents + std::ifstream file(TEST_FILE_NAME); + std::string line; + std::getline(file, line); + CHECK(line == "test"); + std::remove(TEST_FILE_NAME); + REQUIRE(cmdExecutor.getCurrentState() == CommandExecutor::States::IDLE); + + // Now check non-blocking mode + SimpleRingBuffer outputBuffer(524, true); + DynamicFIFO sizesFifo(12); + cmdExecutor.setRingBuffer(&outputBuffer, &sizesFifo); + + result = cmdExecutor.load("echo \"Hello World\"", false, false); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + cmdExecutor.execute(); + bool bytesHaveBeenRead = false; + size_t limitIdx = 0; + while(result != CommandExecutor::EXECUTION_FINISHED) { + limitIdx++; + result = cmdExecutor.check(bytesHaveBeenRead); + REQUIRE(result != CommandExecutor::COMMAND_ERROR); + usleep(500); + REQUIRE(limitIdx < 5); + } + + limitIdx = 0; + CHECK(bytesHaveBeenRead == true); + CHECK(result == CommandExecutor::EXECUTION_FINISHED); + uint16_t readBytes = 0; + sizesFifo.retrieve(&readBytes); + REQUIRE(readBytes == 12); + REQUIRE(outputBuffer.getAvailableReadData() == 12); + uint8_t readBuffer[32]; + REQUIRE(outputBuffer.readData(readBuffer, 12) == HasReturnvaluesIF::RETURN_OK); + CHECK(strcmp(reinterpret_cast(readBuffer), "Hello World\n") == 0); + outputBuffer.deleteData(12, true); + // Test more complex command + result = cmdExecutor.load("ping -c 1 localhost", false, false); + REQUIRE(cmdExecutor.getCurrentState() == CommandExecutor::States::COMMAND_LOADED); + REQUIRE(cmdExecutor.execute() == HasReturnvaluesIF::RETURN_OK); + REQUIRE(cmdExecutor.getCurrentState() == CommandExecutor::States::PENDING); + limitIdx = 0; + while(result != CommandExecutor::EXECUTION_FINISHED) { + limitIdx++; + result = cmdExecutor.check(bytesHaveBeenRead); + REQUIRE(result != CommandExecutor::COMMAND_ERROR); + usleep(500); + REQUIRE(limitIdx < 20); + } + limitIdx = 0; + CHECK(bytesHaveBeenRead == true); + CHECK(result == CommandExecutor::EXECUTION_FINISHED); + REQUIRE(cmdExecutor.getCurrentState() == CommandExecutor::States::IDLE); + readBytes = 0; + sizesFifo.retrieve(&readBytes); + // That's about the size of the reply + bool beTrue = (readBytes > 200) and (readBytes < 300); + REQUIRE(beTrue); + uint8_t largerReadBuffer[1024] = {}; + outputBuffer.readData(largerReadBuffer, readBytes); + // You can also check this output in the debugger + std::string allTheReply(reinterpret_cast(largerReadBuffer)); + // I am just going to assume that this string is the same across ping implementations + // of different Linux systems + REQUIRE(allTheReply.find("localhost ping statistics") != std::string::npos); + + // Now check failing command + result = cmdExecutor.load("false", false, false); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + result = cmdExecutor.execute(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + while(result != CommandExecutor::EXECUTION_FINISHED and result != HasReturnvaluesIF::RETURN_FAILED) { + limitIdx++; + result = cmdExecutor.check(bytesHaveBeenRead); + REQUIRE(result != CommandExecutor::COMMAND_ERROR); + usleep(500); + REQUIRE(limitIdx < 20); + } + REQUIRE(result == HasReturnvaluesIF::RETURN_FAILED); + REQUIRE(cmdExecutor.getLastError() == 1); +} + +#endif From bc5a6b4a51dd630ee5c98207d58165487cc4c47b Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 26 Jan 2022 12:23:12 +0100 Subject: [PATCH 07/56] bump catch2 version to v3.0.0-preview4 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index bb3d48b8..67d07501 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -56,7 +56,7 @@ if(FSFW_BUILD_UNITTESTS) FetchContent_Declare( Catch2 GIT_REPOSITORY https://github.com/catchorg/Catch2.git - GIT_TAG v3.0.0-preview3 + GIT_TAG v3.0.0-preview4 ) FetchContent_MakeAvailable(Catch2) From fe95c3337ab58dd5fd39fe8e10e898effcaadb2a Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 26 Jan 2022 12:28:30 +0100 Subject: [PATCH 08/56] changed builddir name in Jenkinsfile --- automation/Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/automation/Jenkinsfile b/automation/Jenkinsfile index d4a8e2ab..ba3f5afb 100644 --- a/automation/Jenkinsfile +++ b/automation/Jenkinsfile @@ -1,7 +1,7 @@ pipeline { agent any environment { - BUILDDIR = 'build-unittests' + BUILDDIR = 'build-tests' } stages { stage('Create Docker') { From c453af591165b27a61eb86cfb8a258dd77bedb45 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 26 Jan 2022 15:30:01 +0100 Subject: [PATCH 09/56] cleanCI --- automation/Jenkinsfile | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/automation/Jenkinsfile b/automation/Jenkinsfile index ba3f5afb..e7f85e28 100644 --- a/automation/Jenkinsfile +++ b/automation/Jenkinsfile @@ -16,6 +16,18 @@ pipeline { sh 'rm -rf $BUILDDIR' } } + stage('Clean') { + when { + anyOf { + changelog 'cleanCI' + changeset '*.cmake' + changeset 'CMakeLists.txt' + } + } + steps { + sh 'rm -rf $BUILDDIR' + } + } stage('Configure') { agent { dockerfile { From 441b3b83c883cd4ccc41e8c7c07d537998f0bdf7 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 27 Jan 2022 11:30:33 +0100 Subject: [PATCH 10/56] Changes to Dockerfile and Jenkinsfile 1. Install Catch2 from sources inside a Docker stage/layer 2. Some tweaks to Jenkinsfile --- automation/Dockerfile | 6 ++++++ automation/Jenkinsfile | 36 +++++++++++++++++++++--------------- 2 files changed, 27 insertions(+), 15 deletions(-) diff --git a/automation/Dockerfile b/automation/Dockerfile index 93a4fe7d..52e5acfb 100644 --- a/automation/Dockerfile +++ b/automation/Dockerfile @@ -6,3 +6,9 @@ RUN apt-get --yes upgrade #tzdata is a dependency, won't install otherwise ARG DEBIAN_FRONTEND=noninteractive RUN apt-get --yes install gcc g++ cmake make lcov git valgrind nano + +RUN git clone https://github.com/catchorg/Catch2.git && \ + cd Catch2 && \ + git checkout v3.0.0-preview4 && \ + cmake -Bbuild -H. -DBUILD_TESTING=OFF && \ + cmake --build build/ --target install diff --git a/automation/Jenkinsfile b/automation/Jenkinsfile index e7f85e28..3050a68b 100644 --- a/automation/Jenkinsfile +++ b/automation/Jenkinsfile @@ -1,22 +1,28 @@ pipeline { agent any environment { + DOCKER_TAG = 'fsfw-build' BUILDDIR = 'build-tests' } stages { - stage('Create Docker') { - agent { - dockerfile { - dir 'automation' - additionalBuildArgs '--no-cache' - reuseNode true + stage('Build Container') { + when { + anyOf { + changeset "automation/Dockerfile"; + changelog 'cleanDocker' } } steps { - sh 'rm -rf $BUILDDIR' + sh 'docker build -t $DOCKER_TAG - < automation/Dockerfile' } } stage('Clean') { + agent { + docker { + image '$DOCKER_TAG' + reuseNode true + } + } when { anyOf { changelog 'cleanCI' @@ -30,8 +36,8 @@ pipeline { } stage('Configure') { agent { - dockerfile { - dir 'automation' + docker { + image '$DOCKER_TAG' reuseNode true } } @@ -43,8 +49,8 @@ pipeline { } stage('Build') { agent { - dockerfile { - dir 'automation' + docker { + image '$DOCKER_TAG' reuseNode true } } @@ -56,8 +62,8 @@ pipeline { } stage('Unittests') { agent { - dockerfile { - dir 'automation' + docker { + image '$DOCKER_TAG' reuseNode true } } @@ -69,8 +75,8 @@ pipeline { } stage('Valgrind') { agent { - dockerfile { - dir 'automation' + docker { + image '$DOCKER_TAG' reuseNode true } } From 386843e3e70e2249c1e880cdfbfb973e3bf35f59 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 28 Jan 2022 13:33:06 +0100 Subject: [PATCH 11/56] update jenkinsfile --- automation/Jenkinsfile | 39 +++++++++++++++++++++------------------ 1 file changed, 21 insertions(+), 18 deletions(-) diff --git a/automation/Jenkinsfile b/automation/Jenkinsfile index 3050a68b..551dea84 100644 --- a/automation/Jenkinsfile +++ b/automation/Jenkinsfile @@ -1,25 +1,28 @@ pipeline { agent any environment { - DOCKER_TAG = 'fsfw-build' + DOCK_FILE_DIR = 'automation' BUILDDIR = 'build-tests' } stages { - stage('Build Container') { - when { - anyOf { - changeset "automation/Dockerfile"; - changelog 'cleanDocker' + stage('Create Docker') { + agent { + dockerfile { + dir '$DOCK_FILE_DIR' + additionalBuildArgs '--no-cache' } } - steps { - sh 'docker build -t $DOCKER_TAG - < automation/Dockerfile' + when { + anyOf { + changeset "$DOCK_FILE_DIR/Dockerfile"; + changelog 'cleanDocker' + } } } stage('Clean') { agent { - docker { - image '$DOCKER_TAG' + dockerfile { + dir '$DOCK_FILE_DIR' reuseNode true } } @@ -36,8 +39,8 @@ pipeline { } stage('Configure') { agent { - docker { - image '$DOCKER_TAG' + dockerfile { + dir '$DOCK_FILE_DIR' reuseNode true } } @@ -49,8 +52,8 @@ pipeline { } stage('Build') { agent { - docker { - image '$DOCKER_TAG' + dockerfile { + dir '$DOCK_FILE_DIR' reuseNode true } } @@ -62,8 +65,8 @@ pipeline { } stage('Unittests') { agent { - docker { - image '$DOCKER_TAG' + dockerfile { + dir '$DOCK_FILE_DIR' reuseNode true } } @@ -75,8 +78,8 @@ pipeline { } stage('Valgrind') { agent { - docker { - image '$DOCKER_TAG' + dockerfile { + dir '$DOCK_FILE_DIR' reuseNode true } } From 8414c9d47193775ccaa898f35b3dd6755938458a Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 28 Jan 2022 13:36:43 +0100 Subject: [PATCH 12/56] added steps --- automation/Jenkinsfile | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/automation/Jenkinsfile b/automation/Jenkinsfile index 551dea84..eefcdabf 100644 --- a/automation/Jenkinsfile +++ b/automation/Jenkinsfile @@ -10,6 +10,7 @@ pipeline { dockerfile { dir '$DOCK_FILE_DIR' additionalBuildArgs '--no-cache' + reuseNode true } } when { @@ -18,6 +19,9 @@ pipeline { changelog 'cleanDocker' } } + steps { + sh 'rm -rf $BUILDDIR' + } } stage('Clean') { agent { From cf3d4d8de31fddad7ce439908d659688f3a67930 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 28 Jan 2022 13:43:21 +0100 Subject: [PATCH 13/56] cleanDocker --- automation/Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/automation/Jenkinsfile b/automation/Jenkinsfile index eefcdabf..595f6963 100644 --- a/automation/Jenkinsfile +++ b/automation/Jenkinsfile @@ -15,7 +15,7 @@ pipeline { } when { anyOf { - changeset "$DOCK_FILE_DIR/Dockerfile"; + changeset "${DOCK_FILE_DIR}/Dockerfile"; changelog 'cleanDocker' } } From bf7fabd7bac4ef6932020ad11c1796a32cd97c6d Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 28 Jan 2022 13:46:05 +0100 Subject: [PATCH 14/56] commented out when block --- automation/Jenkinsfile | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/automation/Jenkinsfile b/automation/Jenkinsfile index 595f6963..afb43365 100644 --- a/automation/Jenkinsfile +++ b/automation/Jenkinsfile @@ -13,12 +13,13 @@ pipeline { reuseNode true } } - when { - anyOf { - changeset "${DOCK_FILE_DIR}/Dockerfile"; - changelog 'cleanDocker' - } - } + // Does not work, but maybe not necessary anyway.. + //when { + // anyOf { + // changeset "${DOCK_FILE_DIR}/Dockerfile"; + // changelog 'cleanDocker' + // } + //} steps { sh 'rm -rf $BUILDDIR' } From eba9abfc9aa1a97b5a13110f38c9cbdebf3521a0 Mon Sep 17 00:00:00 2001 From: Ulrich Mohr Date: Fri, 28 Jan 2022 14:10:24 +0100 Subject: [PATCH 15/56] Jenkinsfile syntax is weird, maybe this works... --- automation/Jenkinsfile | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/automation/Jenkinsfile b/automation/Jenkinsfile index afb43365..1853308c 100644 --- a/automation/Jenkinsfile +++ b/automation/Jenkinsfile @@ -8,7 +8,7 @@ pipeline { stage('Create Docker') { agent { dockerfile { - dir '$DOCK_FILE_DIR' + dir DOCK_FILE_DIR additionalBuildArgs '--no-cache' reuseNode true } @@ -27,7 +27,7 @@ pipeline { stage('Clean') { agent { dockerfile { - dir '$DOCK_FILE_DIR' + dir DOCK_FILE_DIR reuseNode true } } @@ -45,7 +45,7 @@ pipeline { stage('Configure') { agent { dockerfile { - dir '$DOCK_FILE_DIR' + dir DOCK_FILE_DIR reuseNode true } } @@ -58,7 +58,7 @@ pipeline { stage('Build') { agent { dockerfile { - dir '$DOCK_FILE_DIR' + dir DOCK_FILE_DIR reuseNode true } } @@ -71,7 +71,7 @@ pipeline { stage('Unittests') { agent { dockerfile { - dir '$DOCK_FILE_DIR' + dir DOCK_FILE_DIR reuseNode true } } @@ -84,7 +84,7 @@ pipeline { stage('Valgrind') { agent { dockerfile { - dir '$DOCK_FILE_DIR' + dir DOCK_FILE_DIR reuseNode true } } From b98127cea6496487d3dbc9f0f19406c7431f9117 Mon Sep 17 00:00:00 2001 From: Ulrich Mohr Date: Mon, 31 Jan 2022 14:59:45 +0100 Subject: [PATCH 16/56] Updated CI Build - Always clean and rebuild docker image. - Use single docker container --- automation/Jenkinsfile | 68 ++++++------------------------------------ 1 file changed, 9 insertions(+), 59 deletions(-) diff --git a/automation/Jenkinsfile b/automation/Jenkinsfile index 1853308c..0d62538e 100644 --- a/automation/Jenkinsfile +++ b/automation/Jenkinsfile @@ -1,54 +1,22 @@ pipeline { - agent any environment { - DOCK_FILE_DIR = 'automation' - BUILDDIR = 'build-tests' + DOCK_FILE_DIR = 'automation' + BUILDDIR = 'build-tests' + } + agent { + dockerfile { + dir DOCK_FILE_DIR + additionalBuildArgs '--no-cache' + reuseNode true + } } stages { - stage('Create Docker') { - agent { - dockerfile { - dir DOCK_FILE_DIR - additionalBuildArgs '--no-cache' - reuseNode true - } - } - // Does not work, but maybe not necessary anyway.. - //when { - // anyOf { - // changeset "${DOCK_FILE_DIR}/Dockerfile"; - // changelog 'cleanDocker' - // } - //} - steps { - sh 'rm -rf $BUILDDIR' - } - } stage('Clean') { - agent { - dockerfile { - dir DOCK_FILE_DIR - reuseNode true - } - } - when { - anyOf { - changelog 'cleanCI' - changeset '*.cmake' - changeset 'CMakeLists.txt' - } - } steps { sh 'rm -rf $BUILDDIR' } } stage('Configure') { - agent { - dockerfile { - dir DOCK_FILE_DIR - reuseNode true - } - } steps { dir(BUILDDIR) { sh 'cmake -DFSFW_OSAL=host -DFSFW_BUILD_UNITTESTS=ON ..' @@ -56,12 +24,6 @@ pipeline { } } stage('Build') { - agent { - dockerfile { - dir DOCK_FILE_DIR - reuseNode true - } - } steps { dir(BUILDDIR) { sh 'cmake --build . -j' @@ -69,12 +31,6 @@ pipeline { } } stage('Unittests') { - agent { - dockerfile { - dir DOCK_FILE_DIR - reuseNode true - } - } steps { dir(BUILDDIR) { sh 'cmake --build . -- fsfw-tests_coverage -j' @@ -82,12 +38,6 @@ pipeline { } } stage('Valgrind') { - agent { - dockerfile { - dir DOCK_FILE_DIR - reuseNode true - } - } steps { dir(BUILDDIR) { sh 'valgrind --leak-check=full --error-exitcode=1 ./fsfw-tests' From 5b968f7e5adcb173a229f20e984c4120b86b7382 Mon Sep 17 00:00:00 2001 From: Ulrich Mohr Date: Mon, 31 Jan 2022 15:01:45 +0100 Subject: [PATCH 17/56] Can't use env variables in top leve agent section --- automation/Jenkinsfile | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/automation/Jenkinsfile b/automation/Jenkinsfile index 0d62538e..af4ad6a5 100644 --- a/automation/Jenkinsfile +++ b/automation/Jenkinsfile @@ -1,11 +1,10 @@ pipeline { environment { - DOCK_FILE_DIR = 'automation' - BUILDDIR = 'build-tests' + BUILDDIR = 'build-tests' } agent { dockerfile { - dir DOCK_FILE_DIR + dir 'automation' additionalBuildArgs '--no-cache' reuseNode true } From 1ead156c645c89cdea104268f34e8d7c291a66d1 Mon Sep 17 00:00:00 2001 From: Ulrich Mohr Date: Mon, 31 Jan 2022 15:08:52 +0100 Subject: [PATCH 18/56] added --pull to the docker build --- automation/Jenkinsfile | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/automation/Jenkinsfile b/automation/Jenkinsfile index af4ad6a5..09ac9649 100644 --- a/automation/Jenkinsfile +++ b/automation/Jenkinsfile @@ -5,7 +5,9 @@ pipeline { agent { dockerfile { dir 'automation' - additionalBuildArgs '--no-cache' + #force docker to redownload base image and rebuild all steps instead of caching them + #this way, we always get an up to date docker image one each build + additionalBuildArgs '--no-cache --pull' reuseNode true } } From 8a39971a1c3b86b607814a3fe5738d7357ace588 Mon Sep 17 00:00:00 2001 From: Ulrich Mohr Date: Mon, 31 Jan 2022 15:11:37 +0100 Subject: [PATCH 19/56] oops, wrong language --- automation/Jenkinsfile | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/automation/Jenkinsfile b/automation/Jenkinsfile index 09ac9649..dae2da2c 100644 --- a/automation/Jenkinsfile +++ b/automation/Jenkinsfile @@ -5,8 +5,8 @@ pipeline { agent { dockerfile { dir 'automation' - #force docker to redownload base image and rebuild all steps instead of caching them - #this way, we always get an up to date docker image one each build + //force docker to redownload base image and rebuild all steps instead of caching them + //this way, we always get an up to date docker image one each build additionalBuildArgs '--no-cache --pull' reuseNode true } From 990e8672a888d6ac718f4edca953c1319766a06f Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 1 Feb 2022 13:47:16 +0100 Subject: [PATCH 20/56] update dockerfile --- automation/Dockerfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/automation/Dockerfile b/automation/Dockerfile index 52e5acfb..a530a671 100644 --- a/automation/Dockerfile +++ b/automation/Dockerfile @@ -5,7 +5,7 @@ RUN apt-get --yes upgrade #tzdata is a dependency, won't install otherwise ARG DEBIAN_FRONTEND=noninteractive -RUN apt-get --yes install gcc g++ cmake make lcov git valgrind nano +RUN apt-get --yes install gcc g++ cmake make lcov git valgrind nano iputils-ping RUN git clone https://github.com/catchorg/Catch2.git && \ cd Catch2 && \ From d2b561ba2f068a80b0239b072fbb8c8919ea9535 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 1 Feb 2022 13:57:27 +0100 Subject: [PATCH 21/56] test --- tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp b/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp index 0c825389..959c3da2 100644 --- a/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp +++ b/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp @@ -59,7 +59,8 @@ TEST_CASE( "Command Executor" , "[cmd-exec]") { REQUIRE(outputBuffer.getAvailableReadData() == 12); uint8_t readBuffer[32]; REQUIRE(outputBuffer.readData(readBuffer, 12) == HasReturnvaluesIF::RETURN_OK); - CHECK(strcmp(reinterpret_cast(readBuffer), "Hello World\n") == 0); + std::string cmpString = "Hello World\n"; + CHECK(strcmp(reinterpret_cast(readBuffer), cmpString.c_str()) == 0); outputBuffer.deleteData(12, true); // Test more complex command result = cmdExecutor.load("ping -c 1 localhost", false, false); From 368481f88bdfb548e21645508a5f206f7777bfdc Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 1 Feb 2022 14:04:13 +0100 Subject: [PATCH 22/56] move strcmp outside of macro --- tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp b/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp index 959c3da2..090d60cb 100644 --- a/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp +++ b/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp @@ -60,7 +60,8 @@ TEST_CASE( "Command Executor" , "[cmd-exec]") { uint8_t readBuffer[32]; REQUIRE(outputBuffer.readData(readBuffer, 12) == HasReturnvaluesIF::RETURN_OK); std::string cmpString = "Hello World\n"; - CHECK(strcmp(reinterpret_cast(readBuffer), cmpString.c_str()) == 0); + int cmpResult = strcmp(reinterpret_cast(readBuffer), cmpString.c_str()); + CHECK(cmpResult == 0); outputBuffer.deleteData(12, true); // Test more complex command result = cmdExecutor.load("ping -c 1 localhost", false, false); From acbc2cd749c4ef1def66f27609c5aa5b544acfbe Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 1 Feb 2022 18:04:08 +0100 Subject: [PATCH 23/56] valgrind why --- tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp b/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp index 090d60cb..a72477f0 100644 --- a/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp +++ b/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp @@ -59,9 +59,11 @@ TEST_CASE( "Command Executor" , "[cmd-exec]") { REQUIRE(outputBuffer.getAvailableReadData() == 12); uint8_t readBuffer[32]; REQUIRE(outputBuffer.readData(readBuffer, 12) == HasReturnvaluesIF::RETURN_OK); + std::string readString(reinterpret_cast(readBuffer)); std::string cmpString = "Hello World\n"; - int cmpResult = strcmp(reinterpret_cast(readBuffer), cmpString.c_str()); - CHECK(cmpResult == 0); + //int cmpResult = strcmp(reinterpret_cast(readBuffer), cmpString.c_str()); + int cmpResult = (readString == cmpString); + CHECK(cmpResult); outputBuffer.deleteData(12, true); // Test more complex command result = cmdExecutor.load("ping -c 1 localhost", false, false); From fed39defd3b23b681d63d5d6405ca7d7f330510d Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 2 Feb 2022 09:56:12 +0100 Subject: [PATCH 24/56] update helper script --- scripts/helper.py | 93 ++++++++++++++++++++++++++++------------------- 1 file changed, 55 insertions(+), 38 deletions(-) diff --git a/scripts/helper.py b/scripts/helper.py index 1234a943..4e8a62b4 100755 --- a/scripts/helper.py +++ b/scripts/helper.py @@ -9,36 +9,44 @@ import webbrowser import shutil import sys import time +from shutil import which from typing import List -UNITTEST_FOLDER_NAME = 'build-tests' -DOCS_FOLDER_NAME = 'build-docs' +UNITTEST_FOLDER_NAME = "build-tests" +DOCS_FOLDER_NAME = "build-docs" def main(): parser = argparse.ArgumentParser(description="FSFW helper script") - choices = ('docs', 'tests') + choices = ("docs", "tests") parser.add_argument( - 'type', metavar='type', choices=choices, - help=f'Target type. Choices: {choices}' + "type", metavar="type", choices=choices, help=f"Target type. Choices: {choices}" ) parser.add_argument( - '-a', '--all', action='store_true', - help='Create, build and open specified type' + "-a", "--all", action="store_true", help="Create, build and open specified type" ) parser.add_argument( - '-c', '--create', action='store_true', - help='Create docs or test build configuration' + "-c", + "--create", + action="store_true", + help="Create docs or test build configuration", ) parser.add_argument( - '-b', '--build', action='store_true', - help='Build the specified type' + "-b", "--build", action="store_true", help="Build the specified type" ) parser.add_argument( - '-o', '--open', action='store_true', - help='Open test or documentation data in webbrowser' + "-o", + "--open", + action="store_true", + help="Open test or documentation data in webbrowser", + ) + parser.add_argument( + "-v", + "--valgrind", + action="store_true", + help="Run valgrind on generated test binary", ) args = parser.parse_args() @@ -46,26 +54,26 @@ def main(): args.build = True args.create = True args.open = True - elif not args.build and not args.create and not args.open: + elif not args.build and not args.create and not args.open and not args.valgrind: print( - 'Please select at least one operation to perform. ' - 'Use helper.py -h for more information' + "Please select at least one operation to perform. " + "Use helper.py -h for more information" ) sys.exit(1) # This script can be called from root and from script folder - if not os.path.isfile('README.md'): - os.chdir('..') + if not os.path.isfile("README.md"): + os.chdir("..") build_dir_list = [] if not args.create: build_dir_list = build_build_dir_list() - if args.type == 'tests': + if args.type == "tests": handle_tests_type(args, build_dir_list) - elif args.type == 'docs': + elif args.type == "docs": handle_docs_type(args, build_dir_list) else: - print('Invalid or unknown type') + print("Invalid or unknown type") sys.exit(1) @@ -76,7 +84,9 @@ def handle_docs_type(args, build_dir_list: list): create_docs_build_cfg() build_directory = DOCS_FOLDER_NAME elif len(build_dir_list) == 0: - print('No valid CMake docs build directory found. Trying to set up docs build system') + print( + "No valid CMake docs build directory found. Trying to set up docs build system" + ) shutil.rmtree(DOCS_FOLDER_NAME) create_docs_build_cfg() build_directory = DOCS_FOLDER_NAME @@ -87,18 +97,18 @@ def handle_docs_type(args, build_dir_list: list): build_directory = determine_build_dir(build_dir_list) os.chdir(build_directory) if args.build: - os.system('cmake --build . -j') + os.system("cmake --build . -j") if args.open: - if not os.path.isfile('docs/sphinx/index.html'): + if not os.path.isfile("docs/sphinx/index.html"): # try again.. - os.system('cmake --build . -j') - if not os.path.isfile('docs/sphinx/index.html'): + os.system("cmake --build . -j") + if not os.path.isfile("docs/sphinx/index.html"): print( "No Sphinx documentation file detected. " "Try to build it first with the -b argument" ) sys.exit(1) - webbrowser.open('docs/sphinx/index.html') + webbrowser.open("docs/sphinx/index.html") def handle_tests_type(args, build_dir_list: list): @@ -109,8 +119,8 @@ def handle_tests_type(args, build_dir_list: list): build_directory = UNITTEST_FOLDER_NAME elif len(build_dir_list) == 0: print( - 'No valid CMake tests build directory found. ' - 'Trying to set up test build system' + "No valid CMake tests build directory found. " + "Trying to set up test build system" ) create_tests_build_cfg() build_directory = UNITTEST_FOLDER_NAME @@ -123,26 +133,33 @@ def handle_tests_type(args, build_dir_list: list): if args.build: perform_lcov_operation(build_directory, False) if args.open: - if not os.path.isdir('fsfw-tests_coverage'): - print("No Unittest folder detected. Try to build them first with the -b argument") + if not os.path.isdir("fsfw-tests_coverage"): + print( + "No Unittest folder detected. Try to build them first with the -b argument" + ) sys.exit(1) - webbrowser.open('fsfw-tests_coverage/index.html') + webbrowser.open("fsfw-tests_coverage/index.html") + if args.valgrind: + if which("valgrind") is None: + print("Please install valgrind first") + sys.exit(1) + os.chdir(UNITTEST_FOLDER_NAME) + os.system("valgrind --leak-check=full ./fsfw-tests") + os.chdir("..") def create_tests_build_cfg(): os.mkdir(UNITTEST_FOLDER_NAME) os.chdir(UNITTEST_FOLDER_NAME) - cmake_cmd = "cmake -DFSFW_OSAL=host -DFSFW_BUILD_UNITTESTS=ON .." - print(f"Executing CMake command {cmake_cmd}") - os.system(cmake_cmd) - os.chdir('..') + os.system("cmake -DFSFW_OSAL=host -DFSFW_BUILD_UNITTESTS=ON ..") + os.chdir("..") def create_docs_build_cfg(): os.mkdir(DOCS_FOLDER_NAME) os.chdir(DOCS_FOLDER_NAME) - os.system('cmake -DFSFW_OSAL=host -DFSFW_BUILD_DOCS=ON ..') - os.chdir('..') + os.system("cmake -DFSFW_OSAL=host -DFSFW_BUILD_DOCS=ON ..") + os.chdir("..") def build_build_dir_list() -> list: From e0c50477cbc0dfb7f861cfb55444de6c5cf1d5df Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 2 Feb 2022 10:00:57 +0100 Subject: [PATCH 25/56] it actually was an uninitialized array --- tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp b/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp index a72477f0..d7e55af5 100644 --- a/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp +++ b/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp @@ -57,13 +57,11 @@ TEST_CASE( "Command Executor" , "[cmd-exec]") { sizesFifo.retrieve(&readBytes); REQUIRE(readBytes == 12); REQUIRE(outputBuffer.getAvailableReadData() == 12); - uint8_t readBuffer[32]; + uint8_t readBuffer[32] = {}; REQUIRE(outputBuffer.readData(readBuffer, 12) == HasReturnvaluesIF::RETURN_OK); std::string readString(reinterpret_cast(readBuffer)); std::string cmpString = "Hello World\n"; - //int cmpResult = strcmp(reinterpret_cast(readBuffer), cmpString.c_str()); - int cmpResult = (readString == cmpString); - CHECK(cmpResult); + CHECK(readString == cmpString); outputBuffer.deleteData(12, true); // Test more complex command result = cmdExecutor.load("ping -c 1 localhost", false, false); From ddcac2bbac73bbf4df76754c84136dcb4d35c075 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 2 Feb 2022 10:29:30 +0100 Subject: [PATCH 26/56] reapply clang format --- hal/src/fsfw_hal/common/gpio/GpioCookie.cpp | 70 +- hal/src/fsfw_hal/common/gpio/GpioCookie.h | 35 +- hal/src/fsfw_hal/common/gpio/GpioIF.h | 68 +- .../fsfw_hal/common/gpio/gpioDefinitions.h | 181 +- hal/src/fsfw_hal/common/spi/spiCommon.h | 7 +- .../devicehandlers/GyroL3GD20Handler.cpp | 405 ++- .../devicehandlers/GyroL3GD20Handler.h | 123 +- .../devicehandlers/MgmLIS3MDLHandler.cpp | 692 +++-- .../devicehandlers/MgmLIS3MDLHandler.h | 275 +- .../devicehandlers/MgmRM3100Handler.cpp | 543 ++-- .../devicehandlers/MgmRM3100Handler.h | 146 +- .../devicedefinitions/GyroL3GD20Definitions.h | 62 +- .../devicedefinitions/MgmLIS3HandlerDefs.h | 99 +- .../devicedefinitions/MgmRM3100HandlerDefs.h | 96 +- hal/src/fsfw_hal/linux/CommandExecutor.cpp | 330 ++- hal/src/fsfw_hal/linux/CommandExecutor.h | 194 +- hal/src/fsfw_hal/linux/UnixFileGuard.cpp | 41 +- hal/src/fsfw_hal/linux/UnixFileGuard.h | 33 +- .../fsfw_hal/linux/gpio/LinuxLibgpioIF.cpp | 666 ++--- hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h | 115 +- hal/src/fsfw_hal/linux/i2c/I2cComIF.cpp | 336 ++- hal/src/fsfw_hal/linux/i2c/I2cComIF.h | 68 +- hal/src/fsfw_hal/linux/i2c/I2cCookie.cpp | 18 +- hal/src/fsfw_hal/linux/i2c/I2cCookie.h | 40 +- hal/src/fsfw_hal/linux/rpi/GpioRPi.cpp | 46 +- hal/src/fsfw_hal/linux/rpi/GpioRPi.h | 5 +- hal/src/fsfw_hal/linux/spi/SpiComIF.cpp | 570 ++-- hal/src/fsfw_hal/linux/spi/SpiComIF.h | 115 +- hal/src/fsfw_hal/linux/spi/SpiCookie.cpp | 161 +- hal/src/fsfw_hal/linux/spi/SpiCookie.h | 273 +- hal/src/fsfw_hal/linux/spi/spiDefinitions.h | 21 +- hal/src/fsfw_hal/linux/uart/UartComIF.cpp | 852 +++--- hal/src/fsfw_hal/linux/uart/UartComIF.h | 168 +- hal/src/fsfw_hal/linux/uart/UartCookie.cpp | 94 +- hal/src/fsfw_hal/linux/uart/UartCookie.h | 168 +- hal/src/fsfw_hal/linux/utility.cpp | 25 +- hal/src/fsfw_hal/stm32h7/definitions.h | 15 +- .../stm32h7/devicetest/GyroL3GD20H.cpp | 840 +++--- .../fsfw_hal/stm32h7/devicetest/GyroL3GD20H.h | 87 +- hal/src/fsfw_hal/stm32h7/dma.cpp | 95 +- hal/src/fsfw_hal/stm32h7/dma.h | 37 +- hal/src/fsfw_hal/stm32h7/gpio/gpio.cpp | 66 +- hal/src/fsfw_hal/stm32h7/interrupts.h | 8 +- hal/src/fsfw_hal/stm32h7/spi/SpiComIF.cpp | 648 +++-- hal/src/fsfw_hal/stm32h7/spi/SpiComIF.h | 165 +- hal/src/fsfw_hal/stm32h7/spi/SpiCookie.cpp | 96 +- hal/src/fsfw_hal/stm32h7/spi/SpiCookie.h | 114 +- hal/src/fsfw_hal/stm32h7/spi/mspInit.cpp | 311 +-- hal/src/fsfw_hal/stm32h7/spi/mspInit.h | 129 +- hal/src/fsfw_hal/stm32h7/spi/spiCore.cpp | 434 ++- hal/src/fsfw_hal/stm32h7/spi/spiCore.h | 14 +- .../fsfw_hal/stm32h7/spi/spiDefinitions.cpp | 70 +- hal/src/fsfw_hal/stm32h7/spi/spiDefinitions.h | 26 +- .../fsfw_hal/stm32h7/spi/spiInterrupts.cpp | 111 +- hal/src/fsfw_hal/stm32h7/spi/spiInterrupts.h | 8 +- hal/src/fsfw_hal/stm32h7/spi/stm32h743zi.cpp | 125 +- hal/src/fsfw_hal/stm32h7/spi/stm32h743zi.h | 14 +- src/fsfw/action.h | 2 +- src/fsfw/action/ActionHelper.cpp | 268 +- src/fsfw/action/ActionHelper.h | 206 +- src/fsfw/action/ActionMessage.cpp | 88 +- src/fsfw/action/ActionMessage.h | 47 +- src/fsfw/action/CommandActionHelper.cpp | 192 +- src/fsfw/action/CommandActionHelper.h | 42 +- src/fsfw/action/CommandsActionsIF.h | 36 +- src/fsfw/action/HasActionsIF.h | 51 +- src/fsfw/action/SimpleActionHelper.cpp | 99 +- src/fsfw/action/SimpleActionHelper.h | 33 +- src/fsfw/cfdp/CFDPHandler.cpp | 59 +- src/fsfw/cfdp/CFDPHandler.h | 85 +- src/fsfw/cfdp/CFDPMessage.cpp | 20 +- src/fsfw/cfdp/CFDPMessage.h | 18 +- src/fsfw/cfdp/FileSize.h | 115 +- src/fsfw/cfdp/definitions.h | 180 +- src/fsfw/cfdp/pdu/AckInfo.cpp | 55 +- src/fsfw/cfdp/pdu/AckInfo.h | 36 +- src/fsfw/cfdp/pdu/AckPduDeserializer.cpp | 57 +- src/fsfw/cfdp/pdu/AckPduDeserializer.h | 29 +- src/fsfw/cfdp/pdu/AckPduSerializer.cpp | 58 +- src/fsfw/cfdp/pdu/AckPduSerializer.h | 34 +- src/fsfw/cfdp/pdu/EofInfo.cpp | 67 +- src/fsfw/cfdp/pdu/EofInfo.h | 40 +- src/fsfw/cfdp/pdu/EofPduDeserializer.cpp | 107 +- src/fsfw/cfdp/pdu/EofPduDeserializer.h | 17 +- src/fsfw/cfdp/pdu/EofPduSerializer.cpp | 70 +- src/fsfw/cfdp/pdu/EofPduSerializer.h | 21 +- src/fsfw/cfdp/pdu/FileDataDeserializer.cpp | 78 +- src/fsfw/cfdp/pdu/FileDataDeserializer.h | 21 +- src/fsfw/cfdp/pdu/FileDataInfo.cpp | 119 +- src/fsfw/cfdp/pdu/FileDataInfo.h | 61 +- src/fsfw/cfdp/pdu/FileDataSerializer.cpp | 85 +- src/fsfw/cfdp/pdu/FileDataSerializer.h | 20 +- .../cfdp/pdu/FileDirectiveDeserializer.cpp | 66 +- src/fsfw/cfdp/pdu/FileDirectiveDeserializer.h | 38 +- src/fsfw/cfdp/pdu/FileDirectiveSerializer.cpp | 51 +- src/fsfw/cfdp/pdu/FileDirectiveSerializer.h | 32 +- src/fsfw/cfdp/pdu/FinishedInfo.cpp | 133 +- src/fsfw/cfdp/pdu/FinishedInfo.h | 60 +- src/fsfw/cfdp/pdu/FinishedPduDeserializer.cpp | 164 +- src/fsfw/cfdp/pdu/FinishedPduDeserializer.h | 21 +- src/fsfw/cfdp/pdu/FinishedPduSerializer.cpp | 68 +- src/fsfw/cfdp/pdu/FinishedPduSerializer.h | 23 +- src/fsfw/cfdp/pdu/HeaderDeserializer.cpp | 146 +- src/fsfw/cfdp/pdu/HeaderDeserializer.h | 125 +- src/fsfw/cfdp/pdu/HeaderSerializer.cpp | 156 +- src/fsfw/cfdp/pdu/HeaderSerializer.h | 91 +- .../cfdp/pdu/KeepAlivePduDeserializer.cpp | 26 +- src/fsfw/cfdp/pdu/KeepAlivePduDeserializer.h | 15 +- src/fsfw/cfdp/pdu/KeepAlivePduSerializer.cpp | 28 +- src/fsfw/cfdp/pdu/KeepAlivePduSerializer.h | 19 +- src/fsfw/cfdp/pdu/MetadataInfo.cpp | 143 +- src/fsfw/cfdp/pdu/MetadataInfo.h | 64 +- src/fsfw/cfdp/pdu/MetadataPduDeserializer.cpp | 104 +- src/fsfw/cfdp/pdu/MetadataPduDeserializer.h | 15 +- src/fsfw/cfdp/pdu/MetadataPduSerializer.cpp | 82 +- src/fsfw/cfdp/pdu/MetadataPduSerializer.h | 23 +- src/fsfw/cfdp/pdu/NakInfo.cpp | 109 +- src/fsfw/cfdp/pdu/NakInfo.h | 49 +- src/fsfw/cfdp/pdu/NakPduDeserializer.cpp | 102 +- src/fsfw/cfdp/pdu/NakPduDeserializer.h | 23 +- src/fsfw/cfdp/pdu/NakPduSerializer.cpp | 70 +- src/fsfw/cfdp/pdu/NakPduSerializer.h | 53 +- src/fsfw/cfdp/pdu/PduConfig.cpp | 14 +- src/fsfw/cfdp/pdu/PduConfig.h | 40 +- src/fsfw/cfdp/pdu/PduHeaderIF.h | 44 +- src/fsfw/cfdp/pdu/PromptPduDeserializer.cpp | 27 +- src/fsfw/cfdp/pdu/PromptPduDeserializer.h | 17 +- src/fsfw/cfdp/pdu/PromptPduSerializer.cpp | 33 +- src/fsfw/cfdp/pdu/PromptPduSerializer.h | 17 +- src/fsfw/cfdp/pdu/VarLenField.cpp | 159 +- src/fsfw/cfdp/pdu/VarLenField.h | 54 +- src/fsfw/cfdp/tlv/EntityIdTlv.cpp | 89 +- src/fsfw/cfdp/tlv/EntityIdTlv.h | 49 +- src/fsfw/cfdp/tlv/FaultHandlerOverrideTlv.cpp | 92 +- src/fsfw/cfdp/tlv/FaultHandlerOverrideTlv.h | 39 +- src/fsfw/cfdp/tlv/FilestoreRequestTlv.cpp | 110 +- src/fsfw/cfdp/tlv/FilestoreRequestTlv.h | 53 +- src/fsfw/cfdp/tlv/FilestoreResponseTlv.cpp | 179 +- src/fsfw/cfdp/tlv/FilestoreResponseTlv.h | 62 +- src/fsfw/cfdp/tlv/FilestoreTlvBase.h | 213 +- src/fsfw/cfdp/tlv/FlowLabelTlv.cpp | 5 +- src/fsfw/cfdp/tlv/FlowLabelTlv.h | 8 +- src/fsfw/cfdp/tlv/Lv.cpp | 137 +- src/fsfw/cfdp/tlv/Lv.h | 62 +- src/fsfw/cfdp/tlv/MessageToUserTlv.cpp | 8 +- src/fsfw/cfdp/tlv/MessageToUserTlv.h | 11 +- src/fsfw/cfdp/tlv/Tlv.cpp | 158 +- src/fsfw/cfdp/tlv/Tlv.h | 80 +- src/fsfw/cfdp/tlv/TlvIF.h | 12 +- src/fsfw/container/ArrayList.h | 391 ++- src/fsfw/container/BinaryTree.h | 222 +- src/fsfw/container/DynamicFIFO.h | 70 +- src/fsfw/container/FIFO.h | 53 +- src/fsfw/container/FIFOBase.h | 119 +- src/fsfw/container/FixedArrayList.h | 46 +- src/fsfw/container/FixedMap.h | 383 ++- src/fsfw/container/FixedOrderedMultimap.h | 306 +- src/fsfw/container/HybridIterator.h | 120 +- src/fsfw/container/IndexedRingMemoryArray.h | 1241 ++++----- src/fsfw/container/PlacementFactory.h | 89 +- src/fsfw/container/RingBufferBase.h | 140 +- src/fsfw/container/SharedRingBuffer.cpp | 69 +- src/fsfw/container/SharedRingBuffer.h | 134 +- src/fsfw/container/SimpleRingBuffer.cpp | 199 +- src/fsfw/container/SimpleRingBuffer.h | 208 +- src/fsfw/container/SinglyLinkedList.h | 200 +- src/fsfw/container/group.h | 1 - src/fsfw/controller/ControllerBase.cpp | 172 +- src/fsfw/controller/ControllerBase.h | 112 +- .../controller/ExtendedControllerBase.cpp | 141 +- src/fsfw/controller/ExtendedControllerBase.h | 87 +- .../coordinates/CoordinateTransformations.cpp | 301 +- .../coordinates/CoordinateTransformations.h | 42 +- src/fsfw/coordinates/Jgm3Model.h | 300 +- src/fsfw/coordinates/Sgp4Propagator.cpp | 391 ++- src/fsfw/coordinates/Sgp4Propagator.h | 57 +- src/fsfw/datalinklayer/BCFrame.h | 84 +- src/fsfw/datalinklayer/CCSDSReturnValuesIF.h | 91 +- src/fsfw/datalinklayer/Clcw.cpp | 38 +- src/fsfw/datalinklayer/Clcw.h | 104 +- src/fsfw/datalinklayer/ClcwIF.h | 99 +- src/fsfw/datalinklayer/DataLinkLayer.cpp | 208 +- src/fsfw/datalinklayer/DataLinkLayer.h | 210 +- src/fsfw/datalinklayer/Farm1StateIF.h | 60 +- src/fsfw/datalinklayer/Farm1StateLockout.cpp | 30 +- src/fsfw/datalinklayer/Farm1StateLockout.h | 76 +- src/fsfw/datalinklayer/Farm1StateOpen.cpp | 59 +- src/fsfw/datalinklayer/Farm1StateOpen.h | 82 +- src/fsfw/datalinklayer/Farm1StateWait.cpp | 44 +- src/fsfw/datalinklayer/Farm1StateWait.h | 76 +- .../datalinklayer/MapPacketExtraction.cpp | 235 +- src/fsfw/datalinklayer/MapPacketExtraction.h | 112 +- .../datalinklayer/MapPacketExtractionIF.h | 51 +- src/fsfw/datalinklayer/TcTransferFrame.cpp | 92 +- src/fsfw/datalinklayer/TcTransferFrame.h | 247 +- .../datalinklayer/TcTransferFrameLocal.cpp | 78 +- src/fsfw/datalinklayer/TcTransferFrameLocal.h | 59 +- .../datalinklayer/VirtualChannelReception.cpp | 174 +- .../datalinklayer/VirtualChannelReception.h | 175 +- .../datalinklayer/VirtualChannelReceptionIF.h | 66 +- src/fsfw/datapool/DataSetIF.h | 40 +- src/fsfw/datapool/HkSwitchHelper.cpp | 90 +- src/fsfw/datapool/HkSwitchHelper.h | 56 +- src/fsfw/datapool/PoolDataSetBase.cpp | 326 ++- src/fsfw/datapool/PoolDataSetBase.h | 262 +- src/fsfw/datapool/PoolDataSetIF.h | 40 +- src/fsfw/datapool/PoolEntry.cpp | 88 +- src/fsfw/datapool/PoolEntry.h | 204 +- src/fsfw/datapool/PoolEntryIF.h | 82 +- src/fsfw/datapool/PoolReadGuard.h | 76 +- src/fsfw/datapool/PoolVarList.h | 35 +- src/fsfw/datapool/PoolVariableIF.h | 74 +- src/fsfw/datapool/ReadCommitIF.h | 29 +- src/fsfw/datapool/ReadCommitIFAttorney.h | 26 +- src/fsfw/datapool/SharedDataSetIF.h | 12 +- src/fsfw/datapoollocal.h | 4 +- src/fsfw/datapoollocal/AccessLocalPoolF.h | 21 +- src/fsfw/datapoollocal/HasLocalDataPoolIF.h | 259 +- .../datapoollocal/LocalDataPoolManager.cpp | 1483 +++++----- src/fsfw/datapoollocal/LocalDataPoolManager.h | 631 +++-- src/fsfw/datapoollocal/LocalDataSet.cpp | 22 +- src/fsfw/datapoollocal/LocalDataSet.h | 25 +- .../datapoollocal/LocalPoolDataSetBase.cpp | 462 ++-- src/fsfw/datapoollocal/LocalPoolDataSetBase.h | 342 ++- .../datapoollocal/LocalPoolObjectBase.cpp | 184 +- src/fsfw/datapoollocal/LocalPoolObjectBase.h | 83 +- src/fsfw/datapoollocal/LocalPoolVariable.h | 292 +- src/fsfw/datapoollocal/LocalPoolVector.h | 267 +- src/fsfw/datapoollocal/MarkChangedIF.h | 10 +- .../ProvidesDataPoolSubscriptionIF.h | 121 +- src/fsfw/datapoollocal/SharedLocalDataSet.cpp | 46 +- src/fsfw/datapoollocal/SharedLocalDataSet.h | 35 +- src/fsfw/datapoollocal/StaticLocalDataSet.h | 52 +- .../internal/HasLocalDpIFManagerAttorney.cpp | 15 +- .../internal/HasLocalDpIFManagerAttorney.h | 11 +- .../internal/HasLocalDpIFUserAttorney.cpp | 5 +- .../internal/HasLocalDpIFUserAttorney.h | 11 +- .../internal/LocalDpManagerAttorney.h | 21 +- .../internal/LocalPoolDataSetAttorney.h | 42 +- src/fsfw/datapoollocal/localPoolDefinitions.h | 92 +- .../devicehandlers/AcceptsDeviceResponsesIF.h | 12 +- src/fsfw/devicehandlers/AssemblyBase.cpp | 417 ++- src/fsfw/devicehandlers/AssemblyBase.h | 223 +- src/fsfw/devicehandlers/ChildHandlerBase.cpp | 61 +- src/fsfw/devicehandlers/ChildHandlerBase.h | 27 +- src/fsfw/devicehandlers/ChildHandlerFDIR.cpp | 12 +- src/fsfw/devicehandlers/ChildHandlerFDIR.h | 15 +- src/fsfw/devicehandlers/CookieIF.h | 4 +- .../devicehandlers/DeviceCommunicationIF.h | 162 +- src/fsfw/devicehandlers/DeviceHandlerBase.cpp | 2392 ++++++++-------- src/fsfw/devicehandlers/DeviceHandlerBase.h | 2456 ++++++++--------- .../DeviceHandlerFailureIsolation.cpp | 419 ++- .../DeviceHandlerFailureIsolation.h | 79 +- src/fsfw/devicehandlers/DeviceHandlerIF.h | 287 +- .../devicehandlers/DeviceHandlerMessage.cpp | 119 +- .../devicehandlers/DeviceHandlerMessage.h | 91 +- .../devicehandlers/DeviceHandlerThermalSet.h | 55 +- .../DeviceTmReportingWrapper.cpp | 63 +- .../devicehandlers/DeviceTmReportingWrapper.h | 28 +- src/fsfw/devicehandlers/HealthDevice.cpp | 71 +- src/fsfw/devicehandlers/HealthDevice.h | 39 +- src/fsfw/events/Event.h | 27 +- src/fsfw/events/EventManager.cpp | 277 +- src/fsfw/events/EventManager.h | 90 +- src/fsfw/events/EventManagerIF.h | 98 +- src/fsfw/events/EventMessage.cpp | 116 +- src/fsfw/events/EventMessage.h | 68 +- src/fsfw/events/EventReportingProxyIF.h | 13 +- .../eventmatching/EventIdRangeMatcher.cpp | 10 +- .../eventmatching/EventIdRangeMatcher.h | 10 +- .../events/eventmatching/EventMatchTree.cpp | 254 +- .../events/eventmatching/EventMatchTree.h | 44 +- .../eventmatching/EventRangeMatcherBase.h | 35 +- .../eventmatching/ReporterRangeMatcher.cpp | 11 +- .../eventmatching/ReporterRangeMatcher.h | 10 +- .../eventmatching/SeverityRangeMatcher.cpp | 12 +- .../eventmatching/SeverityRangeMatcher.h | 10 +- src/fsfw/events/eventmatching/eventmatching.h | 1 - src/fsfw/events/fwSubsystemIdRanges.h | 56 +- src/fsfw/fdir/ConfirmsFailuresIF.h | 18 +- src/fsfw/fdir/EventCorrelation.cpp | 60 +- src/fsfw/fdir/EventCorrelation.h | 25 +- src/fsfw/fdir/FailureIsolationBase.cpp | 246 +- src/fsfw/fdir/FailureIsolationBase.h | 87 +- src/fsfw/fdir/FaultCounter.cpp | 109 +- src/fsfw/fdir/FaultCounter.h | 45 +- src/fsfw/globalfunctions/AsciiConverter.cpp | 383 ++- src/fsfw/globalfunctions/AsciiConverter.h | 43 +- src/fsfw/globalfunctions/CRC.cpp | 245 +- src/fsfw/globalfunctions/CRC.h | 12 +- src/fsfw/globalfunctions/DleEncoder.cpp | 496 ++-- src/fsfw/globalfunctions/DleEncoder.h | 148 +- .../PeriodicOperationDivider.cpp | 46 +- .../PeriodicOperationDivider.h | 82 +- src/fsfw/globalfunctions/Type.cpp | 283 +- src/fsfw/globalfunctions/Type.h | 112 +- src/fsfw/globalfunctions/arrayprinter.cpp | 187 +- src/fsfw/globalfunctions/arrayprinter.h | 14 +- src/fsfw/globalfunctions/bitutility.cpp | 44 +- src/fsfw/globalfunctions/bitutility.h | 2 +- src/fsfw/globalfunctions/constants.h | 2 +- .../globalfunctions/matching/BinaryMatcher.h | 54 +- .../globalfunctions/matching/DecimalMatcher.h | 71 +- src/fsfw/globalfunctions/matching/MatchTree.h | 378 ++- src/fsfw/globalfunctions/matching/MatcherIF.h | 12 +- .../globalfunctions/matching/RangeMatcher.h | 106 +- .../matching/SerializeableMatcherIF.h | 8 +- .../globalfunctions/math/MatrixOperations.h | 185 +- .../math/QuaternionOperations.cpp | 202 +- .../math/QuaternionOperations.h | 91 +- .../globalfunctions/math/VectorOperations.h | 151 +- src/fsfw/globalfunctions/sign.h | 5 +- .../globalfunctions/timevalOperations.cpp | 106 +- src/fsfw/globalfunctions/timevalOperations.h | 4 +- src/fsfw/health/HasHealthIF.h | 76 +- src/fsfw/health/HealthHelper.cpp | 147 +- src/fsfw/health/HealthHelper.h | 177 +- src/fsfw/health/HealthMessage.cpp | 29 +- src/fsfw/health/HealthMessage.h | 38 +- src/fsfw/health/HealthTable.cpp | 150 +- src/fsfw/health/HealthTable.h | 56 +- src/fsfw/health/HealthTableIF.h | 29 +- src/fsfw/health/ManagesHealthIF.h | 67 +- src/fsfw/housekeeping/AcceptsHkPacketsIF.h | 6 +- src/fsfw/housekeeping/HousekeepingMessage.cpp | 321 ++- src/fsfw/housekeeping/HousekeepingMessage.h | 180 +- .../housekeeping/HousekeepingPacketDownlink.h | 30 +- src/fsfw/housekeeping/HousekeepingSetPacket.h | 91 +- src/fsfw/housekeeping/HousekeepingSnapshot.h | 178 +- .../PeriodicHousekeepingHelper.cpp | 125 +- .../housekeeping/PeriodicHousekeepingHelper.h | 34 +- src/fsfw/internalerror/InternalErrorDataset.h | 40 +- .../internalerror/InternalErrorReporter.cpp | 240 +- .../internalerror/InternalErrorReporter.h | 114 +- .../internalerror/InternalErrorReporterIF.h | 31 +- src/fsfw/ipc/CommandMessage.cpp | 108 +- src/fsfw/ipc/CommandMessage.h | 187 +- src/fsfw/ipc/CommandMessageCleaner.cpp | 84 +- src/fsfw/ipc/CommandMessageCleaner.h | 7 +- src/fsfw/ipc/CommandMessageIF.h | 109 +- src/fsfw/ipc/FwMessageTypes.h | 32 +- src/fsfw/ipc/MessageQueueIF.h | 292 +- src/fsfw/ipc/MessageQueueMessage.cpp | 98 +- src/fsfw/ipc/MessageQueueMessage.h | 239 +- src/fsfw/ipc/MessageQueueMessageIF.h | 121 +- src/fsfw/ipc/MessageQueueSenderIF.h | 26 +- src/fsfw/ipc/MutexFactory.h | 34 +- src/fsfw/ipc/MutexGuard.h | 63 +- src/fsfw/ipc/MutexIF.h | 140 +- src/fsfw/ipc/QueueFactory.h | 39 +- src/fsfw/memory/AcceptsMemoryMessagesIF.h | 7 +- src/fsfw/memory/FileSystemArgsIF.h | 4 +- src/fsfw/memory/GenericFileSystemMessage.cpp | 212 +- src/fsfw/memory/GenericFileSystemMessage.h | 156 +- src/fsfw/memory/HasFileSystemIF.h | 173 +- src/fsfw/memory/HasMemoryIF.h | 79 +- src/fsfw/memory/MemoryHelper.cpp | 320 ++- src/fsfw/memory/MemoryHelper.h | 62 +- src/fsfw/memory/MemoryMessage.cpp | 124 +- src/fsfw/memory/MemoryMessage.h | 63 +- src/fsfw/modes/HasModesIF.h | 83 +- src/fsfw/modes/ModeHelper.cpp | 187 +- src/fsfw/modes/ModeHelper.h | 56 +- src/fsfw/modes/ModeMessage.cpp | 31 +- src/fsfw/modes/ModeMessage.h | 58 +- src/fsfw/monitoring/AbsLimitMonitor.h | 143 +- src/fsfw/monitoring/HasMonitorsIF.h | 29 +- src/fsfw/monitoring/LimitMonitor.h | 158 +- .../monitoring/LimitViolationReporter.cpp | 79 +- src/fsfw/monitoring/LimitViolationReporter.h | 26 +- src/fsfw/monitoring/MonitorBase.h | 97 +- src/fsfw/monitoring/MonitorReporter.h | 304 +- src/fsfw/monitoring/MonitoringIF.h | 100 +- src/fsfw/monitoring/MonitoringMessage.cpp | 51 +- src/fsfw/monitoring/MonitoringMessage.h | 25 +- .../monitoring/MonitoringMessageContent.h | 139 +- .../monitoring/ReceivesMonitoringReportsIF.h | 11 +- src/fsfw/monitoring/TriplexMonitor.h | 273 +- src/fsfw/monitoring/TwoValueLimitMonitor.h | 72 +- src/fsfw/objectmanager/ObjectManager.cpp | 181 +- src/fsfw/objectmanager/ObjectManager.h | 88 +- src/fsfw/objectmanager/ObjectManagerIF.h | 95 +- src/fsfw/objectmanager/SystemObject.cpp | 42 +- src/fsfw/objectmanager/SystemObject.h | 66 +- src/fsfw/objectmanager/SystemObjectIF.h | 65 +- src/fsfw/objectmanager/frameworkObjects.h | 56 +- src/fsfw/osal/Endiness.h | 11 +- src/fsfw/osal/InternalErrorCodes.h | 55 +- src/fsfw/osal/common/TcpIpBase.cpp | 40 +- src/fsfw/osal/common/TcpIpBase.h | 39 +- src/fsfw/osal/common/TcpTmTcBridge.cpp | 76 +- src/fsfw/osal/common/TcpTmTcBridge.h | 64 +- src/fsfw/osal/common/TcpTmTcServer.cpp | 601 ++-- src/fsfw/osal/common/TcpTmTcServer.h | 173 +- src/fsfw/osal/common/UdpTcPollingTask.cpp | 206 +- src/fsfw/osal/common/UdpTcPollingTask.h | 74 +- src/fsfw/osal/common/UdpTmTcBridge.cpp | 194 +- src/fsfw/osal/common/UdpTmTcBridge.h | 56 +- src/fsfw/osal/common/tcpipCommon.cpp | 125 +- src/fsfw/osal/common/tcpipCommon.h | 36 +- src/fsfw/osal/common/tcpipHelpers.h | 2 - src/fsfw/osal/freertos/BinSemaphUsingTask.cpp | 133 +- src/fsfw/osal/freertos/BinSemaphUsingTask.h | 120 +- src/fsfw/osal/freertos/BinarySemaphore.cpp | 150 +- src/fsfw/osal/freertos/BinarySemaphore.h | 142 +- src/fsfw/osal/freertos/Clock.cpp | 145 +- .../osal/freertos/CountingSemaphUsingTask.cpp | 164 +- .../osal/freertos/CountingSemaphUsingTask.h | 148 +- src/fsfw/osal/freertos/CountingSemaphore.cpp | 58 +- src/fsfw/osal/freertos/CountingSemaphore.h | 37 +- src/fsfw/osal/freertos/FixedTimeslotTask.cpp | 193 +- src/fsfw/osal/freertos/FixedTimeslotTask.h | 147 +- src/fsfw/osal/freertos/FreeRTOSTaskIF.h | 54 +- src/fsfw/osal/freertos/MessageQueue.cpp | 196 +- src/fsfw/osal/freertos/MessageQueue.h | 188 +- src/fsfw/osal/freertos/Mutex.cpp | 69 +- src/fsfw/osal/freertos/Mutex.h | 18 +- src/fsfw/osal/freertos/MutexFactory.cpp | 31 +- src/fsfw/osal/freertos/PeriodicTask.cpp | 163 +- src/fsfw/osal/freertos/PeriodicTask.h | 194 +- src/fsfw/osal/freertos/QueueFactory.cpp | 40 +- src/fsfw/osal/freertos/QueueMapManager.cpp | 79 +- src/fsfw/osal/freertos/QueueMapManager.h | 62 +- src/fsfw/osal/freertos/SemaphoreFactory.cpp | 76 +- src/fsfw/osal/freertos/TaskFactory.cpp | 61 +- src/fsfw/osal/freertos/TaskManagement.cpp | 31 +- src/fsfw/osal/freertos/TaskManagement.h | 12 +- src/fsfw/osal/freertos/Timekeeper.cpp | 38 +- src/fsfw/osal/freertos/Timekeeper.h | 33 +- src/fsfw/osal/host/Clock.cpp | 196 +- src/fsfw/osal/host/FixedTimeslotTask.cpp | 253 +- src/fsfw/osal/host/FixedTimeslotTask.h | 193 +- src/fsfw/osal/host/MessageQueue.cpp | 198 +- src/fsfw/osal/host/MessageQueue.h | 364 +-- src/fsfw/osal/host/Mutex.cpp | 39 +- src/fsfw/osal/host/Mutex.h | 21 +- src/fsfw/osal/host/MutexFactory.cpp | 33 +- src/fsfw/osal/host/PeriodicTask.cpp | 219 +- src/fsfw/osal/host/PeriodicTask.h | 191 +- src/fsfw/osal/host/QueueFactory.cpp | 55 +- src/fsfw/osal/host/QueueMapManager.cpp | 89 +- src/fsfw/osal/host/QueueMapManager.h | 61 +- src/fsfw/osal/host/SemaphoreFactory.cpp | 42 +- src/fsfw/osal/host/TaskFactory.cpp | 68 +- src/fsfw/osal/host/taskHelpers.cpp | 29 +- src/fsfw/osal/host/taskHelpers.h | 5 +- src/fsfw/osal/linux/BinarySemaphore.cpp | 240 +- src/fsfw/osal/linux/BinarySemaphore.h | 108 +- src/fsfw/osal/linux/Clock.cpp | 193 +- src/fsfw/osal/linux/CountingSemaphore.cpp | 88 +- src/fsfw/osal/linux/CountingSemaphore.h | 41 +- src/fsfw/osal/linux/FixedTimeslotTask.cpp | 125 +- src/fsfw/osal/linux/FixedTimeslotTask.h | 117 +- src/fsfw/osal/linux/InternalErrorCodes.cpp | 12 +- src/fsfw/osal/linux/MessageQueue.cpp | 635 +++-- src/fsfw/osal/linux/MessageQueue.h | 312 ++- src/fsfw/osal/linux/Mutex.cpp | 180 +- src/fsfw/osal/linux/Mutex.h | 20 +- src/fsfw/osal/linux/MutexFactory.cpp | 24 +- src/fsfw/osal/linux/PeriodicPosixTask.cpp | 105 +- src/fsfw/osal/linux/PeriodicPosixTask.h | 150 +- src/fsfw/osal/linux/PosixThread.cpp | 375 ++- src/fsfw/osal/linux/PosixThread.h | 124 +- src/fsfw/osal/linux/QueueFactory.cpp | 45 +- src/fsfw/osal/linux/SemaphoreFactory.cpp | 31 +- src/fsfw/osal/linux/TaskFactory.cpp | 78 +- src/fsfw/osal/linux/tcpipHelpers.cpp | 151 +- src/fsfw/osal/linux/unixUtility.cpp | 34 +- src/fsfw/osal/linux/unixUtility.h | 3 +- src/fsfw/osal/rtems/BinarySemaphore.cpp | 18 +- src/fsfw/osal/rtems/BinarySemaphore.h | 23 +- src/fsfw/osal/rtems/Clock.cpp | 209 +- src/fsfw/osal/rtems/CpuUsage.cpp | 253 +- src/fsfw/osal/rtems/CpuUsage.h | 63 +- src/fsfw/osal/rtems/FixedTimeslotTask.cpp | 165 +- src/fsfw/osal/rtems/FixedTimeslotTask.h | 127 +- src/fsfw/osal/rtems/InitTask.cpp | 10 +- src/fsfw/osal/rtems/InitTask.h | 8 +- src/fsfw/osal/rtems/InternalErrorCodes.cpp | 103 +- src/fsfw/osal/rtems/MessageQueue.cpp | 209 +- src/fsfw/osal/rtems/MessageQueue.h | 308 ++- src/fsfw/osal/rtems/Mutex.cpp | 122 +- src/fsfw/osal/rtems/Mutex.h | 17 +- src/fsfw/osal/rtems/MutexFactory.cpp | 21 +- src/fsfw/osal/rtems/PeriodicTask.cpp | 106 +- src/fsfw/osal/rtems/PeriodicTask.h | 173 +- src/fsfw/osal/rtems/QueueFactory.cpp | 89 +- src/fsfw/osal/rtems/RTEMSTaskBase.cpp | 116 +- src/fsfw/osal/rtems/RTEMSTaskBase.h | 66 +- src/fsfw/osal/rtems/RtemsBasic.h | 26 +- src/fsfw/osal/rtems/SemaphoreFactory.cpp | 29 +- src/fsfw/osal/rtems/TaskFactory.cpp | 68 +- src/fsfw/osal/windows/tcpipHelpers.cpp | 79 +- src/fsfw/osal/windows/winTaskHelpers.cpp | 146 +- src/fsfw/osal/windows/winTaskHelpers.h | 44 +- src/fsfw/parameters/HasParametersIF.h | 87 +- src/fsfw/parameters/ParameterHelper.cpp | 196 +- src/fsfw/parameters/ParameterHelper.h | 28 +- src/fsfw/parameters/ParameterMessage.cpp | 89 +- src/fsfw/parameters/ParameterMessage.h | 65 +- src/fsfw/parameters/ParameterWrapper.cpp | 562 ++-- src/fsfw/parameters/ParameterWrapper.h | 287 +- .../parameters/ReceivesParameterMessagesIF.h | 14 +- src/fsfw/power/Fuse.cpp | 373 ++- src/fsfw/power/Fuse.h | 168 +- src/fsfw/power/PowerComponent.cpp | 114 +- src/fsfw/power/PowerComponent.h | 57 +- src/fsfw/power/PowerComponentIF.h | 21 +- src/fsfw/power/PowerSensor.cpp | 187 +- src/fsfw/power/PowerSensor.h | 121 +- src/fsfw/power/PowerSwitchIF.h | 108 +- src/fsfw/power/PowerSwitcher.cpp | 187 +- src/fsfw/power/PowerSwitcher.h | 73 +- src/fsfw/pus/CService200ModeCommanding.cpp | 204 +- src/fsfw/pus/CService200ModeCommanding.h | 110 +- src/fsfw/pus/CService201HealthCommanding.cpp | 154 +- src/fsfw/pus/CService201HealthCommanding.h | 71 +- src/fsfw/pus/Service17Test.cpp | 59 +- src/fsfw/pus/Service17Test.h | 40 +- .../pus/Service1TelecommandVerification.cpp | 148 +- .../pus/Service1TelecommandVerification.h | 92 +- src/fsfw/pus/Service20ParameterManagement.cpp | 272 +- src/fsfw/pus/Service20ParameterManagement.h | 74 +- src/fsfw/pus/Service2DeviceAccess.cpp | 245 +- src/fsfw/pus/Service2DeviceAccess.h | 105 +- src/fsfw/pus/Service3Housekeeping.cpp | 421 ++- src/fsfw/pus/Service3Housekeeping.h | 131 +- src/fsfw/pus/Service5EventReporting.cpp | 141 +- src/fsfw/pus/Service5EventReporting.h | 76 +- src/fsfw/pus/Service8FunctionManagement.cpp | 236 +- src/fsfw/pus/Service8FunctionManagement.h | 62 +- src/fsfw/pus/Service9TimeManagement.cpp | 75 +- src/fsfw/pus/Service9TimeManagement.h | 49 +- src/fsfw/pus/servicepackets/Service1Packets.h | 258 +- .../pus/servicepackets/Service200Packets.h | 74 +- .../pus/servicepackets/Service201Packets.h | 64 +- .../pus/servicepackets/Service20Packets.h | 177 +- src/fsfw/pus/servicepackets/Service2Packets.h | 83 +- src/fsfw/pus/servicepackets/Service3Packets.h | 14 +- src/fsfw/pus/servicepackets/Service5Packets.h | 98 +- src/fsfw/pus/servicepackets/Service8Packets.h | 146 +- src/fsfw/pus/servicepackets/Service9Packets.h | 28 +- src/fsfw/returnvalues/FwClassIds.h | 154 +- src/fsfw/returnvalues/HasReturnvaluesIF.h | 36 +- src/fsfw/rmap/RMAP.cpp | 128 +- src/fsfw/rmap/RMAP.h | 417 +-- src/fsfw/rmap/RMAPChannelIF.h | 214 +- src/fsfw/rmap/RMAPCookie.cpp | 146 +- src/fsfw/rmap/RMAPCookie.h | 69 +- src/fsfw/rmap/RmapDeviceCommunicationIF.cpp | 54 +- src/fsfw/rmap/RmapDeviceCommunicationIF.h | 129 +- src/fsfw/rmap/rmapStructs.h | 112 +- src/fsfw/serialize.h | 2 +- src/fsfw/serialize/EndianConverter.h | 140 +- src/fsfw/serialize/SerialArrayListAdapter.h | 117 +- src/fsfw/serialize/SerialBufferAdapter.cpp | 207 +- src/fsfw/serialize/SerialBufferAdapter.h | 96 +- .../serialize/SerialFixedArrayListAdapter.h | 55 +- src/fsfw/serialize/SerialLinkedListAdapter.h | 150 +- src/fsfw/serialize/SerializeAdapter.h | 472 ++-- src/fsfw/serialize/SerializeElement.h | 63 +- src/fsfw/serialize/SerializeIF.h | 135 +- .../ServiceInterfaceBuffer.cpp | 375 ++- .../serviceinterface/ServiceInterfaceBuffer.h | 199 +- .../ServiceInterfacePrinter.cpp | 160 +- .../ServiceInterfacePrinter.h | 30 +- .../ServiceInterfaceStream.cpp | 22 +- .../serviceinterface/ServiceInterfaceStream.h | 66 +- .../serviceInterfaceDefintions.h | 9 +- .../storagemanager/ConstStorageAccessor.cpp | 118 +- .../storagemanager/ConstStorageAccessor.h | 163 +- src/fsfw/storagemanager/LocalPool.cpp | 520 ++-- src/fsfw/storagemanager/LocalPool.h | 410 ++- src/fsfw/storagemanager/PoolManager.cpp | 67 +- src/fsfw/storagemanager/PoolManager.h | 88 +- src/fsfw/storagemanager/StorageAccessor.cpp | 97 +- src/fsfw/storagemanager/StorageAccessor.h | 54 +- src/fsfw/storagemanager/StorageManagerIF.h | 313 ++- src/fsfw/storagemanager/storeAddress.h | 77 +- src/fsfw/subsystem/Subsystem.cpp | 1004 ++++--- src/fsfw/subsystem/Subsystem.h | 212 +- src/fsfw/subsystem/SubsystemBase.cpp | 516 ++-- src/fsfw/subsystem/SubsystemBase.h | 171 +- src/fsfw/subsystem/modes/HasModeSequenceIF.h | 11 +- src/fsfw/subsystem/modes/ModeDefinitions.h | 181 +- .../subsystem/modes/ModeSequenceMessage.cpp | 104 +- .../subsystem/modes/ModeSequenceMessage.h | 65 +- src/fsfw/subsystem/modes/ModeStore.cpp | 181 +- src/fsfw/subsystem/modes/ModeStore.h | 43 +- src/fsfw/subsystem/modes/ModeStoreIF.h | 30 +- src/fsfw/tasks/ExecutableObjectIF.h | 68 +- src/fsfw/tasks/FixedSequenceSlot.cpp | 22 +- src/fsfw/tasks/FixedSequenceSlot.h | 68 +- src/fsfw/tasks/FixedSlotSequence.cpp | 246 +- src/fsfw/tasks/FixedSlotSequence.h | 274 +- src/fsfw/tasks/FixedTimeslotTaskIF.h | 42 +- src/fsfw/tasks/PeriodicTaskIF.h | 62 +- src/fsfw/tasks/SemaphoreFactory.h | 66 +- src/fsfw/tasks/SemaphoreIF.h | 81 +- src/fsfw/tasks/TaskFactory.h | 156 +- src/fsfw/tasks/Typedef.h | 2 +- src/fsfw/tcdistribution/CCSDSDistributor.cpp | 138 +- src/fsfw/tcdistribution/CCSDSDistributor.h | 94 +- src/fsfw/tcdistribution/CCSDSDistributorIF.h | 51 +- src/fsfw/tcdistribution/CFDPDistributor.cpp | 182 +- src/fsfw/tcdistribution/CFDPDistributor.h | 105 +- src/fsfw/tcdistribution/CFDPDistributorIF.h | 27 +- src/fsfw/tcdistribution/PUSDistributor.cpp | 187 +- src/fsfw/tcdistribution/PUSDistributor.h | 112 +- src/fsfw/tcdistribution/PUSDistributorIF.h | 27 +- src/fsfw/tcdistribution/TcDistributor.cpp | 64 +- src/fsfw/tcdistribution/TcDistributor.h | 177 +- src/fsfw/tcdistribution/TcPacketCheckCFDP.cpp | 12 +- src/fsfw/tcdistribution/TcPacketCheckCFDP.h | 34 +- src/fsfw/tcdistribution/TcPacketCheckIF.h | 29 +- src/fsfw/tcdistribution/TcPacketCheckPUS.cpp | 66 +- src/fsfw/tcdistribution/TcPacketCheckPUS.h | 76 +- .../thermal/AbstractTemperatureSensor.cpp | 87 +- src/fsfw/thermal/AbstractTemperatureSensor.h | 63 +- src/fsfw/thermal/AcceptsThermalMessagesIF.h | 13 +- src/fsfw/thermal/Heater.cpp | 537 ++-- src/fsfw/thermal/Heater.h | 115 +- src/fsfw/thermal/RedundantHeater.cpp | 46 +- src/fsfw/thermal/RedundantHeater.h | 66 +- src/fsfw/thermal/TemperatureSensor.h | 352 ++- src/fsfw/thermal/ThermalComponent.cpp | 270 +- src/fsfw/thermal/ThermalComponent.h | 111 +- src/fsfw/thermal/ThermalComponentCore.cpp | 433 ++- src/fsfw/thermal/ThermalComponentCore.h | 144 +- src/fsfw/thermal/ThermalComponentIF.h | 168 +- src/fsfw/thermal/ThermalModule.cpp | 442 ++- src/fsfw/thermal/ThermalModule.h | 104 +- src/fsfw/thermal/ThermalModuleIF.h | 43 +- src/fsfw/thermal/ThermalMonitorReporter.cpp | 118 +- src/fsfw/thermal/ThermalMonitorReporter.h | 26 +- src/fsfw/timemanager/CCSDSTime.cpp | 973 ++++--- src/fsfw/timemanager/CCSDSTime.h | 380 ++- src/fsfw/timemanager/Clock.h | 289 +- src/fsfw/timemanager/ClockCommon.cpp | 72 +- src/fsfw/timemanager/Countdown.cpp | 58 +- src/fsfw/timemanager/Countdown.h | 115 +- src/fsfw/timemanager/ReceivesTimeInfoIF.h | 23 +- src/fsfw/timemanager/Stopwatch.cpp | 74 +- src/fsfw/timemanager/Stopwatch.h | 87 +- src/fsfw/timemanager/TimeMessage.cpp | 29 +- src/fsfw/timemanager/TimeMessage.h | 77 +- src/fsfw/timemanager/TimeStamper.cpp | 31 +- src/fsfw/timemanager/TimeStamper.h | 36 +- src/fsfw/timemanager/TimeStamperIF.h | 21 +- src/fsfw/tmstorage/TmStoreBackendIF.h | 174 +- src/fsfw/tmstorage/TmStoreFrontendIF.h | 98 +- src/fsfw/tmstorage/TmStoreMessage.cpp | 230 +- src/fsfw/tmstorage/TmStoreMessage.h | 107 +- src/fsfw/tmstorage/TmStorePackets.h | 510 ++-- .../tmtcpacket/RedirectableDataPointerIF.h | 37 +- src/fsfw/tmtcpacket/SpacePacket.cpp | 39 +- src/fsfw/tmtcpacket/SpacePacket.h | 123 +- src/fsfw/tmtcpacket/SpacePacketBase.cpp | 141 +- src/fsfw/tmtcpacket/SpacePacketBase.h | 288 +- src/fsfw/tmtcpacket/ccsds_header.h | 12 +- src/fsfw/tmtcpacket/cfdp/CFDPPacket.cpp | 12 +- src/fsfw/tmtcpacket/cfdp/CFDPPacket.h | 34 +- src/fsfw/tmtcpacket/cfdp/CFDPPacketStored.cpp | 133 +- src/fsfw/tmtcpacket/cfdp/CFDPPacketStored.h | 98 +- .../tmtcpacket/packetmatcher/ApidMatcher.h | 50 +- .../packetmatcher/PacketMatchTree.cpp | 344 ++- .../packetmatcher/PacketMatchTree.h | 50 +- .../tmtcpacket/packetmatcher/ServiceMatcher.h | 49 +- .../packetmatcher/SubserviceMatcher.h | 50 +- .../pus/PacketTimestampInterpreterIF.h | 13 +- src/fsfw/tmtcpacket/pus/definitions.h | 7 +- src/fsfw/tmtcpacket/pus/tc.h | 2 +- src/fsfw/tmtcpacket/pus/tc/TcPacketPus.cpp | 106 +- src/fsfw/tmtcpacket/pus/tc/TcPacketPus.h | 115 +- .../tmtcpacket/pus/tc/TcPacketPusBase.cpp | 12 +- src/fsfw/tmtcpacket/pus/tc/TcPacketPusBase.h | 249 +- .../tmtcpacket/pus/tc/TcPacketStoredBase.cpp | 79 +- .../tmtcpacket/pus/tc/TcPacketStoredBase.h | 129 +- src/fsfw/tmtcpacket/pus/tc/TcPacketStoredIF.h | 37 +- .../tmtcpacket/pus/tc/TcPacketStoredPus.cpp | 117 +- .../tmtcpacket/pus/tc/TcPacketStoredPus.h | 81 +- src/fsfw/tmtcpacket/pus/tm/TmPacketBase.cpp | 52 +- src/fsfw/tmtcpacket/pus/tm/TmPacketBase.h | 200 +- .../tmtcpacket/pus/tm/TmPacketMinimal.cpp | 44 +- src/fsfw/tmtcpacket/pus/tm/TmPacketMinimal.h | 124 +- src/fsfw/tmtcpacket/pus/tm/TmPacketPusA.cpp | 91 +- src/fsfw/tmtcpacket/pus/tm/TmPacketPusA.h | 172 +- src/fsfw/tmtcpacket/pus/tm/TmPacketPusC.cpp | 116 +- src/fsfw/tmtcpacket/pus/tm/TmPacketPusC.h | 165 +- src/fsfw/tmtcpacket/pus/tm/TmPacketStored.h | 1 - .../tmtcpacket/pus/tm/TmPacketStoredBase.cpp | 155 +- .../tmtcpacket/pus/tm/TmPacketStoredBase.h | 118 +- .../tmtcpacket/pus/tm/TmPacketStoredPusA.cpp | 129 +- .../tmtcpacket/pus/tm/TmPacketStoredPusA.h | 104 +- .../tmtcpacket/pus/tm/TmPacketStoredPusC.cpp | 134 +- .../tmtcpacket/pus/tm/TmPacketStoredPusC.h | 108 +- src/fsfw/tmtcservices/AcceptsTelecommandsIF.h | 53 +- src/fsfw/tmtcservices/AcceptsTelemetryIF.h | 24 +- .../tmtcservices/AcceptsVerifyMessageIF.h | 9 +- .../tmtcservices/CommandingServiceBase.cpp | 687 +++-- src/fsfw/tmtcservices/CommandingServiceBase.h | 573 ++-- src/fsfw/tmtcservices/PusServiceBase.cpp | 175 +- src/fsfw/tmtcservices/PusServiceBase.h | 239 +- .../tmtcservices/PusVerificationReport.cpp | 189 +- src/fsfw/tmtcservices/PusVerificationReport.h | 123 +- src/fsfw/tmtcservices/SourceSequenceCounter.h | 30 +- src/fsfw/tmtcservices/SpacePacketParser.cpp | 126 +- src/fsfw/tmtcservices/SpacePacketParser.h | 113 +- src/fsfw/tmtcservices/TmTcBridge.cpp | 356 ++- src/fsfw/tmtcservices/TmTcBridge.h | 251 +- src/fsfw/tmtcservices/TmTcMessage.cpp | 22 +- src/fsfw/tmtcservices/TmTcMessage.h | 65 +- src/fsfw/tmtcservices/VerificationCodes.h | 30 +- .../tmtcservices/VerificationReporter.cpp | 177 +- src/fsfw/tmtcservices/VerificationReporter.h | 42 +- .../integration/assemblies/TestAssembly.cpp | 325 +-- .../integration/assemblies/TestAssembly.h | 80 +- .../integration/controller/TestController.cpp | 37 +- .../integration/controller/TestController.h | 44 +- .../ctrldefinitions/testCtrlDefinitions.h | 10 +- .../integration/devices/TestCookie.cpp | 12 +- .../integration/devices/TestCookie.h | 20 +- .../integration/devices/TestDeviceHandler.cpp | 1203 ++++---- .../integration/devices/TestDeviceHandler.h | 182 +- .../integration/devices/TestEchoComIF.cpp | 118 +- .../integration/devices/TestEchoComIF.h | 62 +- .../devicedefinitions/testDeviceDefinitions.h | 52 +- .../fsfw_tests/integration/task/TestTask.cpp | 77 +- .../fsfw_tests/integration/task/TestTask.h | 42 +- .../internal/InternalUnitTester.cpp | 50 +- .../fsfw_tests/internal/InternalUnitTester.h | 28 +- .../fsfw_tests/internal/UnittDefinitions.cpp | 9 +- .../fsfw_tests/internal/UnittDefinitions.h | 32 +- .../globalfunctions/TestArrayPrinter.cpp | 41 +- .../globalfunctions/TestArrayPrinter.h | 1 + tests/src/fsfw_tests/internal/osal/testMq.cpp | 74 +- tests/src/fsfw_tests/internal/osal/testMq.h | 1 - .../fsfw_tests/internal/osal/testMutex.cpp | 62 +- .../src/fsfw_tests/internal/osal/testMutex.h | 2 - .../internal/osal/testSemaphore.cpp | 254 +- .../fsfw_tests/internal/osal/testSemaphore.h | 6 +- .../serialize/IntTestSerialization.cpp | 372 ++- .../internal/serialize/IntTestSerialization.h | 5 +- .../src/fsfw_tests/unit/CatchDefinitions.cpp | 17 +- tests/src/fsfw_tests/unit/CatchDefinitions.h | 6 +- tests/src/fsfw_tests/unit/CatchFactory.cpp | 69 +- tests/src/fsfw_tests/unit/CatchFactory.h | 18 +- tests/src/fsfw_tests/unit/CatchRunner.cpp | 11 +- tests/src/fsfw_tests/unit/CatchRunner.h | 4 +- tests/src/fsfw_tests/unit/CatchSetup.cpp | 18 +- .../unit/action/TestActionHelper.cpp | 194 +- .../fsfw_tests/unit/action/TestActionHelper.h | 71 +- tests/src/fsfw_tests/unit/cfdp/testAckPdu.cpp | 177 +- tests/src/fsfw_tests/unit/cfdp/testCfdp.cpp | 684 +++-- tests/src/fsfw_tests/unit/cfdp/testEofPdu.cpp | 212 +- .../src/fsfw_tests/unit/cfdp/testFileData.cpp | 316 ++- .../fsfw_tests/unit/cfdp/testFinishedPdu.cpp | 343 ++- .../fsfw_tests/unit/cfdp/testKeepAlivePdu.cpp | 131 +- .../fsfw_tests/unit/cfdp/testMetadataPdu.cpp | 332 ++- tests/src/fsfw_tests/unit/cfdp/testNakPdu.cpp | 276 +- .../fsfw_tests/unit/cfdp/testPromptPdu.cpp | 114 +- .../src/fsfw_tests/unit/cfdp/testTlvsLvs.cpp | 588 ++-- .../unit/container/RingBufferTest.cpp | 586 ++-- .../unit/container/TestArrayList.cpp | 164 +- .../unit/container/TestDynamicFifo.cpp | 258 +- .../fsfw_tests/unit/container/TestFifo.cpp | 235 +- .../unit/container/TestFixedArrayList.cpp | 66 +- .../unit/container/TestFixedMap.cpp | 301 +- .../container/TestFixedOrderedMultimap.cpp | 375 +-- .../unit/container/TestPlacementFactory.cpp | 79 +- .../unit/datapoollocal/DataSetTest.cpp | 531 ++-- .../datapoollocal/LocalPoolManagerTest.cpp | 769 +++--- .../unit/datapoollocal/LocalPoolOwnerBase.cpp | 192 +- .../unit/datapoollocal/LocalPoolOwnerBase.h | 218 +- .../datapoollocal/LocalPoolVariableTest.cpp | 197 +- .../datapoollocal/LocalPoolVectorTest.cpp | 186 +- .../unit/globalfunctions/testBitutil.cpp | 111 +- .../unit/globalfunctions/testDleEncoder.cpp | 379 ++- .../unit/globalfunctions/testOpDivider.cpp | 115 +- .../unit/hal/testCommandExecutor.cpp | 195 +- .../fsfw_tests/unit/mocks/HkReceiverMock.h | 14 +- .../unit/mocks/MessageQueueMockBase.h | 190 +- .../fsfw_tests/unit/osal/TestMessageQueue.cpp | 61 +- .../fsfw_tests/unit/osal/TestSemaphore.cpp | 58 +- tests/src/fsfw_tests/unit/printChar.cpp | 11 +- tests/src/fsfw_tests/unit/printChar.h | 2 - .../serialize/TestSerialBufferAdapter.cpp | 247 +- .../unit/serialize/TestSerialLinkedPacket.cpp | 119 +- .../unit/serialize/TestSerialLinkedPacket.h | 73 +- .../unit/serialize/TestSerialization.cpp | 366 ++- .../unit/storagemanager/TestNewAccessor.cpp | 285 +- .../unit/storagemanager/TestPool.cpp | 505 ++-- .../unit/testcfg/devices/logicalAddresses.cpp | 4 - .../unit/testcfg/devices/logicalAddresses.h | 8 +- .../testcfg/devices/powerSwitcherList.cpp | 3 - .../unit/testcfg/devices/powerSwitcherList.h | 8 +- .../unit/testcfg/events/subsystemIdRanges.h | 8 +- .../unit/testcfg/ipc/MissionMessageTypes.cpp | 10 +- .../unit/testcfg/ipc/MissionMessageTypes.h | 6 +- .../unit/testcfg/objects/systemObjectList.h | 27 +- .../PollingSequenceFactory.cpp | 49 +- .../pollingsequence/PollingSequenceFactory.h | 6 +- .../unit/testcfg/returnvalues/classIds.h | 3 +- tests/src/fsfw_tests/unit/testcfg/tmtc/apid.h | 3 +- .../src/fsfw_tests/unit/testcfg/tmtc/pusIds.h | 30 +- .../unit/testtemplate/TestTemplate.cpp | 21 +- .../unit/timemanager/TestCountdown.cpp | 45 +- .../fsfw_tests/unit/tmtcpacket/PusTmTest.cpp | 2 - .../fsfw_tests/unit/tmtcpacket/testCcsds.cpp | 10 +- 809 files changed, 52010 insertions(+), 56052 deletions(-) diff --git a/hal/src/fsfw_hal/common/gpio/GpioCookie.cpp b/hal/src/fsfw_hal/common/gpio/GpioCookie.cpp index 7c56ebcf..4c4b4d14 100644 --- a/hal/src/fsfw_hal/common/gpio/GpioCookie.cpp +++ b/hal/src/fsfw_hal/common/gpio/GpioCookie.cpp @@ -1,50 +1,48 @@ #include "fsfw_hal/common/gpio/GpioCookie.h" + #include "fsfw/serviceinterface/ServiceInterface.h" -GpioCookie::GpioCookie() { -} +GpioCookie::GpioCookie() {} ReturnValue_t GpioCookie::addGpio(gpioId_t gpioId, GpioBase* gpioConfig) { - if (gpioConfig == nullptr) { + if (gpioConfig == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "GpioCookie::addGpio: gpioConfig is nullpointer" << std::endl; + sif::warning << "GpioCookie::addGpio: gpioConfig is nullpointer" << std::endl; #else - sif::printWarning("GpioCookie::addGpio: gpioConfig is nullpointer\n"); -#endif - return HasReturnvaluesIF::RETURN_FAILED; - } - auto gpioMapIter = gpioMap.find(gpioId); - if(gpioMapIter == gpioMap.end()) { - auto statusPair = gpioMap.emplace(gpioId, gpioConfig); - if (statusPair.second == false) { -#if FSFW_VERBOSE_LEVEL >= 1 -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "GpioCookie::addGpio: Failed to add GPIO " << gpioId << - " to GPIO map" << std::endl; -#else - sif::printWarning("GpioCookie::addGpio: Failed to add GPIO %d to GPIO map\n", gpioId); -#endif -#endif - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; - } -#if FSFW_VERBOSE_LEVEL >= 1 -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "GpioCookie::addGpio: GPIO already exists in GPIO map " << std::endl; -#else - sif::printWarning("GpioCookie::addGpio: GPIO already exists in GPIO map\n"); -#endif + sif::printWarning("GpioCookie::addGpio: gpioConfig is nullpointer\n"); #endif return HasReturnvaluesIF::RETURN_FAILED; + } + auto gpioMapIter = gpioMap.find(gpioId); + if (gpioMapIter == gpioMap.end()) { + auto statusPair = gpioMap.emplace(gpioId, gpioConfig); + if (statusPair.second == false) { +#if FSFW_VERBOSE_LEVEL >= 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "GpioCookie::addGpio: Failed to add GPIO " << gpioId << " to GPIO map" + << std::endl; +#else + sif::printWarning("GpioCookie::addGpio: Failed to add GPIO %d to GPIO map\n", gpioId); +#endif +#endif + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; + } +#if FSFW_VERBOSE_LEVEL >= 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "GpioCookie::addGpio: GPIO already exists in GPIO map " << std::endl; +#else + sif::printWarning("GpioCookie::addGpio: GPIO already exists in GPIO map\n"); +#endif +#endif + return HasReturnvaluesIF::RETURN_FAILED; } -GpioMap GpioCookie::getGpioMap() const { - return gpioMap; -} +GpioMap GpioCookie::getGpioMap() const { return gpioMap; } GpioCookie::~GpioCookie() { - for(auto& config: gpioMap) { - delete(config.second); - } + for (auto& config : gpioMap) { + delete (config.second); + } } diff --git a/hal/src/fsfw_hal/common/gpio/GpioCookie.h b/hal/src/fsfw_hal/common/gpio/GpioCookie.h index 0473fe0f..cf836eae 100644 --- a/hal/src/fsfw_hal/common/gpio/GpioCookie.h +++ b/hal/src/fsfw_hal/common/gpio/GpioCookie.h @@ -1,12 +1,12 @@ #ifndef COMMON_GPIO_GPIOCOOKIE_H_ #define COMMON_GPIO_GPIOCOOKIE_H_ -#include "GpioIF.h" -#include "gpioDefinitions.h" - #include #include +#include "GpioIF.h" +#include "gpioDefinitions.h" + /** * @brief Cookie for the GpioIF. Allows the GpioIF to determine which * GPIOs to initialize and whether they should be configured as in- or @@ -17,25 +17,24 @@ * * @author J. Meier */ -class GpioCookie: public CookieIF { -public: +class GpioCookie : public CookieIF { + public: + GpioCookie(); - GpioCookie(); + virtual ~GpioCookie(); - virtual ~GpioCookie(); + ReturnValue_t addGpio(gpioId_t gpioId, GpioBase* gpioConfig); - ReturnValue_t addGpio(gpioId_t gpioId, GpioBase* gpioConfig); + /** + * @brief Get map with registered GPIOs. + */ + GpioMap getGpioMap() const; - /** - * @brief Get map with registered GPIOs. - */ - GpioMap getGpioMap() const; - -private: - /** - * Returns a copy of the internal GPIO map. - */ - GpioMap gpioMap; + private: + /** + * Returns a copy of the internal GPIO map. + */ + GpioMap gpioMap; }; #endif /* COMMON_GPIO_GPIOCOOKIE_H_ */ diff --git a/hal/src/fsfw_hal/common/gpio/GpioIF.h b/hal/src/fsfw_hal/common/gpio/GpioIF.h index af73f94c..5cca1481 100644 --- a/hal/src/fsfw_hal/common/gpio/GpioIF.h +++ b/hal/src/fsfw_hal/common/gpio/GpioIF.h @@ -1,9 +1,10 @@ #ifndef COMMON_GPIO_GPIOIF_H_ #define COMMON_GPIO_GPIOIF_H_ -#include "gpioDefinitions.h" -#include #include +#include + +#include "gpioDefinitions.h" class GpioCookie; @@ -13,42 +14,41 @@ class GpioCookie; * @author J. Meier */ class GpioIF : public HasReturnvaluesIF { -public: + public: + virtual ~GpioIF(){}; - virtual ~GpioIF() {}; + /** + * @brief Called by the GPIO using object. + * @param cookie Cookie specifying informations of the GPIOs required + * by a object. + */ + virtual ReturnValue_t addGpios(GpioCookie* cookie) = 0; - /** - * @brief Called by the GPIO using object. - * @param cookie Cookie specifying informations of the GPIOs required - * by a object. - */ - virtual ReturnValue_t addGpios(GpioCookie* cookie) = 0; + /** + * @brief By implementing this function a child must provide the + * functionality to pull a certain GPIO to high logic level. + * + * @param gpioId A unique number which specifies the GPIO to drive. + * @return Returns RETURN_OK for success. This should never return RETURN_FAILED. + */ + virtual ReturnValue_t pullHigh(gpioId_t gpioId) = 0; - /** - * @brief By implementing this function a child must provide the - * functionality to pull a certain GPIO to high logic level. - * - * @param gpioId A unique number which specifies the GPIO to drive. - * @return Returns RETURN_OK for success. This should never return RETURN_FAILED. - */ - virtual ReturnValue_t pullHigh(gpioId_t gpioId) = 0; + /** + * @brief By implementing this function a child must provide the + * functionality to pull a certain GPIO to low logic level. + * + * @param gpioId A unique number which specifies the GPIO to drive. + */ + virtual ReturnValue_t pullLow(gpioId_t gpioId) = 0; - /** - * @brief By implementing this function a child must provide the - * functionality to pull a certain GPIO to low logic level. - * - * @param gpioId A unique number which specifies the GPIO to drive. - */ - virtual ReturnValue_t pullLow(gpioId_t gpioId) = 0; - - /** - * @brief This function requires a child to implement the functionality to read the state of - * an ouput or input gpio. - * - * @param gpioId A unique number which specifies the GPIO to read. - * @param gpioState State of GPIO will be written to this pointer. - */ - virtual ReturnValue_t readGpio(gpioId_t gpioId, int* gpioState) = 0; + /** + * @brief This function requires a child to implement the functionality to read the state of + * an ouput or input gpio. + * + * @param gpioId A unique number which specifies the GPIO to read. + * @param gpioState State of GPIO will be written to this pointer. + */ + virtual ReturnValue_t readGpio(gpioId_t gpioId, int* gpioState) = 0; }; #endif /* COMMON_GPIO_GPIOIF_H_ */ diff --git a/hal/src/fsfw_hal/common/gpio/gpioDefinitions.h b/hal/src/fsfw_hal/common/gpio/gpioDefinitions.h index c6f21195..b429449b 100644 --- a/hal/src/fsfw_hal/common/gpio/gpioDefinitions.h +++ b/hal/src/fsfw_hal/common/gpio/gpioDefinitions.h @@ -1,44 +1,34 @@ #ifndef COMMON_GPIO_GPIODEFINITIONS_H_ #define COMMON_GPIO_GPIODEFINITIONS_H_ +#include #include #include -#include using gpioId_t = uint16_t; namespace gpio { -enum Levels: uint8_t { - LOW = 0, - HIGH = 1, - NONE = 99 -}; +enum Levels : uint8_t { LOW = 0, HIGH = 1, NONE = 99 }; -enum Direction: uint8_t { - IN = 0, - OUT = 1 -}; +enum Direction : uint8_t { IN = 0, OUT = 1 }; -enum GpioOperation { - READ, - WRITE -}; +enum GpioOperation { READ, WRITE }; enum class GpioTypes { - NONE, - GPIO_REGULAR_BY_CHIP, - GPIO_REGULAR_BY_LABEL, - GPIO_REGULAR_BY_LINE_NAME, - CALLBACK + NONE, + GPIO_REGULAR_BY_CHIP, + GPIO_REGULAR_BY_LABEL, + GPIO_REGULAR_BY_LINE_NAME, + CALLBACK }; static constexpr gpioId_t NO_GPIO = -1; -using gpio_cb_t = void (*) (gpioId_t gpioId, gpio::GpioOperation gpioOp, gpio::Levels value, - void* args); +using gpio_cb_t = void (*)(gpioId_t gpioId, gpio::GpioOperation gpioOp, gpio::Levels value, + void* args); -} +} // namespace gpio /** * @brief Struct containing information about the GPIO to use. This is @@ -55,78 +45,71 @@ using gpio_cb_t = void (*) (gpioId_t gpioId, gpio::GpioOperation gpioOp, gpio::L * pointer. */ class GpioBase { -public: + public: + GpioBase() = default; - GpioBase() = default; + GpioBase(gpio::GpioTypes gpioType, std::string consumer, gpio::Direction direction, + gpio::Levels initValue) + : gpioType(gpioType), consumer(consumer), direction(direction), initValue(initValue) {} - GpioBase(gpio::GpioTypes gpioType, std::string consumer, gpio::Direction direction, - gpio::Levels initValue): - gpioType(gpioType), consumer(consumer),direction(direction), initValue(initValue) {} + virtual ~GpioBase(){}; - virtual~ GpioBase() {}; - - // Can be used to cast GpioBase to a concrete child implementation - gpio::GpioTypes gpioType = gpio::GpioTypes::NONE; - std::string consumer; - gpio::Direction direction = gpio::Direction::IN; - gpio::Levels initValue = gpio::Levels::NONE; + // Can be used to cast GpioBase to a concrete child implementation + gpio::GpioTypes gpioType = gpio::GpioTypes::NONE; + std::string consumer; + gpio::Direction direction = gpio::Direction::IN; + gpio::Levels initValue = gpio::Levels::NONE; }; -class GpiodRegularBase: public GpioBase { -public: - GpiodRegularBase(gpio::GpioTypes gpioType, std::string consumer, gpio::Direction direction, - gpio::Levels initValue, int lineNum): - GpioBase(gpioType, consumer, direction, initValue), lineNum(lineNum) { - } +class GpiodRegularBase : public GpioBase { + public: + GpiodRegularBase(gpio::GpioTypes gpioType, std::string consumer, gpio::Direction direction, + gpio::Levels initValue, int lineNum) + : GpioBase(gpioType, consumer, direction, initValue), lineNum(lineNum) {} - // line number will be configured at a later point for the open by line name configuration - GpiodRegularBase(gpio::GpioTypes gpioType, std::string consumer, gpio::Direction direction, - gpio::Levels initValue): GpioBase(gpioType, consumer, direction, initValue) { - } + // line number will be configured at a later point for the open by line name configuration + GpiodRegularBase(gpio::GpioTypes gpioType, std::string consumer, gpio::Direction direction, + gpio::Levels initValue) + : GpioBase(gpioType, consumer, direction, initValue) {} - int lineNum = 0; - struct gpiod_line* lineHandle = nullptr; + int lineNum = 0; + struct gpiod_line* lineHandle = nullptr; }; -class GpiodRegularByChip: public GpiodRegularBase { -public: - GpiodRegularByChip() : - GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_CHIP, - std::string(), gpio::Direction::IN, gpio::LOW, 0) { - } +class GpiodRegularByChip : public GpiodRegularBase { + public: + GpiodRegularByChip() + : GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_CHIP, std::string(), gpio::Direction::IN, + gpio::LOW, 0) {} - GpiodRegularByChip(std::string chipname_, int lineNum_, std::string consumer_, - gpio::Direction direction_, gpio::Levels initValue_) : - GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_CHIP, - consumer_, direction_, initValue_, lineNum_), - chipname(chipname_){ - } + GpiodRegularByChip(std::string chipname_, int lineNum_, std::string consumer_, + gpio::Direction direction_, gpio::Levels initValue_) + : GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_CHIP, consumer_, direction_, initValue_, + lineNum_), + chipname(chipname_) {} - GpiodRegularByChip(std::string chipname_, int lineNum_, std::string consumer_) : - GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_CHIP, consumer_, - gpio::Direction::IN, gpio::LOW, lineNum_), - chipname(chipname_) { - } + GpiodRegularByChip(std::string chipname_, int lineNum_, std::string consumer_) + : GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_CHIP, consumer_, gpio::Direction::IN, + gpio::LOW, lineNum_), + chipname(chipname_) {} - std::string chipname; + std::string chipname; }; -class GpiodRegularByLabel: public GpiodRegularBase { -public: - GpiodRegularByLabel(std::string label_, int lineNum_, std::string consumer_, - gpio::Direction direction_, gpio::Levels initValue_) : - GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_LABEL, consumer_, - direction_, initValue_, lineNum_), - label(label_) { - } +class GpiodRegularByLabel : public GpiodRegularBase { + public: + GpiodRegularByLabel(std::string label_, int lineNum_, std::string consumer_, + gpio::Direction direction_, gpio::Levels initValue_) + : GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_LABEL, consumer_, direction_, initValue_, + lineNum_), + label(label_) {} - GpiodRegularByLabel(std::string label_, int lineNum_, std::string consumer_) : - GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_LABEL, consumer_, - gpio::Direction::IN, gpio::LOW, lineNum_), - label(label_) { - } + GpiodRegularByLabel(std::string label_, int lineNum_, std::string consumer_) + : GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_LABEL, consumer_, gpio::Direction::IN, + gpio::LOW, lineNum_), + label(label_) {} - std::string label; + std::string label; }; /** @@ -134,34 +117,34 @@ public: * line name. This line name can be set in the device tree and must be unique. Otherwise * the driver will open the first line with the given name. */ -class GpiodRegularByLineName: public GpiodRegularBase { -public: - GpiodRegularByLineName(std::string lineName_, std::string consumer_, gpio::Direction direction_, - gpio::Levels initValue_) : - GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_LINE_NAME, consumer_, direction_, - initValue_), lineName(lineName_) { - } +class GpiodRegularByLineName : public GpiodRegularBase { + public: + GpiodRegularByLineName(std::string lineName_, std::string consumer_, gpio::Direction direction_, + gpio::Levels initValue_) + : GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_LINE_NAME, consumer_, direction_, + initValue_), + lineName(lineName_) {} - GpiodRegularByLineName(std::string lineName_, std::string consumer_) : - GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_LINE_NAME, consumer_, - gpio::Direction::IN, gpio::LOW), lineName(lineName_) { - } + GpiodRegularByLineName(std::string lineName_, std::string consumer_) + : GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_LINE_NAME, consumer_, gpio::Direction::IN, + gpio::LOW), + lineName(lineName_) {} - std::string lineName; + std::string lineName; }; -class GpioCallback: public GpioBase { -public: - GpioCallback(std::string consumer, gpio::Direction direction_, gpio::Levels initValue_, - gpio::gpio_cb_t callback, void* callbackArgs): - GpioBase(gpio::GpioTypes::CALLBACK, consumer, direction_, initValue_), - callback(callback), callbackArgs(callbackArgs) {} +class GpioCallback : public GpioBase { + public: + GpioCallback(std::string consumer, gpio::Direction direction_, gpio::Levels initValue_, + gpio::gpio_cb_t callback, void* callbackArgs) + : GpioBase(gpio::GpioTypes::CALLBACK, consumer, direction_, initValue_), + callback(callback), + callbackArgs(callbackArgs) {} - gpio::gpio_cb_t callback = nullptr; - void* callbackArgs = nullptr; + gpio::gpio_cb_t callback = nullptr; + void* callbackArgs = nullptr; }; - using GpioMap = std::map; using GpioUnorderedMap = std::unordered_map; using GpioMapIter = GpioMap::iterator; diff --git a/hal/src/fsfw_hal/common/spi/spiCommon.h b/hal/src/fsfw_hal/common/spi/spiCommon.h index 9b3aef6a..bee86823 100644 --- a/hal/src/fsfw_hal/common/spi/spiCommon.h +++ b/hal/src/fsfw_hal/common/spi/spiCommon.h @@ -5,12 +5,7 @@ namespace spi { -enum SpiModes: uint8_t { - MODE_0, - MODE_1, - MODE_2, - MODE_3 -}; +enum SpiModes : uint8_t { MODE_0, MODE_1, MODE_2, MODE_3 }; } diff --git a/hal/src/fsfw_hal/devicehandlers/GyroL3GD20Handler.cpp b/hal/src/fsfw_hal/devicehandlers/GyroL3GD20Handler.cpp index d27351d7..be4c9aa9 100644 --- a/hal/src/fsfw_hal/devicehandlers/GyroL3GD20Handler.cpp +++ b/hal/src/fsfw_hal/devicehandlers/GyroL3GD20Handler.cpp @@ -1,287 +1,274 @@ #include "GyroL3GD20Handler.h" -#include "fsfw/datapool/PoolReadGuard.h" - #include +#include "fsfw/datapool/PoolReadGuard.h" + GyroHandlerL3GD20H::GyroHandlerL3GD20H(object_id_t objectId, object_id_t deviceCommunication, - CookieIF *comCookie, uint32_t transitionDelayMs): - DeviceHandlerBase(objectId, deviceCommunication, comCookie), - transitionDelayMs(transitionDelayMs), dataset(this) { + CookieIF *comCookie, uint32_t transitionDelayMs) + : DeviceHandlerBase(objectId, deviceCommunication, comCookie), + transitionDelayMs(transitionDelayMs), + dataset(this) { #if FSFW_HAL_L3GD20_GYRO_DEBUG == 1 - debugDivider = new PeriodicOperationDivider(3); + debugDivider = new PeriodicOperationDivider(3); #endif } GyroHandlerL3GD20H::~GyroHandlerL3GD20H() {} void GyroHandlerL3GD20H::doStartUp() { - if(internalState == InternalState::NONE) { - internalState = InternalState::CONFIGURE; - } + if (internalState == InternalState::NONE) { + internalState = InternalState::CONFIGURE; + } - if(internalState == InternalState::CONFIGURE) { - if(commandExecuted) { - internalState = InternalState::CHECK_REGS; - commandExecuted = false; - } + if (internalState == InternalState::CONFIGURE) { + if (commandExecuted) { + internalState = InternalState::CHECK_REGS; + commandExecuted = false; } + } - if(internalState == InternalState::CHECK_REGS) { - if(commandExecuted) { - internalState = InternalState::NORMAL; - if(goNormalModeImmediately) { - setMode(MODE_NORMAL); - } - else { - setMode(_MODE_TO_ON); - } - commandExecuted = false; - } + if (internalState == InternalState::CHECK_REGS) { + if (commandExecuted) { + internalState = InternalState::NORMAL; + if (goNormalModeImmediately) { + setMode(MODE_NORMAL); + } else { + setMode(_MODE_TO_ON); + } + commandExecuted = false; } + } } -void GyroHandlerL3GD20H::doShutDown() { - setMode(_MODE_POWER_DOWN); -} +void GyroHandlerL3GD20H::doShutDown() { setMode(_MODE_POWER_DOWN); } ReturnValue_t GyroHandlerL3GD20H::buildTransitionDeviceCommand(DeviceCommandId_t *id) { - switch(internalState) { - case(InternalState::NONE): - case(InternalState::NORMAL): { - return NOTHING_TO_SEND; + switch (internalState) { + case (InternalState::NONE): + case (InternalState::NORMAL): { + return NOTHING_TO_SEND; } - case(InternalState::CONFIGURE): { - *id = L3GD20H::CONFIGURE_CTRL_REGS; - uint8_t command [5]; - command[0] = L3GD20H::CTRL_REG_1_VAL; - command[1] = L3GD20H::CTRL_REG_2_VAL; - command[2] = L3GD20H::CTRL_REG_3_VAL; - command[3] = L3GD20H::CTRL_REG_4_VAL; - command[4] = L3GD20H::CTRL_REG_5_VAL; - return buildCommandFromCommand(*id, command, 5); + case (InternalState::CONFIGURE): { + *id = L3GD20H::CONFIGURE_CTRL_REGS; + uint8_t command[5]; + command[0] = L3GD20H::CTRL_REG_1_VAL; + command[1] = L3GD20H::CTRL_REG_2_VAL; + command[2] = L3GD20H::CTRL_REG_3_VAL; + command[3] = L3GD20H::CTRL_REG_4_VAL; + command[4] = L3GD20H::CTRL_REG_5_VAL; + return buildCommandFromCommand(*id, command, 5); } - case(InternalState::CHECK_REGS): { - *id = L3GD20H::READ_REGS; - return buildCommandFromCommand(*id, nullptr, 0); + case (InternalState::CHECK_REGS): { + *id = L3GD20H::READ_REGS; + return buildCommandFromCommand(*id, nullptr, 0); } default: #if FSFW_CPP_OSTREAM_ENABLED == 1 - /* Might be a configuration error. */ - sif::warning << "GyroL3GD20Handler::buildTransitionDeviceCommand: " - "Unknown internal state!" << std::endl; + /* Might be a configuration error. */ + sif::warning << "GyroL3GD20Handler::buildTransitionDeviceCommand: " + "Unknown internal state!" + << std::endl; #else - sif::printDebug("GyroL3GD20Handler::buildTransitionDeviceCommand: " - "Unknown internal state!\n"); + sif::printDebug( + "GyroL3GD20Handler::buildTransitionDeviceCommand: " + "Unknown internal state!\n"); #endif - return HasReturnvaluesIF::RETURN_OK; - } - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t GyroHandlerL3GD20H::buildNormalDeviceCommand(DeviceCommandId_t *id) { - *id = L3GD20H::READ_REGS; - return buildCommandFromCommand(*id, nullptr, 0); + *id = L3GD20H::READ_REGS; + return buildCommandFromCommand(*id, nullptr, 0); } -ReturnValue_t GyroHandlerL3GD20H::buildCommandFromCommand( - DeviceCommandId_t deviceCommand, const uint8_t *commandData, - size_t commandDataLen) { - switch(deviceCommand) { - case(L3GD20H::READ_REGS): { - commandBuffer[0] = L3GD20H::READ_START | L3GD20H::AUTO_INCREMENT_MASK | L3GD20H::READ_MASK; - std::memset(commandBuffer + 1, 0, L3GD20H::READ_LEN); - rawPacket = commandBuffer; - rawPacketLen = L3GD20H::READ_LEN + 1; - break; +ReturnValue_t GyroHandlerL3GD20H::buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t *commandData, + size_t commandDataLen) { + switch (deviceCommand) { + case (L3GD20H::READ_REGS): { + commandBuffer[0] = L3GD20H::READ_START | L3GD20H::AUTO_INCREMENT_MASK | L3GD20H::READ_MASK; + std::memset(commandBuffer + 1, 0, L3GD20H::READ_LEN); + rawPacket = commandBuffer; + rawPacketLen = L3GD20H::READ_LEN + 1; + break; } - case(L3GD20H::CONFIGURE_CTRL_REGS): { - commandBuffer[0] = L3GD20H::CTRL_REG_1 | L3GD20H::AUTO_INCREMENT_MASK; - if(commandData == nullptr or commandDataLen != 5) { - return DeviceHandlerIF::INVALID_COMMAND_PARAMETER; - } + case (L3GD20H::CONFIGURE_CTRL_REGS): { + commandBuffer[0] = L3GD20H::CTRL_REG_1 | L3GD20H::AUTO_INCREMENT_MASK; + if (commandData == nullptr or commandDataLen != 5) { + return DeviceHandlerIF::INVALID_COMMAND_PARAMETER; + } - ctrlReg1Value = commandData[0]; - ctrlReg2Value = commandData[1]; - ctrlReg3Value = commandData[2]; - ctrlReg4Value = commandData[3]; - ctrlReg5Value = commandData[4]; + ctrlReg1Value = commandData[0]; + ctrlReg2Value = commandData[1]; + ctrlReg3Value = commandData[2]; + ctrlReg4Value = commandData[3]; + ctrlReg5Value = commandData[4]; - bool fsH = ctrlReg4Value & L3GD20H::SET_FS_1; - bool fsL = ctrlReg4Value & L3GD20H::SET_FS_0; + bool fsH = ctrlReg4Value & L3GD20H::SET_FS_1; + bool fsL = ctrlReg4Value & L3GD20H::SET_FS_0; - if(not fsH and not fsL) { - sensitivity = L3GD20H::SENSITIVITY_00; - } - else if(not fsH and fsL) { - sensitivity = L3GD20H::SENSITIVITY_01; - } - else { - sensitivity = L3GD20H::SENSITIVITY_11; - } + if (not fsH and not fsL) { + sensitivity = L3GD20H::SENSITIVITY_00; + } else if (not fsH and fsL) { + sensitivity = L3GD20H::SENSITIVITY_01; + } else { + sensitivity = L3GD20H::SENSITIVITY_11; + } - commandBuffer[1] = ctrlReg1Value; - commandBuffer[2] = ctrlReg2Value; - commandBuffer[3] = ctrlReg3Value; - commandBuffer[4] = ctrlReg4Value; - commandBuffer[5] = ctrlReg5Value; + commandBuffer[1] = ctrlReg1Value; + commandBuffer[2] = ctrlReg2Value; + commandBuffer[3] = ctrlReg3Value; + commandBuffer[4] = ctrlReg4Value; + commandBuffer[5] = ctrlReg5Value; - rawPacket = commandBuffer; - rawPacketLen = 6; - break; + rawPacket = commandBuffer; + rawPacketLen = 6; + break; } - case(L3GD20H::READ_CTRL_REGS): { - commandBuffer[0] = L3GD20H::READ_START | L3GD20H::AUTO_INCREMENT_MASK | - L3GD20H::READ_MASK; + case (L3GD20H::READ_CTRL_REGS): { + commandBuffer[0] = L3GD20H::READ_START | L3GD20H::AUTO_INCREMENT_MASK | L3GD20H::READ_MASK; - std::memset(commandBuffer + 1, 0, 5); - rawPacket = commandBuffer; - rawPacketLen = 6; - break; + std::memset(commandBuffer + 1, 0, 5); + rawPacket = commandBuffer; + rawPacketLen = 6; + break; } default: - return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED; - } - return HasReturnvaluesIF::RETURN_OK; + return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t GyroHandlerL3GD20H::scanForReply(const uint8_t *start, size_t len, - DeviceCommandId_t *foundId, size_t *foundLen) { - // For SPI, the ID will always be the one of the last sent command - *foundId = this->getPendingCommand(); - *foundLen = this->rawPacketLen; + DeviceCommandId_t *foundId, size_t *foundLen) { + // For SPI, the ID will always be the one of the last sent command + *foundId = this->getPendingCommand(); + *foundLen = this->rawPacketLen; - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t GyroHandlerL3GD20H::interpretDeviceReply(DeviceCommandId_t id, - const uint8_t *packet) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - switch(id) { - case(L3GD20H::CONFIGURE_CTRL_REGS): { + const uint8_t *packet) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + switch (id) { + case (L3GD20H::CONFIGURE_CTRL_REGS): { + commandExecuted = true; + break; + } + case (L3GD20H::READ_CTRL_REGS): { + if (packet[1] == ctrlReg1Value and packet[2] == ctrlReg2Value and + packet[3] == ctrlReg3Value and packet[4] == ctrlReg4Value and + packet[5] == ctrlReg5Value) { commandExecuted = true; - break; + } else { + // Attempt reconfiguration + internalState = InternalState::CONFIGURE; + return DeviceHandlerIF::DEVICE_REPLY_INVALID; + } + break; } - case(L3GD20H::READ_CTRL_REGS): { - if(packet[1] == ctrlReg1Value and packet[2] == ctrlReg2Value and - packet[3] == ctrlReg3Value and packet[4] == ctrlReg4Value and - packet[5] == ctrlReg5Value) { - commandExecuted = true; - } - else { - // Attempt reconfiguration - internalState = InternalState::CONFIGURE; - return DeviceHandlerIF::DEVICE_REPLY_INVALID; - } - break; - } - case(L3GD20H::READ_REGS): { - if(packet[1] != ctrlReg1Value and packet[2] != ctrlReg2Value and - packet[3] != ctrlReg3Value and packet[4] != ctrlReg4Value and - packet[5] != ctrlReg5Value) { - return DeviceHandlerIF::DEVICE_REPLY_INVALID; - } - else { - if(internalState == InternalState::CHECK_REGS) { - commandExecuted = true; - } + case (L3GD20H::READ_REGS): { + if (packet[1] != ctrlReg1Value and packet[2] != ctrlReg2Value and + packet[3] != ctrlReg3Value and packet[4] != ctrlReg4Value and + packet[5] != ctrlReg5Value) { + return DeviceHandlerIF::DEVICE_REPLY_INVALID; + } else { + if (internalState == InternalState::CHECK_REGS) { + commandExecuted = true; } + } - statusReg = packet[L3GD20H::STATUS_IDX]; + statusReg = packet[L3GD20H::STATUS_IDX]; - int16_t angVelocXRaw = packet[L3GD20H::OUT_X_H] << 8 | packet[L3GD20H::OUT_X_L]; - int16_t angVelocYRaw = packet[L3GD20H::OUT_Y_H] << 8 | packet[L3GD20H::OUT_Y_L]; - int16_t angVelocZRaw = packet[L3GD20H::OUT_Z_H] << 8 | packet[L3GD20H::OUT_Z_L]; - float angVelocX = angVelocXRaw * sensitivity; - float angVelocY = angVelocYRaw * sensitivity; - float angVelocZ = angVelocZRaw * sensitivity; + int16_t angVelocXRaw = packet[L3GD20H::OUT_X_H] << 8 | packet[L3GD20H::OUT_X_L]; + int16_t angVelocYRaw = packet[L3GD20H::OUT_Y_H] << 8 | packet[L3GD20H::OUT_Y_L]; + int16_t angVelocZRaw = packet[L3GD20H::OUT_Z_H] << 8 | packet[L3GD20H::OUT_Z_L]; + float angVelocX = angVelocXRaw * sensitivity; + float angVelocY = angVelocYRaw * sensitivity; + float angVelocZ = angVelocZRaw * sensitivity; - int8_t temperaturOffset = (-1) * packet[L3GD20H::TEMPERATURE_IDX]; - float temperature = 25.0 + temperaturOffset; + int8_t temperaturOffset = (-1) * packet[L3GD20H::TEMPERATURE_IDX]; + float temperature = 25.0 + temperaturOffset; #if FSFW_HAL_L3GD20_GYRO_DEBUG == 1 - if(debugDivider->checkAndIncrement()) { - /* Set terminal to utf-8 if there is an issue with micro printout. */ + if (debugDivider->checkAndIncrement()) { + /* Set terminal to utf-8 if there is an issue with micro printout. */ #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "GyroHandlerL3GD20H: Angular velocities (deg/s):" << std::endl; - sif::info << "X: " << angVelocX << std::endl; - sif::info << "Y: " << angVelocY << std::endl; - sif::info << "Z: " << angVelocZ << std::endl; + sif::info << "GyroHandlerL3GD20H: Angular velocities (deg/s):" << std::endl; + sif::info << "X: " << angVelocX << std::endl; + sif::info << "Y: " << angVelocY << std::endl; + sif::info << "Z: " << angVelocZ << std::endl; #else - sif::printInfo("GyroHandlerL3GD20H: Angular velocities (deg/s):\n"); - sif::printInfo("X: %f\n", angVelocX); - sif::printInfo("Y: %f\n", angVelocY); - sif::printInfo("Z: %f\n", angVelocZ); + sif::printInfo("GyroHandlerL3GD20H: Angular velocities (deg/s):\n"); + sif::printInfo("X: %f\n", angVelocX); + sif::printInfo("Y: %f\n", angVelocY); + sif::printInfo("Z: %f\n", angVelocZ); #endif - } + } #endif - PoolReadGuard readSet(&dataset); - if(readSet.getReadResult() == HasReturnvaluesIF::RETURN_OK) { - if(std::abs(angVelocX) < this->absLimitX) { - dataset.angVelocX = angVelocX; - dataset.angVelocX.setValid(true); - } - else { - dataset.angVelocX.setValid(false); - } - - if(std::abs(angVelocY) < this->absLimitY) { - dataset.angVelocY = angVelocY; - dataset.angVelocY.setValid(true); - } - else { - dataset.angVelocY.setValid(false); - } - - if(std::abs(angVelocZ) < this->absLimitZ) { - dataset.angVelocZ = angVelocZ; - dataset.angVelocZ.setValid(true); - } - else { - dataset.angVelocZ.setValid(false); - } - - dataset.temperature = temperature; - dataset.temperature.setValid(true); + PoolReadGuard readSet(&dataset); + if (readSet.getReadResult() == HasReturnvaluesIF::RETURN_OK) { + if (std::abs(angVelocX) < this->absLimitX) { + dataset.angVelocX = angVelocX; + dataset.angVelocX.setValid(true); + } else { + dataset.angVelocX.setValid(false); } - break; + + if (std::abs(angVelocY) < this->absLimitY) { + dataset.angVelocY = angVelocY; + dataset.angVelocY.setValid(true); + } else { + dataset.angVelocY.setValid(false); + } + + if (std::abs(angVelocZ) < this->absLimitZ) { + dataset.angVelocZ = angVelocZ; + dataset.angVelocZ.setValid(true); + } else { + dataset.angVelocZ.setValid(false); + } + + dataset.temperature = temperature; + dataset.temperature.setValid(true); + } + break; } default: - return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED; - } - return result; + return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED; + } + return result; } - uint32_t GyroHandlerL3GD20H::getTransitionDelayMs(Mode_t from, Mode_t to) { - return this->transitionDelayMs; + return this->transitionDelayMs; } -void GyroHandlerL3GD20H::setToGoToNormalMode(bool enable) { - this->goNormalModeImmediately = true; -} +void GyroHandlerL3GD20H::setToGoToNormalMode(bool enable) { this->goNormalModeImmediately = true; } -ReturnValue_t GyroHandlerL3GD20H::initializeLocalDataPool( - localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { - localDataPoolMap.emplace(L3GD20H::ANG_VELOC_X, new PoolEntry({0.0})); - localDataPoolMap.emplace(L3GD20H::ANG_VELOC_Y, new PoolEntry({0.0})); - localDataPoolMap.emplace(L3GD20H::ANG_VELOC_Z, new PoolEntry({0.0})); - localDataPoolMap.emplace(L3GD20H::TEMPERATURE, new PoolEntry({0.0})); - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t GyroHandlerL3GD20H::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) { + localDataPoolMap.emplace(L3GD20H::ANG_VELOC_X, new PoolEntry({0.0})); + localDataPoolMap.emplace(L3GD20H::ANG_VELOC_Y, new PoolEntry({0.0})); + localDataPoolMap.emplace(L3GD20H::ANG_VELOC_Z, new PoolEntry({0.0})); + localDataPoolMap.emplace(L3GD20H::TEMPERATURE, new PoolEntry({0.0})); + return HasReturnvaluesIF::RETURN_OK; } void GyroHandlerL3GD20H::fillCommandAndReplyMap() { - insertInCommandAndReplyMap(L3GD20H::READ_REGS, 1, &dataset); - insertInCommandAndReplyMap(L3GD20H::CONFIGURE_CTRL_REGS, 1); - insertInCommandAndReplyMap(L3GD20H::READ_CTRL_REGS, 1); + insertInCommandAndReplyMap(L3GD20H::READ_REGS, 1, &dataset); + insertInCommandAndReplyMap(L3GD20H::CONFIGURE_CTRL_REGS, 1); + insertInCommandAndReplyMap(L3GD20H::READ_CTRL_REGS, 1); } -void GyroHandlerL3GD20H::modeChanged() { - internalState = InternalState::NONE; -} +void GyroHandlerL3GD20H::modeChanged() { internalState = InternalState::NONE; } void GyroHandlerL3GD20H::setAbsoluteLimits(float limitX, float limitY, float limitZ) { - this->absLimitX = limitX; - this->absLimitY = limitY; - this->absLimitZ = limitZ; + this->absLimitX = limitX; + this->absLimitY = limitY; + this->absLimitZ = limitZ; } diff --git a/hal/src/fsfw_hal/devicehandlers/GyroL3GD20Handler.h b/hal/src/fsfw_hal/devicehandlers/GyroL3GD20Handler.h index e73d2fbb..784dcf4c 100644 --- a/hal/src/fsfw_hal/devicehandlers/GyroL3GD20Handler.h +++ b/hal/src/fsfw_hal/devicehandlers/GyroL3GD20Handler.h @@ -1,12 +1,12 @@ #ifndef MISSION_DEVICES_GYROL3GD20HANDLER_H_ #define MISSION_DEVICES_GYROL3GD20HANDLER_H_ -#include "fsfw/FSFW.h" -#include "devicedefinitions/GyroL3GD20Definitions.h" - #include #include +#include "devicedefinitions/GyroL3GD20Definitions.h" +#include "fsfw/FSFW.h" + /** * @brief Device Handler for the L3GD20H gyroscope sensor * (https://www.st.com/en/mems-and-sensors/l3gd20h.html) @@ -16,84 +16,73 @@ * * Data is read big endian with the smallest possible range of 245 degrees per second. */ -class GyroHandlerL3GD20H: public DeviceHandlerBase { -public: - GyroHandlerL3GD20H(object_id_t objectId, object_id_t deviceCommunication, - CookieIF* comCookie, uint32_t transitionDelayMs); - virtual ~GyroHandlerL3GD20H(); +class GyroHandlerL3GD20H : public DeviceHandlerBase { + public: + GyroHandlerL3GD20H(object_id_t objectId, object_id_t deviceCommunication, CookieIF *comCookie, + uint32_t transitionDelayMs); + virtual ~GyroHandlerL3GD20H(); - /** - * Set the absolute limit for the values on the axis in degrees per second. - * The dataset values will be marked as invalid if that limit is exceeded - * @param xLimit - * @param yLimit - * @param zLimit - */ - void setAbsoluteLimits(float limitX, float limitY, float limitZ); + /** + * Set the absolute limit for the values on the axis in degrees per second. + * The dataset values will be marked as invalid if that limit is exceeded + * @param xLimit + * @param yLimit + * @param zLimit + */ + void setAbsoluteLimits(float limitX, float limitY, float limitZ); - /** - * @brief Configure device handler to go to normal mode immediately - */ - void setToGoToNormalMode(bool enable); -protected: + /** + * @brief Configure device handler to go to normal mode immediately + */ + void setToGoToNormalMode(bool enable); - /* DeviceHandlerBase overrides */ - ReturnValue_t buildTransitionDeviceCommand( - DeviceCommandId_t *id) override; - void doStartUp() override; - void doShutDown() override; - ReturnValue_t buildNormalDeviceCommand( - DeviceCommandId_t *id) override; - ReturnValue_t buildCommandFromCommand( - DeviceCommandId_t deviceCommand, const uint8_t *commandData, - size_t commandDataLen) override; - ReturnValue_t scanForReply(const uint8_t *start, size_t len, - DeviceCommandId_t *foundId, size_t *foundLen) override; - virtual ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, - const uint8_t *packet) override; + protected: + /* DeviceHandlerBase overrides */ + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override; + void doStartUp() override; + void doShutDown() override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData, + size_t commandDataLen) override; + ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) override; + virtual ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override; - void fillCommandAndReplyMap() override; - void modeChanged() override; - virtual uint32_t getTransitionDelayMs(Mode_t from, Mode_t to) override; - ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, - LocalDataPoolManager &poolManager) override; + void fillCommandAndReplyMap() override; + void modeChanged() override; + virtual uint32_t getTransitionDelayMs(Mode_t from, Mode_t to) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) override; -private: - uint32_t transitionDelayMs = 0; - GyroPrimaryDataset dataset; + private: + uint32_t transitionDelayMs = 0; + GyroPrimaryDataset dataset; - float absLimitX = L3GD20H::RANGE_DPS_00; - float absLimitY = L3GD20H::RANGE_DPS_00; - float absLimitZ = L3GD20H::RANGE_DPS_00; + float absLimitX = L3GD20H::RANGE_DPS_00; + float absLimitY = L3GD20H::RANGE_DPS_00; + float absLimitZ = L3GD20H::RANGE_DPS_00; - enum class InternalState { - NONE, - CONFIGURE, - CHECK_REGS, - NORMAL - }; - InternalState internalState = InternalState::NONE; - bool commandExecuted = false; + enum class InternalState { NONE, CONFIGURE, CHECK_REGS, NORMAL }; + InternalState internalState = InternalState::NONE; + bool commandExecuted = false; - uint8_t statusReg = 0; - bool goNormalModeImmediately = false; + uint8_t statusReg = 0; + bool goNormalModeImmediately = false; - uint8_t ctrlReg1Value = L3GD20H::CTRL_REG_1_VAL; - uint8_t ctrlReg2Value = L3GD20H::CTRL_REG_2_VAL; - uint8_t ctrlReg3Value = L3GD20H::CTRL_REG_3_VAL; - uint8_t ctrlReg4Value = L3GD20H::CTRL_REG_4_VAL; - uint8_t ctrlReg5Value = L3GD20H::CTRL_REG_5_VAL; + uint8_t ctrlReg1Value = L3GD20H::CTRL_REG_1_VAL; + uint8_t ctrlReg2Value = L3GD20H::CTRL_REG_2_VAL; + uint8_t ctrlReg3Value = L3GD20H::CTRL_REG_3_VAL; + uint8_t ctrlReg4Value = L3GD20H::CTRL_REG_4_VAL; + uint8_t ctrlReg5Value = L3GD20H::CTRL_REG_5_VAL; - uint8_t commandBuffer[L3GD20H::READ_LEN + 1]; + uint8_t commandBuffer[L3GD20H::READ_LEN + 1]; - // Set default value - float sensitivity = L3GD20H::SENSITIVITY_00; + // Set default value + float sensitivity = L3GD20H::SENSITIVITY_00; #if FSFW_HAL_L3GD20_GYRO_DEBUG == 1 - PeriodicOperationDivider* debugDivider = nullptr; + PeriodicOperationDivider *debugDivider = nullptr; #endif }; - - #endif /* MISSION_DEVICES_GYROL3GD20HANDLER_H_ */ diff --git a/hal/src/fsfw_hal/devicehandlers/MgmLIS3MDLHandler.cpp b/hal/src/fsfw_hal/devicehandlers/MgmLIS3MDLHandler.cpp index 1a61bfe2..f3ea9942 100644 --- a/hal/src/fsfw_hal/devicehandlers/MgmLIS3MDLHandler.cpp +++ b/hal/src/fsfw_hal/devicehandlers/MgmLIS3MDLHandler.cpp @@ -8,513 +8,477 @@ #include MgmLIS3MDLHandler::MgmLIS3MDLHandler(object_id_t objectId, object_id_t deviceCommunication, - CookieIF* comCookie, uint32_t transitionDelay): - DeviceHandlerBase(objectId, deviceCommunication, comCookie), - dataset(this), transitionDelay(transitionDelay) { + CookieIF *comCookie, uint32_t transitionDelay) + : DeviceHandlerBase(objectId, deviceCommunication, comCookie), + dataset(this), + transitionDelay(transitionDelay) { #if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1 - debugDivider = new PeriodicOperationDivider(3); + debugDivider = new PeriodicOperationDivider(3); #endif - // Set to default values right away - registers[0] = MGMLIS3MDL::CTRL_REG1_DEFAULT; - registers[1] = MGMLIS3MDL::CTRL_REG2_DEFAULT; - registers[2] = MGMLIS3MDL::CTRL_REG3_DEFAULT; - registers[3] = MGMLIS3MDL::CTRL_REG4_DEFAULT; - registers[4] = MGMLIS3MDL::CTRL_REG5_DEFAULT; - -} - -MgmLIS3MDLHandler::~MgmLIS3MDLHandler() { + // Set to default values right away + registers[0] = MGMLIS3MDL::CTRL_REG1_DEFAULT; + registers[1] = MGMLIS3MDL::CTRL_REG2_DEFAULT; + registers[2] = MGMLIS3MDL::CTRL_REG3_DEFAULT; + registers[3] = MGMLIS3MDL::CTRL_REG4_DEFAULT; + registers[4] = MGMLIS3MDL::CTRL_REG5_DEFAULT; } +MgmLIS3MDLHandler::~MgmLIS3MDLHandler() {} void MgmLIS3MDLHandler::doStartUp() { - switch (internalState) { - case(InternalState::STATE_NONE): { - internalState = InternalState::STATE_FIRST_CONTACT; - break; + switch (internalState) { + case (InternalState::STATE_NONE): { + internalState = InternalState::STATE_FIRST_CONTACT; + break; } - case(InternalState::STATE_FIRST_CONTACT): { - /* Will be set by checking device ID (WHO AM I register) */ - if(commandExecuted) { - commandExecuted = false; - internalState = InternalState::STATE_SETUP; + case (InternalState::STATE_FIRST_CONTACT): { + /* Will be set by checking device ID (WHO AM I register) */ + if (commandExecuted) { + commandExecuted = false; + internalState = InternalState::STATE_SETUP; + } + break; + } + case (InternalState::STATE_SETUP): { + internalState = InternalState::STATE_CHECK_REGISTERS; + break; + } + case (InternalState::STATE_CHECK_REGISTERS): { + /* Set up cached registers which will be used to configure the MGM. */ + if (commandExecuted) { + commandExecuted = false; + if (goToNormalMode) { + setMode(MODE_NORMAL); + } else { + setMode(_MODE_TO_ON); } - break; - } - case(InternalState::STATE_SETUP): { - internalState = InternalState::STATE_CHECK_REGISTERS; - break; - } - case(InternalState::STATE_CHECK_REGISTERS): { - /* Set up cached registers which will be used to configure the MGM. */ - if(commandExecuted) { - commandExecuted = false; - if(goToNormalMode) { - setMode(MODE_NORMAL); - } - else { - setMode(_MODE_TO_ON); - } - } - break; + } + break; } default: - break; - } - + break; + } } -void MgmLIS3MDLHandler::doShutDown() { - setMode(_MODE_POWER_DOWN); -} +void MgmLIS3MDLHandler::doShutDown() { setMode(_MODE_POWER_DOWN); } -ReturnValue_t MgmLIS3MDLHandler::buildTransitionDeviceCommand( - DeviceCommandId_t *id) { - switch (internalState) { - case(InternalState::STATE_NONE): - case(InternalState::STATE_NORMAL): { - return DeviceHandlerBase::NOTHING_TO_SEND; +ReturnValue_t MgmLIS3MDLHandler::buildTransitionDeviceCommand(DeviceCommandId_t *id) { + switch (internalState) { + case (InternalState::STATE_NONE): + case (InternalState::STATE_NORMAL): { + return DeviceHandlerBase::NOTHING_TO_SEND; } - case(InternalState::STATE_FIRST_CONTACT): { - *id = MGMLIS3MDL::IDENTIFY_DEVICE; - break; + case (InternalState::STATE_FIRST_CONTACT): { + *id = MGMLIS3MDL::IDENTIFY_DEVICE; + break; } - case(InternalState::STATE_SETUP): { - *id = MGMLIS3MDL::SETUP_MGM; - break; + case (InternalState::STATE_SETUP): { + *id = MGMLIS3MDL::SETUP_MGM; + break; } - case(InternalState::STATE_CHECK_REGISTERS): { - *id = MGMLIS3MDL::READ_CONFIG_AND_DATA; - break; + case (InternalState::STATE_CHECK_REGISTERS): { + *id = MGMLIS3MDL::READ_CONFIG_AND_DATA; + break; } default: { - /* might be a configuration error. */ + /* might be a configuration error. */ #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "GyroHandler::buildTransitionDeviceCommand: Unknown internal state!" << - std::endl; + sif::warning << "GyroHandler::buildTransitionDeviceCommand: Unknown internal state!" + << std::endl; #else - sif::printWarning("GyroHandler::buildTransitionDeviceCommand: Unknown internal state!\n"); + sif::printWarning("GyroHandler::buildTransitionDeviceCommand: Unknown internal state!\n"); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } - - } - return buildCommandFromCommand(*id, NULL, 0); + } + return buildCommandFromCommand(*id, NULL, 0); } uint8_t MgmLIS3MDLHandler::readCommand(uint8_t command, bool continuousCom) { - command |= (1 << MGMLIS3MDL::RW_BIT); - if (continuousCom == true) { - command |= (1 << MGMLIS3MDL::MS_BIT); - } - return command; + command |= (1 << MGMLIS3MDL::RW_BIT); + if (continuousCom == true) { + command |= (1 << MGMLIS3MDL::MS_BIT); + } + return command; } uint8_t MgmLIS3MDLHandler::writeCommand(uint8_t command, bool continuousCom) { - command &= ~(1 << MGMLIS3MDL::RW_BIT); - if (continuousCom == true) { - command |= (1 << MGMLIS3MDL::MS_BIT); - } - return command; + command &= ~(1 << MGMLIS3MDL::RW_BIT); + if (continuousCom == true) { + command |= (1 << MGMLIS3MDL::MS_BIT); + } + return command; } void MgmLIS3MDLHandler::setupMgm() { + registers[0] = MGMLIS3MDL::CTRL_REG1_DEFAULT; + registers[1] = MGMLIS3MDL::CTRL_REG2_DEFAULT; + registers[2] = MGMLIS3MDL::CTRL_REG3_DEFAULT; + registers[3] = MGMLIS3MDL::CTRL_REG4_DEFAULT; + registers[4] = MGMLIS3MDL::CTRL_REG5_DEFAULT; - registers[0] = MGMLIS3MDL::CTRL_REG1_DEFAULT; - registers[1] = MGMLIS3MDL::CTRL_REG2_DEFAULT; - registers[2] = MGMLIS3MDL::CTRL_REG3_DEFAULT; - registers[3] = MGMLIS3MDL::CTRL_REG4_DEFAULT; - registers[4] = MGMLIS3MDL::CTRL_REG5_DEFAULT; - - prepareCtrlRegisterWrite(); + prepareCtrlRegisterWrite(); } -ReturnValue_t MgmLIS3MDLHandler::buildNormalDeviceCommand( - DeviceCommandId_t *id) { - // Data/config register will be read in an alternating manner. - if(communicationStep == CommunicationStep::DATA) { - *id = MGMLIS3MDL::READ_CONFIG_AND_DATA; - communicationStep = CommunicationStep::TEMPERATURE; - return buildCommandFromCommand(*id, NULL, 0); - } - else { - *id = MGMLIS3MDL::READ_TEMPERATURE; - communicationStep = CommunicationStep::DATA; - return buildCommandFromCommand(*id, NULL, 0); - } - +ReturnValue_t MgmLIS3MDLHandler::buildNormalDeviceCommand(DeviceCommandId_t *id) { + // Data/config register will be read in an alternating manner. + if (communicationStep == CommunicationStep::DATA) { + *id = MGMLIS3MDL::READ_CONFIG_AND_DATA; + communicationStep = CommunicationStep::TEMPERATURE; + return buildCommandFromCommand(*id, NULL, 0); + } else { + *id = MGMLIS3MDL::READ_TEMPERATURE; + communicationStep = CommunicationStep::DATA; + return buildCommandFromCommand(*id, NULL, 0); + } } -ReturnValue_t MgmLIS3MDLHandler::buildCommandFromCommand( - DeviceCommandId_t deviceCommand, const uint8_t *commandData, - size_t commandDataLen) { - switch(deviceCommand) { - case(MGMLIS3MDL::READ_CONFIG_AND_DATA): { - std::memset(commandBuffer, 0, sizeof(commandBuffer)); - commandBuffer[0] = readCommand(MGMLIS3MDL::CTRL_REG1, true); +ReturnValue_t MgmLIS3MDLHandler::buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t *commandData, + size_t commandDataLen) { + switch (deviceCommand) { + case (MGMLIS3MDL::READ_CONFIG_AND_DATA): { + std::memset(commandBuffer, 0, sizeof(commandBuffer)); + commandBuffer[0] = readCommand(MGMLIS3MDL::CTRL_REG1, true); - rawPacket = commandBuffer; - rawPacketLen = MGMLIS3MDL::NR_OF_DATA_AND_CFG_REGISTERS + 1; - return RETURN_OK; + rawPacket = commandBuffer; + rawPacketLen = MGMLIS3MDL::NR_OF_DATA_AND_CFG_REGISTERS + 1; + return RETURN_OK; } - case(MGMLIS3MDL::READ_TEMPERATURE): { - std::memset(commandBuffer, 0, 3); - commandBuffer[0] = readCommand(MGMLIS3MDL::TEMP_LOWBYTE, true); + case (MGMLIS3MDL::READ_TEMPERATURE): { + std::memset(commandBuffer, 0, 3); + commandBuffer[0] = readCommand(MGMLIS3MDL::TEMP_LOWBYTE, true); - rawPacket = commandBuffer; - rawPacketLen = 3; - return RETURN_OK; + rawPacket = commandBuffer; + rawPacketLen = 3; + return RETURN_OK; } - case(MGMLIS3MDL::IDENTIFY_DEVICE): { - return identifyDevice(); + case (MGMLIS3MDL::IDENTIFY_DEVICE): { + return identifyDevice(); } - case(MGMLIS3MDL::TEMP_SENSOR_ENABLE): { - return enableTemperatureSensor(commandData, commandDataLen); + case (MGMLIS3MDL::TEMP_SENSOR_ENABLE): { + return enableTemperatureSensor(commandData, commandDataLen); } - case(MGMLIS3MDL::SETUP_MGM): { - setupMgm(); - return HasReturnvaluesIF::RETURN_OK; + case (MGMLIS3MDL::SETUP_MGM): { + setupMgm(); + return HasReturnvaluesIF::RETURN_OK; } - case(MGMLIS3MDL::ACCURACY_OP_MODE_SET): { - return setOperatingMode(commandData, commandDataLen); + case (MGMLIS3MDL::ACCURACY_OP_MODE_SET): { + return setOperatingMode(commandData, commandDataLen); } default: - return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED; - } - return HasReturnvaluesIF::RETURN_FAILED; + return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED; + } + return HasReturnvaluesIF::RETURN_FAILED; } ReturnValue_t MgmLIS3MDLHandler::identifyDevice() { - uint32_t size = 2; - commandBuffer[0] = readCommand(MGMLIS3MDL::IDENTIFY_DEVICE_REG_ADDR); - commandBuffer[1] = 0x00; + uint32_t size = 2; + commandBuffer[0] = readCommand(MGMLIS3MDL::IDENTIFY_DEVICE_REG_ADDR); + commandBuffer[1] = 0x00; - rawPacket = commandBuffer; - rawPacketLen = size; + rawPacket = commandBuffer; + rawPacketLen = size; - return RETURN_OK; + return RETURN_OK; } -ReturnValue_t MgmLIS3MDLHandler::scanForReply(const uint8_t *start, - size_t len, DeviceCommandId_t *foundId, size_t *foundLen) { +ReturnValue_t MgmLIS3MDLHandler::scanForReply(const uint8_t *start, size_t len, + DeviceCommandId_t *foundId, size_t *foundLen) { + *foundLen = len; + if (len == MGMLIS3MDL::NR_OF_DATA_AND_CFG_REGISTERS + 1) { *foundLen = len; - if (len == MGMLIS3MDL::NR_OF_DATA_AND_CFG_REGISTERS + 1) { - *foundLen = len; - *foundId = MGMLIS3MDL::READ_CONFIG_AND_DATA; - // Check validity by checking config registers - if (start[1] != registers[0] or start[2] != registers[1] or - start[3] != registers[2] or start[4] != registers[3] or - start[5] != registers[4]) { + *foundId = MGMLIS3MDL::READ_CONFIG_AND_DATA; + // Check validity by checking config registers + if (start[1] != registers[0] or start[2] != registers[1] or start[3] != registers[2] or + start[4] != registers[3] or start[5] != registers[4]) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "MGMHandlerLIS3MDL::scanForReply: Invalid registers!" << std::endl; + sif::warning << "MGMHandlerLIS3MDL::scanForReply: Invalid registers!" << std::endl; #else - sif::printWarning("MGMHandlerLIS3MDL::scanForReply: Invalid registers!\n"); + sif::printWarning("MGMHandlerLIS3MDL::scanForReply: Invalid registers!\n"); #endif #endif - return DeviceHandlerIF::INVALID_DATA; - } - if(mode == _MODE_START_UP) { - commandExecuted = true; - } + return DeviceHandlerIF::INVALID_DATA; + } + if (mode == _MODE_START_UP) { + commandExecuted = true; + } - } - else if(len == MGMLIS3MDL::TEMPERATURE_REPLY_LEN) { - *foundLen = len; - *foundId = MGMLIS3MDL::READ_TEMPERATURE; - } - else if (len == MGMLIS3MDL::SETUP_REPLY_LEN) { - *foundLen = len; - *foundId = MGMLIS3MDL::SETUP_MGM; - } - else if (len == SINGLE_COMMAND_ANSWER_LEN) { - *foundLen = len; - *foundId = getPendingCommand(); - if(*foundId == MGMLIS3MDL::IDENTIFY_DEVICE) { - if(start[1] != MGMLIS3MDL::DEVICE_ID) { + } else if (len == MGMLIS3MDL::TEMPERATURE_REPLY_LEN) { + *foundLen = len; + *foundId = MGMLIS3MDL::READ_TEMPERATURE; + } else if (len == MGMLIS3MDL::SETUP_REPLY_LEN) { + *foundLen = len; + *foundId = MGMLIS3MDL::SETUP_MGM; + } else if (len == SINGLE_COMMAND_ANSWER_LEN) { + *foundLen = len; + *foundId = getPendingCommand(); + if (*foundId == MGMLIS3MDL::IDENTIFY_DEVICE) { + if (start[1] != MGMLIS3MDL::DEVICE_ID) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "MGMHandlerLIS3MDL::scanForReply: " - "Device identification failed!" << std::endl; + sif::warning << "MGMHandlerLIS3MDL::scanForReply: " + "Device identification failed!" + << std::endl; #else - sif::printWarning("MGMHandlerLIS3MDL::scanForReply: " - "Device identification failed!\n"); + sif::printWarning( + "MGMHandlerLIS3MDL::scanForReply: " + "Device identification failed!\n"); #endif #endif - return DeviceHandlerIF::INVALID_DATA; - } - - if(mode == _MODE_START_UP) { - commandExecuted = true; - } - } - } - else { return DeviceHandlerIF::INVALID_DATA; - } + } - /* Data with SPI Interface always has this answer */ - if (start[0] == 0b11111111) { - return RETURN_OK; - } - else { - return DeviceHandlerIF::INVALID_DATA; + if (mode == _MODE_START_UP) { + commandExecuted = true; + } } + } else { + return DeviceHandlerIF::INVALID_DATA; + } + /* Data with SPI Interface always has this answer */ + if (start[0] == 0b11111111) { + return RETURN_OK; + } else { + return DeviceHandlerIF::INVALID_DATA; + } } -ReturnValue_t MgmLIS3MDLHandler::interpretDeviceReply(DeviceCommandId_t id, - const uint8_t *packet) { - - switch (id) { +ReturnValue_t MgmLIS3MDLHandler::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) { + switch (id) { case MGMLIS3MDL::IDENTIFY_DEVICE: { - break; + break; } case MGMLIS3MDL::SETUP_MGM: { - break; + break; } case MGMLIS3MDL::READ_CONFIG_AND_DATA: { - // TODO: Store configuration in new local datasets. - float sensitivityFactor = getSensitivityFactor(getSensitivity(registers[2])); + // TODO: Store configuration in new local datasets. + float sensitivityFactor = getSensitivityFactor(getSensitivity(registers[2])); - int16_t mgmMeasurementRawX = packet[MGMLIS3MDL::X_HIGHBYTE_IDX] << 8 - | packet[MGMLIS3MDL::X_LOWBYTE_IDX] ; - int16_t mgmMeasurementRawY = packet[MGMLIS3MDL::Y_HIGHBYTE_IDX] << 8 - | packet[MGMLIS3MDL::Y_LOWBYTE_IDX] ; - int16_t mgmMeasurementRawZ = packet[MGMLIS3MDL::Z_HIGHBYTE_IDX] << 8 - | packet[MGMLIS3MDL::Z_LOWBYTE_IDX] ; + int16_t mgmMeasurementRawX = + packet[MGMLIS3MDL::X_HIGHBYTE_IDX] << 8 | packet[MGMLIS3MDL::X_LOWBYTE_IDX]; + int16_t mgmMeasurementRawY = + packet[MGMLIS3MDL::Y_HIGHBYTE_IDX] << 8 | packet[MGMLIS3MDL::Y_LOWBYTE_IDX]; + int16_t mgmMeasurementRawZ = + packet[MGMLIS3MDL::Z_HIGHBYTE_IDX] << 8 | packet[MGMLIS3MDL::Z_LOWBYTE_IDX]; - /* Target value in microtesla */ - float mgmX = static_cast(mgmMeasurementRawX) * sensitivityFactor - * MGMLIS3MDL::GAUSS_TO_MICROTESLA_FACTOR; - float mgmY = static_cast(mgmMeasurementRawY) * sensitivityFactor - * MGMLIS3MDL::GAUSS_TO_MICROTESLA_FACTOR; - float mgmZ = static_cast(mgmMeasurementRawZ) * sensitivityFactor - * MGMLIS3MDL::GAUSS_TO_MICROTESLA_FACTOR; + /* Target value in microtesla */ + float mgmX = static_cast(mgmMeasurementRawX) * sensitivityFactor * + MGMLIS3MDL::GAUSS_TO_MICROTESLA_FACTOR; + float mgmY = static_cast(mgmMeasurementRawY) * sensitivityFactor * + MGMLIS3MDL::GAUSS_TO_MICROTESLA_FACTOR; + float mgmZ = static_cast(mgmMeasurementRawZ) * sensitivityFactor * + MGMLIS3MDL::GAUSS_TO_MICROTESLA_FACTOR; #if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1 - if(debugDivider->checkAndIncrement()) { + if (debugDivider->checkAndIncrement()) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "MGMHandlerLIS3: Magnetic field strength in" - " microtesla:" << std::endl; - sif::info << "X: " << mgmX << " uT" << std::endl; - sif::info << "Y: " << mgmY << " uT" << std::endl; - sif::info << "Z: " << mgmZ << " uT" << std::endl; + sif::info << "MGMHandlerLIS3: Magnetic field strength in" + " microtesla:" + << std::endl; + sif::info << "X: " << mgmX << " uT" << std::endl; + sif::info << "Y: " << mgmY << " uT" << std::endl; + sif::info << "Z: " << mgmZ << " uT" << std::endl; #else - sif::printInfo("MGMHandlerLIS3: Magnetic field strength in microtesla:\n"); - sif::printInfo("X: %f uT\n", mgmX); - sif::printInfo("Y: %f uT\n", mgmY); - sif::printInfo("Z: %f uT\n", mgmZ); + sif::printInfo("MGMHandlerLIS3: Magnetic field strength in microtesla:\n"); + sif::printInfo("X: %f uT\n", mgmX); + sif::printInfo("Y: %f uT\n", mgmY); + sif::printInfo("Z: %f uT\n", mgmZ); #endif /* FSFW_CPP_OSTREAM_ENABLED == 0 */ - } + } #endif /* OBSW_VERBOSE_LEVEL >= 1 */ - PoolReadGuard readHelper(&dataset); - if(readHelper.getReadResult() == HasReturnvaluesIF::RETURN_OK) { - if(std::abs(mgmX) < absLimitX) { - dataset.fieldStrengthX = mgmX; - dataset.fieldStrengthX.setValid(true); - } - else { - dataset.fieldStrengthX.setValid(false); - } - - if(std::abs(mgmY) < absLimitY) { - dataset.fieldStrengthY = mgmY; - dataset.fieldStrengthY.setValid(true); - } - else { - dataset.fieldStrengthY.setValid(false); - } - - if(std::abs(mgmZ) < absLimitZ) { - dataset.fieldStrengthZ = mgmZ; - dataset.fieldStrengthZ.setValid(true); - } - else { - dataset.fieldStrengthZ.setValid(false); - } + PoolReadGuard readHelper(&dataset); + if (readHelper.getReadResult() == HasReturnvaluesIF::RETURN_OK) { + if (std::abs(mgmX) < absLimitX) { + dataset.fieldStrengthX = mgmX; + dataset.fieldStrengthX.setValid(true); + } else { + dataset.fieldStrengthX.setValid(false); } - break; + + if (std::abs(mgmY) < absLimitY) { + dataset.fieldStrengthY = mgmY; + dataset.fieldStrengthY.setValid(true); + } else { + dataset.fieldStrengthY.setValid(false); + } + + if (std::abs(mgmZ) < absLimitZ) { + dataset.fieldStrengthZ = mgmZ; + dataset.fieldStrengthZ.setValid(true); + } else { + dataset.fieldStrengthZ.setValid(false); + } + } + break; } case MGMLIS3MDL::READ_TEMPERATURE: { - int16_t tempValueRaw = packet[2] << 8 | packet[1]; - float tempValue = 25.0 + ((static_cast(tempValueRaw)) / 8.0); - #if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1 - if(debugDivider->check()) { + int16_t tempValueRaw = packet[2] << 8 | packet[1]; + float tempValue = 25.0 + ((static_cast(tempValueRaw)) / 8.0); +#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1 + if (debugDivider->check()) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "MGMHandlerLIS3: Temperature: " << tempValue << " C" << - std::endl; + sif::info << "MGMHandlerLIS3: Temperature: " << tempValue << " C" << std::endl; #else - sif::printInfo("MGMHandlerLIS3: Temperature: %f C\n"); + sif::printInfo("MGMHandlerLIS3: Temperature: %f C\n"); #endif - } + } #endif - ReturnValue_t result = dataset.read(); - if(result == HasReturnvaluesIF::RETURN_OK) { - dataset.temperature = tempValue; - dataset.commit(); - } - break; + ReturnValue_t result = dataset.read(); + if (result == HasReturnvaluesIF::RETURN_OK) { + dataset.temperature = tempValue; + dataset.commit(); + } + break; } default: { - return DeviceHandlerIF::UNKNOWN_DEVICE_REPLY; + return DeviceHandlerIF::UNKNOWN_DEVICE_REPLY; } - - } - return RETURN_OK; + } + return RETURN_OK; } MGMLIS3MDL::Sensitivies MgmLIS3MDLHandler::getSensitivity(uint8_t ctrlRegister2) { - bool fs0Set = ctrlRegister2 & (1 << MGMLIS3MDL::FSO); // Checks if FS0 bit is set - bool fs1Set = ctrlRegister2 & (1 << MGMLIS3MDL::FS1); // Checks if FS1 bit is set + bool fs0Set = ctrlRegister2 & (1 << MGMLIS3MDL::FSO); // Checks if FS0 bit is set + bool fs1Set = ctrlRegister2 & (1 << MGMLIS3MDL::FS1); // Checks if FS1 bit is set - if (fs0Set && fs1Set) - return MGMLIS3MDL::Sensitivies::GAUSS_16; - else if (!fs0Set && fs1Set) - return MGMLIS3MDL::Sensitivies::GAUSS_12; - else if (fs0Set && !fs1Set) - return MGMLIS3MDL::Sensitivies::GAUSS_8; - else - return MGMLIS3MDL::Sensitivies::GAUSS_4; + if (fs0Set && fs1Set) + return MGMLIS3MDL::Sensitivies::GAUSS_16; + else if (!fs0Set && fs1Set) + return MGMLIS3MDL::Sensitivies::GAUSS_12; + else if (fs0Set && !fs1Set) + return MGMLIS3MDL::Sensitivies::GAUSS_8; + else + return MGMLIS3MDL::Sensitivies::GAUSS_4; } float MgmLIS3MDLHandler::getSensitivityFactor(MGMLIS3MDL::Sensitivies sens) { - switch(sens) { - case(MGMLIS3MDL::GAUSS_4): { - return MGMLIS3MDL::FIELD_LSB_PER_GAUSS_4_SENS; + switch (sens) { + case (MGMLIS3MDL::GAUSS_4): { + return MGMLIS3MDL::FIELD_LSB_PER_GAUSS_4_SENS; } - case(MGMLIS3MDL::GAUSS_8): { - return MGMLIS3MDL::FIELD_LSB_PER_GAUSS_8_SENS; + case (MGMLIS3MDL::GAUSS_8): { + return MGMLIS3MDL::FIELD_LSB_PER_GAUSS_8_SENS; } - case(MGMLIS3MDL::GAUSS_12): { - return MGMLIS3MDL::FIELD_LSB_PER_GAUSS_12_SENS; + case (MGMLIS3MDL::GAUSS_12): { + return MGMLIS3MDL::FIELD_LSB_PER_GAUSS_12_SENS; } - case(MGMLIS3MDL::GAUSS_16): { - return MGMLIS3MDL::FIELD_LSB_PER_GAUSS_16_SENS; + case (MGMLIS3MDL::GAUSS_16): { + return MGMLIS3MDL::FIELD_LSB_PER_GAUSS_16_SENS; } default: { - // Should never happen - return MGMLIS3MDL::FIELD_LSB_PER_GAUSS_4_SENS; - } + // Should never happen + return MGMLIS3MDL::FIELD_LSB_PER_GAUSS_4_SENS; } + } } - -ReturnValue_t MgmLIS3MDLHandler::enableTemperatureSensor( - const uint8_t *commandData, size_t commandDataLen) { - triggerEvent(CHANGE_OF_SETUP_PARAMETER); - uint32_t size = 2; - commandBuffer[0] = writeCommand(MGMLIS3MDL::CTRL_REG1); - if (commandDataLen > 1) { - return INVALID_NUMBER_OR_LENGTH_OF_PARAMETERS; - } - switch (*commandData) { +ReturnValue_t MgmLIS3MDLHandler::enableTemperatureSensor(const uint8_t *commandData, + size_t commandDataLen) { + triggerEvent(CHANGE_OF_SETUP_PARAMETER); + uint32_t size = 2; + commandBuffer[0] = writeCommand(MGMLIS3MDL::CTRL_REG1); + if (commandDataLen > 1) { + return INVALID_NUMBER_OR_LENGTH_OF_PARAMETERS; + } + switch (*commandData) { case (MGMLIS3MDL::ON): { - commandBuffer[1] = registers[0] | (1 << 7); - break; + commandBuffer[1] = registers[0] | (1 << 7); + break; } case (MGMLIS3MDL::OFF): { - commandBuffer[1] = registers[0] & ~(1 << 7); - break; + commandBuffer[1] = registers[0] & ~(1 << 7); + break; } default: - return INVALID_COMMAND_PARAMETER; - } - registers[0] = commandBuffer[1]; + return INVALID_COMMAND_PARAMETER; + } + registers[0] = commandBuffer[1]; - rawPacket = commandBuffer; - rawPacketLen = size; + rawPacket = commandBuffer; + rawPacketLen = size; - return RETURN_OK; + return RETURN_OK; } ReturnValue_t MgmLIS3MDLHandler::setOperatingMode(const uint8_t *commandData, - size_t commandDataLen) { - triggerEvent(CHANGE_OF_SETUP_PARAMETER); - if (commandDataLen != 1) { - return INVALID_NUMBER_OR_LENGTH_OF_PARAMETERS; - } + size_t commandDataLen) { + triggerEvent(CHANGE_OF_SETUP_PARAMETER); + if (commandDataLen != 1) { + return INVALID_NUMBER_OR_LENGTH_OF_PARAMETERS; + } - switch (commandData[0]) { + switch (commandData[0]) { case MGMLIS3MDL::LOW: - registers[0] = (registers[0] & (~(1 << MGMLIS3MDL::OM1))) & (~(1 << MGMLIS3MDL::OM0)); - registers[3] = (registers[3] & (~(1 << MGMLIS3MDL::OMZ1))) & (~(1 << MGMLIS3MDL::OMZ0)); - break; + registers[0] = (registers[0] & (~(1 << MGMLIS3MDL::OM1))) & (~(1 << MGMLIS3MDL::OM0)); + registers[3] = (registers[3] & (~(1 << MGMLIS3MDL::OMZ1))) & (~(1 << MGMLIS3MDL::OMZ0)); + break; case MGMLIS3MDL::MEDIUM: - registers[0] = (registers[0] & (~(1 << MGMLIS3MDL::OM1))) | (1 << MGMLIS3MDL::OM0); - registers[3] = (registers[3] & (~(1 << MGMLIS3MDL::OMZ1))) | (1 << MGMLIS3MDL::OMZ0); - break; + registers[0] = (registers[0] & (~(1 << MGMLIS3MDL::OM1))) | (1 << MGMLIS3MDL::OM0); + registers[3] = (registers[3] & (~(1 << MGMLIS3MDL::OMZ1))) | (1 << MGMLIS3MDL::OMZ0); + break; case MGMLIS3MDL::HIGH: - registers[0] = (registers[0] | (1 << MGMLIS3MDL::OM1)) & (~(1 << MGMLIS3MDL::OM0)); - registers[3] = (registers[3] | (1 << MGMLIS3MDL::OMZ1)) & (~(1 << MGMLIS3MDL::OMZ0)); - break; + registers[0] = (registers[0] | (1 << MGMLIS3MDL::OM1)) & (~(1 << MGMLIS3MDL::OM0)); + registers[3] = (registers[3] | (1 << MGMLIS3MDL::OMZ1)) & (~(1 << MGMLIS3MDL::OMZ0)); + break; case MGMLIS3MDL::ULTRA: - registers[0] = (registers[0] | (1 << MGMLIS3MDL::OM1)) | (1 << MGMLIS3MDL::OM0); - registers[3] = (registers[3] | (1 << MGMLIS3MDL::OMZ1)) | (1 << MGMLIS3MDL::OMZ0); - break; + registers[0] = (registers[0] | (1 << MGMLIS3MDL::OM1)) | (1 << MGMLIS3MDL::OM0); + registers[3] = (registers[3] | (1 << MGMLIS3MDL::OMZ1)) | (1 << MGMLIS3MDL::OMZ0); + break; default: - break; - } + break; + } - return prepareCtrlRegisterWrite(); + return prepareCtrlRegisterWrite(); } void MgmLIS3MDLHandler::fillCommandAndReplyMap() { - insertInCommandAndReplyMap(MGMLIS3MDL::READ_CONFIG_AND_DATA, 1, &dataset); - insertInCommandAndReplyMap(MGMLIS3MDL::READ_TEMPERATURE, 1); - insertInCommandAndReplyMap(MGMLIS3MDL::SETUP_MGM, 1); - insertInCommandAndReplyMap(MGMLIS3MDL::IDENTIFY_DEVICE, 1); - insertInCommandAndReplyMap(MGMLIS3MDL::TEMP_SENSOR_ENABLE, 1); - insertInCommandAndReplyMap(MGMLIS3MDL::ACCURACY_OP_MODE_SET, 1); + insertInCommandAndReplyMap(MGMLIS3MDL::READ_CONFIG_AND_DATA, 1, &dataset); + insertInCommandAndReplyMap(MGMLIS3MDL::READ_TEMPERATURE, 1); + insertInCommandAndReplyMap(MGMLIS3MDL::SETUP_MGM, 1); + insertInCommandAndReplyMap(MGMLIS3MDL::IDENTIFY_DEVICE, 1); + insertInCommandAndReplyMap(MGMLIS3MDL::TEMP_SENSOR_ENABLE, 1); + insertInCommandAndReplyMap(MGMLIS3MDL::ACCURACY_OP_MODE_SET, 1); } -void MgmLIS3MDLHandler::setToGoToNormalMode(bool enable) { - this->goToNormalMode = enable; -} +void MgmLIS3MDLHandler::setToGoToNormalMode(bool enable) { this->goToNormalMode = enable; } ReturnValue_t MgmLIS3MDLHandler::prepareCtrlRegisterWrite() { - commandBuffer[0] = writeCommand(MGMLIS3MDL::CTRL_REG1, true); + commandBuffer[0] = writeCommand(MGMLIS3MDL::CTRL_REG1, true); - for (size_t i = 0; i < MGMLIS3MDL::NR_OF_CTRL_REGISTERS; i++) { - commandBuffer[i + 1] = registers[i]; - } - rawPacket = commandBuffer; - rawPacketLen = MGMLIS3MDL::NR_OF_CTRL_REGISTERS + 1; + for (size_t i = 0; i < MGMLIS3MDL::NR_OF_CTRL_REGISTERS; i++) { + commandBuffer[i + 1] = registers[i]; + } + rawPacket = commandBuffer; + rawPacketLen = MGMLIS3MDL::NR_OF_CTRL_REGISTERS + 1; - // We dont have to check if this is working because we just did i - return RETURN_OK; + // We dont have to check if this is working because we just did i + return RETURN_OK; } -void MgmLIS3MDLHandler::doTransition(Mode_t modeFrom, Submode_t subModeFrom) { +void MgmLIS3MDLHandler::doTransition(Mode_t modeFrom, Submode_t subModeFrom) {} -} +uint32_t MgmLIS3MDLHandler::getTransitionDelayMs(Mode_t from, Mode_t to) { return transitionDelay; } -uint32_t MgmLIS3MDLHandler::getTransitionDelayMs(Mode_t from, Mode_t to) { - return transitionDelay; -} +void MgmLIS3MDLHandler::modeChanged(void) { internalState = InternalState::STATE_NONE; } -void MgmLIS3MDLHandler::modeChanged(void) { - internalState = InternalState::STATE_NONE; -} - -ReturnValue_t MgmLIS3MDLHandler::initializeLocalDataPool( - localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { - localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTH_X, - new PoolEntry({0.0})); - localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTH_Y, - new PoolEntry({0.0})); - localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTH_Z, - new PoolEntry({0.0})); - localDataPoolMap.emplace(MGMLIS3MDL::TEMPERATURE_CELCIUS, - new PoolEntry({0.0})); - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t MgmLIS3MDLHandler::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) { + localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTH_X, new PoolEntry({0.0})); + localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTH_Y, new PoolEntry({0.0})); + localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTH_Z, new PoolEntry({0.0})); + localDataPoolMap.emplace(MGMLIS3MDL::TEMPERATURE_CELCIUS, new PoolEntry({0.0})); + return HasReturnvaluesIF::RETURN_OK; } void MgmLIS3MDLHandler::setAbsoluteLimits(float xLimit, float yLimit, float zLimit) { - this->absLimitX = xLimit; - this->absLimitY = yLimit; - this->absLimitZ = zLimit; + this->absLimitX = xLimit; + this->absLimitY = yLimit; + this->absLimitZ = zLimit; } diff --git a/hal/src/fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h b/hal/src/fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h index 6bf89a49..b7cfc378 100644 --- a/hal/src/fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h +++ b/hal/src/fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h @@ -1,10 +1,9 @@ #ifndef MISSION_DEVICES_MGMLIS3MDLHANDLER_H_ #define MISSION_DEVICES_MGMLIS3MDLHANDLER_H_ -#include "fsfw/FSFW.h" -#include "events/subsystemIdRanges.h" #include "devicedefinitions/MgmLIS3HandlerDefs.h" - +#include "events/subsystemIdRanges.h" +#include "fsfw/FSFW.h" #include "fsfw/devicehandlers/DeviceHandlerBase.h" class PeriodicOperationDivider; @@ -18,168 +17,158 @@ class PeriodicOperationDivider; * https://egit.irs.uni-stuttgart.de/redmine/projects/eive-flight-manual/wiki/LIS3MDL_MGM * @author L. Loidold, R. Mueller */ -class MgmLIS3MDLHandler: public DeviceHandlerBase { -public: - enum class CommunicationStep { - DATA, - TEMPERATURE - }; +class MgmLIS3MDLHandler : public DeviceHandlerBase { + public: + enum class CommunicationStep { DATA, TEMPERATURE }; - static const uint8_t INTERFACE_ID = CLASS_ID::MGM_LIS3MDL; - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::MGM_LIS3MDL; - //Notifies a command to change the setup parameters - static const Event CHANGE_OF_SETUP_PARAMETER = MAKE_EVENT(0, severity::LOW); + static const uint8_t INTERFACE_ID = CLASS_ID::MGM_LIS3MDL; + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::MGM_LIS3MDL; + // Notifies a command to change the setup parameters + static const Event CHANGE_OF_SETUP_PARAMETER = MAKE_EVENT(0, severity::LOW); - MgmLIS3MDLHandler(uint32_t objectId, object_id_t deviceCommunication, CookieIF* comCookie, - uint32_t transitionDelay); - virtual ~MgmLIS3MDLHandler(); + MgmLIS3MDLHandler(uint32_t objectId, object_id_t deviceCommunication, CookieIF *comCookie, + uint32_t transitionDelay); + virtual ~MgmLIS3MDLHandler(); - /** - * Set the absolute limit for the values on the axis in microtesla. The dataset values will - * be marked as invalid if that limit is exceeded - * @param xLimit - * @param yLimit - * @param zLimit - */ - void setAbsoluteLimits(float xLimit, float yLimit, float zLimit); - void setToGoToNormalMode(bool enable); + /** + * Set the absolute limit for the values on the axis in microtesla. The dataset values will + * be marked as invalid if that limit is exceeded + * @param xLimit + * @param yLimit + * @param zLimit + */ + void setAbsoluteLimits(float xLimit, float yLimit, float zLimit); + void setToGoToNormalMode(bool enable); -protected: + protected: + /** DeviceHandlerBase overrides */ + void doShutDown() override; + void doStartUp() override; + void doTransition(Mode_t modeFrom, Submode_t subModeFrom) override; + virtual uint32_t getTransitionDelayMs(Mode_t from, Mode_t to) override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData, + size_t commandDataLen) override; + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) override; + /** + * This implementation is tailored towards space applications and will flag values larger + * than 100 microtesla on X,Y and 150 microtesla on Z as invalid + * @param id + * @param packet + * @return + */ + virtual ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override; + void fillCommandAndReplyMap() override; + void modeChanged(void) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) override; - /** DeviceHandlerBase overrides */ - void doShutDown() override; - void doStartUp() override; - void doTransition(Mode_t modeFrom, Submode_t subModeFrom) override; - virtual uint32_t getTransitionDelayMs(Mode_t from, Mode_t to) override; - ReturnValue_t buildCommandFromCommand( - DeviceCommandId_t deviceCommand, const uint8_t *commandData, - size_t commandDataLen) override; - ReturnValue_t buildTransitionDeviceCommand( - DeviceCommandId_t *id) override; - ReturnValue_t buildNormalDeviceCommand( - DeviceCommandId_t *id) override; - ReturnValue_t scanForReply(const uint8_t *start, size_t len, - DeviceCommandId_t *foundId, size_t *foundLen) override; - /** - * This implementation is tailored towards space applications and will flag values larger - * than 100 microtesla on X,Y and 150 microtesla on Z as invalid - * @param id - * @param packet - * @return - */ - virtual ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, - const uint8_t *packet) override; - void fillCommandAndReplyMap() override; - void modeChanged(void) override; - ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, - LocalDataPoolManager &poolManager) override; + private: + MGMLIS3MDL::MgmPrimaryDataset dataset; + // Length a single command SPI answer + static const uint8_t SINGLE_COMMAND_ANSWER_LEN = 2; -private: - MGMLIS3MDL::MgmPrimaryDataset dataset; - //Length a single command SPI answer - static const uint8_t SINGLE_COMMAND_ANSWER_LEN = 2; + uint32_t transitionDelay; + // Single SPI command has 2 bytes, first for adress, second for content + size_t singleComandSize = 2; + // Has the size for all adresses of the lis3mdl + the continous write bit + uint8_t commandBuffer[MGMLIS3MDL::NR_OF_DATA_AND_CFG_REGISTERS + 1]; - uint32_t transitionDelay; - // Single SPI command has 2 bytes, first for adress, second for content - size_t singleComandSize = 2; - // Has the size for all adresses of the lis3mdl + the continous write bit - uint8_t commandBuffer[MGMLIS3MDL::NR_OF_DATA_AND_CFG_REGISTERS + 1]; + float absLimitX = 100; + float absLimitY = 100; + float absLimitZ = 150; - float absLimitX = 100; - float absLimitY = 100; - float absLimitZ = 150; + /** + * We want to save the registers we set, so we dont have to read the + * registers when we want to change something. + * --> everytime we change set a register we have to save it + */ + uint8_t registers[MGMLIS3MDL::NR_OF_CTRL_REGISTERS]; - /** - * We want to save the registers we set, so we dont have to read the - * registers when we want to change something. - * --> everytime we change set a register we have to save it - */ - uint8_t registers[MGMLIS3MDL::NR_OF_CTRL_REGISTERS]; + uint8_t statusRegister = 0; + bool goToNormalMode = false; - uint8_t statusRegister = 0; - bool goToNormalMode = false; + enum class InternalState { + STATE_NONE, + STATE_FIRST_CONTACT, + STATE_SETUP, + STATE_CHECK_REGISTERS, + STATE_NORMAL + }; - enum class InternalState { - STATE_NONE, - STATE_FIRST_CONTACT, - STATE_SETUP, - STATE_CHECK_REGISTERS, - STATE_NORMAL - }; + InternalState internalState = InternalState::STATE_NONE; + CommunicationStep communicationStep = CommunicationStep::DATA; + bool commandExecuted = false; - InternalState internalState = InternalState::STATE_NONE; - CommunicationStep communicationStep = CommunicationStep::DATA; - bool commandExecuted = false; + /*------------------------------------------------------------------------*/ + /* Device specific commands and variables */ + /*------------------------------------------------------------------------*/ + /** + * Sets the read bit for the command + * @param single command to set the read-bit at + * @param boolean to select a continuous read bit, default = false + */ + uint8_t readCommand(uint8_t command, bool continuousCom = false); - /*------------------------------------------------------------------------*/ - /* Device specific commands and variables */ - /*------------------------------------------------------------------------*/ - /** - * Sets the read bit for the command - * @param single command to set the read-bit at - * @param boolean to select a continuous read bit, default = false - */ - uint8_t readCommand(uint8_t command, bool continuousCom = false); + /** + * Sets the write bit for the command + * @param single command to set the write-bit at + * @param boolean to select a continuous write bit, default = false + */ + uint8_t writeCommand(uint8_t command, bool continuousCom = false); - /** - * Sets the write bit for the command - * @param single command to set the write-bit at - * @param boolean to select a continuous write bit, default = false - */ - uint8_t writeCommand(uint8_t command, bool continuousCom = false); + /** + * This Method gets the full scale for the measurement range + * e.g.: +- 4 gauss. See p.25 datasheet. + * @return The ReturnValue does not contain the sign of the value + */ + MGMLIS3MDL::Sensitivies getSensitivity(uint8_t ctrlReg2); - /** - * This Method gets the full scale for the measurement range - * e.g.: +- 4 gauss. See p.25 datasheet. - * @return The ReturnValue does not contain the sign of the value - */ - MGMLIS3MDL::Sensitivies getSensitivity(uint8_t ctrlReg2); + /** + * The 16 bit value needs to be multiplied with a sensitivity factor + * which depends on the sensitivity configuration + * + * @param sens Configured sensitivity of the LIS3 device + * @return Multiplication factor to get the sensor value from raw data. + */ + float getSensitivityFactor(MGMLIS3MDL::Sensitivies sens); - /** - * The 16 bit value needs to be multiplied with a sensitivity factor - * which depends on the sensitivity configuration - * - * @param sens Configured sensitivity of the LIS3 device - * @return Multiplication factor to get the sensor value from raw data. - */ - float getSensitivityFactor(MGMLIS3MDL::Sensitivies sens); + /** + * This Command detects the device ID + */ + ReturnValue_t identifyDevice(); - /** - * This Command detects the device ID - */ - ReturnValue_t identifyDevice(); + virtual void setupMgm(); - virtual void setupMgm(); + /*------------------------------------------------------------------------*/ + /* Non normal commands */ + /*------------------------------------------------------------------------*/ + /** + * Enables/Disables the integrated Temperaturesensor + * @param commandData On or Off + * @param length of the commandData: has to be 1 + */ + virtual ReturnValue_t enableTemperatureSensor(const uint8_t *commandData, size_t commandDataLen); - /*------------------------------------------------------------------------*/ - /* Non normal commands */ - /*------------------------------------------------------------------------*/ - /** - * Enables/Disables the integrated Temperaturesensor - * @param commandData On or Off - * @param length of the commandData: has to be 1 - */ - virtual ReturnValue_t enableTemperatureSensor(const uint8_t *commandData, - size_t commandDataLen); + /** + * Sets the accuracy of the measurement of the axis. The noise is changing. + * @param commandData LOW, MEDIUM, HIGH, ULTRA + * @param length of the command, has to be 1 + */ + virtual ReturnValue_t setOperatingMode(const uint8_t *commandData, size_t commandDataLen); - /** - * Sets the accuracy of the measurement of the axis. The noise is changing. - * @param commandData LOW, MEDIUM, HIGH, ULTRA - * @param length of the command, has to be 1 - */ - virtual ReturnValue_t setOperatingMode(const uint8_t *commandData, - size_t commandDataLen); - - /** - * We always update all registers together, so this method updates - * the rawpacket and rawpacketLen, so we just manipulate the local - * saved register - * - */ - ReturnValue_t prepareCtrlRegisterWrite(); + /** + * We always update all registers together, so this method updates + * the rawpacket and rawpacketLen, so we just manipulate the local + * saved register + * + */ + ReturnValue_t prepareCtrlRegisterWrite(); #if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1 - PeriodicOperationDivider* debugDivider; + PeriodicOperationDivider *debugDivider; #endif }; diff --git a/hal/src/fsfw_hal/devicehandlers/MgmRM3100Handler.cpp b/hal/src/fsfw_hal/devicehandlers/MgmRM3100Handler.cpp index db4ea607..4c6e09b1 100644 --- a/hal/src/fsfw_hal/devicehandlers/MgmRM3100Handler.cpp +++ b/hal/src/fsfw_hal/devicehandlers/MgmRM3100Handler.cpp @@ -1,376 +1,367 @@ #include "MgmRM3100Handler.h" #include "fsfw/datapool/PoolReadGuard.h" -#include "fsfw/globalfunctions/bitutility.h" #include "fsfw/devicehandlers/DeviceHandlerMessage.h" +#include "fsfw/globalfunctions/bitutility.h" #include "fsfw/objectmanager/SystemObjectIF.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" - -MgmRM3100Handler::MgmRM3100Handler(object_id_t objectId, - object_id_t deviceCommunication, CookieIF* comCookie, uint32_t transitionDelay): - DeviceHandlerBase(objectId, deviceCommunication, comCookie), - primaryDataset(this), transitionDelay(transitionDelay) { +MgmRM3100Handler::MgmRM3100Handler(object_id_t objectId, object_id_t deviceCommunication, + CookieIF *comCookie, uint32_t transitionDelay) + : DeviceHandlerBase(objectId, deviceCommunication, comCookie), + primaryDataset(this), + transitionDelay(transitionDelay) { #if FSFW_HAL_RM3100_MGM_DEBUG == 1 - debugDivider = new PeriodicOperationDivider(3); + debugDivider = new PeriodicOperationDivider(3); #endif } MgmRM3100Handler::~MgmRM3100Handler() {} void MgmRM3100Handler::doStartUp() { - switch(internalState) { - case(InternalState::NONE): { - internalState = InternalState::CONFIGURE_CMM; - break; + switch (internalState) { + case (InternalState::NONE): { + internalState = InternalState::CONFIGURE_CMM; + break; } - case(InternalState::CONFIGURE_CMM): { - internalState = InternalState::READ_CMM; - break; + case (InternalState::CONFIGURE_CMM): { + internalState = InternalState::READ_CMM; + break; } - case(InternalState::READ_CMM): { - if(commandExecuted) { - internalState = InternalState::STATE_CONFIGURE_TMRC; + case (InternalState::READ_CMM): { + if (commandExecuted) { + internalState = InternalState::STATE_CONFIGURE_TMRC; + } + break; + } + case (InternalState::STATE_CONFIGURE_TMRC): { + if (commandExecuted) { + internalState = InternalState::STATE_READ_TMRC; + } + break; + } + case (InternalState::STATE_READ_TMRC): { + if (commandExecuted) { + internalState = InternalState::NORMAL; + if (goToNormalModeAtStartup) { + setMode(MODE_NORMAL); + } else { + setMode(_MODE_TO_ON); } - break; - } - case(InternalState::STATE_CONFIGURE_TMRC): { - if(commandExecuted) { - internalState = InternalState::STATE_READ_TMRC; - } - break; - } - case(InternalState::STATE_READ_TMRC): { - if(commandExecuted) { - internalState = InternalState::NORMAL; - if(goToNormalModeAtStartup) { - setMode(MODE_NORMAL); - } - else { - setMode(_MODE_TO_ON); - } - } - break; + } + break; } default: { - break; - } + break; } + } } -void MgmRM3100Handler::doShutDown() { - setMode(_MODE_POWER_DOWN); -} +void MgmRM3100Handler::doShutDown() { setMode(_MODE_POWER_DOWN); } -ReturnValue_t MgmRM3100Handler::buildTransitionDeviceCommand( - DeviceCommandId_t *id) { - size_t commandLen = 0; - switch(internalState) { - case(InternalState::NONE): - case(InternalState::NORMAL): { - return NOTHING_TO_SEND; +ReturnValue_t MgmRM3100Handler::buildTransitionDeviceCommand(DeviceCommandId_t *id) { + size_t commandLen = 0; + switch (internalState) { + case (InternalState::NONE): + case (InternalState::NORMAL): { + return NOTHING_TO_SEND; } - case(InternalState::CONFIGURE_CMM): { - *id = RM3100::CONFIGURE_CMM; - break; + case (InternalState::CONFIGURE_CMM): { + *id = RM3100::CONFIGURE_CMM; + break; } - case(InternalState::READ_CMM): { - *id = RM3100::READ_CMM; - break; + case (InternalState::READ_CMM): { + *id = RM3100::READ_CMM; + break; } - case(InternalState::STATE_CONFIGURE_TMRC): { - commandBuffer[0] = RM3100::TMRC_DEFAULT_VALUE; - commandLen = 1; - *id = RM3100::CONFIGURE_TMRC; - break; + case (InternalState::STATE_CONFIGURE_TMRC): { + commandBuffer[0] = RM3100::TMRC_DEFAULT_VALUE; + commandLen = 1; + *id = RM3100::CONFIGURE_TMRC; + break; } - case(InternalState::STATE_READ_TMRC): { - *id = RM3100::READ_TMRC; - break; + case (InternalState::STATE_READ_TMRC): { + *id = RM3100::READ_TMRC; + break; } default: #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - // Might be a configuration error - sif::warning << "MgmRM3100Handler::buildTransitionDeviceCommand: " - "Unknown internal state" << std::endl; + // Might be a configuration error + sif::warning << "MgmRM3100Handler::buildTransitionDeviceCommand: " + "Unknown internal state" + << std::endl; #else - sif::printWarning("MgmRM3100Handler::buildTransitionDeviceCommand: " - "Unknown internal state\n"); + sif::printWarning( + "MgmRM3100Handler::buildTransitionDeviceCommand: " + "Unknown internal state\n"); #endif #endif - return HasReturnvaluesIF::RETURN_OK; - } + return HasReturnvaluesIF::RETURN_OK; + } - return buildCommandFromCommand(*id, commandBuffer, commandLen); + return buildCommandFromCommand(*id, commandBuffer, commandLen); } ReturnValue_t MgmRM3100Handler::buildCommandFromCommand(DeviceCommandId_t deviceCommand, - const uint8_t *commandData, size_t commandDataLen) { - switch(deviceCommand) { - case(RM3100::CONFIGURE_CMM): { - commandBuffer[0] = RM3100::CMM_REGISTER; - commandBuffer[1] = RM3100::CMM_VALUE; - rawPacket = commandBuffer; - rawPacketLen = 2; - break; + const uint8_t *commandData, + size_t commandDataLen) { + switch (deviceCommand) { + case (RM3100::CONFIGURE_CMM): { + commandBuffer[0] = RM3100::CMM_REGISTER; + commandBuffer[1] = RM3100::CMM_VALUE; + rawPacket = commandBuffer; + rawPacketLen = 2; + break; } - case(RM3100::READ_CMM): { - commandBuffer[0] = RM3100::CMM_REGISTER | RM3100::READ_MASK; - commandBuffer[1] = 0; - rawPacket = commandBuffer; - rawPacketLen = 2; - break; + case (RM3100::READ_CMM): { + commandBuffer[0] = RM3100::CMM_REGISTER | RM3100::READ_MASK; + commandBuffer[1] = 0; + rawPacket = commandBuffer; + rawPacketLen = 2; + break; } - case(RM3100::CONFIGURE_TMRC): { - return handleTmrcConfigCommand(deviceCommand, commandData, commandDataLen); + case (RM3100::CONFIGURE_TMRC): { + return handleTmrcConfigCommand(deviceCommand, commandData, commandDataLen); } - case(RM3100::READ_TMRC): { - commandBuffer[0] = RM3100::TMRC_REGISTER | RM3100::READ_MASK; - commandBuffer[1] = 0; - rawPacket = commandBuffer; - rawPacketLen = 2; - break; + case (RM3100::READ_TMRC): { + commandBuffer[0] = RM3100::TMRC_REGISTER | RM3100::READ_MASK; + commandBuffer[1] = 0; + rawPacket = commandBuffer; + rawPacketLen = 2; + break; } - case(RM3100::CONFIGURE_CYCLE_COUNT): { - return handleCycleCountConfigCommand(deviceCommand, commandData, commandDataLen); + case (RM3100::CONFIGURE_CYCLE_COUNT): { + return handleCycleCountConfigCommand(deviceCommand, commandData, commandDataLen); } - case(RM3100::READ_CYCLE_COUNT): { - commandBuffer[0] = RM3100::CYCLE_COUNT_START_REGISTER | RM3100::READ_MASK; - std::memset(commandBuffer + 1, 0, 6); - rawPacket = commandBuffer; - rawPacketLen = 7; - break; + case (RM3100::READ_CYCLE_COUNT): { + commandBuffer[0] = RM3100::CYCLE_COUNT_START_REGISTER | RM3100::READ_MASK; + std::memset(commandBuffer + 1, 0, 6); + rawPacket = commandBuffer; + rawPacketLen = 7; + break; } - case(RM3100::READ_DATA): { - commandBuffer[0] = RM3100::MEASUREMENT_REG_START | RM3100::READ_MASK; - std::memset(commandBuffer + 1, 0, 9); - rawPacketLen = 10; - break; + case (RM3100::READ_DATA): { + commandBuffer[0] = RM3100::MEASUREMENT_REG_START | RM3100::READ_MASK; + std::memset(commandBuffer + 1, 0, 9); + rawPacketLen = 10; + break; } default: - return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED; - } - return RETURN_OK; + return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED; + } + return RETURN_OK; } -ReturnValue_t MgmRM3100Handler::buildNormalDeviceCommand( - DeviceCommandId_t *id) { - *id = RM3100::READ_DATA; - return buildCommandFromCommand(*id, nullptr, 0); +ReturnValue_t MgmRM3100Handler::buildNormalDeviceCommand(DeviceCommandId_t *id) { + *id = RM3100::READ_DATA; + return buildCommandFromCommand(*id, nullptr, 0); } -ReturnValue_t MgmRM3100Handler::scanForReply(const uint8_t *start, - size_t len, DeviceCommandId_t *foundId, - size_t *foundLen) { - - // For SPI, ID will always be the one of the last sent command - *foundId = this->getPendingCommand(); - *foundLen = len; - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t MgmRM3100Handler::scanForReply(const uint8_t *start, size_t len, + DeviceCommandId_t *foundId, size_t *foundLen) { + // For SPI, ID will always be the one of the last sent command + *foundId = this->getPendingCommand(); + *foundLen = len; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t MgmRM3100Handler::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - switch(id) { - case(RM3100::CONFIGURE_CMM): - case(RM3100::CONFIGURE_CYCLE_COUNT): - case(RM3100::CONFIGURE_TMRC): { - // We can only check whether write was successful with read operation - if(mode == _MODE_START_UP) { - commandExecuted = true; - } - break; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + switch (id) { + case (RM3100::CONFIGURE_CMM): + case (RM3100::CONFIGURE_CYCLE_COUNT): + case (RM3100::CONFIGURE_TMRC): { + // We can only check whether write was successful with read operation + if (mode == _MODE_START_UP) { + commandExecuted = true; + } + break; } - case(RM3100::READ_CMM): { - uint8_t cmmValue = packet[1]; - // We clear the seventh bit in any case - // because this one is zero sometimes for some reason - bitutil::clear(&cmmValue, 6); - if(cmmValue == cmmRegValue and internalState == InternalState::READ_CMM) { - commandExecuted = true; - } - else { - // Attempt reconfiguration - internalState = InternalState::CONFIGURE_CMM; - return DeviceHandlerIF::DEVICE_REPLY_INVALID; - } - break; + case (RM3100::READ_CMM): { + uint8_t cmmValue = packet[1]; + // We clear the seventh bit in any case + // because this one is zero sometimes for some reason + bitutil::clear(&cmmValue, 6); + if (cmmValue == cmmRegValue and internalState == InternalState::READ_CMM) { + commandExecuted = true; + } else { + // Attempt reconfiguration + internalState = InternalState::CONFIGURE_CMM; + return DeviceHandlerIF::DEVICE_REPLY_INVALID; + } + break; } - case(RM3100::READ_TMRC): { - if(packet[1] == tmrcRegValue) { - commandExecuted = true; - // Reading TMRC was commanded. Trigger event to inform ground - if(mode != _MODE_START_UP) { - triggerEvent(tmrcSet, tmrcRegValue, 0); - } - } - else { - // Attempt reconfiguration - internalState = InternalState::STATE_CONFIGURE_TMRC; - return DeviceHandlerIF::DEVICE_REPLY_INVALID; - } - break; - } - case(RM3100::READ_CYCLE_COUNT): { - uint16_t cycleCountX = packet[1] << 8 | packet[2]; - uint16_t cycleCountY = packet[3] << 8 | packet[4]; - uint16_t cycleCountZ = packet[5] << 8 | packet[6]; - if(cycleCountX != cycleCountRegValueX or cycleCountY != cycleCountRegValueY or - cycleCountZ != cycleCountRegValueZ) { - return DeviceHandlerIF::DEVICE_REPLY_INVALID; - } + case (RM3100::READ_TMRC): { + if (packet[1] == tmrcRegValue) { + commandExecuted = true; // Reading TMRC was commanded. Trigger event to inform ground - if(mode != _MODE_START_UP) { - uint32_t eventParam1 = (cycleCountX << 16) | cycleCountY; - triggerEvent(cycleCountersSet, eventParam1, cycleCountZ); + if (mode != _MODE_START_UP) { + triggerEvent(tmrcSet, tmrcRegValue, 0); } - break; + } else { + // Attempt reconfiguration + internalState = InternalState::STATE_CONFIGURE_TMRC; + return DeviceHandlerIF::DEVICE_REPLY_INVALID; + } + break; } - case(RM3100::READ_DATA): { - result = handleDataReadout(packet); - break; + case (RM3100::READ_CYCLE_COUNT): { + uint16_t cycleCountX = packet[1] << 8 | packet[2]; + uint16_t cycleCountY = packet[3] << 8 | packet[4]; + uint16_t cycleCountZ = packet[5] << 8 | packet[6]; + if (cycleCountX != cycleCountRegValueX or cycleCountY != cycleCountRegValueY or + cycleCountZ != cycleCountRegValueZ) { + return DeviceHandlerIF::DEVICE_REPLY_INVALID; + } + // Reading TMRC was commanded. Trigger event to inform ground + if (mode != _MODE_START_UP) { + uint32_t eventParam1 = (cycleCountX << 16) | cycleCountY; + triggerEvent(cycleCountersSet, eventParam1, cycleCountZ); + } + break; + } + case (RM3100::READ_DATA): { + result = handleDataReadout(packet); + break; } default: - return DeviceHandlerIF::UNKNOWN_DEVICE_REPLY; - } + return DeviceHandlerIF::UNKNOWN_DEVICE_REPLY; + } - return result; + return result; } ReturnValue_t MgmRM3100Handler::handleCycleCountConfigCommand(DeviceCommandId_t deviceCommand, - const uint8_t *commandData, size_t commandDataLen) { - if(commandData == nullptr) { - return DeviceHandlerIF::INVALID_COMMAND_PARAMETER; - } + const uint8_t *commandData, + size_t commandDataLen) { + if (commandData == nullptr) { + return DeviceHandlerIF::INVALID_COMMAND_PARAMETER; + } - // Set cycle count - if(commandDataLen == 2) { - handleCycleCommand(true, commandData, commandDataLen); - } - else if(commandDataLen == 6) { - handleCycleCommand(false, commandData, commandDataLen); - } - else { - return DeviceHandlerIF::INVALID_COMMAND_PARAMETER; - } + // Set cycle count + if (commandDataLen == 2) { + handleCycleCommand(true, commandData, commandDataLen); + } else if (commandDataLen == 6) { + handleCycleCommand(false, commandData, commandDataLen); + } else { + return DeviceHandlerIF::INVALID_COMMAND_PARAMETER; + } - commandBuffer[0] = RM3100::CYCLE_COUNT_VALUE; - std::memcpy(commandBuffer + 1, &cycleCountRegValueX, 2); - std::memcpy(commandBuffer + 3, &cycleCountRegValueY, 2); - std::memcpy(commandBuffer + 5, &cycleCountRegValueZ, 2); - rawPacketLen = 7; - rawPacket = commandBuffer; - return HasReturnvaluesIF::RETURN_OK; + commandBuffer[0] = RM3100::CYCLE_COUNT_VALUE; + std::memcpy(commandBuffer + 1, &cycleCountRegValueX, 2); + std::memcpy(commandBuffer + 3, &cycleCountRegValueY, 2); + std::memcpy(commandBuffer + 5, &cycleCountRegValueZ, 2); + rawPacketLen = 7; + rawPacket = commandBuffer; + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t MgmRM3100Handler::handleCycleCommand(bool oneCycleValue, - const uint8_t *commandData, size_t commandDataLen) { - RM3100::CycleCountCommand command(oneCycleValue); - ReturnValue_t result = command.deSerialize(&commandData, &commandDataLen, - SerializeIF::Endianness::BIG); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } +ReturnValue_t MgmRM3100Handler::handleCycleCommand(bool oneCycleValue, const uint8_t *commandData, + size_t commandDataLen) { + RM3100::CycleCountCommand command(oneCycleValue); + ReturnValue_t result = + command.deSerialize(&commandData, &commandDataLen, SerializeIF::Endianness::BIG); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - // Data sheet p.30 "while noise limits the useful upper range to ~400 cycle counts." - if(command.cycleCountX > 450 ) { - return DeviceHandlerIF::INVALID_COMMAND_PARAMETER; - } + // Data sheet p.30 "while noise limits the useful upper range to ~400 cycle counts." + if (command.cycleCountX > 450) { + return DeviceHandlerIF::INVALID_COMMAND_PARAMETER; + } - if(not oneCycleValue and (command.cycleCountY > 450 or command.cycleCountZ > 450)) { - return DeviceHandlerIF::INVALID_COMMAND_PARAMETER; - } + if (not oneCycleValue and (command.cycleCountY > 450 or command.cycleCountZ > 450)) { + return DeviceHandlerIF::INVALID_COMMAND_PARAMETER; + } - cycleCountRegValueX = command.cycleCountX; - cycleCountRegValueY = command.cycleCountY; - cycleCountRegValueZ = command.cycleCountZ; - return HasReturnvaluesIF::RETURN_OK; + cycleCountRegValueX = command.cycleCountX; + cycleCountRegValueY = command.cycleCountY; + cycleCountRegValueZ = command.cycleCountZ; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t MgmRM3100Handler::handleTmrcConfigCommand(DeviceCommandId_t deviceCommand, - const uint8_t *commandData, size_t commandDataLen) { - if(commandData == nullptr or commandDataLen != 1) { - return DeviceHandlerIF::INVALID_COMMAND_PARAMETER; - } + const uint8_t *commandData, + size_t commandDataLen) { + if (commandData == nullptr or commandDataLen != 1) { + return DeviceHandlerIF::INVALID_COMMAND_PARAMETER; + } - commandBuffer[0] = RM3100::TMRC_REGISTER; - commandBuffer[1] = commandData[0]; - tmrcRegValue = commandData[0]; - rawPacketLen = 2; - rawPacket = commandBuffer; - return HasReturnvaluesIF::RETURN_OK; + commandBuffer[0] = RM3100::TMRC_REGISTER; + commandBuffer[1] = commandData[0]; + tmrcRegValue = commandData[0]; + rawPacketLen = 2; + rawPacket = commandBuffer; + return HasReturnvaluesIF::RETURN_OK; } void MgmRM3100Handler::fillCommandAndReplyMap() { - insertInCommandAndReplyMap(RM3100::CONFIGURE_CMM, 3); - insertInCommandAndReplyMap(RM3100::READ_CMM, 3); + insertInCommandAndReplyMap(RM3100::CONFIGURE_CMM, 3); + insertInCommandAndReplyMap(RM3100::READ_CMM, 3); - insertInCommandAndReplyMap(RM3100::CONFIGURE_TMRC, 3); - insertInCommandAndReplyMap(RM3100::READ_TMRC, 3); + insertInCommandAndReplyMap(RM3100::CONFIGURE_TMRC, 3); + insertInCommandAndReplyMap(RM3100::READ_TMRC, 3); - insertInCommandAndReplyMap(RM3100::CONFIGURE_CYCLE_COUNT, 3); - insertInCommandAndReplyMap(RM3100::READ_CYCLE_COUNT, 3); + insertInCommandAndReplyMap(RM3100::CONFIGURE_CYCLE_COUNT, 3); + insertInCommandAndReplyMap(RM3100::READ_CYCLE_COUNT, 3); - insertInCommandAndReplyMap(RM3100::READ_DATA, 3, &primaryDataset); + insertInCommandAndReplyMap(RM3100::READ_DATA, 3, &primaryDataset); } -void MgmRM3100Handler::modeChanged(void) { - internalState = InternalState::NONE; -} +void MgmRM3100Handler::modeChanged(void) { internalState = InternalState::NONE; } -ReturnValue_t MgmRM3100Handler::initializeLocalDataPool( - localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { - localDataPoolMap.emplace(RM3100::FIELD_STRENGTH_X, new PoolEntry({0.0})); - localDataPoolMap.emplace(RM3100::FIELD_STRENGTH_Y, new PoolEntry({0.0})); - localDataPoolMap.emplace(RM3100::FIELD_STRENGTH_Z, new PoolEntry({0.0})); - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t MgmRM3100Handler::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) { + localDataPoolMap.emplace(RM3100::FIELD_STRENGTH_X, new PoolEntry({0.0})); + localDataPoolMap.emplace(RM3100::FIELD_STRENGTH_Y, new PoolEntry({0.0})); + localDataPoolMap.emplace(RM3100::FIELD_STRENGTH_Z, new PoolEntry({0.0})); + return HasReturnvaluesIF::RETURN_OK; } uint32_t MgmRM3100Handler::getTransitionDelayMs(Mode_t from, Mode_t to) { - return this->transitionDelay; + return this->transitionDelay; } -void MgmRM3100Handler::setToGoToNormalMode(bool enable) { - goToNormalModeAtStartup = enable; -} +void MgmRM3100Handler::setToGoToNormalMode(bool enable) { goToNormalModeAtStartup = enable; } ReturnValue_t MgmRM3100Handler::handleDataReadout(const uint8_t *packet) { - // Analyze data here. The sensor generates 24 bit signed values so we need to do some bitshift - // trickery here to calculate the raw values first - int32_t fieldStrengthRawX = ((packet[1] << 24) | (packet[2] << 16) | (packet[3] << 8)) >> 8; - int32_t fieldStrengthRawY = ((packet[4] << 24) | (packet[5] << 16) | (packet[6] << 8)) >> 8; - int32_t fieldStrengthRawZ = ((packet[7] << 24) | (packet[8] << 16) | (packet[3] << 8)) >> 8; + // Analyze data here. The sensor generates 24 bit signed values so we need to do some bitshift + // trickery here to calculate the raw values first + int32_t fieldStrengthRawX = ((packet[1] << 24) | (packet[2] << 16) | (packet[3] << 8)) >> 8; + int32_t fieldStrengthRawY = ((packet[4] << 24) | (packet[5] << 16) | (packet[6] << 8)) >> 8; + int32_t fieldStrengthRawZ = ((packet[7] << 24) | (packet[8] << 16) | (packet[3] << 8)) >> 8; - // Now scale to physical value in microtesla - float fieldStrengthX = fieldStrengthRawX * scaleFactorX; - float fieldStrengthY = fieldStrengthRawY * scaleFactorX; - float fieldStrengthZ = fieldStrengthRawZ * scaleFactorX; + // Now scale to physical value in microtesla + float fieldStrengthX = fieldStrengthRawX * scaleFactorX; + float fieldStrengthY = fieldStrengthRawY * scaleFactorX; + float fieldStrengthZ = fieldStrengthRawZ * scaleFactorX; #if FSFW_HAL_RM3100_MGM_DEBUG == 1 - if(debugDivider->checkAndIncrement()) { + if (debugDivider->checkAndIncrement()) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "MgmRM3100Handler: Magnetic field strength in" - " microtesla:" << std::endl; - sif::info << "X: " << fieldStrengthX << " uT" << std::endl; - sif::info << "Y: " << fieldStrengthY << " uT" << std::endl; - sif::info << "Z: " << fieldStrengthZ << " uT" << std::endl; + sif::info << "MgmRM3100Handler: Magnetic field strength in" + " microtesla:" + << std::endl; + sif::info << "X: " << fieldStrengthX << " uT" << std::endl; + sif::info << "Y: " << fieldStrengthY << " uT" << std::endl; + sif::info << "Z: " << fieldStrengthZ << " uT" << std::endl; #else - sif::printInfo("MgmRM3100Handler: Magnetic field strength in microtesla:\n"); - sif::printInfo("X: %f uT\n", fieldStrengthX); - sif::printInfo("Y: %f uT\n", fieldStrengthY); - sif::printInfo("Z: %f uT\n", fieldStrengthZ); + sif::printInfo("MgmRM3100Handler: Magnetic field strength in microtesla:\n"); + sif::printInfo("X: %f uT\n", fieldStrengthX); + sif::printInfo("Y: %f uT\n", fieldStrengthY); + sif::printInfo("Z: %f uT\n", fieldStrengthZ); #endif - } + } #endif - // TODO: Sanity check on values? - PoolReadGuard readGuard(&primaryDataset); - if(readGuard.getReadResult() == HasReturnvaluesIF::RETURN_OK) { - primaryDataset.fieldStrengthX = fieldStrengthX; - primaryDataset.fieldStrengthY = fieldStrengthY; - primaryDataset.fieldStrengthZ = fieldStrengthZ; - primaryDataset.setValidity(true, true); - } - return RETURN_OK; + // TODO: Sanity check on values? + PoolReadGuard readGuard(&primaryDataset); + if (readGuard.getReadResult() == HasReturnvaluesIF::RETURN_OK) { + primaryDataset.fieldStrengthX = fieldStrengthX; + primaryDataset.fieldStrengthY = fieldStrengthY; + primaryDataset.fieldStrengthZ = fieldStrengthZ; + primaryDataset.setValidity(true, true); + } + return RETURN_OK; } diff --git a/hal/src/fsfw_hal/devicehandlers/MgmRM3100Handler.h b/hal/src/fsfw_hal/devicehandlers/MgmRM3100Handler.h index 6627cbb7..67362f59 100644 --- a/hal/src/fsfw_hal/devicehandlers/MgmRM3100Handler.h +++ b/hal/src/fsfw_hal/devicehandlers/MgmRM3100Handler.h @@ -1,8 +1,8 @@ #ifndef MISSION_DEVICES_MGMRM3100HANDLER_H_ #define MISSION_DEVICES_MGMRM3100HANDLER_H_ -#include "fsfw/FSFW.h" #include "devicedefinitions/MgmRM3100HandlerDefs.h" +#include "fsfw/FSFW.h" #include "fsfw/devicehandlers/DeviceHandlerBase.h" #if FSFW_HAL_RM3100_MGM_DEBUG == 1 @@ -16,94 +16,90 @@ * Flight manual: * https://egit.irs.uni-stuttgart.de/redmine/projects/eive-flight-manual/wiki/RM3100_MGM */ -class MgmRM3100Handler: public DeviceHandlerBase { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::MGM_RM3100; +class MgmRM3100Handler : public DeviceHandlerBase { + public: + static const uint8_t INTERFACE_ID = CLASS_ID::MGM_RM3100; - //! [EXPORT] : [COMMENT] P1: TMRC value which was set, P2: 0 - static constexpr Event tmrcSet = event::makeEvent(SUBSYSTEM_ID::MGM_RM3100, - 0x00, severity::INFO); + //! [EXPORT] : [COMMENT] P1: TMRC value which was set, P2: 0 + static constexpr Event tmrcSet = event::makeEvent(SUBSYSTEM_ID::MGM_RM3100, 0x00, severity::INFO); - //! [EXPORT] : [COMMENT] Cycle counter set. P1: First two bytes new Cycle Count X - //! P1: Second two bytes new Cycle Count Y - //! P2: New cycle count Z - static constexpr Event cycleCountersSet = event::makeEvent( - SUBSYSTEM_ID::MGM_RM3100, 0x01, severity::INFO); + //! [EXPORT] : [COMMENT] Cycle counter set. P1: First two bytes new Cycle Count X + //! P1: Second two bytes new Cycle Count Y + //! P2: New cycle count Z + static constexpr Event cycleCountersSet = + event::makeEvent(SUBSYSTEM_ID::MGM_RM3100, 0x01, severity::INFO); - MgmRM3100Handler(object_id_t objectId, object_id_t deviceCommunication, - CookieIF* comCookie, uint32_t transitionDelay); - virtual ~MgmRM3100Handler(); + MgmRM3100Handler(object_id_t objectId, object_id_t deviceCommunication, CookieIF *comCookie, + uint32_t transitionDelay); + virtual ~MgmRM3100Handler(); - /** - * Configure device handler to go to normal mode after startup immediately - * @param enable - */ - void setToGoToNormalMode(bool enable); + /** + * Configure device handler to go to normal mode after startup immediately + * @param enable + */ + void setToGoToNormalMode(bool enable); -protected: + protected: + /* DeviceHandlerBase overrides */ + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override; + void doStartUp() override; + void doShutDown() override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData, + size_t commandDataLen) override; + ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) override; + ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override; - /* DeviceHandlerBase overrides */ - ReturnValue_t buildTransitionDeviceCommand( - DeviceCommandId_t *id) override; - void doStartUp() override; - void doShutDown() override; - ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override; - ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, - const uint8_t *commandData, size_t commandDataLen) override; - ReturnValue_t scanForReply(const uint8_t *start, size_t len, - DeviceCommandId_t *foundId, size_t *foundLen) override; - ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override; + void fillCommandAndReplyMap() override; + void modeChanged(void) override; + virtual uint32_t getTransitionDelayMs(Mode_t from, Mode_t to) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) override; - void fillCommandAndReplyMap() override; - void modeChanged(void) override; - virtual uint32_t getTransitionDelayMs(Mode_t from, Mode_t to) override; - ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, - LocalDataPoolManager &poolManager) override; + private: + enum class InternalState { + NONE, + CONFIGURE_CMM, + READ_CMM, + // The cycle count states are propably not going to be used because + // the default cycle count will be used. + STATE_CONFIGURE_CYCLE_COUNT, + STATE_READ_CYCLE_COUNT, + STATE_CONFIGURE_TMRC, + STATE_READ_TMRC, + NORMAL + }; + InternalState internalState = InternalState::NONE; + bool commandExecuted = false; + RM3100::Rm3100PrimaryDataset primaryDataset; -private: + uint8_t commandBuffer[10]; + uint8_t commandBufferLen = 0; - enum class InternalState { - NONE, - CONFIGURE_CMM, - READ_CMM, - // The cycle count states are propably not going to be used because - // the default cycle count will be used. - STATE_CONFIGURE_CYCLE_COUNT, - STATE_READ_CYCLE_COUNT, - STATE_CONFIGURE_TMRC, - STATE_READ_TMRC, - NORMAL - }; - InternalState internalState = InternalState::NONE; - bool commandExecuted = false; - RM3100::Rm3100PrimaryDataset primaryDataset; + uint8_t cmmRegValue = RM3100::CMM_VALUE; + uint8_t tmrcRegValue = RM3100::TMRC_DEFAULT_VALUE; + uint16_t cycleCountRegValueX = RM3100::CYCLE_COUNT_VALUE; + uint16_t cycleCountRegValueY = RM3100::CYCLE_COUNT_VALUE; + uint16_t cycleCountRegValueZ = RM3100::CYCLE_COUNT_VALUE; + float scaleFactorX = 1.0 / RM3100::DEFAULT_GAIN; + float scaleFactorY = 1.0 / RM3100::DEFAULT_GAIN; + float scaleFactorZ = 1.0 / RM3100::DEFAULT_GAIN; - uint8_t commandBuffer[10]; - uint8_t commandBufferLen = 0; + bool goToNormalModeAtStartup = false; + uint32_t transitionDelay; - uint8_t cmmRegValue = RM3100::CMM_VALUE; - uint8_t tmrcRegValue = RM3100::TMRC_DEFAULT_VALUE; - uint16_t cycleCountRegValueX = RM3100::CYCLE_COUNT_VALUE; - uint16_t cycleCountRegValueY = RM3100::CYCLE_COUNT_VALUE; - uint16_t cycleCountRegValueZ = RM3100::CYCLE_COUNT_VALUE; - float scaleFactorX = 1.0 / RM3100::DEFAULT_GAIN; - float scaleFactorY = 1.0 / RM3100::DEFAULT_GAIN; - float scaleFactorZ = 1.0 / RM3100::DEFAULT_GAIN; + ReturnValue_t handleCycleCountConfigCommand(DeviceCommandId_t deviceCommand, + const uint8_t *commandData, size_t commandDataLen); + ReturnValue_t handleCycleCommand(bool oneCycleValue, const uint8_t *commandData, + size_t commandDataLen); - bool goToNormalModeAtStartup = false; - uint32_t transitionDelay; + ReturnValue_t handleTmrcConfigCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData, + size_t commandDataLen); - ReturnValue_t handleCycleCountConfigCommand(DeviceCommandId_t deviceCommand, - const uint8_t *commandData,size_t commandDataLen); - ReturnValue_t handleCycleCommand(bool oneCycleValue, - const uint8_t *commandData, size_t commandDataLen); - - ReturnValue_t handleTmrcConfigCommand(DeviceCommandId_t deviceCommand, - const uint8_t *commandData,size_t commandDataLen); - - ReturnValue_t handleDataReadout(const uint8_t* packet); + ReturnValue_t handleDataReadout(const uint8_t *packet); #if FSFW_HAL_RM3100_MGM_DEBUG == 1 - PeriodicOperationDivider* debugDivider; + PeriodicOperationDivider *debugDivider; #endif }; diff --git a/hal/src/fsfw_hal/devicehandlers/devicedefinitions/GyroL3GD20Definitions.h b/hal/src/fsfw_hal/devicehandlers/devicedefinitions/GyroL3GD20Definitions.h index 56a2468d..2a85ff3e 100644 --- a/hal/src/fsfw_hal/devicehandlers/devicedefinitions/GyroL3GD20Definitions.h +++ b/hal/src/fsfw_hal/devicehandlers/devicedefinitions/GyroL3GD20Definitions.h @@ -3,6 +3,7 @@ #include #include + #include namespace L3GD20H { @@ -36,8 +37,8 @@ static constexpr uint8_t SET_Z_ENABLE = 1 << 2; static constexpr uint8_t SET_X_ENABLE = 1 << 1; static constexpr uint8_t SET_Y_ENABLE = 1; -static constexpr uint8_t CTRL_REG_1_VAL = SET_POWER_NORMAL_MODE | SET_Z_ENABLE | - SET_Y_ENABLE | SET_X_ENABLE; +static constexpr uint8_t CTRL_REG_1_VAL = + SET_POWER_NORMAL_MODE | SET_Z_ENABLE | SET_Y_ENABLE | SET_X_ENABLE; /* Register 2 */ static constexpr uint8_t EXTERNAL_EDGE_ENB = 1 << 7; @@ -104,40 +105,29 @@ static constexpr DeviceCommandId_t READ_CTRL_REGS = 2; static constexpr uint32_t GYRO_DATASET_ID = READ_REGS; -enum GyroPoolIds: lp_id_t { - ANG_VELOC_X, - ANG_VELOC_Y, - ANG_VELOC_Z, - TEMPERATURE +enum GyroPoolIds : lp_id_t { ANG_VELOC_X, ANG_VELOC_Y, ANG_VELOC_Z, TEMPERATURE }; + +} // namespace L3GD20H + +class GyroPrimaryDataset : public StaticLocalDataSet<5> { + public: + /** Constructor for data users like controllers */ + GyroPrimaryDataset(object_id_t mgmId) + : StaticLocalDataSet(sid_t(mgmId, L3GD20H::GYRO_DATASET_ID)) { + setAllVariablesReadOnly(); + } + + /* Angular velocities in degrees per second (DPS) */ + lp_var_t angVelocX = lp_var_t(sid.objectId, L3GD20H::ANG_VELOC_X, this); + lp_var_t angVelocY = lp_var_t(sid.objectId, L3GD20H::ANG_VELOC_Y, this); + lp_var_t angVelocZ = lp_var_t(sid.objectId, L3GD20H::ANG_VELOC_Z, this); + lp_var_t temperature = lp_var_t(sid.objectId, L3GD20H::TEMPERATURE, this); + + private: + friend class GyroHandlerL3GD20H; + /** Constructor for the data creator */ + GyroPrimaryDataset(HasLocalDataPoolIF* hkOwner) + : StaticLocalDataSet(hkOwner, L3GD20H::GYRO_DATASET_ID) {} }; -} - -class GyroPrimaryDataset: public StaticLocalDataSet<5> { -public: - - /** Constructor for data users like controllers */ - GyroPrimaryDataset(object_id_t mgmId): - StaticLocalDataSet(sid_t(mgmId, L3GD20H::GYRO_DATASET_ID)) { - setAllVariablesReadOnly(); - } - - /* Angular velocities in degrees per second (DPS) */ - lp_var_t angVelocX = lp_var_t(sid.objectId, - L3GD20H::ANG_VELOC_X, this); - lp_var_t angVelocY = lp_var_t(sid.objectId, - L3GD20H::ANG_VELOC_Y, this); - lp_var_t angVelocZ = lp_var_t(sid.objectId, - L3GD20H::ANG_VELOC_Z, this); - lp_var_t temperature = lp_var_t(sid.objectId, - L3GD20H::TEMPERATURE, this); -private: - - friend class GyroHandlerL3GD20H; - /** Constructor for the data creator */ - GyroPrimaryDataset(HasLocalDataPoolIF* hkOwner): - StaticLocalDataSet(hkOwner, L3GD20H::GYRO_DATASET_ID) {} -}; - - #endif /* MISSION_DEVICES_DEVICEDEFINITIONS_GYROL3GD20DEFINITIONS_H_ */ diff --git a/hal/src/fsfw_hal/devicehandlers/devicedefinitions/MgmLIS3HandlerDefs.h b/hal/src/fsfw_hal/devicehandlers/devicedefinitions/MgmLIS3HandlerDefs.h index 9d65aae2..3d78c5c9 100644 --- a/hal/src/fsfw_hal/devicehandlers/devicedefinitions/MgmLIS3HandlerDefs.h +++ b/hal/src/fsfw_hal/devicehandlers/devicedefinitions/MgmLIS3HandlerDefs.h @@ -1,26 +1,18 @@ #ifndef MISSION_DEVICES_DEVICEDEFINITIONS_MGMLIS3HANDLERDEFS_H_ #define MISSION_DEVICES_DEVICEDEFINITIONS_MGMLIS3HANDLERDEFS_H_ -#include #include +#include #include + #include namespace MGMLIS3MDL { -enum Set { - ON, OFF -}; -enum OpMode { - LOW, MEDIUM, HIGH, ULTRA -}; +enum Set { ON, OFF }; +enum OpMode { LOW, MEDIUM, HIGH, ULTRA }; -enum Sensitivies: uint8_t { - GAUSS_4 = 4, - GAUSS_8 = 8, - GAUSS_12 = 12, - GAUSS_16 = 16 -}; +enum Sensitivies : uint8_t { GAUSS_4 = 4, GAUSS_8 = 8, GAUSS_12 = 12, GAUSS_16 = 16 }; /* Actually 15, we just round up a bit */ static constexpr size_t MAX_BUFFER_SIZE = 16; @@ -54,7 +46,7 @@ static const uint8_t SETUP_REPLY_LEN = 6; /*------------------------------------------------------------------------*/ /* Register adress returns identifier of device with default 0b00111101 */ static const uint8_t IDENTIFY_DEVICE_REG_ADDR = 0b00001111; -static const uint8_t DEVICE_ID = 0b00111101; // Identifier for Device +static const uint8_t DEVICE_ID = 0b00111101; // Identifier for Device /* Register adress to access register 1 */ static const uint8_t CTRL_REG1 = 0b00100000; @@ -105,74 +97,67 @@ static const uint8_t RW_BIT = 7; static const uint8_t MS_BIT = 6; /* CTRL_REG1 bits */ -static const uint8_t ST = 0; // Self test enable bit, enabled = 1 +static const uint8_t ST = 0; // Self test enable bit, enabled = 1 // Enable rates higher than 80 Hz enabled = 1 static const uint8_t FAST_ODR = 1; -static const uint8_t DO0 = 2; // Output data rate bit 2 -static const uint8_t DO1 = 3; // Output data rate bit 3 -static const uint8_t DO2 = 4; // Output data rate bit 4 -static const uint8_t OM0 = 5; // XY operating mode bit 5 -static const uint8_t OM1 = 6; // XY operating mode bit 6 -static const uint8_t TEMP_EN = 7; // Temperature sensor enable enabled = 1 -static const uint8_t CTRL_REG1_DEFAULT = (1 << TEMP_EN) | (1 << OM1) | - (1 << DO0) | (1 << DO1) | (1 << DO2); +static const uint8_t DO0 = 2; // Output data rate bit 2 +static const uint8_t DO1 = 3; // Output data rate bit 3 +static const uint8_t DO2 = 4; // Output data rate bit 4 +static const uint8_t OM0 = 5; // XY operating mode bit 5 +static const uint8_t OM1 = 6; // XY operating mode bit 6 +static const uint8_t TEMP_EN = 7; // Temperature sensor enable enabled = 1 +static const uint8_t CTRL_REG1_DEFAULT = + (1 << TEMP_EN) | (1 << OM1) | (1 << DO0) | (1 << DO1) | (1 << DO2); /* CTRL_REG2 bits */ -//reset configuration registers and user registers +// reset configuration registers and user registers static const uint8_t SOFT_RST = 2; -static const uint8_t REBOOT = 3; //reboot memory content -static const uint8_t FSO = 5; //full-scale selection bit 5 -static const uint8_t FS1 = 6; //full-scale selection bit 6 +static const uint8_t REBOOT = 3; // reboot memory content +static const uint8_t FSO = 5; // full-scale selection bit 5 +static const uint8_t FS1 = 6; // full-scale selection bit 6 static const uint8_t CTRL_REG2_DEFAULT = 0; /* CTRL_REG3 bits */ -static const uint8_t MD0 = 0; //Operating mode bit 0 -static const uint8_t MD1 = 1; //Operating mode bit 1 -//SPI serial interface mode selection enabled = 3-wire-mode +static const uint8_t MD0 = 0; // Operating mode bit 0 +static const uint8_t MD1 = 1; // Operating mode bit 1 +// SPI serial interface mode selection enabled = 3-wire-mode static const uint8_t SIM = 2; -static const uint8_t LP = 5; //low-power mode +static const uint8_t LP = 5; // low-power mode static const uint8_t CTRL_REG3_DEFAULT = 0; /* CTRL_REG4 bits */ -//big/little endian data selection enabled = MSb at lower adress +// big/little endian data selection enabled = MSb at lower adress static const uint8_t BLE = 1; -static const uint8_t OMZ0 = 2; //Z operating mode bit 2 -static const uint8_t OMZ1 = 3; //Z operating mode bit 3 +static const uint8_t OMZ0 = 2; // Z operating mode bit 2 +static const uint8_t OMZ1 = 3; // Z operating mode bit 3 static const uint8_t CTRL_REG4_DEFAULT = (1 << OMZ1); /* CTRL_REG5 bits */ -static const uint8_t BDU = 6; //Block data update -static const uint8_t FAST_READ = 7; //Fast read enabled = 1 +static const uint8_t BDU = 6; // Block data update +static const uint8_t FAST_READ = 7; // Fast read enabled = 1 static const uint8_t CTRL_REG5_DEFAULT = 0; static const uint32_t MGM_DATA_SET_ID = READ_CONFIG_AND_DATA; -enum MgmPoolIds: lp_id_t { - FIELD_STRENGTH_X, - FIELD_STRENGTH_Y, - FIELD_STRENGTH_Z, - TEMPERATURE_CELCIUS +enum MgmPoolIds : lp_id_t { + FIELD_STRENGTH_X, + FIELD_STRENGTH_Y, + FIELD_STRENGTH_Z, + TEMPERATURE_CELCIUS }; -class MgmPrimaryDataset: public StaticLocalDataSet<4> { -public: - MgmPrimaryDataset(HasLocalDataPoolIF* hkOwner): - StaticLocalDataSet(hkOwner, MGM_DATA_SET_ID) {} +class MgmPrimaryDataset : public StaticLocalDataSet<4> { + public: + MgmPrimaryDataset(HasLocalDataPoolIF* hkOwner) : StaticLocalDataSet(hkOwner, MGM_DATA_SET_ID) {} - MgmPrimaryDataset(object_id_t mgmId): - StaticLocalDataSet(sid_t(mgmId, MGM_DATA_SET_ID)) {} + MgmPrimaryDataset(object_id_t mgmId) : StaticLocalDataSet(sid_t(mgmId, MGM_DATA_SET_ID)) {} - lp_var_t fieldStrengthX = lp_var_t(sid.objectId, - FIELD_STRENGTH_X, this); - lp_var_t fieldStrengthY = lp_var_t(sid.objectId, - FIELD_STRENGTH_Y, this); - lp_var_t fieldStrengthZ = lp_var_t(sid.objectId, - FIELD_STRENGTH_Z, this); - lp_var_t temperature = lp_var_t(sid.objectId, - TEMPERATURE_CELCIUS, this); + lp_var_t fieldStrengthX = lp_var_t(sid.objectId, FIELD_STRENGTH_X, this); + lp_var_t fieldStrengthY = lp_var_t(sid.objectId, FIELD_STRENGTH_Y, this); + lp_var_t fieldStrengthZ = lp_var_t(sid.objectId, FIELD_STRENGTH_Z, this); + lp_var_t temperature = lp_var_t(sid.objectId, TEMPERATURE_CELCIUS, this); }; -} - +} // namespace MGMLIS3MDL #endif /* MISSION_DEVICES_DEVICEDEFINITIONS_MGMLIS3HANDLERDEFS_H_ */ diff --git a/hal/src/fsfw_hal/devicehandlers/devicedefinitions/MgmRM3100HandlerDefs.h b/hal/src/fsfw_hal/devicehandlers/devicedefinitions/MgmRM3100HandlerDefs.h index b6375692..e3eaff22 100644 --- a/hal/src/fsfw_hal/devicehandlers/devicedefinitions/MgmRM3100HandlerDefs.h +++ b/hal/src/fsfw_hal/devicehandlers/devicedefinitions/MgmRM3100HandlerDefs.h @@ -1,10 +1,11 @@ #ifndef MISSION_DEVICES_DEVICEDEFINITIONS_MGMHANDLERRM3100DEFINITIONS_H_ #define MISSION_DEVICES_DEVICEDEFINITIONS_MGMHANDLERRM3100DEFINITIONS_H_ -#include #include +#include #include #include + #include namespace RM3100 { @@ -24,8 +25,8 @@ static constexpr uint8_t SET_CMM_DRDM = 1 << 2; static constexpr uint8_t SET_CMM_START = 1; static constexpr uint8_t CMM_REGISTER = 0x01; -static constexpr uint8_t CMM_VALUE = SET_CMM_CMZ | SET_CMM_CMY | SET_CMM_CMX | - SET_CMM_DRDM | SET_CMM_START; +static constexpr uint8_t CMM_VALUE = + SET_CMM_CMZ | SET_CMM_CMY | SET_CMM_CMX | SET_CMM_DRDM | SET_CMM_START; /*----------------------------------------------------------------------------*/ /* Cycle count register */ @@ -33,8 +34,7 @@ static constexpr uint8_t CMM_VALUE = SET_CMM_CMZ | SET_CMM_CMY | SET_CMM_CMX | // Default value (200) static constexpr uint8_t CYCLE_COUNT_VALUE = 0xC8; -static constexpr float DEFAULT_GAIN = static_cast(CYCLE_COUNT_VALUE) / - 100 * 38; +static constexpr float DEFAULT_GAIN = static_cast(CYCLE_COUNT_VALUE) / 100 * 38; static constexpr uint8_t CYCLE_COUNT_START_REGISTER = 0x04; /*----------------------------------------------------------------------------*/ @@ -67,66 +67,58 @@ static constexpr DeviceCommandId_t READ_TMRC = 4; static constexpr DeviceCommandId_t CONFIGURE_CYCLE_COUNT = 5; static constexpr DeviceCommandId_t READ_CYCLE_COUNT = 6; -class CycleCountCommand: public SerialLinkedListAdapter { -public: - CycleCountCommand(bool oneCycleCount = true): oneCycleCount(oneCycleCount) { - setLinks(oneCycleCount); - } +class CycleCountCommand : public SerialLinkedListAdapter { + public: + CycleCountCommand(bool oneCycleCount = true) : oneCycleCount(oneCycleCount) { + setLinks(oneCycleCount); + } - ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) override { - ReturnValue_t result = SerialLinkedListAdapter::deSerialize(buffer, - size, streamEndianness); - if(oneCycleCount) { - cycleCountY = cycleCountX; - cycleCountZ = cycleCountX; - } - return result; - } + ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + Endianness streamEndianness) override { + ReturnValue_t result = SerialLinkedListAdapter::deSerialize(buffer, size, streamEndianness); + if (oneCycleCount) { + cycleCountY = cycleCountX; + cycleCountZ = cycleCountX; + } + return result; + } - SerializeElement cycleCountX; - SerializeElement cycleCountY; - SerializeElement cycleCountZ; + SerializeElement cycleCountX; + SerializeElement cycleCountY; + SerializeElement cycleCountZ; -private: - void setLinks(bool oneCycleCount) { - setStart(&cycleCountX); - if(not oneCycleCount) { - cycleCountX.setNext(&cycleCountY); - cycleCountY.setNext(&cycleCountZ); - } - } + private: + void setLinks(bool oneCycleCount) { + setStart(&cycleCountX); + if (not oneCycleCount) { + cycleCountX.setNext(&cycleCountY); + cycleCountY.setNext(&cycleCountZ); + } + } - bool oneCycleCount; + bool oneCycleCount; }; static constexpr uint32_t MGM_DATASET_ID = READ_DATA; -enum MgmPoolIds: lp_id_t { - FIELD_STRENGTH_X, - FIELD_STRENGTH_Y, - FIELD_STRENGTH_Z, +enum MgmPoolIds : lp_id_t { + FIELD_STRENGTH_X, + FIELD_STRENGTH_Y, + FIELD_STRENGTH_Z, }; -class Rm3100PrimaryDataset: public StaticLocalDataSet<3> { -public: - Rm3100PrimaryDataset(HasLocalDataPoolIF* hkOwner): - StaticLocalDataSet(hkOwner, MGM_DATASET_ID) {} +class Rm3100PrimaryDataset : public StaticLocalDataSet<3> { + public: + Rm3100PrimaryDataset(HasLocalDataPoolIF* hkOwner) : StaticLocalDataSet(hkOwner, MGM_DATASET_ID) {} - Rm3100PrimaryDataset(object_id_t mgmId): - StaticLocalDataSet(sid_t(mgmId, MGM_DATASET_ID)) {} + Rm3100PrimaryDataset(object_id_t mgmId) : StaticLocalDataSet(sid_t(mgmId, MGM_DATASET_ID)) {} - // Field strengths in micro Tesla. - lp_var_t fieldStrengthX = lp_var_t(sid.objectId, - FIELD_STRENGTH_X, this); - lp_var_t fieldStrengthY = lp_var_t(sid.objectId, - FIELD_STRENGTH_Y, this); - lp_var_t fieldStrengthZ = lp_var_t(sid.objectId, - FIELD_STRENGTH_Z, this); + // Field strengths in micro Tesla. + lp_var_t fieldStrengthX = lp_var_t(sid.objectId, FIELD_STRENGTH_X, this); + lp_var_t fieldStrengthY = lp_var_t(sid.objectId, FIELD_STRENGTH_Y, this); + lp_var_t fieldStrengthZ = lp_var_t(sid.objectId, FIELD_STRENGTH_Z, this); }; -} - - +} // namespace RM3100 #endif /* MISSION_DEVICES_DEVICEDEFINITIONS_MGMHANDLERRM3100DEFINITIONS_H_ */ diff --git a/hal/src/fsfw_hal/linux/CommandExecutor.cpp b/hal/src/fsfw_hal/linux/CommandExecutor.cpp index 016217e1..49c44ebf 100644 --- a/hal/src/fsfw_hal/linux/CommandExecutor.cpp +++ b/hal/src/fsfw_hal/linux/CommandExecutor.cpp @@ -1,213 +1,207 @@ #include "CommandExecutor.h" -#include "fsfw/serviceinterface.h" -#include "fsfw/container/SimpleRingBuffer.h" -#include "fsfw/container/DynamicFIFO.h" - #include #include -CommandExecutor::CommandExecutor(const size_t maxSize): -readVec(maxSize) { - waiter.events = POLLIN; +#include "fsfw/container/DynamicFIFO.h" +#include "fsfw/container/SimpleRingBuffer.h" +#include "fsfw/serviceinterface.h" + +CommandExecutor::CommandExecutor(const size_t maxSize) : readVec(maxSize) { + waiter.events = POLLIN; } ReturnValue_t CommandExecutor::load(std::string command, bool blocking, bool printOutput) { - if(state == States::PENDING) { - return COMMAND_PENDING; - } + if (state == States::PENDING) { + return COMMAND_PENDING; + } - currentCmd = command; - this->blocking = blocking; - this->printOutput = printOutput; - if(state == States::IDLE) { - state = States::COMMAND_LOADED; - } - return HasReturnvaluesIF::RETURN_OK; + currentCmd = command; + this->blocking = blocking; + this->printOutput = printOutput; + if (state == States::IDLE) { + state = States::COMMAND_LOADED; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t CommandExecutor::execute() { - if(state == States::IDLE) { - return NO_COMMAND_LOADED_OR_PENDING; - } - else if(state == States::PENDING) { - return COMMAND_PENDING; - } - currentCmdFile = popen(currentCmd.c_str(), "r"); - if(currentCmdFile == nullptr) { - lastError = errno; - return HasReturnvaluesIF::RETURN_FAILED; - } - if(blocking) { - ReturnValue_t result = executeBlocking(); - state = States::IDLE; - return result; - } - else { - currentFd = fileno(currentCmdFile); - waiter.fd = currentFd; - } - state = States::PENDING; - return HasReturnvaluesIF::RETURN_OK; + if (state == States::IDLE) { + return NO_COMMAND_LOADED_OR_PENDING; + } else if (state == States::PENDING) { + return COMMAND_PENDING; + } + currentCmdFile = popen(currentCmd.c_str(), "r"); + if (currentCmdFile == nullptr) { + lastError = errno; + return HasReturnvaluesIF::RETURN_FAILED; + } + if (blocking) { + ReturnValue_t result = executeBlocking(); + state = States::IDLE; + return result; + } else { + currentFd = fileno(currentCmdFile); + waiter.fd = currentFd; + } + state = States::PENDING; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t CommandExecutor::close() { - if(state == States::PENDING) { - // Attempt to close process, irrespective of if it is running or not - if(currentCmdFile != nullptr) { - pclose(currentCmdFile); - } + if (state == States::PENDING) { + // Attempt to close process, irrespective of if it is running or not + if (currentCmdFile != nullptr) { + pclose(currentCmdFile); } - return HasReturnvaluesIF::RETURN_OK; + } + return HasReturnvaluesIF::RETURN_OK; } void CommandExecutor::printLastError(std::string funcName) const { - if(lastError != 0) { + if (lastError != 0) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << funcName << " pclose failed with code " << lastError << ": " << - strerror(lastError) << std::endl; + sif::warning << funcName << " pclose failed with code " << lastError << ": " + << strerror(lastError) << std::endl; #else - sif::printError("%s pclose failed with code %d: %s\n", - funcName, lastError, strerror(lastError)); + sif::printError("%s pclose failed with code %d: %s\n", funcName, lastError, + strerror(lastError)); #endif - } + } } -void CommandExecutor::setRingBuffer(SimpleRingBuffer *ringBuffer, - DynamicFIFO* sizesFifo) { - this->ringBuffer = ringBuffer; - this->sizesFifo = sizesFifo; +void CommandExecutor::setRingBuffer(SimpleRingBuffer* ringBuffer, + DynamicFIFO* sizesFifo) { + this->ringBuffer = ringBuffer; + this->sizesFifo = sizesFifo; } ReturnValue_t CommandExecutor::check(bool& replyReceived) { - if(blocking) { - return HasReturnvaluesIF::RETURN_OK; - } - switch(state) { - case(States::IDLE): - case(States::COMMAND_LOADED): { - return NO_COMMAND_LOADED_OR_PENDING; - } - case(States::PENDING): { - break; - } - } - - int result = poll(&waiter, 1, 0); - switch(result) { - case(0): { - return HasReturnvaluesIF::RETURN_OK; - break; - } - case(1): { - if (waiter.revents & POLLIN) { - ssize_t readBytes = read(currentFd, readVec.data(), readVec.size()); - if(readBytes == 0) { - // Should not happen -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "CommandExecutor::check: No bytes read " - "after poll event.." << std::endl; -#else - sif::printWarning("CommandExecutor::check: No bytes read after poll event..\n"); -#endif - break; - } - else if(readBytes > 0) { - replyReceived = true; - if(printOutput) { - // It is assumed the command output is line terminated -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << currentCmd << " | " << readVec.data(); -#else - sif::printInfo("%s | %s", currentCmd, readVec.data()); -#endif - } - if(ringBuffer != nullptr) { - ringBuffer->writeData(reinterpret_cast( - readVec.data()), readBytes); - } - if(sizesFifo != nullptr) { - if(not sizesFifo->full()) { - sizesFifo->insert(readBytes); - } - } - } - else { - // Should also not happen -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "CommandExecutor::check: Error " << errno << ": " << - strerror(errno) << std::endl; -#else - sif::printWarning("CommandExecutor::check: Error %d: %s\n", errno, strerror(errno)); -#endif - } - } - if(waiter.revents & POLLERR) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "CommandExecuter::check: Poll error" << std::endl; -#else - sif::printWarning("CommandExecuter::check: Poll error\n"); -#endif - return COMMAND_ERROR; - } - if(waiter.revents & POLLHUP) { - result = pclose(currentCmdFile); - ReturnValue_t retval = EXECUTION_FINISHED; - if(result != 0) { - lastError = result; - retval = HasReturnvaluesIF::RETURN_FAILED; - } - state = States::IDLE; - currentCmdFile = nullptr; - currentFd = 0; - return retval; - } - break; - } - } + if (blocking) { return HasReturnvaluesIF::RETURN_OK; + } + switch (state) { + case (States::IDLE): + case (States::COMMAND_LOADED): { + return NO_COMMAND_LOADED_OR_PENDING; + } + case (States::PENDING): { + break; + } + } + + int result = poll(&waiter, 1, 0); + switch (result) { + case (0): { + return HasReturnvaluesIF::RETURN_OK; + break; + } + case (1): { + if (waiter.revents & POLLIN) { + ssize_t readBytes = read(currentFd, readVec.data(), readVec.size()); + if (readBytes == 0) { + // Should not happen +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "CommandExecutor::check: No bytes read " + "after poll event.." + << std::endl; +#else + sif::printWarning("CommandExecutor::check: No bytes read after poll event..\n"); +#endif + break; + } else if (readBytes > 0) { + replyReceived = true; + if (printOutput) { + // It is assumed the command output is line terminated +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::info << currentCmd << " | " << readVec.data(); +#else + sif::printInfo("%s | %s", currentCmd, readVec.data()); +#endif + } + if (ringBuffer != nullptr) { + ringBuffer->writeData(reinterpret_cast(readVec.data()), readBytes); + } + if (sizesFifo != nullptr) { + if (not sizesFifo->full()) { + sizesFifo->insert(readBytes); + } + } + } else { + // Should also not happen +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "CommandExecutor::check: Error " << errno << ": " << strerror(errno) + << std::endl; +#else + sif::printWarning("CommandExecutor::check: Error %d: %s\n", errno, strerror(errno)); +#endif + } + } + if (waiter.revents & POLLERR) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "CommandExecuter::check: Poll error" << std::endl; +#else + sif::printWarning("CommandExecuter::check: Poll error\n"); +#endif + return COMMAND_ERROR; + } + if (waiter.revents & POLLHUP) { + result = pclose(currentCmdFile); + ReturnValue_t retval = EXECUTION_FINISHED; + if (result != 0) { + lastError = result; + retval = HasReturnvaluesIF::RETURN_FAILED; + } + state = States::IDLE; + currentCmdFile = nullptr; + currentFd = 0; + return retval; + } + break; + } + } + return HasReturnvaluesIF::RETURN_OK; } void CommandExecutor::reset() { - CommandExecutor::close(); - currentCmdFile = nullptr; - currentFd = 0; - state = States::IDLE; + CommandExecutor::close(); + currentCmdFile = nullptr; + currentFd = 0; + state = States::IDLE; } int CommandExecutor::getLastError() const { - // See: https://stackoverflow.com/questions/808541/any-benefit-in-using-wexitstatus-macro-in-c-over-division-by-256-on-exit-statu - return WEXITSTATUS(this->lastError); + // See: + // https://stackoverflow.com/questions/808541/any-benefit-in-using-wexitstatus-macro-in-c-over-division-by-256-on-exit-statu + return WEXITSTATUS(this->lastError); } -CommandExecutor::States CommandExecutor::getCurrentState() const { - return state; -} +CommandExecutor::States CommandExecutor::getCurrentState() const { return state; } ReturnValue_t CommandExecutor::executeBlocking() { - while(fgets(readVec.data(), readVec.size(), currentCmdFile) != nullptr) { - std::string output(readVec.data()); - if(printOutput) { + while (fgets(readVec.data(), readVec.size(), currentCmdFile) != nullptr) { + std::string output(readVec.data()); + if (printOutput) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << currentCmd << " | " << output; + sif::info << currentCmd << " | " << output; #else - sif::printInfo("%s | %s", currentCmd, output); + sif::printInfo("%s | %s", currentCmd, output); #endif - } - if(ringBuffer != nullptr) { - ringBuffer->writeData(reinterpret_cast(output.data()), output.size()); - } - if(sizesFifo != nullptr) { - if(not sizesFifo->full()) { - sizesFifo->insert(output.size()); - } - } } - int result = pclose(currentCmdFile); - if(result != 0) { - lastError = result; - return HasReturnvaluesIF::RETURN_FAILED; + if (ringBuffer != nullptr) { + ringBuffer->writeData(reinterpret_cast(output.data()), output.size()); } - return HasReturnvaluesIF::RETURN_OK; + if (sizesFifo != nullptr) { + if (not sizesFifo->full()) { + sizesFifo->insert(output.size()); + } + } + } + int result = pclose(currentCmdFile); + if (result != 0) { + lastError = result; + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } diff --git a/hal/src/fsfw_hal/linux/CommandExecutor.h b/hal/src/fsfw_hal/linux/CommandExecutor.h index 895bd943..90662c0f 100644 --- a/hal/src/fsfw_hal/linux/CommandExecutor.h +++ b/hal/src/fsfw_hal/linux/CommandExecutor.h @@ -1,16 +1,17 @@ #ifndef FSFW_SRC_FSFW_OSAL_LINUX_COMMANDEXECUTOR_H_ #define FSFW_SRC_FSFW_OSAL_LINUX_COMMANDEXECUTOR_H_ -#include "fsfw/returnvalues/HasReturnvaluesIF.h" -#include "fsfw/returnvalues/FwClassIds.h" - #include #include #include +#include "fsfw/returnvalues/FwClassIds.h" +#include "fsfw/returnvalues/HasReturnvaluesIF.h" + class SimpleRingBuffer; -template class DynamicFIFO; +template +class DynamicFIFO; /** * @brief Helper class to execute shell commands in blocking and non-blocking mode @@ -24,112 +25,105 @@ template class DynamicFIFO; * has finished */ class CommandExecutor { -public: - enum class States { - IDLE, - COMMAND_LOADED, - PENDING - }; + public: + enum class States { IDLE, COMMAND_LOADED, PENDING }; - static constexpr uint8_t CLASS_ID = CLASS_ID::LINUX_OSAL; + static constexpr uint8_t CLASS_ID = CLASS_ID::LINUX_OSAL; - //! [EXPORT] : [COMMENT] Execution of the current command has finished - static constexpr ReturnValue_t EXECUTION_FINISHED = - HasReturnvaluesIF::makeReturnCode(CLASS_ID, 0); + //! [EXPORT] : [COMMENT] Execution of the current command has finished + static constexpr ReturnValue_t EXECUTION_FINISHED = + HasReturnvaluesIF::makeReturnCode(CLASS_ID, 0); - //! [EXPORT] : [COMMENT] Command is pending. This will also be returned if the user tries - //! to load another command but a command is still pending - static constexpr ReturnValue_t COMMAND_PENDING = - HasReturnvaluesIF::makeReturnCode(CLASS_ID, 1); - //! [EXPORT] : [COMMENT] Some bytes have been read from the executing process - static constexpr ReturnValue_t BYTES_READ = - HasReturnvaluesIF::makeReturnCode(CLASS_ID, 2); - //! [EXPORT] : [COMMENT] Command execution failed - static constexpr ReturnValue_t COMMAND_ERROR = - HasReturnvaluesIF::makeReturnCode(CLASS_ID, 3); - //! [EXPORT] : [COMMENT] - static constexpr ReturnValue_t NO_COMMAND_LOADED_OR_PENDING = - HasReturnvaluesIF::makeReturnCode(CLASS_ID, 4); - static constexpr ReturnValue_t PCLOSE_CALL_ERROR = - HasReturnvaluesIF::makeReturnCode(CLASS_ID, 6); + //! [EXPORT] : [COMMENT] Command is pending. This will also be returned if the user tries + //! to load another command but a command is still pending + static constexpr ReturnValue_t COMMAND_PENDING = HasReturnvaluesIF::makeReturnCode(CLASS_ID, 1); + //! [EXPORT] : [COMMENT] Some bytes have been read from the executing process + static constexpr ReturnValue_t BYTES_READ = HasReturnvaluesIF::makeReturnCode(CLASS_ID, 2); + //! [EXPORT] : [COMMENT] Command execution failed + static constexpr ReturnValue_t COMMAND_ERROR = HasReturnvaluesIF::makeReturnCode(CLASS_ID, 3); + //! [EXPORT] : [COMMENT] + static constexpr ReturnValue_t NO_COMMAND_LOADED_OR_PENDING = + HasReturnvaluesIF::makeReturnCode(CLASS_ID, 4); + static constexpr ReturnValue_t PCLOSE_CALL_ERROR = HasReturnvaluesIF::makeReturnCode(CLASS_ID, 6); - /** - * Constructor. Is initialized with maximum size of internal buffer to read data from the - * executed process. - * @param maxSize - */ - CommandExecutor(const size_t maxSize); + /** + * Constructor. Is initialized with maximum size of internal buffer to read data from the + * executed process. + * @param maxSize + */ + CommandExecutor(const size_t maxSize); - /** - * Load a new command which should be executed - * @param command - * @param blocking - * @param printOutput - * @return - */ - ReturnValue_t load(std::string command, bool blocking, bool printOutput = true); - /** - * Execute the loaded command. - * @return - * - In blocking mode, it will return RETURN_FAILED if - * the result of the system call was not 0. The error value can be accessed using - * getLastError - * - In non-blocking mode, this call will start - * the execution and then return RETURN_OK - */ - ReturnValue_t execute(); - /** - * Only used in non-blocking mode. Checks the currently running command. - * @param bytesRead Will be set to the number of bytes read, if bytes have been read - * @return - * - BYTES_READ if bytes have been read from the executing process. It is recommended to call - * check again after this - * - RETURN_OK execution is pending, but no bytes have been read from the executing process - * - RETURN_FAILED if execution has failed, error value can be accessed using getLastError - * - EXECUTION_FINISHED if the process was executed successfully - * - NO_COMMAND_LOADED_OR_PENDING self-explanatory - * - COMMAND_ERROR internal poll error - */ - ReturnValue_t check(bool& replyReceived); - /** - * Abort the current command. Should normally not be necessary, check can be used to find - * out whether command execution was successful - * @return RETURN_OK - */ - ReturnValue_t close(); + /** + * Load a new command which should be executed + * @param command + * @param blocking + * @param printOutput + * @return + */ + ReturnValue_t load(std::string command, bool blocking, bool printOutput = true); + /** + * Execute the loaded command. + * @return + * - In blocking mode, it will return RETURN_FAILED if + * the result of the system call was not 0. The error value can be accessed using + * getLastError + * - In non-blocking mode, this call will start + * the execution and then return RETURN_OK + */ + ReturnValue_t execute(); + /** + * Only used in non-blocking mode. Checks the currently running command. + * @param bytesRead Will be set to the number of bytes read, if bytes have been read + * @return + * - BYTES_READ if bytes have been read from the executing process. It is recommended to call + * check again after this + * - RETURN_OK execution is pending, but no bytes have been read from the executing process + * - RETURN_FAILED if execution has failed, error value can be accessed using getLastError + * - EXECUTION_FINISHED if the process was executed successfully + * - NO_COMMAND_LOADED_OR_PENDING self-explanatory + * - COMMAND_ERROR internal poll error + */ + ReturnValue_t check(bool& replyReceived); + /** + * Abort the current command. Should normally not be necessary, check can be used to find + * out whether command execution was successful + * @return RETURN_OK + */ + ReturnValue_t close(); - States getCurrentState() const; - int getLastError() const; - void printLastError(std::string funcName) const; + States getCurrentState() const; + int getLastError() const; + void printLastError(std::string funcName) const; - /** - * Assign a ring buffer and a FIFO which will be filled by the executor with the output - * read from the started process - * @param ringBuffer - * @param sizesFifo - */ - void setRingBuffer(SimpleRingBuffer* ringBuffer, DynamicFIFO* sizesFifo); + /** + * Assign a ring buffer and a FIFO which will be filled by the executor with the output + * read from the started process + * @param ringBuffer + * @param sizesFifo + */ + void setRingBuffer(SimpleRingBuffer* ringBuffer, DynamicFIFO* sizesFifo); - /** - * Reset the executor. This calls close internally and then reset the state machine so new - * commands can be loaded and executed - */ - void reset(); -private: - std::string currentCmd; - bool blocking = true; - FILE* currentCmdFile = nullptr; - int currentFd = 0; - bool printOutput = true; - std::vector readVec; - struct pollfd waiter {}; - SimpleRingBuffer* ringBuffer = nullptr; - DynamicFIFO* sizesFifo = nullptr; + /** + * Reset the executor. This calls close internally and then reset the state machine so new + * commands can be loaded and executed + */ + void reset(); - States state = States::IDLE; - int lastError = 0; + private: + std::string currentCmd; + bool blocking = true; + FILE* currentCmdFile = nullptr; + int currentFd = 0; + bool printOutput = true; + std::vector readVec; + struct pollfd waiter {}; + SimpleRingBuffer* ringBuffer = nullptr; + DynamicFIFO* sizesFifo = nullptr; - ReturnValue_t executeBlocking(); + States state = States::IDLE; + int lastError = 0; + + ReturnValue_t executeBlocking(); }; #endif /* FSFW_SRC_FSFW_OSAL_LINUX_COMMANDEXECUTOR_H_ */ diff --git a/hal/src/fsfw_hal/linux/UnixFileGuard.cpp b/hal/src/fsfw_hal/linux/UnixFileGuard.cpp index 5019343e..41293815 100644 --- a/hal/src/fsfw_hal/linux/UnixFileGuard.cpp +++ b/hal/src/fsfw_hal/linux/UnixFileGuard.cpp @@ -1,37 +1,36 @@ -#include "fsfw/FSFW.h" -#include "fsfw/serviceinterface.h" #include "fsfw_hal/linux/UnixFileGuard.h" #include #include +#include "fsfw/FSFW.h" +#include "fsfw/serviceinterface.h" + UnixFileGuard::UnixFileGuard(std::string device, int* fileDescriptor, int flags, - std::string diagnosticPrefix): - fileDescriptor(fileDescriptor) { - if(fileDescriptor == nullptr) { - return; - } - *fileDescriptor = open(device.c_str(), flags); - if (*fileDescriptor < 0) { + std::string diagnosticPrefix) + : fileDescriptor(fileDescriptor) { + if (fileDescriptor == nullptr) { + return; + } + *fileDescriptor = open(device.c_str(), flags); + if (*fileDescriptor < 0) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << diagnosticPrefix << ": Opening device failed with error code " << - errno << ": " << strerror(errno) << std::endl; + sif::warning << diagnosticPrefix << ": Opening device failed with error code " << errno << ": " + << strerror(errno) << std::endl; #else - sif::printWarning("%s: Opening device failed with error code %d: %s\n", - diagnosticPrefix, errno, strerror(errno)); + sif::printWarning("%s: Opening device failed with error code %d: %s\n", diagnosticPrefix, errno, + strerror(errno)); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - openStatus = OPEN_FILE_FAILED; - } + openStatus = OPEN_FILE_FAILED; + } } UnixFileGuard::~UnixFileGuard() { - if(fileDescriptor != nullptr) { - close(*fileDescriptor); - } + if (fileDescriptor != nullptr) { + close(*fileDescriptor); + } } -ReturnValue_t UnixFileGuard::getOpenResult() const { - return openStatus; -} +ReturnValue_t UnixFileGuard::getOpenResult() const { return openStatus; } diff --git a/hal/src/fsfw_hal/linux/UnixFileGuard.h b/hal/src/fsfw_hal/linux/UnixFileGuard.h index fb595704..d94234b6 100644 --- a/hal/src/fsfw_hal/linux/UnixFileGuard.h +++ b/hal/src/fsfw_hal/linux/UnixFileGuard.h @@ -1,33 +1,30 @@ #ifndef LINUX_UTILITY_UNIXFILEGUARD_H_ #define LINUX_UTILITY_UNIXFILEGUARD_H_ +#include #include +#include #include -#include -#include - - class UnixFileGuard { -public: - static constexpr int READ_WRITE_FLAG = O_RDWR; - static constexpr int READ_ONLY_FLAG = O_RDONLY; - static constexpr int NON_BLOCKING_IO_FLAG = O_NONBLOCK; + public: + static constexpr int READ_WRITE_FLAG = O_RDWR; + static constexpr int READ_ONLY_FLAG = O_RDONLY; + static constexpr int NON_BLOCKING_IO_FLAG = O_NONBLOCK; - static constexpr ReturnValue_t OPEN_FILE_FAILED = 1; + static constexpr ReturnValue_t OPEN_FILE_FAILED = 1; - UnixFileGuard(std::string device, int* fileDescriptor, int flags, - std::string diagnosticPrefix = ""); + UnixFileGuard(std::string device, int* fileDescriptor, int flags, + std::string diagnosticPrefix = ""); - virtual~ UnixFileGuard(); + virtual ~UnixFileGuard(); - ReturnValue_t getOpenResult() const; -private: - int* fileDescriptor = nullptr; - ReturnValue_t openStatus = HasReturnvaluesIF::RETURN_OK; + ReturnValue_t getOpenResult() const; + + private: + int* fileDescriptor = nullptr; + ReturnValue_t openStatus = HasReturnvaluesIF::RETURN_OK; }; - - #endif /* LINUX_UTILITY_UNIXFILEGUARD_H_ */ diff --git a/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.cpp b/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.cpp index 020ba964..a33305b6 100644 --- a/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.cpp +++ b/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.cpp @@ -1,442 +1,446 @@ #include "LinuxLibgpioIF.h" -#include "fsfw_hal/common/gpio/gpioDefinitions.h" -#include "fsfw_hal/common/gpio/GpioCookie.h" - -#include "fsfw/serviceinterface/ServiceInterface.h" +#include +#include #include -#include -#include -LinuxLibgpioIF::LinuxLibgpioIF(object_id_t objectId) : SystemObject(objectId) { -} +#include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw_hal/common/gpio/GpioCookie.h" +#include "fsfw_hal/common/gpio/gpioDefinitions.h" + +LinuxLibgpioIF::LinuxLibgpioIF(object_id_t objectId) : SystemObject(objectId) {} LinuxLibgpioIF::~LinuxLibgpioIF() { - for(auto& config: gpioMap) { - delete(config.second); - } + for (auto& config : gpioMap) { + delete (config.second); + } } ReturnValue_t LinuxLibgpioIF::addGpios(GpioCookie* gpioCookie) { - ReturnValue_t result; - if(gpioCookie == nullptr) { - sif::error << "LinuxLibgpioIF::addGpios: Invalid cookie" << std::endl; - return RETURN_FAILED; - } + ReturnValue_t result; + if (gpioCookie == nullptr) { + sif::error << "LinuxLibgpioIF::addGpios: Invalid cookie" << std::endl; + return RETURN_FAILED; + } - GpioMap mapToAdd = gpioCookie->getGpioMap(); + GpioMap mapToAdd = gpioCookie->getGpioMap(); - /* Check whether this ID already exists in the map and remove duplicates */ - result = checkForConflicts(mapToAdd); - if (result != RETURN_OK){ - return result; - } + /* Check whether this ID already exists in the map and remove duplicates */ + result = checkForConflicts(mapToAdd); + if (result != RETURN_OK) { + return result; + } - result = configureGpios(mapToAdd); - if (result != RETURN_OK) { - return RETURN_FAILED; - } + result = configureGpios(mapToAdd); + if (result != RETURN_OK) { + return RETURN_FAILED; + } - /* Register new GPIOs in gpioMap */ - gpioMap.insert(mapToAdd.begin(), mapToAdd.end()); + /* Register new GPIOs in gpioMap */ + gpioMap.insert(mapToAdd.begin(), mapToAdd.end()); - return RETURN_OK; + return RETURN_OK; } ReturnValue_t LinuxLibgpioIF::configureGpios(GpioMap& mapToAdd) { - for(auto& gpioConfig: mapToAdd) { - auto& gpioType = gpioConfig.second->gpioType; - switch(gpioType) { - case(gpio::GpioTypes::NONE): { - return GPIO_INVALID_INSTANCE; + for (auto& gpioConfig : mapToAdd) { + auto& gpioType = gpioConfig.second->gpioType; + switch (gpioType) { + case (gpio::GpioTypes::NONE): { + return GPIO_INVALID_INSTANCE; + } + case (gpio::GpioTypes::GPIO_REGULAR_BY_CHIP): { + auto regularGpio = dynamic_cast(gpioConfig.second); + if (regularGpio == nullptr) { + return GPIO_INVALID_INSTANCE; } - case(gpio::GpioTypes::GPIO_REGULAR_BY_CHIP): { - auto regularGpio = dynamic_cast(gpioConfig.second); - if(regularGpio == nullptr) { - return GPIO_INVALID_INSTANCE; - } - configureGpioByChip(gpioConfig.first, *regularGpio); - break; + configureGpioByChip(gpioConfig.first, *regularGpio); + break; + } + case (gpio::GpioTypes::GPIO_REGULAR_BY_LABEL): { + auto regularGpio = dynamic_cast(gpioConfig.second); + if (regularGpio == nullptr) { + return GPIO_INVALID_INSTANCE; } - case(gpio::GpioTypes::GPIO_REGULAR_BY_LABEL):{ - auto regularGpio = dynamic_cast(gpioConfig.second); - if(regularGpio == nullptr) { - return GPIO_INVALID_INSTANCE; - } - configureGpioByLabel(gpioConfig.first, *regularGpio); - break; - } - case(gpio::GpioTypes::GPIO_REGULAR_BY_LINE_NAME):{ - auto regularGpio = dynamic_cast(gpioConfig.second); - if(regularGpio == nullptr) { - return GPIO_INVALID_INSTANCE; - } - configureGpioByLineName(gpioConfig.first, *regularGpio); - break; - } - case(gpio::GpioTypes::CALLBACK): { - auto gpioCallback = dynamic_cast(gpioConfig.second); - if(gpioCallback->callback == nullptr) { - return GPIO_INVALID_INSTANCE; - } - gpioCallback->callback(gpioConfig.first, gpio::GpioOperation::WRITE, - gpioCallback->initValue, gpioCallback->callbackArgs); + configureGpioByLabel(gpioConfig.first, *regularGpio); + break; + } + case (gpio::GpioTypes::GPIO_REGULAR_BY_LINE_NAME): { + auto regularGpio = dynamic_cast(gpioConfig.second); + if (regularGpio == nullptr) { + return GPIO_INVALID_INSTANCE; } + configureGpioByLineName(gpioConfig.first, *regularGpio); + break; + } + case (gpio::GpioTypes::CALLBACK): { + auto gpioCallback = dynamic_cast(gpioConfig.second); + if (gpioCallback->callback == nullptr) { + return GPIO_INVALID_INSTANCE; } + gpioCallback->callback(gpioConfig.first, gpio::GpioOperation::WRITE, + gpioCallback->initValue, gpioCallback->callbackArgs); + } } - return RETURN_OK; + } + return RETURN_OK; } ReturnValue_t LinuxLibgpioIF::configureGpioByLabel(gpioId_t gpioId, - GpiodRegularByLabel &gpioByLabel) { - std::string& label = gpioByLabel.label; - struct gpiod_chip* chip = gpiod_chip_open_by_label(label.c_str()); - if (chip == nullptr) { - sif::warning << "LinuxLibgpioIF::configureGpioByLabel: Failed to open gpio from gpio " - << "group with label " << label << ". Gpio ID: " << gpioId << std::endl; - return RETURN_FAILED; - - } - std::string failOutput = "label: " + label; - return configureRegularGpio(gpioId, chip, gpioByLabel, failOutput); + GpiodRegularByLabel& gpioByLabel) { + std::string& label = gpioByLabel.label; + struct gpiod_chip* chip = gpiod_chip_open_by_label(label.c_str()); + if (chip == nullptr) { + sif::warning << "LinuxLibgpioIF::configureGpioByLabel: Failed to open gpio from gpio " + << "group with label " << label << ". Gpio ID: " << gpioId << std::endl; + return RETURN_FAILED; + } + std::string failOutput = "label: " + label; + return configureRegularGpio(gpioId, chip, gpioByLabel, failOutput); } -ReturnValue_t LinuxLibgpioIF::configureGpioByChip(gpioId_t gpioId, - GpiodRegularByChip &gpioByChip) { - std::string& chipname = gpioByChip.chipname; - struct gpiod_chip* chip = gpiod_chip_open_by_name(chipname.c_str()); - if (chip == nullptr) { - sif::warning << "LinuxLibgpioIF::configureGpioByChip: Failed to open chip " - << chipname << ". Gpio ID: " << gpioId << std::endl; - return RETURN_FAILED; - } - std::string failOutput = "chipname: " + chipname; - return configureRegularGpio(gpioId, chip, gpioByChip, failOutput); +ReturnValue_t LinuxLibgpioIF::configureGpioByChip(gpioId_t gpioId, GpiodRegularByChip& gpioByChip) { + std::string& chipname = gpioByChip.chipname; + struct gpiod_chip* chip = gpiod_chip_open_by_name(chipname.c_str()); + if (chip == nullptr) { + sif::warning << "LinuxLibgpioIF::configureGpioByChip: Failed to open chip " << chipname + << ". Gpio ID: " << gpioId << std::endl; + return RETURN_FAILED; + } + std::string failOutput = "chipname: " + chipname; + return configureRegularGpio(gpioId, chip, gpioByChip, failOutput); } ReturnValue_t LinuxLibgpioIF::configureGpioByLineName(gpioId_t gpioId, - GpiodRegularByLineName &gpioByLineName) { - std::string& lineName = gpioByLineName.lineName; - char chipname[MAX_CHIPNAME_LENGTH]; - unsigned int lineOffset; + GpiodRegularByLineName& gpioByLineName) { + std::string& lineName = gpioByLineName.lineName; + char chipname[MAX_CHIPNAME_LENGTH]; + unsigned int lineOffset; - int result = gpiod_ctxless_find_line(lineName.c_str(), chipname, MAX_CHIPNAME_LENGTH, - &lineOffset); - if (result != LINE_FOUND) { - parseFindeLineResult(result, lineName); - return RETURN_FAILED; - } + int result = + gpiod_ctxless_find_line(lineName.c_str(), chipname, MAX_CHIPNAME_LENGTH, &lineOffset); + if (result != LINE_FOUND) { + parseFindeLineResult(result, lineName); + return RETURN_FAILED; + } - gpioByLineName.lineNum = static_cast(lineOffset); + gpioByLineName.lineNum = static_cast(lineOffset); - struct gpiod_chip* chip = gpiod_chip_open_by_name(chipname); - if (chip == nullptr) { - sif::warning << "LinuxLibgpioIF::configureGpioByLineName: Failed to open chip " - << chipname << ". second->gpioType; - if (gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_CHIP - or gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_LABEL - or gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_LINE_NAME) { - auto regularGpio = dynamic_cast(gpioMapIter->second); - if(regularGpio == nullptr) { - return GPIO_TYPE_FAILURE; - } - return driveGpio(gpioId, *regularGpio, gpio::HIGH); + auto gpioType = gpioMapIter->second->gpioType; + if (gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_CHIP or + gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_LABEL or + gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_LINE_NAME) { + auto regularGpio = dynamic_cast(gpioMapIter->second); + if (regularGpio == nullptr) { + return GPIO_TYPE_FAILURE; } - else { - auto gpioCallback = dynamic_cast(gpioMapIter->second); - if(gpioCallback->callback == nullptr) { - return GPIO_INVALID_INSTANCE; - } - gpioCallback->callback(gpioMapIter->first, gpio::GpioOperation::WRITE, - gpio::Levels::HIGH, gpioCallback->callbackArgs); - return RETURN_OK; + return driveGpio(gpioId, *regularGpio, gpio::HIGH); + } else { + auto gpioCallback = dynamic_cast(gpioMapIter->second); + if (gpioCallback->callback == nullptr) { + return GPIO_INVALID_INSTANCE; } - return GPIO_TYPE_FAILURE; + gpioCallback->callback(gpioMapIter->first, gpio::GpioOperation::WRITE, gpio::Levels::HIGH, + gpioCallback->callbackArgs); + return RETURN_OK; + } + return GPIO_TYPE_FAILURE; } ReturnValue_t LinuxLibgpioIF::pullLow(gpioId_t gpioId) { - gpioMapIter = gpioMap.find(gpioId); - if (gpioMapIter == gpioMap.end()) { + gpioMapIter = gpioMap.find(gpioId); + if (gpioMapIter == gpioMap.end()) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "LinuxLibgpioIF::pullLow: Unknown GPIO ID " << gpioId << std::endl; + sif::warning << "LinuxLibgpioIF::pullLow: Unknown GPIO ID " << gpioId << std::endl; #else - sif::printWarning("LinuxLibgpioIF::pullLow: Unknown GPIO ID %d\n", gpioId); + sif::printWarning("LinuxLibgpioIF::pullLow: Unknown GPIO ID %d\n", gpioId); #endif - return UNKNOWN_GPIO_ID; - } + return UNKNOWN_GPIO_ID; + } - auto& gpioType = gpioMapIter->second->gpioType; - if (gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_CHIP - or gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_LABEL - or gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_LINE_NAME) { - auto regularGpio = dynamic_cast(gpioMapIter->second); - if(regularGpio == nullptr) { - return GPIO_TYPE_FAILURE; - } - return driveGpio(gpioId, *regularGpio, gpio::LOW); + auto& gpioType = gpioMapIter->second->gpioType; + if (gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_CHIP or + gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_LABEL or + gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_LINE_NAME) { + auto regularGpio = dynamic_cast(gpioMapIter->second); + if (regularGpio == nullptr) { + return GPIO_TYPE_FAILURE; } - else { - auto gpioCallback = dynamic_cast(gpioMapIter->second); - if(gpioCallback->callback == nullptr) { - return GPIO_INVALID_INSTANCE; - } - gpioCallback->callback(gpioMapIter->first, gpio::GpioOperation::WRITE, - gpio::Levels::LOW, gpioCallback->callbackArgs); - return RETURN_OK; + return driveGpio(gpioId, *regularGpio, gpio::LOW); + } else { + auto gpioCallback = dynamic_cast(gpioMapIter->second); + if (gpioCallback->callback == nullptr) { + return GPIO_INVALID_INSTANCE; } - return GPIO_TYPE_FAILURE; + gpioCallback->callback(gpioMapIter->first, gpio::GpioOperation::WRITE, gpio::Levels::LOW, + gpioCallback->callbackArgs); + return RETURN_OK; + } + return GPIO_TYPE_FAILURE; } -ReturnValue_t LinuxLibgpioIF::driveGpio(gpioId_t gpioId, - GpiodRegularBase& regularGpio, gpio::Levels logicLevel) { - int result = gpiod_line_set_value(regularGpio.lineHandle, logicLevel); - if (result < 0) { +ReturnValue_t LinuxLibgpioIF::driveGpio(gpioId_t gpioId, GpiodRegularBase& regularGpio, + gpio::Levels logicLevel) { + int result = gpiod_line_set_value(regularGpio.lineHandle, logicLevel); + if (result < 0) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "LinuxLibgpioIF::driveGpio: Failed to pull GPIO with ID " << gpioId << - " to logic level " << logicLevel << std::endl; + sif::warning << "LinuxLibgpioIF::driveGpio: Failed to pull GPIO with ID " << gpioId + << " to logic level " << logicLevel << std::endl; #else - sif::printWarning("LinuxLibgpioIF::driveGpio: Failed to pull GPIO with ID %d to " - "logic level %d\n", gpioId, logicLevel); + sif::printWarning( + "LinuxLibgpioIF::driveGpio: Failed to pull GPIO with ID %d to " + "logic level %d\n", + gpioId, logicLevel); #endif - return DRIVE_GPIO_FAILURE; - } + return DRIVE_GPIO_FAILURE; + } - return RETURN_OK; + return RETURN_OK; } ReturnValue_t LinuxLibgpioIF::readGpio(gpioId_t gpioId, int* gpioState) { - gpioMapIter = gpioMap.find(gpioId); - if (gpioMapIter == gpioMap.end()){ + gpioMapIter = gpioMap.find(gpioId); + if (gpioMapIter == gpioMap.end()) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "LinuxLibgpioIF::readGpio: Unknown GPIOD ID " << gpioId << std::endl; + sif::warning << "LinuxLibgpioIF::readGpio: Unknown GPIOD ID " << gpioId << std::endl; #else - sif::printWarning("LinuxLibgpioIF::readGpio: Unknown GPIOD ID %d\n", gpioId); + sif::printWarning("LinuxLibgpioIF::readGpio: Unknown GPIOD ID %d\n", gpioId); #endif - return UNKNOWN_GPIO_ID; - } + return UNKNOWN_GPIO_ID; + } - auto gpioType = gpioMapIter->second->gpioType; - if (gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_CHIP - or gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_LABEL - or gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_LINE_NAME) { - auto regularGpio = dynamic_cast(gpioMapIter->second); - if(regularGpio == nullptr) { - return GPIO_TYPE_FAILURE; - } - *gpioState = gpiod_line_get_value(regularGpio->lineHandle); + auto gpioType = gpioMapIter->second->gpioType; + if (gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_CHIP or + gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_LABEL or + gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_LINE_NAME) { + auto regularGpio = dynamic_cast(gpioMapIter->second); + if (regularGpio == nullptr) { + return GPIO_TYPE_FAILURE; } - else { - auto gpioCallback = dynamic_cast(gpioMapIter->second); - if(gpioCallback->callback == nullptr) { - return GPIO_INVALID_INSTANCE; - } - gpioCallback->callback(gpioMapIter->first, gpio::GpioOperation::READ, - gpio::Levels::NONE, gpioCallback->callbackArgs); - return RETURN_OK; + *gpioState = gpiod_line_get_value(regularGpio->lineHandle); + } else { + auto gpioCallback = dynamic_cast(gpioMapIter->second); + if (gpioCallback->callback == nullptr) { + return GPIO_INVALID_INSTANCE; } + gpioCallback->callback(gpioMapIter->first, gpio::GpioOperation::READ, gpio::Levels::NONE, + gpioCallback->callbackArgs); return RETURN_OK; + } + return RETURN_OK; } -ReturnValue_t LinuxLibgpioIF::checkForConflicts(GpioMap& mapToAdd){ - ReturnValue_t status = HasReturnvaluesIF::RETURN_OK; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - for(auto& gpioConfig: mapToAdd) { - switch(gpioConfig.second->gpioType) { - case(gpio::GpioTypes::GPIO_REGULAR_BY_CHIP): - case(gpio::GpioTypes::GPIO_REGULAR_BY_LABEL): - case(gpio::GpioTypes::GPIO_REGULAR_BY_LINE_NAME): { - auto regularGpio = dynamic_cast(gpioConfig.second); - if(regularGpio == nullptr) { - return GPIO_TYPE_FAILURE; - } - // Check for conflicts and remove duplicates if necessary - result = checkForConflictsById(gpioConfig.first, gpioConfig.second->gpioType, mapToAdd); - if(result != HasReturnvaluesIF::RETURN_OK) { - status = result; - } - break; +ReturnValue_t LinuxLibgpioIF::checkForConflicts(GpioMap& mapToAdd) { + ReturnValue_t status = HasReturnvaluesIF::RETURN_OK; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + for (auto& gpioConfig : mapToAdd) { + switch (gpioConfig.second->gpioType) { + case (gpio::GpioTypes::GPIO_REGULAR_BY_CHIP): + case (gpio::GpioTypes::GPIO_REGULAR_BY_LABEL): + case (gpio::GpioTypes::GPIO_REGULAR_BY_LINE_NAME): { + auto regularGpio = dynamic_cast(gpioConfig.second); + if (regularGpio == nullptr) { + return GPIO_TYPE_FAILURE; } - case(gpio::GpioTypes::CALLBACK): { - auto callbackGpio = dynamic_cast(gpioConfig.second); - if(callbackGpio == nullptr) { - return GPIO_TYPE_FAILURE; - } - // Check for conflicts and remove duplicates if necessary - result = checkForConflictsById(gpioConfig.first, - gpioConfig.second->gpioType, mapToAdd); - if(result != HasReturnvaluesIF::RETURN_OK) { - status = result; - } - break; + // Check for conflicts and remove duplicates if necessary + result = checkForConflictsById(gpioConfig.first, gpioConfig.second->gpioType, mapToAdd); + if (result != HasReturnvaluesIF::RETURN_OK) { + status = result; } - default: { + break; + } + case (gpio::GpioTypes::CALLBACK): { + auto callbackGpio = dynamic_cast(gpioConfig.second); + if (callbackGpio == nullptr) { + return GPIO_TYPE_FAILURE; + } + // Check for conflicts and remove duplicates if necessary + result = checkForConflictsById(gpioConfig.first, gpioConfig.second->gpioType, mapToAdd); + if (result != HasReturnvaluesIF::RETURN_OK) { + status = result; + } + break; + } + default: { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "Invalid GPIO type detected for GPIO ID " << gpioConfig.first - << std::endl; + sif::warning << "Invalid GPIO type detected for GPIO ID " << gpioConfig.first << std::endl; #else - sif::printWarning("Invalid GPIO type detected for GPIO ID %d\n", gpioConfig.first); + sif::printWarning("Invalid GPIO type detected for GPIO ID %d\n", gpioConfig.first); #endif - status = GPIO_TYPE_FAILURE; - } - } + status = GPIO_TYPE_FAILURE; + } } - return status; + } + return status; } ReturnValue_t LinuxLibgpioIF::checkForConflictsById(gpioId_t gpioIdToCheck, - gpio::GpioTypes expectedType, GpioMap& mapToAdd) { - // Cross check with private map - gpioMapIter = gpioMap.find(gpioIdToCheck); - if(gpioMapIter != gpioMap.end()) { - auto& gpioType = gpioMapIter->second->gpioType; - bool eraseDuplicateDifferentType = false; - switch(expectedType) { - case(gpio::GpioTypes::NONE): { - break; + gpio::GpioTypes expectedType, + GpioMap& mapToAdd) { + // Cross check with private map + gpioMapIter = gpioMap.find(gpioIdToCheck); + if (gpioMapIter != gpioMap.end()) { + auto& gpioType = gpioMapIter->second->gpioType; + bool eraseDuplicateDifferentType = false; + switch (expectedType) { + case (gpio::GpioTypes::NONE): { + break; + } + case (gpio::GpioTypes::GPIO_REGULAR_BY_CHIP): + case (gpio::GpioTypes::GPIO_REGULAR_BY_LABEL): + case (gpio::GpioTypes::GPIO_REGULAR_BY_LINE_NAME): { + if (gpioType == gpio::GpioTypes::NONE or gpioType == gpio::GpioTypes::CALLBACK) { + eraseDuplicateDifferentType = true; } - case(gpio::GpioTypes::GPIO_REGULAR_BY_CHIP): - case(gpio::GpioTypes::GPIO_REGULAR_BY_LABEL): - case(gpio::GpioTypes::GPIO_REGULAR_BY_LINE_NAME): { - if(gpioType == gpio::GpioTypes::NONE or gpioType == gpio::GpioTypes::CALLBACK) { - eraseDuplicateDifferentType = true; - } - break; + break; + } + case (gpio::GpioTypes::CALLBACK): { + if (gpioType != gpio::GpioTypes::CALLBACK) { + eraseDuplicateDifferentType = true; } - case(gpio::GpioTypes::CALLBACK): { - if(gpioType != gpio::GpioTypes::CALLBACK) { - eraseDuplicateDifferentType = true; - } - } - } - if(eraseDuplicateDifferentType) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "LinuxLibgpioIF::checkForConflicts: ID already exists for " - "different GPIO type " << gpioIdToCheck << - ". Removing duplicate from map to add" << std::endl; -#else - sif::printWarning("LinuxLibgpioIF::checkForConflicts: ID already exists for " - "different GPIO type %d. Removing duplicate from map to add\n", gpioIdToCheck); -#endif - mapToAdd.erase(gpioIdToCheck); - return GPIO_DUPLICATE_DETECTED; - } - - // Remove element from map to add because a entry for this GPIO already exists -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "LinuxLibgpioIF::checkForConflictsRegularGpio: Duplicate GPIO " - "definition with ID " << gpioIdToCheck << " detected. " << - "Duplicate will be removed from map to add" << std::endl; -#else - sif::printWarning("LinuxLibgpioIF::checkForConflictsRegularGpio: Duplicate GPIO definition " - "with ID %d detected. Duplicate will be removed from map to add\n", gpioIdToCheck); -#endif - mapToAdd.erase(gpioIdToCheck); - return GPIO_DUPLICATE_DETECTED; + } } - return HasReturnvaluesIF::RETURN_OK; + if (eraseDuplicateDifferentType) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "LinuxLibgpioIF::checkForConflicts: ID already exists for " + "different GPIO type " + << gpioIdToCheck << ". Removing duplicate from map to add" << std::endl; +#else + sif::printWarning( + "LinuxLibgpioIF::checkForConflicts: ID already exists for " + "different GPIO type %d. Removing duplicate from map to add\n", + gpioIdToCheck); +#endif + mapToAdd.erase(gpioIdToCheck); + return GPIO_DUPLICATE_DETECTED; + } + + // Remove element from map to add because a entry for this GPIO already exists +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "LinuxLibgpioIF::checkForConflictsRegularGpio: Duplicate GPIO " + "definition with ID " + << gpioIdToCheck << " detected. " + << "Duplicate will be removed from map to add" << std::endl; +#else + sif::printWarning( + "LinuxLibgpioIF::checkForConflictsRegularGpio: Duplicate GPIO definition " + "with ID %d detected. Duplicate will be removed from map to add\n", + gpioIdToCheck); +#endif + mapToAdd.erase(gpioIdToCheck); + return GPIO_DUPLICATE_DETECTED; + } + return HasReturnvaluesIF::RETURN_OK; } void LinuxLibgpioIF::parseFindeLineResult(int result, std::string& lineName) { - switch (result) { + switch (result) { #if FSFW_CPP_OSTREAM_ENABLED == 1 case LINE_NOT_EXISTS: case LINE_ERROR: { - sif::warning << "LinuxLibgpioIF::parseFindeLineResult: Line with name " << lineName << - " does not exist" << std::endl; - break; + sif::warning << "LinuxLibgpioIF::parseFindeLineResult: Line with name " << lineName + << " does not exist" << std::endl; + break; } default: { - sif::warning << "LinuxLibgpioIF::parseFindeLineResult: Unknown return code for line " - "with name " << lineName << std::endl; - break; + sif::warning << "LinuxLibgpioIF::parseFindeLineResult: Unknown return code for line " + "with name " + << lineName << std::endl; + break; } #else case LINE_NOT_EXISTS: case LINE_ERROR: { - sif::printWarning("LinuxLibgpioIF::parseFindeLineResult: Line with name %s " - "does not exist\n", lineName); - break; + sif::printWarning( + "LinuxLibgpioIF::parseFindeLineResult: Line with name %s " + "does not exist\n", + lineName); + break; } default: { - sif::printWarning("LinuxLibgpioIF::parseFindeLineResult: Unknown return code for line " - "with name %s\n", lineName); - break; + sif::printWarning( + "LinuxLibgpioIF::parseFindeLineResult: Unknown return code for line " + "with name %s\n", + lineName); + break; } #endif - } - + } } diff --git a/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h b/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h index cc32bd70..7d49e6e2 100644 --- a/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +++ b/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h @@ -1,9 +1,9 @@ #ifndef LINUX_GPIO_LINUXLIBGPIOIF_H_ #define LINUX_GPIO_LINUXLIBGPIOIF_H_ +#include "fsfw/objectmanager/SystemObject.h" #include "fsfw/returnvalues/FwClassIds.h" #include "fsfw_hal/common/gpio/GpioIF.h" -#include "fsfw/objectmanager/SystemObject.h" class GpioCookie; class GpiodRegularIF; @@ -16,76 +16,71 @@ class GpiodRegularIF; * The Petalinux SDK from Xilinx supports libgpiod since Petalinux 2019.1. */ class LinuxLibgpioIF : public GpioIF, public SystemObject { -public: + public: + static const uint8_t gpioRetvalId = CLASS_ID::HAL_GPIO; - static const uint8_t gpioRetvalId = CLASS_ID::HAL_GPIO; + static constexpr ReturnValue_t UNKNOWN_GPIO_ID = + HasReturnvaluesIF::makeReturnCode(gpioRetvalId, 1); + static constexpr ReturnValue_t DRIVE_GPIO_FAILURE = + HasReturnvaluesIF::makeReturnCode(gpioRetvalId, 2); + static constexpr ReturnValue_t GPIO_TYPE_FAILURE = + HasReturnvaluesIF::makeReturnCode(gpioRetvalId, 3); + static constexpr ReturnValue_t GPIO_INVALID_INSTANCE = + HasReturnvaluesIF::makeReturnCode(gpioRetvalId, 4); + static constexpr ReturnValue_t GPIO_DUPLICATE_DETECTED = + HasReturnvaluesIF::makeReturnCode(gpioRetvalId, 5); - static constexpr ReturnValue_t UNKNOWN_GPIO_ID = - HasReturnvaluesIF::makeReturnCode(gpioRetvalId, 1); - static constexpr ReturnValue_t DRIVE_GPIO_FAILURE = - HasReturnvaluesIF::makeReturnCode(gpioRetvalId, 2); - static constexpr ReturnValue_t GPIO_TYPE_FAILURE = - HasReturnvaluesIF::makeReturnCode(gpioRetvalId, 3); - static constexpr ReturnValue_t GPIO_INVALID_INSTANCE = - HasReturnvaluesIF::makeReturnCode(gpioRetvalId, 4); - static constexpr ReturnValue_t GPIO_DUPLICATE_DETECTED = - HasReturnvaluesIF::makeReturnCode(gpioRetvalId, 5); + LinuxLibgpioIF(object_id_t objectId); + virtual ~LinuxLibgpioIF(); - LinuxLibgpioIF(object_id_t objectId); - virtual ~LinuxLibgpioIF(); + ReturnValue_t addGpios(GpioCookie* gpioCookie) override; + ReturnValue_t pullHigh(gpioId_t gpioId) override; + ReturnValue_t pullLow(gpioId_t gpioId) override; + ReturnValue_t readGpio(gpioId_t gpioId, int* gpioState) override; - ReturnValue_t addGpios(GpioCookie* gpioCookie) override; - ReturnValue_t pullHigh(gpioId_t gpioId) override; - ReturnValue_t pullLow(gpioId_t gpioId) override; - ReturnValue_t readGpio(gpioId_t gpioId, int* gpioState) override; + private: + static const size_t MAX_CHIPNAME_LENGTH = 11; + static const int LINE_NOT_EXISTS = 0; + static const int LINE_ERROR = -1; + static const int LINE_FOUND = 1; -private: + // Holds the information and configuration of all used GPIOs + GpioUnorderedMap gpioMap; + GpioUnorderedMapIter gpioMapIter; - static const size_t MAX_CHIPNAME_LENGTH = 11; - static const int LINE_NOT_EXISTS = 0; - static const int LINE_ERROR = -1; - static const int LINE_FOUND = 1; + /** + * @brief This functions drives line of a GPIO specified by the GPIO ID. + * + * @param gpioId The GPIO ID of the GPIO to drive. + * @param logiclevel The logic level to set. O or 1. + */ + ReturnValue_t driveGpio(gpioId_t gpioId, GpiodRegularBase& regularGpio, gpio::Levels logicLevel); - // Holds the information and configuration of all used GPIOs - GpioUnorderedMap gpioMap; - GpioUnorderedMapIter gpioMapIter; + ReturnValue_t configureGpioByLabel(gpioId_t gpioId, GpiodRegularByLabel& gpioByLabel); + ReturnValue_t configureGpioByChip(gpioId_t gpioId, GpiodRegularByChip& gpioByChip); + ReturnValue_t configureGpioByLineName(gpioId_t gpioId, GpiodRegularByLineName& gpioByLineName); + ReturnValue_t configureRegularGpio(gpioId_t gpioId, struct gpiod_chip* chip, + GpiodRegularBase& regularGpio, std::string failOutput); - /** - * @brief This functions drives line of a GPIO specified by the GPIO ID. - * - * @param gpioId The GPIO ID of the GPIO to drive. - * @param logiclevel The logic level to set. O or 1. - */ - ReturnValue_t driveGpio(gpioId_t gpioId, GpiodRegularBase& regularGpio, - gpio::Levels logicLevel); + /** + * @brief This function checks if GPIOs are already registered and whether + * there exists a conflict in the GPIO configuration. E.g. the + * direction. + * + * @param mapToAdd The GPIOs which shall be added to the gpioMap. + * + * @return RETURN_OK if successful, otherwise RETURN_FAILED + */ + ReturnValue_t checkForConflicts(GpioMap& mapToAdd); - ReturnValue_t configureGpioByLabel(gpioId_t gpioId, GpiodRegularByLabel& gpioByLabel); - ReturnValue_t configureGpioByChip(gpioId_t gpioId, GpiodRegularByChip& gpioByChip); - ReturnValue_t configureGpioByLineName(gpioId_t gpioId, - GpiodRegularByLineName &gpioByLineName); - ReturnValue_t configureRegularGpio(gpioId_t gpioId, struct gpiod_chip* chip, - GpiodRegularBase& regularGpio, std::string failOutput); + ReturnValue_t checkForConflictsById(gpioId_t gpiodId, gpio::GpioTypes type, GpioMap& mapToAdd); - /** - * @brief This function checks if GPIOs are already registered and whether - * there exists a conflict in the GPIO configuration. E.g. the - * direction. - * - * @param mapToAdd The GPIOs which shall be added to the gpioMap. - * - * @return RETURN_OK if successful, otherwise RETURN_FAILED - */ - ReturnValue_t checkForConflicts(GpioMap& mapToAdd); + /** + * @brief Performs the initial configuration of all GPIOs specified in the GpioMap mapToAdd. + */ + ReturnValue_t configureGpios(GpioMap& mapToAdd); - ReturnValue_t checkForConflictsById(gpioId_t gpiodId, gpio::GpioTypes type, - GpioMap& mapToAdd); - - /** - * @brief Performs the initial configuration of all GPIOs specified in the GpioMap mapToAdd. - */ - ReturnValue_t configureGpios(GpioMap& mapToAdd); - - void parseFindeLineResult(int result, std::string& lineName); + void parseFindeLineResult(int result, std::string& lineName); }; #endif /* LINUX_GPIO_LINUXLIBGPIOIF_H_ */ diff --git a/hal/src/fsfw_hal/linux/i2c/I2cComIF.cpp b/hal/src/fsfw_hal/linux/i2c/I2cComIF.cpp index fd5e8454..dc23542d 100644 --- a/hal/src/fsfw_hal/linux/i2c/I2cComIF.cpp +++ b/hal/src/fsfw_hal/linux/i2c/I2cComIF.cpp @@ -1,233 +1,223 @@ -#include "fsfw/FSFW.h" - #include "fsfw_hal/linux/i2c/I2cComIF.h" -#include "fsfw_hal/linux/utility.h" -#include "fsfw_hal/linux/UnixFileGuard.h" -#include "fsfw/serviceinterface.h" - -#include -#include -#include -#include #include +#include +#include +#include +#include #include +#include "fsfw/FSFW.h" +#include "fsfw/serviceinterface.h" +#include "fsfw_hal/linux/UnixFileGuard.h" +#include "fsfw_hal/linux/utility.h" -I2cComIF::I2cComIF(object_id_t objectId): SystemObject(objectId){ -} +I2cComIF::I2cComIF(object_id_t objectId) : SystemObject(objectId) {} I2cComIF::~I2cComIF() {} ReturnValue_t I2cComIF::initializeInterface(CookieIF* cookie) { + address_t i2cAddress; + std::string deviceFile; - address_t i2cAddress; - std::string deviceFile; - - if(cookie == nullptr) { + if (cookie == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "I2cComIF::initializeInterface: Invalid cookie!" << std::endl; + sif::error << "I2cComIF::initializeInterface: Invalid cookie!" << std::endl; #endif - return NULLPOINTER; - } - I2cCookie* i2cCookie = dynamic_cast(cookie); - if(i2cCookie == nullptr) { + return NULLPOINTER; + } + I2cCookie* i2cCookie = dynamic_cast(cookie); + if (i2cCookie == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "I2cComIF::initializeInterface: Invalid I2C cookie!" << std::endl; + sif::error << "I2cComIF::initializeInterface: Invalid I2C cookie!" << std::endl; #endif - return NULLPOINTER; - } + return NULLPOINTER; + } - i2cAddress = i2cCookie->getAddress(); + i2cAddress = i2cCookie->getAddress(); - i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); - if(i2cDeviceMapIter == i2cDeviceMap.end()) { - size_t maxReplyLen = i2cCookie->getMaxReplyLen(); - I2cInstance i2cInstance = {std::vector(maxReplyLen), 0}; - auto statusPair = i2cDeviceMap.emplace(i2cAddress, i2cInstance); - if (not statusPair.second) { + i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); + if (i2cDeviceMapIter == i2cDeviceMap.end()) { + size_t maxReplyLen = i2cCookie->getMaxReplyLen(); + I2cInstance i2cInstance = {std::vector(maxReplyLen), 0}; + auto statusPair = i2cDeviceMap.emplace(i2cAddress, i2cInstance); + if (not statusPair.second) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "I2cComIF::initializeInterface: Failed to insert device with address " << - i2cAddress << "to I2C device " << "map" << std::endl; + sif::error << "I2cComIF::initializeInterface: Failed to insert device with address " + << i2cAddress << "to I2C device " + << "map" << std::endl; #endif - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_FAILED; } + return HasReturnvaluesIF::RETURN_OK; + } #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "I2cComIF::initializeInterface: Device with address " << i2cAddress << - "already in use" << std::endl; + sif::error << "I2cComIF::initializeInterface: Device with address " << i2cAddress + << "already in use" << std::endl; +#endif + return HasReturnvaluesIF::RETURN_FAILED; +} + +ReturnValue_t I2cComIF::sendMessage(CookieIF* cookie, const uint8_t* sendData, size_t sendLen) { + ReturnValue_t result; + int fd; + std::string deviceFile; + + if (sendData == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::error << "I2cComIF::sendMessage: Send Data is nullptr" << std::endl; #endif return HasReturnvaluesIF::RETURN_FAILED; -} + } -ReturnValue_t I2cComIF::sendMessage(CookieIF *cookie, - const uint8_t *sendData, size_t sendLen) { - - ReturnValue_t result; - int fd; - std::string deviceFile; - - if(sendData == nullptr) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "I2cComIF::sendMessage: Send Data is nullptr" - << std::endl; -#endif - return HasReturnvaluesIF::RETURN_FAILED; - } - - if(sendLen == 0) { - return HasReturnvaluesIF::RETURN_OK; - } - - I2cCookie* i2cCookie = dynamic_cast(cookie); - if(i2cCookie == nullptr) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "I2cComIF::sendMessage: Invalid I2C Cookie!" << std::endl; -#endif - return NULLPOINTER; - } - - address_t i2cAddress = i2cCookie->getAddress(); - i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); - if (i2cDeviceMapIter == i2cDeviceMap.end()) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "I2cComIF::sendMessage: i2cAddress of Cookie not " - << "registered in i2cDeviceMap" << std::endl; -#endif - return HasReturnvaluesIF::RETURN_FAILED; - } - - deviceFile = i2cCookie->getDeviceFile(); - UnixFileGuard fileHelper(deviceFile, &fd, O_RDWR, "I2cComIF::sendMessage"); - if(fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { - return fileHelper.getOpenResult(); - } - result = openDevice(deviceFile, i2cAddress, &fd); - if (result != HasReturnvaluesIF::RETURN_OK){ - return result; - } - - if (write(fd, sendData, sendLen) != static_cast(sendLen)) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "I2cComIF::sendMessage: Failed to send data to I2C " - "device with error code " << errno << ". Error description: " - << strerror(errno) << std::endl; -#endif - return HasReturnvaluesIF::RETURN_FAILED; - } + if (sendLen == 0) { return HasReturnvaluesIF::RETURN_OK; + } + + I2cCookie* i2cCookie = dynamic_cast(cookie); + if (i2cCookie == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::error << "I2cComIF::sendMessage: Invalid I2C Cookie!" << std::endl; +#endif + return NULLPOINTER; + } + + address_t i2cAddress = i2cCookie->getAddress(); + i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); + if (i2cDeviceMapIter == i2cDeviceMap.end()) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::error << "I2cComIF::sendMessage: i2cAddress of Cookie not " + << "registered in i2cDeviceMap" << std::endl; +#endif + return HasReturnvaluesIF::RETURN_FAILED; + } + + deviceFile = i2cCookie->getDeviceFile(); + UnixFileGuard fileHelper(deviceFile, &fd, O_RDWR, "I2cComIF::sendMessage"); + if (fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { + return fileHelper.getOpenResult(); + } + result = openDevice(deviceFile, i2cAddress, &fd); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + + if (write(fd, sendData, sendLen) != static_cast(sendLen)) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::error << "I2cComIF::sendMessage: Failed to send data to I2C " + "device with error code " + << errno << ". Error description: " << strerror(errno) << std::endl; +#endif + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t I2cComIF::getSendSuccess(CookieIF *cookie) { +ReturnValue_t I2cComIF::getSendSuccess(CookieIF* cookie) { return HasReturnvaluesIF::RETURN_OK; } + +ReturnValue_t I2cComIF::requestReceiveMessage(CookieIF* cookie, size_t requestLen) { + ReturnValue_t result; + int fd; + std::string deviceFile; + + if (requestLen == 0) { return HasReturnvaluesIF::RETURN_OK; -} + } -ReturnValue_t I2cComIF::requestReceiveMessage(CookieIF *cookie, - size_t requestLen) { - ReturnValue_t result; - int fd; - std::string deviceFile; - - if (requestLen == 0) { - return HasReturnvaluesIF::RETURN_OK; - } - - I2cCookie* i2cCookie = dynamic_cast(cookie); - if(i2cCookie == nullptr) { + I2cCookie* i2cCookie = dynamic_cast(cookie); + if (i2cCookie == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "I2cComIF::requestReceiveMessage: Invalid I2C Cookie!" << std::endl; + sif::error << "I2cComIF::requestReceiveMessage: Invalid I2C Cookie!" << std::endl; #endif - i2cDeviceMapIter->second.replyLen = 0; - return NULLPOINTER; - } + i2cDeviceMapIter->second.replyLen = 0; + return NULLPOINTER; + } - address_t i2cAddress = i2cCookie->getAddress(); - i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); - if (i2cDeviceMapIter == i2cDeviceMap.end()) { + address_t i2cAddress = i2cCookie->getAddress(); + i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); + if (i2cDeviceMapIter == i2cDeviceMap.end()) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "I2cComIF::requestReceiveMessage: i2cAddress of Cookie not " - << "registered in i2cDeviceMap" << std::endl; + sif::error << "I2cComIF::requestReceiveMessage: i2cAddress of Cookie not " + << "registered in i2cDeviceMap" << std::endl; #endif - i2cDeviceMapIter->second.replyLen = 0; - return HasReturnvaluesIF::RETURN_FAILED; - } + i2cDeviceMapIter->second.replyLen = 0; + return HasReturnvaluesIF::RETURN_FAILED; + } - deviceFile = i2cCookie->getDeviceFile(); - UnixFileGuard fileHelper(deviceFile, &fd, O_RDWR, "I2cComIF::requestReceiveMessage"); - if(fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { - return fileHelper.getOpenResult(); - } - result = openDevice(deviceFile, i2cAddress, &fd); - if (result != HasReturnvaluesIF::RETURN_OK){ - i2cDeviceMapIter->second.replyLen = 0; - return result; - } + deviceFile = i2cCookie->getDeviceFile(); + UnixFileGuard fileHelper(deviceFile, &fd, O_RDWR, "I2cComIF::requestReceiveMessage"); + if (fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { + return fileHelper.getOpenResult(); + } + result = openDevice(deviceFile, i2cAddress, &fd); + if (result != HasReturnvaluesIF::RETURN_OK) { + i2cDeviceMapIter->second.replyLen = 0; + return result; + } - uint8_t* replyBuffer = i2cDeviceMapIter->second.replyBuffer.data(); + uint8_t* replyBuffer = i2cDeviceMapIter->second.replyBuffer.data(); - int readLen = read(fd, replyBuffer, requestLen); - if (readLen != static_cast(requestLen)) { + int readLen = read(fd, replyBuffer, requestLen); + if (readLen != static_cast(requestLen)) { #if FSFW_VERBOSE_LEVEL >= 1 and FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "I2cComIF::requestReceiveMessage: Reading from I2C " - << "device failed with error code " << errno <<". Description" - << " of error: " << strerror(errno) << std::endl; - sif::error << "I2cComIF::requestReceiveMessage: Read only " << readLen << " from " - << requestLen << " bytes" << std::endl; + sif::error << "I2cComIF::requestReceiveMessage: Reading from I2C " + << "device failed with error code " << errno << ". Description" + << " of error: " << strerror(errno) << std::endl; + sif::error << "I2cComIF::requestReceiveMessage: Read only " << readLen << " from " << requestLen + << " bytes" << std::endl; #endif - i2cDeviceMapIter->second.replyLen = 0; + i2cDeviceMapIter->second.replyLen = 0; #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "I2cComIF::requestReceiveMessage: Read " << readLen << " of " << requestLen << " bytes" << std::endl; + sif::debug << "I2cComIF::requestReceiveMessage: Read " << readLen << " of " << requestLen + << " bytes" << std::endl; #endif - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; + } - i2cDeviceMapIter->second.replyLen = requestLen; - return HasReturnvaluesIF::RETURN_OK; + i2cDeviceMapIter->second.replyLen = requestLen; + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t I2cComIF::readReceivedMessage(CookieIF *cookie, - uint8_t **buffer, size_t* size) { - I2cCookie* i2cCookie = dynamic_cast(cookie); - if(i2cCookie == nullptr) { +ReturnValue_t I2cComIF::readReceivedMessage(CookieIF* cookie, uint8_t** buffer, size_t* size) { + I2cCookie* i2cCookie = dynamic_cast(cookie); + if (i2cCookie == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "I2cComIF::readReceivedMessage: Invalid I2C Cookie!" << std::endl; + sif::error << "I2cComIF::readReceivedMessage: Invalid I2C Cookie!" << std::endl; #endif - return NULLPOINTER; - } + return NULLPOINTER; + } - address_t i2cAddress = i2cCookie->getAddress(); - i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); - if (i2cDeviceMapIter == i2cDeviceMap.end()) { + address_t i2cAddress = i2cCookie->getAddress(); + i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); + if (i2cDeviceMapIter == i2cDeviceMap.end()) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "I2cComIF::readReceivedMessage: i2cAddress of Cookie not " - << "found in i2cDeviceMap" << std::endl; + sif::error << "I2cComIF::readReceivedMessage: i2cAddress of Cookie not " + << "found in i2cDeviceMap" << std::endl; #endif - return HasReturnvaluesIF::RETURN_FAILED; - } - *buffer = i2cDeviceMapIter->second.replyBuffer.data(); - *size = i2cDeviceMapIter->second.replyLen; + return HasReturnvaluesIF::RETURN_FAILED; + } + *buffer = i2cDeviceMapIter->second.replyBuffer.data(); + *size = i2cDeviceMapIter->second.replyLen; - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t I2cComIF::openDevice(std::string deviceFile, - address_t i2cAddress, int* fileDescriptor) { - - if (ioctl(*fileDescriptor, I2C_SLAVE, i2cAddress) < 0) { +ReturnValue_t I2cComIF::openDevice(std::string deviceFile, address_t i2cAddress, + int* fileDescriptor) { + if (ioctl(*fileDescriptor, I2C_SLAVE, i2cAddress) < 0) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "I2cComIF: Specifying target device failed with error code " << errno << "." - << std::endl; - sif::warning << "Error description " << strerror(errno) << std::endl; + sif::warning << "I2cComIF: Specifying target device failed with error code " << errno << "." + << std::endl; + sif::warning << "Error description " << strerror(errno) << std::endl; #else - sif::printWarning("I2cComIF: Specifying target device failed with error code %d.\n"); - sif::printWarning("Error description: %s\n", strerror(errno)); + sif::printWarning("I2cComIF: Specifying target device failed with error code %d.\n"); + sif::printWarning("Error description: %s\n", strerror(errno)); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } diff --git a/hal/src/fsfw_hal/linux/i2c/I2cComIF.h b/hal/src/fsfw_hal/linux/i2c/I2cComIF.h index 0856c9bd..cf3bbe49 100644 --- a/hal/src/fsfw_hal/linux/i2c/I2cComIF.h +++ b/hal/src/fsfw_hal/linux/i2c/I2cComIF.h @@ -1,13 +1,14 @@ #ifndef LINUX_I2C_I2COMIF_H_ #define LINUX_I2C_I2COMIF_H_ -#include "I2cCookie.h" -#include #include +#include #include #include +#include "I2cCookie.h" + /** * @brief This is the communication interface for I2C devices connected * to a system running a Linux OS. @@ -16,46 +17,41 @@ * * @author J. Meier */ -class I2cComIF: public DeviceCommunicationIF, public SystemObject { -public: - I2cComIF(object_id_t objectId); +class I2cComIF : public DeviceCommunicationIF, public SystemObject { + public: + I2cComIF(object_id_t objectId); - virtual ~I2cComIF(); + virtual ~I2cComIF(); - ReturnValue_t initializeInterface(CookieIF * cookie) override; - ReturnValue_t sendMessage(CookieIF *cookie,const uint8_t *sendData, - size_t sendLen) override; - ReturnValue_t getSendSuccess(CookieIF *cookie) override; - ReturnValue_t requestReceiveMessage(CookieIF *cookie, - size_t requestLen) override; - ReturnValue_t readReceivedMessage(CookieIF *cookie, uint8_t **buffer, - size_t *size) override; + ReturnValue_t initializeInterface(CookieIF *cookie) override; + ReturnValue_t sendMessage(CookieIF *cookie, const uint8_t *sendData, size_t sendLen) override; + ReturnValue_t getSendSuccess(CookieIF *cookie) override; + ReturnValue_t requestReceiveMessage(CookieIF *cookie, size_t requestLen) override; + ReturnValue_t readReceivedMessage(CookieIF *cookie, uint8_t **buffer, size_t *size) override; -private: + private: + struct I2cInstance { + std::vector replyBuffer; + size_t replyLen; + }; - struct I2cInstance { - std::vector replyBuffer; - size_t replyLen; - }; + using I2cDeviceMap = std::unordered_map; + using I2cDeviceMapIter = I2cDeviceMap::iterator; - using I2cDeviceMap = std::unordered_map; - using I2cDeviceMapIter = I2cDeviceMap::iterator; + /* In this map all i2c devices will be registered with their address and + * the appropriate file descriptor will be stored */ + I2cDeviceMap i2cDeviceMap; + I2cDeviceMapIter i2cDeviceMapIter; - /* In this map all i2c devices will be registered with their address and - * the appropriate file descriptor will be stored */ - I2cDeviceMap i2cDeviceMap; - I2cDeviceMapIter i2cDeviceMapIter; - - /** - * @brief This function opens an I2C device and binds the opened file - * to a specific I2C address. - * @param deviceFile The name of the device file. E.g. i2c-0 - * @param i2cAddress The address of the i2c slave device. - * @param fileDescriptor Pointer to device descriptor. - * @return RETURN_OK if successful, otherwise RETURN_FAILED. - */ - ReturnValue_t openDevice(std::string deviceFile, - address_t i2cAddress, int* fileDescriptor); + /** + * @brief This function opens an I2C device and binds the opened file + * to a specific I2C address. + * @param deviceFile The name of the device file. E.g. i2c-0 + * @param i2cAddress The address of the i2c slave device. + * @param fileDescriptor Pointer to device descriptor. + * @return RETURN_OK if successful, otherwise RETURN_FAILED. + */ + ReturnValue_t openDevice(std::string deviceFile, address_t i2cAddress, int *fileDescriptor); }; #endif /* LINUX_I2C_I2COMIF_H_ */ diff --git a/hal/src/fsfw_hal/linux/i2c/I2cCookie.cpp b/hal/src/fsfw_hal/linux/i2c/I2cCookie.cpp index aebffedb..0186be60 100644 --- a/hal/src/fsfw_hal/linux/i2c/I2cCookie.cpp +++ b/hal/src/fsfw_hal/linux/i2c/I2cCookie.cpp @@ -1,20 +1,12 @@ #include "fsfw_hal/linux/i2c/I2cCookie.h" -I2cCookie::I2cCookie(address_t i2cAddress_, size_t maxReplyLen_, - std::string deviceFile_) : - i2cAddress(i2cAddress_), maxReplyLen(maxReplyLen_), deviceFile(deviceFile_) { -} +I2cCookie::I2cCookie(address_t i2cAddress_, size_t maxReplyLen_, std::string deviceFile_) + : i2cAddress(i2cAddress_), maxReplyLen(maxReplyLen_), deviceFile(deviceFile_) {} -address_t I2cCookie::getAddress() const { - return i2cAddress; -} +address_t I2cCookie::getAddress() const { return i2cAddress; } -size_t I2cCookie::getMaxReplyLen() const { - return maxReplyLen; -} +size_t I2cCookie::getMaxReplyLen() const { return maxReplyLen; } -std::string I2cCookie::getDeviceFile() const { - return deviceFile; -} +std::string I2cCookie::getDeviceFile() const { return deviceFile; } I2cCookie::~I2cCookie() {} diff --git a/hal/src/fsfw_hal/linux/i2c/I2cCookie.h b/hal/src/fsfw_hal/linux/i2c/I2cCookie.h index 888a2b12..84a1873c 100644 --- a/hal/src/fsfw_hal/linux/i2c/I2cCookie.h +++ b/hal/src/fsfw_hal/linux/i2c/I2cCookie.h @@ -2,6 +2,7 @@ #define LINUX_I2C_I2CCOOKIE_H_ #include + #include /** @@ -9,30 +10,27 @@ * * @author J. Meier */ -class I2cCookie: public CookieIF { -public: +class I2cCookie : public CookieIF { + public: + /** + * @brief Constructor for the I2C cookie. + * @param i2cAddress_ The i2c address of the target device. + * @param maxReplyLen_ The maximum expected length of a reply from the + * target device. + * @param devicFile_ The device file specifying the i2c interface to use. E.g. "/dev/i2c-0". + */ + I2cCookie(address_t i2cAddress_, size_t maxReplyLen_, std::string deviceFile_); - /** - * @brief Constructor for the I2C cookie. - * @param i2cAddress_ The i2c address of the target device. - * @param maxReplyLen_ The maximum expected length of a reply from the - * target device. - * @param devicFile_ The device file specifying the i2c interface to use. E.g. "/dev/i2c-0". - */ - I2cCookie(address_t i2cAddress_, size_t maxReplyLen_, - std::string deviceFile_); + virtual ~I2cCookie(); - virtual ~I2cCookie(); + address_t getAddress() const; + size_t getMaxReplyLen() const; + std::string getDeviceFile() const; - address_t getAddress() const; - size_t getMaxReplyLen() const; - std::string getDeviceFile() const; - -private: - - address_t i2cAddress = 0; - size_t maxReplyLen = 0; - std::string deviceFile; + private: + address_t i2cAddress = 0; + size_t maxReplyLen = 0; + std::string deviceFile; }; #endif /* LINUX_I2C_I2CCOOKIE_H_ */ diff --git a/hal/src/fsfw_hal/linux/rpi/GpioRPi.cpp b/hal/src/fsfw_hal/linux/rpi/GpioRPi.cpp index e1c274c0..c005e24f 100644 --- a/hal/src/fsfw_hal/linux/rpi/GpioRPi.cpp +++ b/hal/src/fsfw_hal/linux/rpi/GpioRPi.cpp @@ -1,38 +1,38 @@ -#include "fsfw/FSFW.h" - #include "fsfw_hal/linux/rpi/GpioRPi.h" -#include "fsfw_hal/common/gpio/GpioCookie.h" #include +#include "fsfw/FSFW.h" +#include "fsfw_hal/common/gpio/GpioCookie.h" ReturnValue_t gpio::createRpiGpioConfig(GpioCookie* cookie, gpioId_t gpioId, int bcmPin, - std::string consumer, gpio::Direction direction, int initValue) { - if(cookie == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } + std::string consumer, gpio::Direction direction, + int initValue) { + if (cookie == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } - auto config = new GpiodRegularByChip(); - /* Default chipname for Raspberry Pi. There is still gpiochip1 for expansion, but most users - will not need this */ - config->chipname = "gpiochip0"; + auto config = new GpiodRegularByChip(); + /* Default chipname for Raspberry Pi. There is still gpiochip1 for expansion, but most users + will not need this */ + config->chipname = "gpiochip0"; - config->consumer = consumer; - config->direction = direction; - config->initValue = initValue; + config->consumer = consumer; + config->direction = direction; + config->initValue = initValue; - /* Sanity check for the BCM pins before assigning it */ - if(bcmPin > 27) { + /* Sanity check for the BCM pins before assigning it */ + if (bcmPin > 27) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "createRpiGpioConfig: BCM pin " << bcmPin << " invalid!" << std::endl; + sif::error << "createRpiGpioConfig: BCM pin " << bcmPin << " invalid!" << std::endl; #else - sif::printError("createRpiGpioConfig: BCM pin %d invalid!\n", bcmPin); + sif::printError("createRpiGpioConfig: BCM pin %d invalid!\n", bcmPin); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - return HasReturnvaluesIF::RETURN_FAILED; - } - config->lineNum = bcmPin; - cookie->addGpio(gpioId, config); - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_FAILED; + } + config->lineNum = bcmPin; + cookie->addGpio(gpioId, config); + return HasReturnvaluesIF::RETURN_OK; } diff --git a/hal/src/fsfw_hal/linux/rpi/GpioRPi.h b/hal/src/fsfw_hal/linux/rpi/GpioRPi.h index 54917e6d..499f984b 100644 --- a/hal/src/fsfw_hal/linux/rpi/GpioRPi.h +++ b/hal/src/fsfw_hal/linux/rpi/GpioRPi.h @@ -2,6 +2,7 @@ #define BSP_RPI_GPIO_GPIORPI_H_ #include + #include "../../common/gpio/gpioDefinitions.h" class GpioCookie; @@ -20,7 +21,7 @@ namespace gpio { * @return */ ReturnValue_t createRpiGpioConfig(GpioCookie* cookie, gpioId_t gpioId, int bcmPin, - std::string consumer, gpio::Direction direction, int initValue); -} + std::string consumer, gpio::Direction direction, int initValue); +} // namespace gpio #endif /* BSP_RPI_GPIO_GPIORPI_H_ */ diff --git a/hal/src/fsfw_hal/linux/spi/SpiComIF.cpp b/hal/src/fsfw_hal/linux/spi/SpiComIF.cpp index 9c4e66ae..d95232c1 100644 --- a/hal/src/fsfw_hal/linux/spi/SpiComIF.cpp +++ b/hal/src/fsfw_hal/linux/spi/SpiComIF.cpp @@ -1,408 +1,404 @@ -#include "fsfw/FSFW.h" #include "fsfw_hal/linux/spi/SpiComIF.h" -#include "fsfw_hal/linux/spi/SpiCookie.h" -#include "fsfw_hal/linux/utility.h" -#include "fsfw_hal/linux/UnixFileGuard.h" -#include -#include - -#include #include -#include +#include +#include +#include #include +#include #include #include -SpiComIF::SpiComIF(object_id_t objectId, GpioIF* gpioComIF): - SystemObject(objectId), gpioComIF(gpioComIF) { - if(gpioComIF == nullptr) { +#include "fsfw/FSFW.h" +#include "fsfw_hal/linux/UnixFileGuard.h" +#include "fsfw_hal/linux/spi/SpiCookie.h" +#include "fsfw_hal/linux/utility.h" + +SpiComIF::SpiComIF(object_id_t objectId, GpioIF* gpioComIF) + : SystemObject(objectId), gpioComIF(gpioComIF) { + if (gpioComIF == nullptr) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "SpiComIF::SpiComIF: GPIO communication interface invalid!" << std::endl; + sif::error << "SpiComIF::SpiComIF: GPIO communication interface invalid!" << std::endl; #else - sif::printError("SpiComIF::SpiComIF: GPIO communication interface invalid!\n"); + sif::printError("SpiComIF::SpiComIF: GPIO communication interface invalid!\n"); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - } + } - spiMutex = MutexFactory::instance()->createMutex(); + spiMutex = MutexFactory::instance()->createMutex(); } -ReturnValue_t SpiComIF::initializeInterface(CookieIF *cookie) { - int retval = 0; - SpiCookie* spiCookie = dynamic_cast(cookie); - if(spiCookie == nullptr) { - return NULLPOINTER; - } +ReturnValue_t SpiComIF::initializeInterface(CookieIF* cookie) { + int retval = 0; + SpiCookie* spiCookie = dynamic_cast(cookie); + if (spiCookie == nullptr) { + return NULLPOINTER; + } - address_t spiAddress = spiCookie->getSpiAddress(); + address_t spiAddress = spiCookie->getSpiAddress(); - auto iter = spiDeviceMap.find(spiAddress); - if(iter == spiDeviceMap.end()) { - size_t bufferSize = spiCookie->getMaxBufferSize(); - SpiInstance spiInstance(bufferSize); - auto statusPair = spiDeviceMap.emplace(spiAddress, spiInstance); - if (not statusPair.second) { + auto iter = spiDeviceMap.find(spiAddress); + if (iter == spiDeviceMap.end()) { + size_t bufferSize = spiCookie->getMaxBufferSize(); + SpiInstance spiInstance(bufferSize); + auto statusPair = spiDeviceMap.emplace(spiAddress, spiInstance); + if (not statusPair.second) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "SpiComIF::initializeInterface: Failed to insert device with address " << - spiAddress << "to SPI device map" << std::endl; + sif::error << "SpiComIF::initializeInterface: Failed to insert device with address " + << spiAddress << "to SPI device map" << std::endl; #else - sif::printError("SpiComIF::initializeInterface: Failed to insert device with address " - "%lu to SPI device map\n", static_cast(spiAddress)); + sif::printError( + "SpiComIF::initializeInterface: Failed to insert device with address " + "%lu to SPI device map\n", + static_cast(spiAddress)); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - return HasReturnvaluesIF::RETURN_FAILED; - } - /* Now we emplaced the read buffer in the map, we still need to assign that location - to the SPI driver transfer struct */ - spiCookie->assignReadBuffer(statusPair.first->second.replyBuffer.data()); + return HasReturnvaluesIF::RETURN_FAILED; } - else { + /* Now we emplaced the read buffer in the map, we still need to assign that location + to the SPI driver transfer struct */ + spiCookie->assignReadBuffer(statusPair.first->second.replyBuffer.data()); + } else { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "SpiComIF::initializeInterface: SPI address already exists!" << std::endl; + sif::error << "SpiComIF::initializeInterface: SPI address already exists!" << std::endl; #else - sif::printError("SpiComIF::initializeInterface: SPI address already exists!\n"); + sif::printError("SpiComIF::initializeInterface: SPI address already exists!\n"); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - return HasReturnvaluesIF::RETURN_FAILED; + return HasReturnvaluesIF::RETURN_FAILED; + } + + /* Pull CS high in any case to be sure that device is inactive */ + gpioId_t gpioId = spiCookie->getChipSelectPin(); + if (gpioId != gpio::NO_GPIO) { + gpioComIF->pullHigh(gpioId); + } + + uint32_t spiSpeed = 0; + spi::SpiModes spiMode = spi::SpiModes::MODE_0; + + SpiCookie::UncommonParameters params; + spiCookie->getSpiParameters(spiMode, spiSpeed, ¶ms); + + int fileDescriptor = 0; + UnixFileGuard fileHelper(spiCookie->getSpiDevice(), &fileDescriptor, O_RDWR, + "SpiComIF::initializeInterface"); + if (fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { + return fileHelper.getOpenResult(); + } + + /* These flags are rather uncommon */ + if (params.threeWireSpi or params.noCs or params.csHigh) { + uint32_t currentMode = 0; + retval = ioctl(fileDescriptor, SPI_IOC_RD_MODE32, ¤tMode); + if (retval != 0) { + utility::handleIoctlError("SpiComIF::initialiezInterface: Could not read full mode!"); } - /* Pull CS high in any case to be sure that device is inactive */ - gpioId_t gpioId = spiCookie->getChipSelectPin(); - if(gpioId != gpio::NO_GPIO) { - gpioComIF->pullHigh(gpioId); + if (params.threeWireSpi) { + currentMode |= SPI_3WIRE; } - - uint32_t spiSpeed = 0; - spi::SpiModes spiMode = spi::SpiModes::MODE_0; - - SpiCookie::UncommonParameters params; - spiCookie->getSpiParameters(spiMode, spiSpeed, ¶ms); - - int fileDescriptor = 0; - UnixFileGuard fileHelper(spiCookie->getSpiDevice(), &fileDescriptor, O_RDWR, - "SpiComIF::initializeInterface"); - if(fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { - return fileHelper.getOpenResult(); + if (params.noCs) { + /* Some drivers like the Raspberry Pi ignore this flag in any case */ + currentMode |= SPI_NO_CS; } - - /* These flags are rather uncommon */ - if(params.threeWireSpi or params.noCs or params.csHigh) { - uint32_t currentMode = 0; - retval = ioctl(fileDescriptor, SPI_IOC_RD_MODE32, ¤tMode); - if(retval != 0) { - utility::handleIoctlError("SpiComIF::initialiezInterface: Could not read full mode!"); - } - - if(params.threeWireSpi) { - currentMode |= SPI_3WIRE; - } - if(params.noCs) { - /* Some drivers like the Raspberry Pi ignore this flag in any case */ - currentMode |= SPI_NO_CS; - } - if(params.csHigh) { - currentMode |= SPI_CS_HIGH; - } - /* Write adapted mode */ - retval = ioctl(fileDescriptor, SPI_IOC_WR_MODE32, ¤tMode); - if(retval != 0) { - utility::handleIoctlError("SpiComIF::initialiezInterface: Could not write full mode!"); - } + if (params.csHigh) { + currentMode |= SPI_CS_HIGH; } - if(params.lsbFirst) { - retval = ioctl(fileDescriptor, SPI_IOC_WR_LSB_FIRST, ¶ms.lsbFirst); - if(retval != 0) { - utility::handleIoctlError("SpiComIF::initializeInterface: Setting LSB first failed"); - } + /* Write adapted mode */ + retval = ioctl(fileDescriptor, SPI_IOC_WR_MODE32, ¤tMode); + if (retval != 0) { + utility::handleIoctlError("SpiComIF::initialiezInterface: Could not write full mode!"); } - if(params.bitsPerWord != 8) { - retval = ioctl(fileDescriptor, SPI_IOC_WR_BITS_PER_WORD, ¶ms.bitsPerWord); - if(retval != 0) { - utility::handleIoctlError("SpiComIF::initializeInterface: " - "Could not write bits per word!"); - } + } + if (params.lsbFirst) { + retval = ioctl(fileDescriptor, SPI_IOC_WR_LSB_FIRST, ¶ms.lsbFirst); + if (retval != 0) { + utility::handleIoctlError("SpiComIF::initializeInterface: Setting LSB first failed"); } - return HasReturnvaluesIF::RETURN_OK; + } + if (params.bitsPerWord != 8) { + retval = ioctl(fileDescriptor, SPI_IOC_WR_BITS_PER_WORD, ¶ms.bitsPerWord); + if (retval != 0) { + utility::handleIoctlError( + "SpiComIF::initializeInterface: " + "Could not write bits per word!"); + } + } + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t SpiComIF::sendMessage(CookieIF *cookie, const uint8_t *sendData, size_t sendLen) { - SpiCookie* spiCookie = dynamic_cast(cookie); - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; +ReturnValue_t SpiComIF::sendMessage(CookieIF* cookie, const uint8_t* sendData, size_t sendLen) { + SpiCookie* spiCookie = dynamic_cast(cookie); + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - if(spiCookie == nullptr) { - return NULLPOINTER; - } + if (spiCookie == nullptr) { + return NULLPOINTER; + } - if(sendLen > spiCookie->getMaxBufferSize()) { + if (sendLen > spiCookie->getMaxBufferSize()) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "SpiComIF::sendMessage: Too much data sent, send length " << sendLen << - "larger than maximum buffer length " << spiCookie->getMaxBufferSize() << std::endl; + sif::warning << "SpiComIF::sendMessage: Too much data sent, send length " << sendLen + << "larger than maximum buffer length " << spiCookie->getMaxBufferSize() + << std::endl; #else - sif::printWarning("SpiComIF::sendMessage: Too much data sent, send length %lu larger " - "than maximum buffer length %lu!\n", static_cast(sendLen), - static_cast(spiCookie->getMaxBufferSize())); + sif::printWarning( + "SpiComIF::sendMessage: Too much data sent, send length %lu larger " + "than maximum buffer length %lu!\n", + static_cast(sendLen), + static_cast(spiCookie->getMaxBufferSize())); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - return DeviceCommunicationIF::TOO_MUCH_DATA; - } + return DeviceCommunicationIF::TOO_MUCH_DATA; + } - if(spiCookie->getComIfMode() == spi::SpiComIfModes::REGULAR) { - result = performRegularSendOperation(spiCookie, sendData, sendLen); + if (spiCookie->getComIfMode() == spi::SpiComIfModes::REGULAR) { + result = performRegularSendOperation(spiCookie, sendData, sendLen); + } else if (spiCookie->getComIfMode() == spi::SpiComIfModes::CALLBACK) { + spi::send_callback_function_t sendFunc = nullptr; + void* funcArgs = nullptr; + spiCookie->getCallback(&sendFunc, &funcArgs); + if (sendFunc != nullptr) { + result = sendFunc(this, spiCookie, sendData, sendLen, funcArgs); } - else if(spiCookie->getComIfMode() == spi::SpiComIfModes::CALLBACK) { - spi::send_callback_function_t sendFunc = nullptr; - void* funcArgs = nullptr; - spiCookie->getCallback(&sendFunc, &funcArgs); - if(sendFunc != nullptr) { - result = sendFunc(this, spiCookie, sendData, sendLen, funcArgs); - } - } - return result; + } + return result; } -ReturnValue_t SpiComIF::performRegularSendOperation(SpiCookie *spiCookie, const uint8_t *sendData, - size_t sendLen) { - address_t spiAddress = spiCookie->getSpiAddress(); - auto iter = spiDeviceMap.find(spiAddress); - if(iter != spiDeviceMap.end()) { - spiCookie->assignReadBuffer(iter->second.replyBuffer.data()); - } +ReturnValue_t SpiComIF::performRegularSendOperation(SpiCookie* spiCookie, const uint8_t* sendData, + size_t sendLen) { + address_t spiAddress = spiCookie->getSpiAddress(); + auto iter = spiDeviceMap.find(spiAddress); + if (iter != spiDeviceMap.end()) { + spiCookie->assignReadBuffer(iter->second.replyBuffer.data()); + } - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - int retval = 0; - /* Prepare transfer */ - int fileDescriptor = 0; - std::string device = spiCookie->getSpiDevice(); - UnixFileGuard fileHelper(device, &fileDescriptor, O_RDWR, "SpiComIF::sendMessage"); - if(fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { - return OPENING_FILE_FAILED; - } - spi::SpiModes spiMode = spi::SpiModes::MODE_0; - uint32_t spiSpeed = 0; - spiCookie->getSpiParameters(spiMode, spiSpeed, nullptr); - setSpiSpeedAndMode(fileDescriptor, spiMode, spiSpeed); - spiCookie->assignWriteBuffer(sendData); - spiCookie->setTransferSize(sendLen); + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + int retval = 0; + /* Prepare transfer */ + int fileDescriptor = 0; + std::string device = spiCookie->getSpiDevice(); + UnixFileGuard fileHelper(device, &fileDescriptor, O_RDWR, "SpiComIF::sendMessage"); + if (fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { + return OPENING_FILE_FAILED; + } + spi::SpiModes spiMode = spi::SpiModes::MODE_0; + uint32_t spiSpeed = 0; + spiCookie->getSpiParameters(spiMode, spiSpeed, nullptr); + setSpiSpeedAndMode(fileDescriptor, spiMode, spiSpeed); + spiCookie->assignWriteBuffer(sendData); + spiCookie->setTransferSize(sendLen); - bool fullDuplex = spiCookie->isFullDuplex(); - gpioId_t gpioId = spiCookie->getChipSelectPin(); + bool fullDuplex = spiCookie->isFullDuplex(); + gpioId_t gpioId = spiCookie->getChipSelectPin(); - /* Pull SPI CS low. For now, no support for active high given */ - if(gpioId != gpio::NO_GPIO) { - result = spiMutex->lockMutex(timeoutType, timeoutMs); - if (result != RETURN_OK) { + /* Pull SPI CS low. For now, no support for active high given */ + if (gpioId != gpio::NO_GPIO) { + result = spiMutex->lockMutex(timeoutType, timeoutMs); + if (result != RETURN_OK) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "SpiComIF::sendMessage: Failed to lock mutex" << std::endl; + sif::error << "SpiComIF::sendMessage: Failed to lock mutex" << std::endl; #else - sif::printError("SpiComIF::sendMessage: Failed to lock mutex\n"); + sif::printError("SpiComIF::sendMessage: Failed to lock mutex\n"); #endif #endif - return result; - } - ReturnValue_t result = gpioComIF->pullLow(gpioId); - if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + ReturnValue_t result = gpioComIF->pullLow(gpioId); + if (result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "SpiComIF::sendMessage: Pulling low CS pin failed" << std::endl; + sif::warning << "SpiComIF::sendMessage: Pulling low CS pin failed" << std::endl; #else - sif::printWarning("SpiComIF::sendMessage: Pulling low CS pin failed"); + sif::printWarning("SpiComIF::sendMessage: Pulling low CS pin failed"); #endif #endif - return result; - } + return result; } + } - /* Execute transfer */ - if(fullDuplex) { - /* Initiate a full duplex SPI transfer. */ - retval = ioctl(fileDescriptor, SPI_IOC_MESSAGE(1), spiCookie->getTransferStructHandle()); - if(retval < 0) { - utility::handleIoctlError("SpiComIF::sendMessage: ioctl error."); - result = FULL_DUPLEX_TRANSFER_FAILED; - } + /* Execute transfer */ + if (fullDuplex) { + /* Initiate a full duplex SPI transfer. */ + retval = ioctl(fileDescriptor, SPI_IOC_MESSAGE(1), spiCookie->getTransferStructHandle()); + if (retval < 0) { + utility::handleIoctlError("SpiComIF::sendMessage: ioctl error."); + result = FULL_DUPLEX_TRANSFER_FAILED; + } #if FSFW_HAL_SPI_WIRETAPPING == 1 - performSpiWiretapping(spiCookie); + performSpiWiretapping(spiCookie); #endif /* FSFW_LINUX_SPI_WIRETAPPING == 1 */ - } - else { - /* We write with a blocking half-duplex transfer here */ - if (write(fileDescriptor, sendData, sendLen) != static_cast(sendLen)) { + } else { + /* We write with a blocking half-duplex transfer here */ + if (write(fileDescriptor, sendData, sendLen) != static_cast(sendLen)) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "SpiComIF::sendMessage: Half-Duplex write operation failed!" << - std::endl; + sif::warning << "SpiComIF::sendMessage: Half-Duplex write operation failed!" << std::endl; #else - sif::printWarning("SpiComIF::sendMessage: Half-Duplex write operation failed!\n"); + sif::printWarning("SpiComIF::sendMessage: Half-Duplex write operation failed!\n"); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - result = HALF_DUPLEX_TRANSFER_FAILED; - } + result = HALF_DUPLEX_TRANSFER_FAILED; } + } - if(gpioId != gpio::NO_GPIO) { - gpioComIF->pullHigh(gpioId); - result = spiMutex->unlockMutex(); - if (result != RETURN_OK) { + if (gpioId != gpio::NO_GPIO) { + gpioComIF->pullHigh(gpioId); + result = spiMutex->unlockMutex(); + if (result != RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "SpiComIF::sendMessage: Failed to unlock mutex" << std::endl; + sif::error << "SpiComIF::sendMessage: Failed to unlock mutex" << std::endl; #endif - return result; - } + return result; } - return result; + } + return result; } -ReturnValue_t SpiComIF::getSendSuccess(CookieIF *cookie) { +ReturnValue_t SpiComIF::getSendSuccess(CookieIF* cookie) { return HasReturnvaluesIF::RETURN_OK; } + +ReturnValue_t SpiComIF::requestReceiveMessage(CookieIF* cookie, size_t requestLen) { + SpiCookie* spiCookie = dynamic_cast(cookie); + if (spiCookie == nullptr) { + return NULLPOINTER; + } + + if (spiCookie->isFullDuplex()) { return HasReturnvaluesIF::RETURN_OK; + } + + return performHalfDuplexReception(spiCookie); } -ReturnValue_t SpiComIF::requestReceiveMessage(CookieIF *cookie, size_t requestLen) { - SpiCookie* spiCookie = dynamic_cast(cookie); - if(spiCookie == nullptr) { - return NULLPOINTER; - } - - if(spiCookie->isFullDuplex()) { - return HasReturnvaluesIF::RETURN_OK; - } - - return performHalfDuplexReception(spiCookie); -} - - ReturnValue_t SpiComIF::performHalfDuplexReception(SpiCookie* spiCookie) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - std::string device = spiCookie->getSpiDevice(); - int fileDescriptor = 0; - UnixFileGuard fileHelper(device, &fileDescriptor, O_RDWR, - "SpiComIF::requestReceiveMessage"); - if(fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { - return OPENING_FILE_FAILED; - } + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + std::string device = spiCookie->getSpiDevice(); + int fileDescriptor = 0; + UnixFileGuard fileHelper(device, &fileDescriptor, O_RDWR, "SpiComIF::requestReceiveMessage"); + if (fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { + return OPENING_FILE_FAILED; + } - uint8_t* rxBuf = nullptr; - size_t readSize = spiCookie->getCurrentTransferSize(); - result = getReadBuffer(spiCookie->getSpiAddress(), &rxBuf); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + uint8_t* rxBuf = nullptr; + size_t readSize = spiCookie->getCurrentTransferSize(); + result = getReadBuffer(spiCookie->getSpiAddress(), &rxBuf); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - gpioId_t gpioId = spiCookie->getChipSelectPin(); - if(gpioId != gpio::NO_GPIO) { - result = spiMutex->lockMutex(timeoutType, timeoutMs); - if (result != RETURN_OK) { + gpioId_t gpioId = spiCookie->getChipSelectPin(); + if (gpioId != gpio::NO_GPIO) { + result = spiMutex->lockMutex(timeoutType, timeoutMs); + if (result != RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "SpiComIF::getSendSuccess: Failed to lock mutex" << std::endl; + sif::error << "SpiComIF::getSendSuccess: Failed to lock mutex" << std::endl; #endif - return result; - } - gpioComIF->pullLow(gpioId); + return result; } + gpioComIF->pullLow(gpioId); + } - if(read(fileDescriptor, rxBuf, readSize) != static_cast(readSize)) { + if (read(fileDescriptor, rxBuf, readSize) != static_cast(readSize)) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "SpiComIF::sendMessage: Half-Duplex read operation failed!" << std::endl; + sif::warning << "SpiComIF::sendMessage: Half-Duplex read operation failed!" << std::endl; #else - sif::printWarning("SpiComIF::sendMessage: Half-Duplex read operation failed!\n"); + sif::printWarning("SpiComIF::sendMessage: Half-Duplex read operation failed!\n"); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - result = HALF_DUPLEX_TRANSFER_FAILED; - } + result = HALF_DUPLEX_TRANSFER_FAILED; + } - if(gpioId != gpio::NO_GPIO) { - gpioComIF->pullHigh(gpioId); - result = spiMutex->unlockMutex(); - if (result != RETURN_OK) { + if (gpioId != gpio::NO_GPIO) { + gpioComIF->pullHigh(gpioId); + result = spiMutex->unlockMutex(); + if (result != RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "SpiComIF::getSendSuccess: Failed to unlock mutex" << std::endl; + sif::error << "SpiComIF::getSendSuccess: Failed to unlock mutex" << std::endl; #endif - return result; - } + return result; } + } - return result; + return result; } -ReturnValue_t SpiComIF::readReceivedMessage(CookieIF *cookie, uint8_t **buffer, size_t *size) { - SpiCookie* spiCookie = dynamic_cast(cookie); - if(spiCookie == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - uint8_t* rxBuf = nullptr; - ReturnValue_t result = getReadBuffer(spiCookie->getSpiAddress(), &rxBuf); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } +ReturnValue_t SpiComIF::readReceivedMessage(CookieIF* cookie, uint8_t** buffer, size_t* size) { + SpiCookie* spiCookie = dynamic_cast(cookie); + if (spiCookie == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + uint8_t* rxBuf = nullptr; + ReturnValue_t result = getReadBuffer(spiCookie->getSpiAddress(), &rxBuf); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - *buffer = rxBuf; - *size = spiCookie->getCurrentTransferSize(); - spiCookie->setTransferSize(0); - return HasReturnvaluesIF::RETURN_OK; + *buffer = rxBuf; + *size = spiCookie->getCurrentTransferSize(); + spiCookie->setTransferSize(0); + return HasReturnvaluesIF::RETURN_OK; } MutexIF* SpiComIF::getMutex(MutexIF::TimeoutType* timeoutType, uint32_t* timeoutMs) { - if(timeoutType != nullptr) { - *timeoutType = this->timeoutType; - } - if(timeoutMs != nullptr) { - *timeoutMs = this->timeoutMs; - } - return spiMutex; + if (timeoutType != nullptr) { + *timeoutType = this->timeoutType; + } + if (timeoutMs != nullptr) { + *timeoutMs = this->timeoutMs; + } + return spiMutex; } void SpiComIF::performSpiWiretapping(SpiCookie* spiCookie) { - if(spiCookie == nullptr) { - return; - } - size_t dataLen = spiCookie->getTransferStructHandle()->len; - uint8_t* dataPtr = reinterpret_cast(spiCookie->getTransferStructHandle()->tx_buf); + if (spiCookie == nullptr) { + return; + } + size_t dataLen = spiCookie->getTransferStructHandle()->len; + uint8_t* dataPtr = reinterpret_cast(spiCookie->getTransferStructHandle()->tx_buf); #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "Sent SPI data: " << std::endl; - arrayprinter::print(dataPtr, dataLen, OutputType::HEX, false); - sif::info << "Received SPI data: " << std::endl; + sif::info << "Sent SPI data: " << std::endl; + arrayprinter::print(dataPtr, dataLen, OutputType::HEX, false); + sif::info << "Received SPI data: " << std::endl; #else - sif::printInfo("Sent SPI data: \n"); - arrayprinter::print(dataPtr, dataLen, OutputType::HEX, false); - sif::printInfo("Received SPI data: \n"); + sif::printInfo("Sent SPI data: \n"); + arrayprinter::print(dataPtr, dataLen, OutputType::HEX, false); + sif::printInfo("Received SPI data: \n"); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ - dataPtr = reinterpret_cast(spiCookie->getTransferStructHandle()->rx_buf); - arrayprinter::print(dataPtr, dataLen, OutputType::HEX, false); + dataPtr = reinterpret_cast(spiCookie->getTransferStructHandle()->rx_buf); + arrayprinter::print(dataPtr, dataLen, OutputType::HEX, false); } ReturnValue_t SpiComIF::getReadBuffer(address_t spiAddress, uint8_t** buffer) { - if(buffer == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } + if (buffer == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } - auto iter = spiDeviceMap.find(spiAddress); - if(iter == spiDeviceMap.end()) { - return HasReturnvaluesIF::RETURN_FAILED; - } + auto iter = spiDeviceMap.find(spiAddress); + if (iter == spiDeviceMap.end()) { + return HasReturnvaluesIF::RETURN_FAILED; + } - *buffer = iter->second.replyBuffer.data(); - return HasReturnvaluesIF::RETURN_OK; + *buffer = iter->second.replyBuffer.data(); + return HasReturnvaluesIF::RETURN_OK; } -GpioIF* SpiComIF::getGpioInterface() { - return gpioComIF; -} +GpioIF* SpiComIF::getGpioInterface() { return gpioComIF; } void SpiComIF::setSpiSpeedAndMode(int spiFd, spi::SpiModes mode, uint32_t speed) { - int retval = ioctl(spiFd, SPI_IOC_WR_MODE, reinterpret_cast(&mode)); - if(retval != 0) { - utility::handleIoctlError("SpiComIF::setSpiSpeedAndMode: Setting SPI mode failed"); - } + int retval = ioctl(spiFd, SPI_IOC_WR_MODE, reinterpret_cast(&mode)); + if (retval != 0) { + utility::handleIoctlError("SpiComIF::setSpiSpeedAndMode: Setting SPI mode failed"); + } - retval = ioctl(spiFd, SPI_IOC_WR_MAX_SPEED_HZ, &speed); - if(retval != 0) { - utility::handleIoctlError("SpiComIF::setSpiSpeedAndMode: Setting SPI speed failed"); - } + retval = ioctl(spiFd, SPI_IOC_WR_MAX_SPEED_HZ, &speed); + if (retval != 0) { + utility::handleIoctlError("SpiComIF::setSpiSpeedAndMode: Setting SPI speed failed"); + } } diff --git a/hal/src/fsfw_hal/linux/spi/SpiComIF.h b/hal/src/fsfw_hal/linux/spi/SpiComIF.h index bcca7462..1f825d52 100644 --- a/hal/src/fsfw_hal/linux/spi/SpiComIF.h +++ b/hal/src/fsfw_hal/linux/spi/SpiComIF.h @@ -1,16 +1,15 @@ #ifndef LINUX_SPI_SPICOMIF_H_ #define LINUX_SPI_SPICOMIF_H_ -#include "fsfw/FSFW.h" -#include "spiDefinitions.h" -#include "returnvalues/classIds.h" -#include "fsfw_hal/common/gpio/GpioIF.h" +#include +#include +#include "fsfw/FSFW.h" #include "fsfw/devicehandlers/DeviceCommunicationIF.h" #include "fsfw/objectmanager/SystemObject.h" - -#include -#include +#include "fsfw_hal/common/gpio/GpioIF.h" +#include "returnvalues/classIds.h" +#include "spiDefinitions.h" class SpiCookie; @@ -21,71 +20,67 @@ class SpiCookie; * are contained in the SPI cookie. * @author R. Mueller */ -class SpiComIF: public DeviceCommunicationIF, public SystemObject { -public: - static constexpr uint8_t spiRetvalId = CLASS_ID::HAL_SPI; - static constexpr ReturnValue_t OPENING_FILE_FAILED = - HasReturnvaluesIF::makeReturnCode(spiRetvalId, 0); - /* Full duplex (ioctl) transfer failure */ - static constexpr ReturnValue_t FULL_DUPLEX_TRANSFER_FAILED = - HasReturnvaluesIF::makeReturnCode(spiRetvalId, 1); - /* Half duplex (read/write) transfer failure */ - static constexpr ReturnValue_t HALF_DUPLEX_TRANSFER_FAILED = - HasReturnvaluesIF::makeReturnCode(spiRetvalId, 2); +class SpiComIF : public DeviceCommunicationIF, public SystemObject { + public: + static constexpr uint8_t spiRetvalId = CLASS_ID::HAL_SPI; + static constexpr ReturnValue_t OPENING_FILE_FAILED = + HasReturnvaluesIF::makeReturnCode(spiRetvalId, 0); + /* Full duplex (ioctl) transfer failure */ + static constexpr ReturnValue_t FULL_DUPLEX_TRANSFER_FAILED = + HasReturnvaluesIF::makeReturnCode(spiRetvalId, 1); + /* Half duplex (read/write) transfer failure */ + static constexpr ReturnValue_t HALF_DUPLEX_TRANSFER_FAILED = + HasReturnvaluesIF::makeReturnCode(spiRetvalId, 2); - SpiComIF(object_id_t objectId, GpioIF* gpioComIF); + SpiComIF(object_id_t objectId, GpioIF* gpioComIF); - ReturnValue_t initializeInterface(CookieIF * cookie) override; - ReturnValue_t sendMessage(CookieIF *cookie,const uint8_t *sendData, - size_t sendLen) override; - ReturnValue_t getSendSuccess(CookieIF *cookie) override; - ReturnValue_t requestReceiveMessage(CookieIF *cookie, - size_t requestLen) override; - ReturnValue_t readReceivedMessage(CookieIF *cookie, uint8_t **buffer, - size_t *size) override; + ReturnValue_t initializeInterface(CookieIF* cookie) override; + ReturnValue_t sendMessage(CookieIF* cookie, const uint8_t* sendData, size_t sendLen) override; + ReturnValue_t getSendSuccess(CookieIF* cookie) override; + ReturnValue_t requestReceiveMessage(CookieIF* cookie, size_t requestLen) override; + ReturnValue_t readReceivedMessage(CookieIF* cookie, uint8_t** buffer, size_t* size) override; - /** - * @brief This function returns the mutex which can be used to protect the spi bus when - * the chip select must be driven from outside of the com if. - */ - MutexIF* getMutex(MutexIF::TimeoutType* timeoutType = nullptr, uint32_t* timeoutMs = nullptr); + /** + * @brief This function returns the mutex which can be used to protect the spi bus when + * the chip select must be driven from outside of the com if. + */ + MutexIF* getMutex(MutexIF::TimeoutType* timeoutType = nullptr, uint32_t* timeoutMs = nullptr); - /** - * Perform a regular send operation using Linux iotcl. This is public so it can be used - * in functions like a user callback if special handling is only necessary for certain commands. - * @param spiCookie - * @param sendData - * @param sendLen - * @return - */ - ReturnValue_t performRegularSendOperation(SpiCookie* spiCookie, const uint8_t *sendData, - size_t sendLen); + /** + * Perform a regular send operation using Linux iotcl. This is public so it can be used + * in functions like a user callback if special handling is only necessary for certain commands. + * @param spiCookie + * @param sendData + * @param sendLen + * @return + */ + ReturnValue_t performRegularSendOperation(SpiCookie* spiCookie, const uint8_t* sendData, + size_t sendLen); - GpioIF* getGpioInterface(); - void setSpiSpeedAndMode(int spiFd, spi::SpiModes mode, uint32_t speed); - void performSpiWiretapping(SpiCookie* spiCookie); + GpioIF* getGpioInterface(); + void setSpiSpeedAndMode(int spiFd, spi::SpiModes mode, uint32_t speed); + void performSpiWiretapping(SpiCookie* spiCookie); - ReturnValue_t getReadBuffer(address_t spiAddress, uint8_t** buffer); + ReturnValue_t getReadBuffer(address_t spiAddress, uint8_t** buffer); -private: + private: + struct SpiInstance { + SpiInstance(size_t maxRecvSize) : replyBuffer(std::vector(maxRecvSize)) {} + std::vector replyBuffer; + }; - struct SpiInstance { - SpiInstance(size_t maxRecvSize): replyBuffer(std::vector(maxRecvSize)) {} - std::vector replyBuffer; - }; + GpioIF* gpioComIF = nullptr; - GpioIF* gpioComIF = nullptr; + MutexIF* spiMutex = nullptr; + MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING; + uint32_t timeoutMs = 20; - MutexIF* spiMutex = nullptr; - MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING; - uint32_t timeoutMs = 20; + using SpiDeviceMap = std::unordered_map; + using SpiDeviceMapIter = SpiDeviceMap::iterator; - using SpiDeviceMap = std::unordered_map; - using SpiDeviceMapIter = SpiDeviceMap::iterator; + SpiDeviceMap spiDeviceMap; - SpiDeviceMap spiDeviceMap; - - ReturnValue_t performHalfDuplexReception(SpiCookie* spiCookie); + ReturnValue_t performHalfDuplexReception(SpiCookie* spiCookie); }; #endif /* LINUX_SPI_SPICOMIF_H_ */ diff --git a/hal/src/fsfw_hal/linux/spi/SpiCookie.cpp b/hal/src/fsfw_hal/linux/spi/SpiCookie.cpp index f07954e9..e6271c5e 100644 --- a/hal/src/fsfw_hal/linux/spi/SpiCookie.cpp +++ b/hal/src/fsfw_hal/linux/spi/SpiCookie.cpp @@ -1,144 +1,109 @@ #include "fsfw_hal/linux/spi/SpiCookie.h" SpiCookie::SpiCookie(address_t spiAddress, gpioId_t chipSelect, std::string spiDev, - const size_t maxSize, spi::SpiModes spiMode, uint32_t spiSpeed): - SpiCookie(spi::SpiComIfModes::REGULAR, spiAddress, chipSelect, spiDev, maxSize, spiMode, - spiSpeed, nullptr, nullptr) { - -} + const size_t maxSize, spi::SpiModes spiMode, uint32_t spiSpeed) + : SpiCookie(spi::SpiComIfModes::REGULAR, spiAddress, chipSelect, spiDev, maxSize, spiMode, + spiSpeed, nullptr, nullptr) {} SpiCookie::SpiCookie(address_t spiAddress, std::string spiDev, const size_t maxSize, - spi::SpiModes spiMode, uint32_t spiSpeed): - SpiCookie(spiAddress, gpio::NO_GPIO, spiDev, maxSize, spiMode, spiSpeed) { -} + spi::SpiModes spiMode, uint32_t spiSpeed) + : SpiCookie(spiAddress, gpio::NO_GPIO, spiDev, maxSize, spiMode, spiSpeed) {} SpiCookie::SpiCookie(address_t spiAddress, gpioId_t chipSelect, std::string spiDev, - const size_t maxSize, spi::SpiModes spiMode, uint32_t spiSpeed, - spi::send_callback_function_t callback, void *args): - SpiCookie(spi::SpiComIfModes::CALLBACK, spiAddress, chipSelect, spiDev, maxSize, - spiMode, spiSpeed, callback, args) { -} + const size_t maxSize, spi::SpiModes spiMode, uint32_t spiSpeed, + spi::send_callback_function_t callback, void* args) + : SpiCookie(spi::SpiComIfModes::CALLBACK, spiAddress, chipSelect, spiDev, maxSize, spiMode, + spiSpeed, callback, args) {} SpiCookie::SpiCookie(spi::SpiComIfModes comIfMode, address_t spiAddress, gpioId_t chipSelect, - std::string spiDev, const size_t maxSize, spi::SpiModes spiMode, uint32_t spiSpeed, - spi::send_callback_function_t callback, void* args): - spiAddress(spiAddress), chipSelectPin(chipSelect), spiDevice(spiDev), - comIfMode(comIfMode), maxSize(maxSize), spiMode(spiMode), spiSpeed(spiSpeed), - sendCallback(callback), callbackArgs(args) { -} + std::string spiDev, const size_t maxSize, spi::SpiModes spiMode, + uint32_t spiSpeed, spi::send_callback_function_t callback, void* args) + : spiAddress(spiAddress), + chipSelectPin(chipSelect), + spiDevice(spiDev), + comIfMode(comIfMode), + maxSize(maxSize), + spiMode(spiMode), + spiSpeed(spiSpeed), + sendCallback(callback), + callbackArgs(args) {} -spi::SpiComIfModes SpiCookie::getComIfMode() const { - return this->comIfMode; -} +spi::SpiComIfModes SpiCookie::getComIfMode() const { return this->comIfMode; } void SpiCookie::getSpiParameters(spi::SpiModes& spiMode, uint32_t& spiSpeed, - UncommonParameters* parameters) const { - spiMode = this->spiMode; - spiSpeed = this->spiSpeed; + UncommonParameters* parameters) const { + spiMode = this->spiMode; + spiSpeed = this->spiSpeed; - if(parameters != nullptr) { - parameters->threeWireSpi = uncommonParameters.threeWireSpi; - parameters->lsbFirst = uncommonParameters.lsbFirst; - parameters->noCs = uncommonParameters.noCs; - parameters->bitsPerWord = uncommonParameters.bitsPerWord; - parameters->csHigh = uncommonParameters.csHigh; - } + if (parameters != nullptr) { + parameters->threeWireSpi = uncommonParameters.threeWireSpi; + parameters->lsbFirst = uncommonParameters.lsbFirst; + parameters->noCs = uncommonParameters.noCs; + parameters->bitsPerWord = uncommonParameters.bitsPerWord; + parameters->csHigh = uncommonParameters.csHigh; + } } -gpioId_t SpiCookie::getChipSelectPin() const { - return chipSelectPin; -} +gpioId_t SpiCookie::getChipSelectPin() const { return chipSelectPin; } -size_t SpiCookie::getMaxBufferSize() const { - return maxSize; -} +size_t SpiCookie::getMaxBufferSize() const { return maxSize; } -address_t SpiCookie::getSpiAddress() const { - return spiAddress; -} +address_t SpiCookie::getSpiAddress() const { return spiAddress; } -std::string SpiCookie::getSpiDevice() const { - return spiDevice; -} +std::string SpiCookie::getSpiDevice() const { return spiDevice; } -void SpiCookie::setThreeWireSpi(bool enable) { - uncommonParameters.threeWireSpi = enable; -} +void SpiCookie::setThreeWireSpi(bool enable) { uncommonParameters.threeWireSpi = enable; } -void SpiCookie::setLsbFirst(bool enable) { - uncommonParameters.lsbFirst = enable; -} +void SpiCookie::setLsbFirst(bool enable) { uncommonParameters.lsbFirst = enable; } -void SpiCookie::setNoCs(bool enable) { - uncommonParameters.noCs = enable; -} +void SpiCookie::setNoCs(bool enable) { uncommonParameters.noCs = enable; } void SpiCookie::setBitsPerWord(uint8_t bitsPerWord) { - uncommonParameters.bitsPerWord = bitsPerWord; + uncommonParameters.bitsPerWord = bitsPerWord; } -void SpiCookie::setCsHigh(bool enable) { - uncommonParameters.csHigh = enable; -} +void SpiCookie::setCsHigh(bool enable) { uncommonParameters.csHigh = enable; } void SpiCookie::activateCsDeselect(bool deselectCs, uint16_t delayUsecs) { - spiTransferStruct.cs_change = deselectCs; - spiTransferStruct.delay_usecs = delayUsecs; + spiTransferStruct.cs_change = deselectCs; + spiTransferStruct.delay_usecs = delayUsecs; } void SpiCookie::assignReadBuffer(uint8_t* rx) { - if(rx != nullptr) { - spiTransferStruct.rx_buf = reinterpret_cast<__u64>(rx); - } + if (rx != nullptr) { + spiTransferStruct.rx_buf = reinterpret_cast<__u64>(rx); + } } void SpiCookie::assignWriteBuffer(const uint8_t* tx) { - if(tx != nullptr) { - spiTransferStruct.tx_buf = reinterpret_cast<__u64>(tx); - } + if (tx != nullptr) { + spiTransferStruct.tx_buf = reinterpret_cast<__u64>(tx); + } } -void SpiCookie::setCallbackMode(spi::send_callback_function_t callback, - void *args) { - this->comIfMode = spi::SpiComIfModes::CALLBACK; - this->sendCallback = callback; - this->callbackArgs = args; +void SpiCookie::setCallbackMode(spi::send_callback_function_t callback, void* args) { + this->comIfMode = spi::SpiComIfModes::CALLBACK; + this->sendCallback = callback; + this->callbackArgs = args; } -void SpiCookie::setCallbackArgs(void *args) { - this->callbackArgs = args; -} +void SpiCookie::setCallbackArgs(void* args) { this->callbackArgs = args; } -spi_ioc_transfer* SpiCookie::getTransferStructHandle() { - return &spiTransferStruct; -} +spi_ioc_transfer* SpiCookie::getTransferStructHandle() { return &spiTransferStruct; } -void SpiCookie::setFullOrHalfDuplex(bool halfDuplex) { - this->halfDuplex = halfDuplex; -} +void SpiCookie::setFullOrHalfDuplex(bool halfDuplex) { this->halfDuplex = halfDuplex; } -bool SpiCookie::isFullDuplex() const { - return not this->halfDuplex; -} +bool SpiCookie::isFullDuplex() const { return not this->halfDuplex; } -void SpiCookie::setTransferSize(size_t transferSize) { - spiTransferStruct.len = transferSize; -} +void SpiCookie::setTransferSize(size_t transferSize) { spiTransferStruct.len = transferSize; } -size_t SpiCookie::getCurrentTransferSize() const { - return spiTransferStruct.len; -} +size_t SpiCookie::getCurrentTransferSize() const { return spiTransferStruct.len; } -void SpiCookie::setSpiSpeed(uint32_t newSpeed) { - this->spiSpeed = newSpeed; -} +void SpiCookie::setSpiSpeed(uint32_t newSpeed) { this->spiSpeed = newSpeed; } -void SpiCookie::setSpiMode(spi::SpiModes newMode) { - this->spiMode = newMode; -} +void SpiCookie::setSpiMode(spi::SpiModes newMode) { this->spiMode = newMode; } -void SpiCookie::getCallback(spi::send_callback_function_t *callback, - void **args) { - *callback = this->sendCallback; - *args = this->callbackArgs; +void SpiCookie::getCallback(spi::send_callback_function_t* callback, void** args) { + *callback = this->sendCallback; + *args = this->callbackArgs; } diff --git a/hal/src/fsfw_hal/linux/spi/SpiCookie.h b/hal/src/fsfw_hal/linux/spi/SpiCookie.h index 844fd421..5f4bf2d5 100644 --- a/hal/src/fsfw_hal/linux/spi/SpiCookie.h +++ b/hal/src/fsfw_hal/linux/spi/SpiCookie.h @@ -1,13 +1,12 @@ #ifndef LINUX_SPI_SPICOOKIE_H_ #define LINUX_SPI_SPICOOKIE_H_ -#include "spiDefinitions.h" -#include "../../common/gpio/gpioDefinitions.h" - #include - #include +#include "../../common/gpio/gpioDefinitions.h" +#include "spiDefinitions.h" + /** * @brief This cookie class is passed to the SPI communication interface * @details @@ -19,165 +18,163 @@ * special requirements like expander slave select switching (e.g. GPIO or I2C expander) * or special timing related requirements. */ -class SpiCookie: public CookieIF { -public: - /** - * Each SPI device will have a corresponding cookie. The cookie is used by the communication - * interface and contains device specific information like the largest expected size to be - * sent and received and the GPIO pin used to toggle the SPI slave select pin. - * @param spiAddress - * @param chipSelect Chip select. gpio::NO_GPIO can be used for hardware slave selects. - * @param spiDev - * @param maxSize - */ - SpiCookie(address_t spiAddress, gpioId_t chipSelect, std::string spiDev, - const size_t maxSize, spi::SpiModes spiMode, uint32_t spiSpeed); - - /** - * Like constructor above, but without a dedicated GPIO CS. Can be used for hardware - * slave select or if CS logic is performed with decoders. - */ - SpiCookie(address_t spiAddress, std::string spiDev, const size_t maxReplySize, +class SpiCookie : public CookieIF { + public: + /** + * Each SPI device will have a corresponding cookie. The cookie is used by the communication + * interface and contains device specific information like the largest expected size to be + * sent and received and the GPIO pin used to toggle the SPI slave select pin. + * @param spiAddress + * @param chipSelect Chip select. gpio::NO_GPIO can be used for hardware slave selects. + * @param spiDev + * @param maxSize + */ + SpiCookie(address_t spiAddress, gpioId_t chipSelect, std::string spiDev, const size_t maxSize, spi::SpiModes spiMode, uint32_t spiSpeed); - /** - * Use the callback mode of the SPI communication interface. The user can pass the callback - * function here or by using the setter function #setCallbackMode - */ - SpiCookie(address_t spiAddress, gpioId_t chipSelect, std::string spiDev, const size_t maxSize, + /** + * Like constructor above, but without a dedicated GPIO CS. Can be used for hardware + * slave select or if CS logic is performed with decoders. + */ + SpiCookie(address_t spiAddress, std::string spiDev, const size_t maxReplySize, + spi::SpiModes spiMode, uint32_t spiSpeed); + + /** + * Use the callback mode of the SPI communication interface. The user can pass the callback + * function here or by using the setter function #setCallbackMode + */ + SpiCookie(address_t spiAddress, gpioId_t chipSelect, std::string spiDev, const size_t maxSize, spi::SpiModes spiMode, uint32_t spiSpeed, spi::send_callback_function_t callback, - void *args); + void* args); - /** - * Get the callback function - * @param callback - * @param args - */ - void getCallback(spi::send_callback_function_t* callback, void** args); + /** + * Get the callback function + * @param callback + * @param args + */ + void getCallback(spi::send_callback_function_t* callback, void** args); - address_t getSpiAddress() const; - std::string getSpiDevice() const; - gpioId_t getChipSelectPin() const; - size_t getMaxBufferSize() const; + address_t getSpiAddress() const; + std::string getSpiDevice() const; + gpioId_t getChipSelectPin() const; + size_t getMaxBufferSize() const; - spi::SpiComIfModes getComIfMode() const; + spi::SpiComIfModes getComIfMode() const; - /** Enables changing SPI speed at run-time */ - void setSpiSpeed(uint32_t newSpeed); - /** Enables changing the SPI mode at run-time */ - void setSpiMode(spi::SpiModes newMode); + /** Enables changing SPI speed at run-time */ + void setSpiSpeed(uint32_t newSpeed); + /** Enables changing the SPI mode at run-time */ + void setSpiMode(spi::SpiModes newMode); - /** - * Set the SPI to callback mode and assigns the user supplied callback and an argument - * passed to the callback. - * @param callback - * @param args - */ - void setCallbackMode(spi::send_callback_function_t callback, void* args); + /** + * Set the SPI to callback mode and assigns the user supplied callback and an argument + * passed to the callback. + * @param callback + * @param args + */ + void setCallbackMode(spi::send_callback_function_t callback, void* args); - /** - * Can be used to set the callback arguments and a later point than initialization. - * @param args - */ - void setCallbackArgs(void* args); + /** + * Can be used to set the callback arguments and a later point than initialization. + * @param args + */ + void setCallbackArgs(void* args); - /** - * True if SPI transfers should be performed in full duplex mode - * @return - */ - bool isFullDuplex() const; + /** + * True if SPI transfers should be performed in full duplex mode + * @return + */ + bool isFullDuplex() const; - /** - * Set transfer type to full duplex or half duplex. Full duplex is the default setting, - * ressembling common SPI hardware implementation with shift registers, where read and writes - * happen simultaneosly. - * @param fullDuplex - */ - void setFullOrHalfDuplex(bool halfDuplex); + /** + * Set transfer type to full duplex or half duplex. Full duplex is the default setting, + * ressembling common SPI hardware implementation with shift registers, where read and writes + * happen simultaneosly. + * @param fullDuplex + */ + void setFullOrHalfDuplex(bool halfDuplex); - /** - * This needs to be called to specify where the SPI driver writes to or reads from. - * @param readLocation - * @param writeLocation - */ - void assignReadBuffer(uint8_t* rx); - void assignWriteBuffer(const uint8_t* tx); - /** - * Set size for the next transfer. Set to 0 for no transfer - * @param transferSize - */ - void setTransferSize(size_t transferSize); - size_t getCurrentTransferSize() const; + /** + * This needs to be called to specify where the SPI driver writes to or reads from. + * @param readLocation + * @param writeLocation + */ + void assignReadBuffer(uint8_t* rx); + void assignWriteBuffer(const uint8_t* tx); + /** + * Set size for the next transfer. Set to 0 for no transfer + * @param transferSize + */ + void setTransferSize(size_t transferSize); + size_t getCurrentTransferSize() const; - struct UncommonParameters { - uint8_t bitsPerWord = 8; - bool noCs = false; - bool csHigh = false; - bool threeWireSpi = false; - /* MSB first is more common */ - bool lsbFirst = false; - }; + struct UncommonParameters { + uint8_t bitsPerWord = 8; + bool noCs = false; + bool csHigh = false; + bool threeWireSpi = false; + /* MSB first is more common */ + bool lsbFirst = false; + }; - /** - * Can be used to explicitely disable hardware chip select. - * Some drivers like the Raspberry Pi Linux driver will not use hardware chip select by default - * (see https://www.raspberrypi.org/documentation/hardware/raspberrypi/spi/README.md) - * @param enable - */ - void setNoCs(bool enable); - void setThreeWireSpi(bool enable); - void setLsbFirst(bool enable); - void setCsHigh(bool enable); - void setBitsPerWord(uint8_t bitsPerWord); + /** + * Can be used to explicitely disable hardware chip select. + * Some drivers like the Raspberry Pi Linux driver will not use hardware chip select by default + * (see https://www.raspberrypi.org/documentation/hardware/raspberrypi/spi/README.md) + * @param enable + */ + void setNoCs(bool enable); + void setThreeWireSpi(bool enable); + void setLsbFirst(bool enable); + void setCsHigh(bool enable); + void setBitsPerWord(uint8_t bitsPerWord); - void getSpiParameters(spi::SpiModes& spiMode, uint32_t& spiSpeed, - UncommonParameters* parameters = nullptr) const; + void getSpiParameters(spi::SpiModes& spiMode, uint32_t& spiSpeed, + UncommonParameters* parameters = nullptr) const; - /** - * See spidev.h cs_change and delay_usecs - * @param deselectCs - * @param delayUsecs - */ - void activateCsDeselect(bool deselectCs, uint16_t delayUsecs); + /** + * See spidev.h cs_change and delay_usecs + * @param deselectCs + * @param delayUsecs + */ + void activateCsDeselect(bool deselectCs, uint16_t delayUsecs); - spi_ioc_transfer* getTransferStructHandle(); -private: + spi_ioc_transfer* getTransferStructHandle(); - /** - * Internal constructor which initializes every field - * @param spiAddress - * @param chipSelect - * @param spiDev - * @param maxSize - * @param spiMode - * @param spiSpeed - * @param callback - * @param args - */ - SpiCookie(spi::SpiComIfModes comIfMode, address_t spiAddress, gpioId_t chipSelect, + private: + /** + * Internal constructor which initializes every field + * @param spiAddress + * @param chipSelect + * @param spiDev + * @param maxSize + * @param spiMode + * @param spiSpeed + * @param callback + * @param args + */ + SpiCookie(spi::SpiComIfModes comIfMode, address_t spiAddress, gpioId_t chipSelect, std::string spiDev, const size_t maxSize, spi::SpiModes spiMode, uint32_t spiSpeed, spi::send_callback_function_t callback, void* args); - address_t spiAddress; - gpioId_t chipSelectPin; - std::string spiDevice; + address_t spiAddress; + gpioId_t chipSelectPin; + std::string spiDevice; - spi::SpiComIfModes comIfMode; + spi::SpiComIfModes comIfMode; - // Required for regular mode - const size_t maxSize; - spi::SpiModes spiMode; - uint32_t spiSpeed; - bool halfDuplex = false; + // Required for regular mode + const size_t maxSize; + spi::SpiModes spiMode; + uint32_t spiSpeed; + bool halfDuplex = false; - // Required for callback mode - spi::send_callback_function_t sendCallback = nullptr; - void* callbackArgs = nullptr; + // Required for callback mode + spi::send_callback_function_t sendCallback = nullptr; + void* callbackArgs = nullptr; - struct spi_ioc_transfer spiTransferStruct = {}; - UncommonParameters uncommonParameters; + struct spi_ioc_transfer spiTransferStruct = {}; + UncommonParameters uncommonParameters; }; - - #endif /* LINUX_SPI_SPICOOKIE_H_ */ diff --git a/hal/src/fsfw_hal/linux/spi/spiDefinitions.h b/hal/src/fsfw_hal/linux/spi/spiDefinitions.h index 14af4fd5..b4bae3c2 100644 --- a/hal/src/fsfw_hal/linux/spi/spiDefinitions.h +++ b/hal/src/fsfw_hal/linux/spi/spiDefinitions.h @@ -1,28 +1,25 @@ #ifndef LINUX_SPI_SPIDEFINITONS_H_ #define LINUX_SPI_SPIDEFINITONS_H_ -#include "../../common/gpio/gpioDefinitions.h" -#include "../../common/spi/spiCommon.h" - -#include "fsfw/returnvalues/HasReturnvaluesIF.h" #include #include +#include "../../common/gpio/gpioDefinitions.h" +#include "../../common/spi/spiCommon.h" +#include "fsfw/returnvalues/HasReturnvaluesIF.h" + class SpiCookie; class SpiComIF; namespace spi { -enum SpiComIfModes { - REGULAR, - CALLBACK -}; +enum SpiComIfModes { REGULAR, CALLBACK }; +using send_callback_function_t = ReturnValue_t (*)(SpiComIF* comIf, SpiCookie* cookie, + const uint8_t* sendData, size_t sendLen, + void* args); -using send_callback_function_t = ReturnValue_t (*) (SpiComIF* comIf, SpiCookie *cookie, - const uint8_t *sendData, size_t sendLen, void* args); - -} +} // namespace spi #endif /* LINUX_SPI_SPIDEFINITONS_H_ */ diff --git a/hal/src/fsfw_hal/linux/uart/UartComIF.cpp b/hal/src/fsfw_hal/linux/uart/UartComIF.cpp index 08ec9aa0..a648df3a 100644 --- a/hal/src/fsfw_hal/linux/uart/UartComIF.cpp +++ b/hal/src/fsfw_hal/linux/uart/UartComIF.cpp @@ -1,569 +1,557 @@ #include "UartComIF.h" -#include "fsfw/FSFW.h" -#include "fsfw_hal/linux/utility.h" -#include "fsfw/serviceinterface.h" - -#include -#include #include +#include #include #include -UartComIF::UartComIF(object_id_t objectId): SystemObject(objectId){ -} +#include + +#include "fsfw/FSFW.h" +#include "fsfw/serviceinterface.h" +#include "fsfw_hal/linux/utility.h" + +UartComIF::UartComIF(object_id_t objectId) : SystemObject(objectId) {} UartComIF::~UartComIF() {} ReturnValue_t UartComIF::initializeInterface(CookieIF* cookie) { + std::string deviceFile; + UartDeviceMapIter uartDeviceMapIter; - std::string deviceFile; - UartDeviceMapIter uartDeviceMapIter; + if (cookie == nullptr) { + return NULLPOINTER; + } - if(cookie == nullptr) { - return NULLPOINTER; - } - - UartCookie* uartCookie = dynamic_cast(cookie); - if (uartCookie == nullptr) { + UartCookie* uartCookie = dynamic_cast(cookie); + if (uartCookie == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "UartComIF::initializeInterface: Invalid UART Cookie!" << std::endl; + sif::error << "UartComIF::initializeInterface: Invalid UART Cookie!" << std::endl; #endif - return NULLPOINTER; + return NULLPOINTER; + } + + deviceFile = uartCookie->getDeviceFile(); + + uartDeviceMapIter = uartDeviceMap.find(deviceFile); + if (uartDeviceMapIter == uartDeviceMap.end()) { + int fileDescriptor = configureUartPort(uartCookie); + if (fileDescriptor < 0) { + return RETURN_FAILED; } - - deviceFile = uartCookie->getDeviceFile(); - - uartDeviceMapIter = uartDeviceMap.find(deviceFile); - if(uartDeviceMapIter == uartDeviceMap.end()) { - int fileDescriptor = configureUartPort(uartCookie); - if (fileDescriptor < 0) { - return RETURN_FAILED; - } - size_t maxReplyLen = uartCookie->getMaxReplyLen(); - UartElements uartElements = {fileDescriptor, std::vector(maxReplyLen), 0}; - auto status = uartDeviceMap.emplace(deviceFile, uartElements); - if (status.second == false) { + size_t maxReplyLen = uartCookie->getMaxReplyLen(); + UartElements uartElements = {fileDescriptor, std::vector(maxReplyLen), 0}; + auto status = uartDeviceMap.emplace(deviceFile, uartElements); + if (status.second == false) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "UartComIF::initializeInterface: Failed to insert device " << - deviceFile << "to UART device map" << std::endl; + sif::warning << "UartComIF::initializeInterface: Failed to insert device " << deviceFile + << "to UART device map" << std::endl; #endif - return RETURN_FAILED; - } + return RETURN_FAILED; } - else { + } else { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "UartComIF::initializeInterface: UART device " << deviceFile << - " already in use" << std::endl; + sif::warning << "UartComIF::initializeInterface: UART device " << deviceFile + << " already in use" << std::endl; #endif - return RETURN_FAILED; - } + return RETURN_FAILED; + } - return RETURN_OK; + return RETURN_OK; } int UartComIF::configureUartPort(UartCookie* uartCookie) { + struct termios options = {}; - struct termios options = {}; + std::string deviceFile = uartCookie->getDeviceFile(); + int flags = O_RDWR; + if (uartCookie->getUartMode() == UartModes::CANONICAL) { + // In non-canonical mode, don't specify O_NONBLOCK because these properties will be + // controlled by the VTIME and VMIN parameters and O_NONBLOCK would override this + flags |= O_NONBLOCK; + } + int fd = open(deviceFile.c_str(), flags); - std::string deviceFile = uartCookie->getDeviceFile(); - int flags = O_RDWR; - if(uartCookie->getUartMode() == UartModes::CANONICAL) { - // In non-canonical mode, don't specify O_NONBLOCK because these properties will be - // controlled by the VTIME and VMIN parameters and O_NONBLOCK would override this - flags |= O_NONBLOCK; - } - int fd = open(deviceFile.c_str(), flags); - - if (fd < 0) { + if (fd < 0) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "UartComIF::configureUartPort: Failed to open uart " << deviceFile << - "with error code " << errno << strerror(errno) << std::endl; + sif::warning << "UartComIF::configureUartPort: Failed to open uart " << deviceFile + << "with error code " << errno << strerror(errno) << std::endl; #endif - return fd; - } - - /* Read in existing settings */ - if(tcgetattr(fd, &options) != 0) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "UartComIF::configureUartPort: Error " << errno << "from tcgetattr: " - << strerror(errno) << std::endl; -#endif - return fd; - } - - setParityOptions(&options, uartCookie); - setStopBitOptions(&options, uartCookie); - setDatasizeOptions(&options, uartCookie); - setFixedOptions(&options); - setUartMode(&options, *uartCookie); - if(uartCookie->getInputShouldBeFlushed()) { - tcflush(fd, TCIFLUSH); - } - - /* Sets uart to non-blocking mode. Read returns immediately when there are no data available */ - options.c_cc[VTIME] = 0; - options.c_cc[VMIN] = 0; - - configureBaudrate(&options, uartCookie); - - /* Save option settings */ - if (tcsetattr(fd, TCSANOW, &options) != 0) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "UartComIF::configureUartPort: Failed to set options with error " << - errno << ": " << strerror(errno); -#endif - return fd; - } return fd; + } + + /* Read in existing settings */ + if (tcgetattr(fd, &options) != 0) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "UartComIF::configureUartPort: Error " << errno + << "from tcgetattr: " << strerror(errno) << std::endl; +#endif + return fd; + } + + setParityOptions(&options, uartCookie); + setStopBitOptions(&options, uartCookie); + setDatasizeOptions(&options, uartCookie); + setFixedOptions(&options); + setUartMode(&options, *uartCookie); + if (uartCookie->getInputShouldBeFlushed()) { + tcflush(fd, TCIFLUSH); + } + + /* Sets uart to non-blocking mode. Read returns immediately when there are no data available */ + options.c_cc[VTIME] = 0; + options.c_cc[VMIN] = 0; + + configureBaudrate(&options, uartCookie); + + /* Save option settings */ + if (tcsetattr(fd, TCSANOW, &options) != 0) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "UartComIF::configureUartPort: Failed to set options with error " << errno + << ": " << strerror(errno); +#endif + return fd; + } + return fd; } void UartComIF::setParityOptions(struct termios* options, UartCookie* uartCookie) { - /* Clear parity bit */ - options->c_cflag &= ~PARENB; - switch (uartCookie->getParity()) { + /* Clear parity bit */ + options->c_cflag &= ~PARENB; + switch (uartCookie->getParity()) { case Parity::EVEN: - options->c_cflag |= PARENB; - options->c_cflag &= ~PARODD; - break; + options->c_cflag |= PARENB; + options->c_cflag &= ~PARODD; + break; case Parity::ODD: - options->c_cflag |= PARENB; - options->c_cflag |= PARODD; - break; + options->c_cflag |= PARENB; + options->c_cflag |= PARODD; + break; default: - break; - } + break; + } } void UartComIF::setStopBitOptions(struct termios* options, UartCookie* uartCookie) { - /* Clear stop field. Sets stop bit to one bit */ - options->c_cflag &= ~CSTOPB; - switch (uartCookie->getStopBits()) { + /* Clear stop field. Sets stop bit to one bit */ + options->c_cflag &= ~CSTOPB; + switch (uartCookie->getStopBits()) { case StopBits::TWO_STOP_BITS: - options->c_cflag |= CSTOPB; - break; + options->c_cflag |= CSTOPB; + break; default: - break; - } + break; + } } void UartComIF::setDatasizeOptions(struct termios* options, UartCookie* uartCookie) { - /* Clear size bits */ - options->c_cflag &= ~CSIZE; - switch (uartCookie->getBitsPerWord()) { + /* Clear size bits */ + options->c_cflag &= ~CSIZE; + switch (uartCookie->getBitsPerWord()) { case 5: - options->c_cflag |= CS5; - break; + options->c_cflag |= CS5; + break; case 6: - options->c_cflag |= CS6; - break; + options->c_cflag |= CS6; + break; case 7: - options->c_cflag |= CS7; - break; + options->c_cflag |= CS7; + break; case 8: - options->c_cflag |= CS8; - break; + options->c_cflag |= CS8; + break; default: #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "UartComIF::setDatasizeOptions: Invalid size specified" << std::endl; + sif::warning << "UartComIF::setDatasizeOptions: Invalid size specified" << std::endl; #endif - break; - } + break; + } } void UartComIF::setFixedOptions(struct termios* options) { - /* Disable RTS/CTS hardware flow control */ - options->c_cflag &= ~CRTSCTS; - /* Turn on READ & ignore ctrl lines (CLOCAL = 1) */ - options->c_cflag |= CREAD | CLOCAL; - /* Disable echo */ - options->c_lflag &= ~ECHO; - /* Disable erasure */ - options->c_lflag &= ~ECHOE; - /* Disable new-line echo */ - options->c_lflag &= ~ECHONL; - /* Disable interpretation of INTR, QUIT and SUSP */ - options->c_lflag &= ~ISIG; - /* Turn off s/w flow ctrl */ - options->c_iflag &= ~(IXON | IXOFF | IXANY); - /* Disable any special handling of received bytes */ - options->c_iflag &= ~(IGNBRK|BRKINT|PARMRK|ISTRIP|INLCR|IGNCR|ICRNL); - /* Prevent special interpretation of output bytes (e.g. newline chars) */ - options->c_oflag &= ~OPOST; - /* Prevent conversion of newline to carriage return/line feed */ - options->c_oflag &= ~ONLCR; + /* Disable RTS/CTS hardware flow control */ + options->c_cflag &= ~CRTSCTS; + /* Turn on READ & ignore ctrl lines (CLOCAL = 1) */ + options->c_cflag |= CREAD | CLOCAL; + /* Disable echo */ + options->c_lflag &= ~ECHO; + /* Disable erasure */ + options->c_lflag &= ~ECHOE; + /* Disable new-line echo */ + options->c_lflag &= ~ECHONL; + /* Disable interpretation of INTR, QUIT and SUSP */ + options->c_lflag &= ~ISIG; + /* Turn off s/w flow ctrl */ + options->c_iflag &= ~(IXON | IXOFF | IXANY); + /* Disable any special handling of received bytes */ + options->c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR | IGNCR | ICRNL); + /* Prevent special interpretation of output bytes (e.g. newline chars) */ + options->c_oflag &= ~OPOST; + /* Prevent conversion of newline to carriage return/line feed */ + options->c_oflag &= ~ONLCR; } void UartComIF::configureBaudrate(struct termios* options, UartCookie* uartCookie) { - switch (uartCookie->getBaudrate()) { + switch (uartCookie->getBaudrate()) { case 50: - cfsetispeed(options, B50); - cfsetospeed(options, B50); - break; + cfsetispeed(options, B50); + cfsetospeed(options, B50); + break; case 75: - cfsetispeed(options, B75); - cfsetospeed(options, B75); - break; + cfsetispeed(options, B75); + cfsetospeed(options, B75); + break; case 110: - cfsetispeed(options, B110); - cfsetospeed(options, B110); - break; + cfsetispeed(options, B110); + cfsetospeed(options, B110); + break; case 134: - cfsetispeed(options, B134); - cfsetospeed(options, B134); - break; + cfsetispeed(options, B134); + cfsetospeed(options, B134); + break; case 150: - cfsetispeed(options, B150); - cfsetospeed(options, B150); - break; + cfsetispeed(options, B150); + cfsetospeed(options, B150); + break; case 200: - cfsetispeed(options, B200); - cfsetospeed(options, B200); - break; + cfsetispeed(options, B200); + cfsetospeed(options, B200); + break; case 300: - cfsetispeed(options, B300); - cfsetospeed(options, B300); - break; + cfsetispeed(options, B300); + cfsetospeed(options, B300); + break; case 600: - cfsetispeed(options, B600); - cfsetospeed(options, B600); - break; + cfsetispeed(options, B600); + cfsetospeed(options, B600); + break; case 1200: - cfsetispeed(options, B1200); - cfsetospeed(options, B1200); - break; + cfsetispeed(options, B1200); + cfsetospeed(options, B1200); + break; case 1800: - cfsetispeed(options, B1800); - cfsetospeed(options, B1800); - break; + cfsetispeed(options, B1800); + cfsetospeed(options, B1800); + break; case 2400: - cfsetispeed(options, B2400); - cfsetospeed(options, B2400); - break; + cfsetispeed(options, B2400); + cfsetospeed(options, B2400); + break; case 4800: - cfsetispeed(options, B4800); - cfsetospeed(options, B4800); - break; + cfsetispeed(options, B4800); + cfsetospeed(options, B4800); + break; case 9600: - cfsetispeed(options, B9600); - cfsetospeed(options, B9600); - break; + cfsetispeed(options, B9600); + cfsetospeed(options, B9600); + break; case 19200: - cfsetispeed(options, B19200); - cfsetospeed(options, B19200); - break; + cfsetispeed(options, B19200); + cfsetospeed(options, B19200); + break; case 38400: - cfsetispeed(options, B38400); - cfsetospeed(options, B38400); - break; + cfsetispeed(options, B38400); + cfsetospeed(options, B38400); + break; case 57600: - cfsetispeed(options, B57600); - cfsetospeed(options, B57600); - break; + cfsetispeed(options, B57600); + cfsetospeed(options, B57600); + break; case 115200: - cfsetispeed(options, B115200); - cfsetospeed(options, B115200); - break; + cfsetispeed(options, B115200); + cfsetospeed(options, B115200); + break; case 230400: - cfsetispeed(options, B230400); - cfsetospeed(options, B230400); - break; + cfsetispeed(options, B230400); + cfsetospeed(options, B230400); + break; case 460800: - cfsetispeed(options, B460800); - cfsetospeed(options, B460800); - break; + cfsetispeed(options, B460800); + cfsetospeed(options, B460800); + break; default: #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "UartComIF::configureBaudrate: Baudrate not supported" << std::endl; + sif::warning << "UartComIF::configureBaudrate: Baudrate not supported" << std::endl; #endif - break; - } + break; + } } -ReturnValue_t UartComIF::sendMessage(CookieIF *cookie, - const uint8_t *sendData, size_t sendLen) { - int fd = 0; - std::string deviceFile; - UartDeviceMapIter uartDeviceMapIter; - - if(sendLen == 0) { - return RETURN_OK; - } - - if(sendData == nullptr) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "UartComIF::sendMessage: Send data is nullptr" << std::endl; -#endif - return RETURN_FAILED; - } - - UartCookie* uartCookie = dynamic_cast(cookie); - if(uartCookie == nullptr) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "UartComIF::sendMessasge: Invalid UART Cookie!" << std::endl; -#endif - return NULLPOINTER; - } - - deviceFile = uartCookie->getDeviceFile(); - uartDeviceMapIter = uartDeviceMap.find(deviceFile); - if (uartDeviceMapIter == uartDeviceMap.end()) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "UartComIF::sendMessage: Device file " << deviceFile << - "not in UART map" << std::endl; -#endif - return RETURN_FAILED; - } - - fd = uartDeviceMapIter->second.fileDescriptor; - - if (write(fd, sendData, sendLen) != static_cast(sendLen)) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "UartComIF::sendMessage: Failed to send data with error code " << - errno << ": Error description: " << strerror(errno) << std::endl; -#endif - return RETURN_FAILED; - } +ReturnValue_t UartComIF::sendMessage(CookieIF* cookie, const uint8_t* sendData, size_t sendLen) { + int fd = 0; + std::string deviceFile; + UartDeviceMapIter uartDeviceMapIter; + if (sendLen == 0) { return RETURN_OK; + } + + if (sendData == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "UartComIF::sendMessage: Send data is nullptr" << std::endl; +#endif + return RETURN_FAILED; + } + + UartCookie* uartCookie = dynamic_cast(cookie); + if (uartCookie == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "UartComIF::sendMessasge: Invalid UART Cookie!" << std::endl; +#endif + return NULLPOINTER; + } + + deviceFile = uartCookie->getDeviceFile(); + uartDeviceMapIter = uartDeviceMap.find(deviceFile); + if (uartDeviceMapIter == uartDeviceMap.end()) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::debug << "UartComIF::sendMessage: Device file " << deviceFile << "not in UART map" + << std::endl; +#endif + return RETURN_FAILED; + } + + fd = uartDeviceMapIter->second.fileDescriptor; + + if (write(fd, sendData, sendLen) != static_cast(sendLen)) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::error << "UartComIF::sendMessage: Failed to send data with error code " << errno + << ": Error description: " << strerror(errno) << std::endl; +#endif + return RETURN_FAILED; + } + + return RETURN_OK; } -ReturnValue_t UartComIF::getSendSuccess(CookieIF *cookie) { +ReturnValue_t UartComIF::getSendSuccess(CookieIF* cookie) { return RETURN_OK; } + +ReturnValue_t UartComIF::requestReceiveMessage(CookieIF* cookie, size_t requestLen) { + std::string deviceFile; + UartDeviceMapIter uartDeviceMapIter; + + UartCookie* uartCookie = dynamic_cast(cookie); + if (uartCookie == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::debug << "UartComIF::requestReceiveMessage: Invalid Uart Cookie!" << std::endl; +#endif + return NULLPOINTER; + } + + UartModes uartMode = uartCookie->getUartMode(); + deviceFile = uartCookie->getDeviceFile(); + uartDeviceMapIter = uartDeviceMap.find(deviceFile); + + if (uartMode == UartModes::NON_CANONICAL and requestLen == 0) { return RETURN_OK; -} + } -ReturnValue_t UartComIF::requestReceiveMessage(CookieIF *cookie, size_t requestLen) { - std::string deviceFile; - UartDeviceMapIter uartDeviceMapIter; - - UartCookie* uartCookie = dynamic_cast(cookie); - if(uartCookie == nullptr) { + if (uartDeviceMapIter == uartDeviceMap.end()) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "UartComIF::requestReceiveMessage: Invalid Uart Cookie!" << std::endl; + sif::debug << "UartComIF::requestReceiveMessage: Device file " << deviceFile + << " not in uart map" << std::endl; #endif - return NULLPOINTER; - } + return RETURN_FAILED; + } - UartModes uartMode = uartCookie->getUartMode(); - deviceFile = uartCookie->getDeviceFile(); - uartDeviceMapIter = uartDeviceMap.find(deviceFile); - - if(uartMode == UartModes::NON_CANONICAL and requestLen == 0) { - return RETURN_OK; - } - - if (uartDeviceMapIter == uartDeviceMap.end()) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "UartComIF::requestReceiveMessage: Device file " << deviceFile - << " not in uart map" << std::endl; -#endif - return RETURN_FAILED; - } - - if (uartMode == UartModes::CANONICAL) { - return handleCanonicalRead(*uartCookie, uartDeviceMapIter, requestLen); - } - else if (uartMode == UartModes::NON_CANONICAL) { - return handleNoncanonicalRead(*uartCookie, uartDeviceMapIter, requestLen); - } - else { - return HasReturnvaluesIF::RETURN_FAILED; - } + if (uartMode == UartModes::CANONICAL) { + return handleCanonicalRead(*uartCookie, uartDeviceMapIter, requestLen); + } else if (uartMode == UartModes::NON_CANONICAL) { + return handleNoncanonicalRead(*uartCookie, uartDeviceMapIter, requestLen); + } else { + return HasReturnvaluesIF::RETURN_FAILED; + } } ReturnValue_t UartComIF::handleCanonicalRead(UartCookie& uartCookie, UartDeviceMapIter& iter, - size_t requestLen) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - uint8_t maxReadCycles = uartCookie.getReadCycles(); - uint8_t currentReadCycles = 0; - int bytesRead = 0; - size_t currentBytesRead = 0; - size_t maxReplySize = uartCookie.getMaxReplyLen(); - int fd = iter->second.fileDescriptor; - auto bufferPtr = iter->second.replyBuffer.data(); - iter->second.replyLen = 0; - do { - size_t allowedReadSize = 0; - if(currentBytesRead >= maxReplySize) { - // Overflow risk. Emit warning, trigger event and break. If this happens, - // the reception buffer is not large enough or data is not polled often enough. + size_t requestLen) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + uint8_t maxReadCycles = uartCookie.getReadCycles(); + uint8_t currentReadCycles = 0; + int bytesRead = 0; + size_t currentBytesRead = 0; + size_t maxReplySize = uartCookie.getMaxReplyLen(); + int fd = iter->second.fileDescriptor; + auto bufferPtr = iter->second.replyBuffer.data(); + iter->second.replyLen = 0; + do { + size_t allowedReadSize = 0; + if (currentBytesRead >= maxReplySize) { + // Overflow risk. Emit warning, trigger event and break. If this happens, + // the reception buffer is not large enough or data is not polled often enough. #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "UartComIF::requestReceiveMessage: Next read would cause overflow!" - << std::endl; + sif::warning << "UartComIF::requestReceiveMessage: Next read would cause overflow!" + << std::endl; #else - sif::printWarning("UartComIF::requestReceiveMessage: " - "Next read would cause overflow!"); + sif::printWarning( + "UartComIF::requestReceiveMessage: " + "Next read would cause overflow!"); #endif #endif - result = UART_RX_BUFFER_TOO_SMALL; - break; - } - else { - allowedReadSize = maxReplySize - currentBytesRead; - } + result = UART_RX_BUFFER_TOO_SMALL; + break; + } else { + allowedReadSize = maxReplySize - currentBytesRead; + } - bytesRead = read(fd, bufferPtr, allowedReadSize); - if (bytesRead < 0) { - // EAGAIN: No data available in non-blocking mode - if(errno != EAGAIN) { + bytesRead = read(fd, bufferPtr, allowedReadSize); + if (bytesRead < 0) { + // EAGAIN: No data available in non-blocking mode + if (errno != EAGAIN) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "UartComIF::handleCanonicalRead: read failed with code" << - errno << ": " << strerror(errno) << std::endl; + sif::warning << "UartComIF::handleCanonicalRead: read failed with code" << errno << ": " + << strerror(errno) << std::endl; #else - sif::printWarning("UartComIF::handleCanonicalRead: read failed with code %d: %s\n", - errno, strerror(errno)); + sif::printWarning("UartComIF::handleCanonicalRead: read failed with code %d: %s\n", errno, + strerror(errno)); #endif #endif - return RETURN_FAILED; - } + return RETURN_FAILED; + } - } - else if(bytesRead > 0) { - iter->second.replyLen += bytesRead; - bufferPtr += bytesRead; - currentBytesRead += bytesRead; - } - currentReadCycles++; - } while(bytesRead > 0 and currentReadCycles < maxReadCycles); - return result; + } else if (bytesRead > 0) { + iter->second.replyLen += bytesRead; + bufferPtr += bytesRead; + currentBytesRead += bytesRead; + } + currentReadCycles++; + } while (bytesRead > 0 and currentReadCycles < maxReadCycles); + return result; } -ReturnValue_t UartComIF::handleNoncanonicalRead(UartCookie &uartCookie, UartDeviceMapIter &iter, - size_t requestLen) { - int fd = iter->second.fileDescriptor; - auto bufferPtr = iter->second.replyBuffer.data(); - // Size check to prevent buffer overflow - if(requestLen > uartCookie.getMaxReplyLen()) { +ReturnValue_t UartComIF::handleNoncanonicalRead(UartCookie& uartCookie, UartDeviceMapIter& iter, + size_t requestLen) { + int fd = iter->second.fileDescriptor; + auto bufferPtr = iter->second.replyBuffer.data(); + // Size check to prevent buffer overflow + if (requestLen > uartCookie.getMaxReplyLen()) { #if OBSW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "UartComIF::requestReceiveMessage: Next read would cause overflow!" - << std::endl; + sif::warning << "UartComIF::requestReceiveMessage: Next read would cause overflow!" + << std::endl; #else - sif::printWarning("UartComIF::requestReceiveMessage: " - "Next read would cause overflow!"); + sif::printWarning( + "UartComIF::requestReceiveMessage: " + "Next read would cause overflow!"); #endif #endif - return UART_RX_BUFFER_TOO_SMALL; - } - int bytesRead = read(fd, bufferPtr, requestLen); - if (bytesRead < 0) { - return RETURN_FAILED; - } - else if (bytesRead != static_cast(requestLen)) { - if(uartCookie.isReplySizeFixed()) { + return UART_RX_BUFFER_TOO_SMALL; + } + int bytesRead = read(fd, bufferPtr, requestLen); + if (bytesRead < 0) { + return RETURN_FAILED; + } else if (bytesRead != static_cast(requestLen)) { + if (uartCookie.isReplySizeFixed()) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "UartComIF::requestReceiveMessage: Only read " << bytesRead << - " of " << requestLen << " bytes" << std::endl; + sif::warning << "UartComIF::requestReceiveMessage: Only read " << bytesRead << " of " + << requestLen << " bytes" << std::endl; #endif - return RETURN_FAILED; - } + return RETURN_FAILED; } - iter->second.replyLen = bytesRead; - return HasReturnvaluesIF::RETURN_OK; + } + iter->second.replyLen = bytesRead; + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t UartComIF::readReceivedMessage(CookieIF *cookie, - uint8_t **buffer, size_t* size) { +ReturnValue_t UartComIF::readReceivedMessage(CookieIF* cookie, uint8_t** buffer, size_t* size) { + std::string deviceFile; + UartDeviceMapIter uartDeviceMapIter; - std::string deviceFile; - UartDeviceMapIter uartDeviceMapIter; - - UartCookie* uartCookie = dynamic_cast(cookie); - if(uartCookie == nullptr) { + UartCookie* uartCookie = dynamic_cast(cookie); + if (uartCookie == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "UartComIF::readReceivedMessage: Invalid uart cookie!" << std::endl; + sif::debug << "UartComIF::readReceivedMessage: Invalid uart cookie!" << std::endl; #endif - return NULLPOINTER; - } + return NULLPOINTER; + } - deviceFile = uartCookie->getDeviceFile(); - uartDeviceMapIter = uartDeviceMap.find(deviceFile); - if (uartDeviceMapIter == uartDeviceMap.end()) { + deviceFile = uartCookie->getDeviceFile(); + uartDeviceMapIter = uartDeviceMap.find(deviceFile); + if (uartDeviceMapIter == uartDeviceMap.end()) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "UartComIF::readReceivedMessage: Device file " << deviceFile << - " not in uart map" << std::endl; + sif::debug << "UartComIF::readReceivedMessage: Device file " << deviceFile << " not in uart map" + << std::endl; #endif - return RETURN_FAILED; - } + return RETURN_FAILED; + } - *buffer = uartDeviceMapIter->second.replyBuffer.data(); - *size = uartDeviceMapIter->second.replyLen; + *buffer = uartDeviceMapIter->second.replyBuffer.data(); + *size = uartDeviceMapIter->second.replyLen; - /* Length is reset to 0 to prevent reading the same data twice */ - uartDeviceMapIter->second.replyLen = 0; + /* Length is reset to 0 to prevent reading the same data twice */ + uartDeviceMapIter->second.replyLen = 0; + return RETURN_OK; +} + +ReturnValue_t UartComIF::flushUartRxBuffer(CookieIF* cookie) { + std::string deviceFile; + UartDeviceMapIter uartDeviceMapIter; + UartCookie* uartCookie = dynamic_cast(cookie); + if (uartCookie == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "UartComIF::flushUartRxBuffer: Invalid uart cookie!" << std::endl; +#endif + return NULLPOINTER; + } + deviceFile = uartCookie->getDeviceFile(); + uartDeviceMapIter = uartDeviceMap.find(deviceFile); + if (uartDeviceMapIter != uartDeviceMap.end()) { + int fd = uartDeviceMapIter->second.fileDescriptor; + tcflush(fd, TCIFLUSH); return RETURN_OK; + } + return RETURN_FAILED; } -ReturnValue_t UartComIF::flushUartRxBuffer(CookieIF *cookie) { - std::string deviceFile; - UartDeviceMapIter uartDeviceMapIter; - UartCookie* uartCookie = dynamic_cast(cookie); - if(uartCookie == nullptr) { +ReturnValue_t UartComIF::flushUartTxBuffer(CookieIF* cookie) { + std::string deviceFile; + UartDeviceMapIter uartDeviceMapIter; + UartCookie* uartCookie = dynamic_cast(cookie); + if (uartCookie == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "UartComIF::flushUartRxBuffer: Invalid uart cookie!" << std::endl; + sif::warning << "UartComIF::flushUartTxBuffer: Invalid uart cookie!" << std::endl; #endif - return NULLPOINTER; - } - deviceFile = uartCookie->getDeviceFile(); - uartDeviceMapIter = uartDeviceMap.find(deviceFile); - if(uartDeviceMapIter != uartDeviceMap.end()) { - int fd = uartDeviceMapIter->second.fileDescriptor; - tcflush(fd, TCIFLUSH); - return RETURN_OK; - } - return RETURN_FAILED; + return NULLPOINTER; + } + deviceFile = uartCookie->getDeviceFile(); + uartDeviceMapIter = uartDeviceMap.find(deviceFile); + if (uartDeviceMapIter != uartDeviceMap.end()) { + int fd = uartDeviceMapIter->second.fileDescriptor; + tcflush(fd, TCOFLUSH); + return RETURN_OK; + } + return RETURN_FAILED; } -ReturnValue_t UartComIF::flushUartTxBuffer(CookieIF *cookie) { - std::string deviceFile; - UartDeviceMapIter uartDeviceMapIter; - UartCookie* uartCookie = dynamic_cast(cookie); - if(uartCookie == nullptr) { +ReturnValue_t UartComIF::flushUartTxAndRxBuf(CookieIF* cookie) { + std::string deviceFile; + UartDeviceMapIter uartDeviceMapIter; + UartCookie* uartCookie = dynamic_cast(cookie); + if (uartCookie == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "UartComIF::flushUartTxBuffer: Invalid uart cookie!" << std::endl; + sif::warning << "UartComIF::flushUartTxAndRxBuf: Invalid uart cookie!" << std::endl; #endif - return NULLPOINTER; - } - deviceFile = uartCookie->getDeviceFile(); - uartDeviceMapIter = uartDeviceMap.find(deviceFile); - if(uartDeviceMapIter != uartDeviceMap.end()) { - int fd = uartDeviceMapIter->second.fileDescriptor; - tcflush(fd, TCOFLUSH); - return RETURN_OK; - } - return RETURN_FAILED; + return NULLPOINTER; + } + deviceFile = uartCookie->getDeviceFile(); + uartDeviceMapIter = uartDeviceMap.find(deviceFile); + if (uartDeviceMapIter != uartDeviceMap.end()) { + int fd = uartDeviceMapIter->second.fileDescriptor; + tcflush(fd, TCIOFLUSH); + return RETURN_OK; + } + return RETURN_FAILED; } -ReturnValue_t UartComIF::flushUartTxAndRxBuf(CookieIF *cookie) { - std::string deviceFile; - UartDeviceMapIter uartDeviceMapIter; - UartCookie* uartCookie = dynamic_cast(cookie); - if(uartCookie == nullptr) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "UartComIF::flushUartTxAndRxBuf: Invalid uart cookie!" << std::endl; -#endif - return NULLPOINTER; - } - deviceFile = uartCookie->getDeviceFile(); - uartDeviceMapIter = uartDeviceMap.find(deviceFile); - if(uartDeviceMapIter != uartDeviceMap.end()) { - int fd = uartDeviceMapIter->second.fileDescriptor; - tcflush(fd, TCIOFLUSH); - return RETURN_OK; - } - return RETURN_FAILED; -} - -void UartComIF::setUartMode(struct termios *options, UartCookie &uartCookie) { - UartModes uartMode = uartCookie.getUartMode(); - if(uartMode == UartModes::NON_CANONICAL) { - /* Disable canonical mode */ - options->c_lflag &= ~ICANON; - } - else if(uartMode == UartModes::CANONICAL) { - options->c_lflag |= ICANON; - } +void UartComIF::setUartMode(struct termios* options, UartCookie& uartCookie) { + UartModes uartMode = uartCookie.getUartMode(); + if (uartMode == UartModes::NON_CANONICAL) { + /* Disable canonical mode */ + options->c_lflag &= ~ICANON; + } else if (uartMode == UartModes::CANONICAL) { + options->c_lflag |= ICANON; + } } diff --git a/hal/src/fsfw_hal/linux/uart/UartComIF.h b/hal/src/fsfw_hal/linux/uart/UartComIF.h index 68d2b9f5..224f1e77 100644 --- a/hal/src/fsfw_hal/linux/uart/UartComIF.h +++ b/hal/src/fsfw_hal/linux/uart/UartComIF.h @@ -1,13 +1,14 @@ #ifndef BSP_Q7S_COMIF_UARTCOMIF_H_ #define BSP_Q7S_COMIF_UARTCOMIF_H_ -#include "UartCookie.h" -#include #include +#include #include #include +#include "UartCookie.h" + /** * @brief This is the communication interface to access serial ports on linux based operating * systems. @@ -17,109 +18,104 @@ * * @author J. Meier */ -class UartComIF: public DeviceCommunicationIF, public SystemObject { -public: - static constexpr uint8_t uartRetvalId = CLASS_ID::HAL_UART; +class UartComIF : public DeviceCommunicationIF, public SystemObject { + public: + static constexpr uint8_t uartRetvalId = CLASS_ID::HAL_UART; - static constexpr ReturnValue_t UART_READ_FAILURE = - HasReturnvaluesIF::makeReturnCode(uartRetvalId, 1); - static constexpr ReturnValue_t UART_READ_SIZE_MISSMATCH = - HasReturnvaluesIF::makeReturnCode(uartRetvalId, 2); - static constexpr ReturnValue_t UART_RX_BUFFER_TOO_SMALL = - HasReturnvaluesIF::makeReturnCode(uartRetvalId, 3); + static constexpr ReturnValue_t UART_READ_FAILURE = + HasReturnvaluesIF::makeReturnCode(uartRetvalId, 1); + static constexpr ReturnValue_t UART_READ_SIZE_MISSMATCH = + HasReturnvaluesIF::makeReturnCode(uartRetvalId, 2); + static constexpr ReturnValue_t UART_RX_BUFFER_TOO_SMALL = + HasReturnvaluesIF::makeReturnCode(uartRetvalId, 3); - UartComIF(object_id_t objectId); + UartComIF(object_id_t objectId); - virtual ~UartComIF(); + virtual ~UartComIF(); - ReturnValue_t initializeInterface(CookieIF * cookie) override; - ReturnValue_t sendMessage(CookieIF *cookie,const uint8_t *sendData, - size_t sendLen) override; - ReturnValue_t getSendSuccess(CookieIF *cookie) override; - ReturnValue_t requestReceiveMessage(CookieIF *cookie, - size_t requestLen) override; - ReturnValue_t readReceivedMessage(CookieIF *cookie, uint8_t **buffer, - size_t *size) override; + ReturnValue_t initializeInterface(CookieIF* cookie) override; + ReturnValue_t sendMessage(CookieIF* cookie, const uint8_t* sendData, size_t sendLen) override; + ReturnValue_t getSendSuccess(CookieIF* cookie) override; + ReturnValue_t requestReceiveMessage(CookieIF* cookie, size_t requestLen) override; + ReturnValue_t readReceivedMessage(CookieIF* cookie, uint8_t** buffer, size_t* size) override; - /** - * @brief This function discards all data received but not read in the UART buffer. - */ - ReturnValue_t flushUartRxBuffer(CookieIF *cookie); + /** + * @brief This function discards all data received but not read in the UART buffer. + */ + ReturnValue_t flushUartRxBuffer(CookieIF* cookie); - /** - * @brief This function discards all data in the transmit buffer of the UART driver. - */ - ReturnValue_t flushUartTxBuffer(CookieIF *cookie); + /** + * @brief This function discards all data in the transmit buffer of the UART driver. + */ + ReturnValue_t flushUartTxBuffer(CookieIF* cookie); - /** - * @brief This function discards both data in the transmit and receive buffer of the UART. - */ - ReturnValue_t flushUartTxAndRxBuf(CookieIF *cookie); + /** + * @brief This function discards both data in the transmit and receive buffer of the UART. + */ + ReturnValue_t flushUartTxAndRxBuf(CookieIF* cookie); -private: + private: + using UartDeviceFile_t = std::string; - using UartDeviceFile_t = std::string; + struct UartElements { + int fileDescriptor; + std::vector replyBuffer; + /** Number of bytes read will be written to this variable */ + size_t replyLen; + }; - struct UartElements { - int fileDescriptor; - std::vector replyBuffer; - /** Number of bytes read will be written to this variable */ - size_t replyLen; - }; + using UartDeviceMap = std::unordered_map; + using UartDeviceMapIter = UartDeviceMap::iterator; - using UartDeviceMap = std::unordered_map; - using UartDeviceMapIter = UartDeviceMap::iterator; + /** + * The uart devie map stores informations of initialized uart ports. + */ + UartDeviceMap uartDeviceMap; - /** - * The uart devie map stores informations of initialized uart ports. - */ - UartDeviceMap uartDeviceMap; + /** + * @brief This function opens and configures a uart device by using the information stored + * in the uart cookie. + * @param uartCookie Pointer to uart cookie with information about the uart. Contains the + * uart device file, baudrate, parity, stopbits etc. + * @return The file descriptor of the configured uart. + */ + int configureUartPort(UartCookie* uartCookie); - /** - * @brief This function opens and configures a uart device by using the information stored - * in the uart cookie. - * @param uartCookie Pointer to uart cookie with information about the uart. Contains the - * uart device file, baudrate, parity, stopbits etc. - * @return The file descriptor of the configured uart. - */ - int configureUartPort(UartCookie* uartCookie); + /** + * @brief This function adds the parity settings to the termios options struct. + * + * @param options Pointer to termios options struct which will be modified to enable or disable + * parity checking. + * @param uartCookie Pointer to uart cookie containing the information about the desired + * parity settings. + * + */ + void setParityOptions(struct termios* options, UartCookie* uartCookie); - /** - * @brief This function adds the parity settings to the termios options struct. - * - * @param options Pointer to termios options struct which will be modified to enable or disable - * parity checking. - * @param uartCookie Pointer to uart cookie containing the information about the desired - * parity settings. - * - */ - void setParityOptions(struct termios* options, UartCookie* uartCookie); + void setStopBitOptions(struct termios* options, UartCookie* uartCookie); - void setStopBitOptions(struct termios* options, UartCookie* uartCookie); + /** + * @brief This function sets options which are not configurable by the uartCookie. + */ + void setFixedOptions(struct termios* options); - /** - * @brief This function sets options which are not configurable by the uartCookie. - */ - void setFixedOptions(struct termios* options); + /** + * @brief With this function the datasize settings are added to the termios options struct. + */ + void setDatasizeOptions(struct termios* options, UartCookie* uartCookie); - /** - * @brief With this function the datasize settings are added to the termios options struct. - */ - void setDatasizeOptions(struct termios* options, UartCookie* uartCookie); + /** + * @brief This functions adds the baudrate specified in the uartCookie to the termios options + * struct. + */ + void configureBaudrate(struct termios* options, UartCookie* uartCookie); - /** - * @brief This functions adds the baudrate specified in the uartCookie to the termios options - * struct. - */ - void configureBaudrate(struct termios* options, UartCookie* uartCookie); - - void setUartMode(struct termios* options, UartCookie& uartCookie); - - ReturnValue_t handleCanonicalRead(UartCookie& uartCookie, UartDeviceMapIter& iter, - size_t requestLen); - ReturnValue_t handleNoncanonicalRead(UartCookie& uartCookie, UartDeviceMapIter& iter, - size_t requestLen); + void setUartMode(struct termios* options, UartCookie& uartCookie); + ReturnValue_t handleCanonicalRead(UartCookie& uartCookie, UartDeviceMapIter& iter, + size_t requestLen); + ReturnValue_t handleNoncanonicalRead(UartCookie& uartCookie, UartDeviceMapIter& iter, + size_t requestLen); }; #endif /* BSP_Q7S_COMIF_UARTCOMIF_H_ */ diff --git a/hal/src/fsfw_hal/linux/uart/UartCookie.cpp b/hal/src/fsfw_hal/linux/uart/UartCookie.cpp index 140b1992..99e80a8e 100644 --- a/hal/src/fsfw_hal/linux/uart/UartCookie.cpp +++ b/hal/src/fsfw_hal/linux/uart/UartCookie.cpp @@ -3,97 +3,63 @@ #include UartCookie::UartCookie(object_id_t handlerId, std::string deviceFile, UartModes uartMode, - uint32_t baudrate, size_t maxReplyLen): - handlerId(handlerId), deviceFile(deviceFile), uartMode(uartMode), - baudrate(baudrate), maxReplyLen(maxReplyLen) { -} + uint32_t baudrate, size_t maxReplyLen) + : handlerId(handlerId), + deviceFile(deviceFile), + uartMode(uartMode), + baudrate(baudrate), + maxReplyLen(maxReplyLen) {} UartCookie::~UartCookie() {} -uint32_t UartCookie::getBaudrate() const { - return baudrate; -} +uint32_t UartCookie::getBaudrate() const { return baudrate; } -size_t UartCookie::getMaxReplyLen() const { - return maxReplyLen; -} +size_t UartCookie::getMaxReplyLen() const { return maxReplyLen; } -std::string UartCookie::getDeviceFile() const { - return deviceFile; -} +std::string UartCookie::getDeviceFile() const { return deviceFile; } -void UartCookie::setParityOdd() { - parity = Parity::ODD; -} +void UartCookie::setParityOdd() { parity = Parity::ODD; } -void UartCookie::setParityEven() { - parity = Parity::EVEN; -} +void UartCookie::setParityEven() { parity = Parity::EVEN; } -Parity UartCookie::getParity() const { - return parity; -} +Parity UartCookie::getParity() const { return parity; } void UartCookie::setBitsPerWord(uint8_t bitsPerWord_) { - switch(bitsPerWord_) { + switch (bitsPerWord_) { case 5: case 6: case 7: case 8: - break; + break; default: #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "UartCookie::setBitsPerWord: Invalid bits per word specified" << std::endl; + sif::debug << "UartCookie::setBitsPerWord: Invalid bits per word specified" << std::endl; #endif - return; - } - bitsPerWord = bitsPerWord_; + return; + } + bitsPerWord = bitsPerWord_; } -uint8_t UartCookie::getBitsPerWord() const { - return bitsPerWord; -} +uint8_t UartCookie::getBitsPerWord() const { return bitsPerWord; } -StopBits UartCookie::getStopBits() const { - return stopBits; -} +StopBits UartCookie::getStopBits() const { return stopBits; } -void UartCookie::setTwoStopBits() { - stopBits = StopBits::TWO_STOP_BITS; -} +void UartCookie::setTwoStopBits() { stopBits = StopBits::TWO_STOP_BITS; } -void UartCookie::setOneStopBit() { - stopBits = StopBits::ONE_STOP_BIT; -} +void UartCookie::setOneStopBit() { stopBits = StopBits::ONE_STOP_BIT; } -UartModes UartCookie::getUartMode() const { - return uartMode; -} +UartModes UartCookie::getUartMode() const { return uartMode; } -void UartCookie::setReadCycles(uint8_t readCycles) { - this->readCycles = readCycles; -} +void UartCookie::setReadCycles(uint8_t readCycles) { this->readCycles = readCycles; } -void UartCookie::setToFlushInput(bool enable) { - this->flushInput = enable; -} +void UartCookie::setToFlushInput(bool enable) { this->flushInput = enable; } -uint8_t UartCookie::getReadCycles() const { - return readCycles; -} +uint8_t UartCookie::getReadCycles() const { return readCycles; } -bool UartCookie::getInputShouldBeFlushed() { - return this->flushInput; -} +bool UartCookie::getInputShouldBeFlushed() { return this->flushInput; } -object_id_t UartCookie::getHandlerId() const { - return this->handlerId; -} +object_id_t UartCookie::getHandlerId() const { return this->handlerId; } -void UartCookie::setNoFixedSizeReply() { - replySizeFixed = false; -} +void UartCookie::setNoFixedSizeReply() { replySizeFixed = false; } -bool UartCookie::isReplySizeFixed() { - return replySizeFixed; -} +bool UartCookie::isReplySizeFixed() { return replySizeFixed; } diff --git a/hal/src/fsfw_hal/linux/uart/UartCookie.h b/hal/src/fsfw_hal/linux/uart/UartCookie.h index faf95d50..884665e5 100644 --- a/hal/src/fsfw_hal/linux/uart/UartCookie.h +++ b/hal/src/fsfw_hal/linux/uart/UartCookie.h @@ -6,21 +6,11 @@ #include -enum class Parity { - NONE, - EVEN, - ODD -}; +enum class Parity { NONE, EVEN, ODD }; -enum class StopBits { - ONE_STOP_BIT, - TWO_STOP_BITS -}; +enum class StopBits { ONE_STOP_BIT, TWO_STOP_BITS }; -enum class UartModes { - CANONICAL, - NON_CANONICAL -}; +enum class UartModes { CANONICAL, NON_CANONICAL }; /** * @brief Cookie for the UartComIF. There are many options available to configure the UART driver. @@ -29,93 +19,91 @@ enum class UartModes { * * @author J. Meier */ -class UartCookie: public CookieIF { -public: +class UartCookie : public CookieIF { + public: + /** + * @brief Constructor for the uart cookie. + * @param deviceFile The device file specifying the uart to use, e.g. "/dev/ttyPS1" + * @param uartMode Specify the UART mode. The canonical mode should be used if the + * messages are separated by a delimited character like '\n'. See the + * termios documentation for more information + * @param baudrate The baudrate to use for input and output. Possible Baudrates are: 50, + * 75, 110, 134, 150, 200, 300, 600, 1200, 1800, 2400, 4800, 9600, B19200, + * 38400, 57600, 115200, 230400, 460800 + * @param maxReplyLen The maximum size an object using this cookie expects + * @details + * Default configuration: No parity + * 8 databits (number of bits transfered with one uart frame) + * One stop bit + */ + UartCookie(object_id_t handlerId, std::string deviceFile, UartModes uartMode, uint32_t baudrate, + size_t maxReplyLen); - /** - * @brief Constructor for the uart cookie. - * @param deviceFile The device file specifying the uart to use, e.g. "/dev/ttyPS1" - * @param uartMode Specify the UART mode. The canonical mode should be used if the - * messages are separated by a delimited character like '\n'. See the - * termios documentation for more information - * @param baudrate The baudrate to use for input and output. Possible Baudrates are: 50, - * 75, 110, 134, 150, 200, 300, 600, 1200, 1800, 2400, 4800, 9600, B19200, - * 38400, 57600, 115200, 230400, 460800 - * @param maxReplyLen The maximum size an object using this cookie expects - * @details - * Default configuration: No parity - * 8 databits (number of bits transfered with one uart frame) - * One stop bit - */ - UartCookie(object_id_t handlerId, std::string deviceFile, UartModes uartMode, - uint32_t baudrate, size_t maxReplyLen); + virtual ~UartCookie(); - virtual ~UartCookie(); + uint32_t getBaudrate() const; + size_t getMaxReplyLen() const; + std::string getDeviceFile() const; + Parity getParity() const; + uint8_t getBitsPerWord() const; + StopBits getStopBits() const; + UartModes getUartMode() const; + object_id_t getHandlerId() const; - uint32_t getBaudrate() const; - size_t getMaxReplyLen() const; - std::string getDeviceFile() const; - Parity getParity() const; - uint8_t getBitsPerWord() const; - StopBits getStopBits() const; - UartModes getUartMode() const; - object_id_t getHandlerId() const; + /** + * The UART ComIF will only perform a specified number of read cycles for the canonical mode. + * The user can specify how many of those read cycles are performed for one device handler + * communication cycle. An example use-case would be to read all available GPS NMEA strings + * at once. + * @param readCycles + */ + void setReadCycles(uint8_t readCycles); + uint8_t getReadCycles() const; - /** - * The UART ComIF will only perform a specified number of read cycles for the canonical mode. - * The user can specify how many of those read cycles are performed for one device handler - * communication cycle. An example use-case would be to read all available GPS NMEA strings - * at once. - * @param readCycles - */ - void setReadCycles(uint8_t readCycles); - uint8_t getReadCycles() const; + /** + * Allows to flush the data which was received but has not been read yet. This is useful + * to discard obsolete data at software startup. + */ + void setToFlushInput(bool enable); + bool getInputShouldBeFlushed(); - /** - * Allows to flush the data which was received but has not been read yet. This is useful - * to discard obsolete data at software startup. - */ - void setToFlushInput(bool enable); - bool getInputShouldBeFlushed(); + /** + * Functions two enable parity checking. + */ + void setParityOdd(); + void setParityEven(); - /** - * Functions two enable parity checking. - */ - void setParityOdd(); - void setParityEven(); + /** + * Function two set number of bits per UART frame. + */ + void setBitsPerWord(uint8_t bitsPerWord_); - /** - * Function two set number of bits per UART frame. - */ - void setBitsPerWord(uint8_t bitsPerWord_); + /** + * Function to specify the number of stopbits. + */ + void setTwoStopBits(); + void setOneStopBit(); - /** - * Function to specify the number of stopbits. - */ - void setTwoStopBits(); - void setOneStopBit(); + /** + * Calling this function prevents the UartComIF to return failed if not all requested bytes + * could be read. This is required by a device handler when the size of a reply is not known. + */ + void setNoFixedSizeReply(); - /** - * Calling this function prevents the UartComIF to return failed if not all requested bytes - * could be read. This is required by a device handler when the size of a reply is not known. - */ - void setNoFixedSizeReply(); + bool isReplySizeFixed(); - bool isReplySizeFixed(); - -private: - - const object_id_t handlerId; - std::string deviceFile; - const UartModes uartMode; - bool flushInput = false; - uint32_t baudrate; - size_t maxReplyLen = 0; - Parity parity = Parity::NONE; - uint8_t bitsPerWord = 8; - uint8_t readCycles = 1; - StopBits stopBits = StopBits::ONE_STOP_BIT; - bool replySizeFixed = true; + private: + const object_id_t handlerId; + std::string deviceFile; + const UartModes uartMode; + bool flushInput = false; + uint32_t baudrate; + size_t maxReplyLen = 0; + Parity parity = Parity::NONE; + uint8_t bitsPerWord = 8; + uint8_t readCycles = 1; + StopBits stopBits = StopBits::ONE_STOP_BIT; + bool replySizeFixed = true; }; #endif diff --git a/hal/src/fsfw_hal/linux/utility.cpp b/hal/src/fsfw_hal/linux/utility.cpp index 99489e3f..95d3f0d7 100644 --- a/hal/src/fsfw_hal/linux/utility.cpp +++ b/hal/src/fsfw_hal/linux/utility.cpp @@ -1,26 +1,23 @@ -#include "fsfw/FSFW.h" -#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw_hal/linux/utility.h" #include #include +#include "fsfw/FSFW.h" +#include "fsfw/serviceinterface/ServiceInterface.h" + void utility::handleIoctlError(const char* const customPrintout) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - if(customPrintout != nullptr) { - sif::warning << customPrintout << std::endl; - } - sif::warning << "handleIoctlError: Error code " << errno << ", "<< strerror(errno) << - std::endl; + if (customPrintout != nullptr) { + sif::warning << customPrintout << std::endl; + } + sif::warning << "handleIoctlError: Error code " << errno << ", " << strerror(errno) << std::endl; #else - if(customPrintout != nullptr) { - sif::printWarning("%s\n", customPrintout); - } - sif::printWarning("handleIoctlError: Error code %d, %s\n", errno, strerror(errno)); + if (customPrintout != nullptr) { + sif::printWarning("%s\n", customPrintout); + } + sif::printWarning("handleIoctlError: Error code %d, %s\n", errno, strerror(errno)); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - } - - diff --git a/hal/src/fsfw_hal/stm32h7/definitions.h b/hal/src/fsfw_hal/stm32h7/definitions.h index af63a541..4612d2b7 100644 --- a/hal/src/fsfw_hal/stm32h7/definitions.h +++ b/hal/src/fsfw_hal/stm32h7/definitions.h @@ -2,6 +2,7 @@ #define FSFW_HAL_STM32H7_DEFINITIONS_H_ #include + #include "stm32h7xx.h" namespace stm32h7 { @@ -11,15 +12,15 @@ namespace stm32h7 { * and the second entry is the pin number */ struct GpioCfg { - GpioCfg(): port(nullptr), pin(0), altFnc(0) {}; + GpioCfg() : port(nullptr), pin(0), altFnc(0){}; - GpioCfg(GPIO_TypeDef* port, uint16_t pin, uint8_t altFnc = 0): - port(port), pin(pin), altFnc(altFnc) {}; - GPIO_TypeDef* port; - uint16_t pin; - uint8_t altFnc; + GpioCfg(GPIO_TypeDef* port, uint16_t pin, uint8_t altFnc = 0) + : port(port), pin(pin), altFnc(altFnc){}; + GPIO_TypeDef* port; + uint16_t pin; + uint8_t altFnc; }; -} +} // namespace stm32h7 #endif /* #ifndef FSFW_HAL_STM32H7_DEFINITIONS_H_ */ diff --git a/hal/src/fsfw_hal/stm32h7/devicetest/GyroL3GD20H.cpp b/hal/src/fsfw_hal/stm32h7/devicetest/GyroL3GD20H.cpp index d1fdd1e5..cbf8def5 100644 --- a/hal/src/fsfw_hal/stm32h7/devicetest/GyroL3GD20H.cpp +++ b/hal/src/fsfw_hal/stm32h7/devicetest/GyroL3GD20H.cpp @@ -1,549 +1,547 @@ #include "fsfw_hal/stm32h7/devicetest/GyroL3GD20H.h" -#include "fsfw_hal/stm32h7/spi/mspInit.h" -#include "fsfw_hal/stm32h7/spi/spiDefinitions.h" -#include "fsfw_hal/stm32h7/spi/spiCore.h" -#include "fsfw_hal/stm32h7/spi/spiInterrupts.h" -#include "fsfw_hal/stm32h7/spi/stm32h743zi.h" - -#include "fsfw/tasks/TaskFactory.h" -#include "fsfw/serviceinterface/ServiceInterface.h" - -#include "stm32h7xx_hal_spi.h" -#include "stm32h7xx_hal_rcc.h" - #include +#include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/tasks/TaskFactory.h" +#include "fsfw_hal/stm32h7/spi/mspInit.h" +#include "fsfw_hal/stm32h7/spi/spiCore.h" +#include "fsfw_hal/stm32h7/spi/spiDefinitions.h" +#include "fsfw_hal/stm32h7/spi/spiInterrupts.h" +#include "fsfw_hal/stm32h7/spi/stm32h743zi.h" +#include "stm32h7xx_hal_rcc.h" +#include "stm32h7xx_hal_spi.h" + alignas(32) std::array GyroL3GD20H::rxBuffer; -alignas(32) std::array -GyroL3GD20H::txBuffer __attribute__((section(".dma_buffer"))); +alignas(32) std::array GyroL3GD20H::txBuffer + __attribute__((section(".dma_buffer"))); TransferStates transferState = TransferStates::IDLE; -spi::TransferModes GyroL3GD20H::transferMode = spi::TransferModes::POLLING; +spi::TransferModes GyroL3GD20H::transferMode = spi::TransferModes::POLLING; +GyroL3GD20H::GyroL3GD20H(SPI_HandleTypeDef *spiHandle, spi::TransferModes transferMode_) + : spiHandle(spiHandle) { + txDmaHandle = new DMA_HandleTypeDef(); + rxDmaHandle = new DMA_HandleTypeDef(); + spi::setSpiHandle(spiHandle); + spi::assignSpiUserArgs(spi::SpiBus::SPI_1, spiHandle); + transferMode = transferMode_; + if (transferMode == spi::TransferModes::DMA) { + mspCfg = new spi::MspDmaConfigStruct(); + auto typedCfg = dynamic_cast(mspCfg); + spi::setDmaHandles(txDmaHandle, rxDmaHandle); + stm32h7::h743zi::standardDmaCfg(*typedCfg, IrqPriorities::HIGHEST_FREERTOS, + IrqPriorities::HIGHEST_FREERTOS, + IrqPriorities::HIGHEST_FREERTOS); + spi::setSpiDmaMspFunctions(typedCfg); + } else if (transferMode == spi::TransferModes::INTERRUPT) { + mspCfg = new spi::MspIrqConfigStruct(); + auto typedCfg = dynamic_cast(mspCfg); + stm32h7::h743zi::standardInterruptCfg(*typedCfg, IrqPriorities::HIGHEST_FREERTOS); + spi::setSpiIrqMspFunctions(typedCfg); + } else if (transferMode == spi::TransferModes::POLLING) { + mspCfg = new spi::MspPollingConfigStruct(); + auto typedCfg = dynamic_cast(mspCfg); + stm32h7::h743zi::standardPollingCfg(*typedCfg); + spi::setSpiPollingMspFunctions(typedCfg); + } -GyroL3GD20H::GyroL3GD20H(SPI_HandleTypeDef *spiHandle, spi::TransferModes transferMode_): - spiHandle(spiHandle) { - txDmaHandle = new DMA_HandleTypeDef(); - rxDmaHandle = new DMA_HandleTypeDef(); - spi::setSpiHandle(spiHandle); - spi::assignSpiUserArgs(spi::SpiBus::SPI_1, spiHandle); - transferMode = transferMode_; - if(transferMode == spi::TransferModes::DMA) { - mspCfg = new spi::MspDmaConfigStruct(); - auto typedCfg = dynamic_cast(mspCfg); - spi::setDmaHandles(txDmaHandle, rxDmaHandle); - stm32h7::h743zi::standardDmaCfg(*typedCfg, IrqPriorities::HIGHEST_FREERTOS, - IrqPriorities::HIGHEST_FREERTOS, IrqPriorities::HIGHEST_FREERTOS); - spi::setSpiDmaMspFunctions(typedCfg); - } - else if(transferMode == spi::TransferModes::INTERRUPT) { - mspCfg = new spi::MspIrqConfigStruct(); - auto typedCfg = dynamic_cast(mspCfg); - stm32h7::h743zi::standardInterruptCfg(*typedCfg, IrqPriorities::HIGHEST_FREERTOS); - spi::setSpiIrqMspFunctions(typedCfg); - } - else if(transferMode == spi::TransferModes::POLLING) { - mspCfg = new spi::MspPollingConfigStruct(); - auto typedCfg = dynamic_cast(mspCfg); - stm32h7::h743zi::standardPollingCfg(*typedCfg); - spi::setSpiPollingMspFunctions(typedCfg); - } + spi::assignTransferRxTxCompleteCallback(&spiTransferCompleteCallback, nullptr); + spi::assignTransferErrorCallback(&spiTransferErrorCallback, nullptr); - spi::assignTransferRxTxCompleteCallback(&spiTransferCompleteCallback, nullptr); - spi::assignTransferErrorCallback(&spiTransferErrorCallback, nullptr); - - GPIO_InitTypeDef chipSelect = {}; - __HAL_RCC_GPIOD_CLK_ENABLE(); - chipSelect.Pin = GPIO_PIN_14; - chipSelect.Mode = GPIO_MODE_OUTPUT_PP; - HAL_GPIO_Init(GPIOD, &chipSelect); - HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_SET); + GPIO_InitTypeDef chipSelect = {}; + __HAL_RCC_GPIOD_CLK_ENABLE(); + chipSelect.Pin = GPIO_PIN_14; + chipSelect.Mode = GPIO_MODE_OUTPUT_PP; + HAL_GPIO_Init(GPIOD, &chipSelect); + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_SET); } GyroL3GD20H::~GyroL3GD20H() { - delete txDmaHandle; - delete rxDmaHandle; - if(mspCfg != nullptr) { - delete mspCfg; - } + delete txDmaHandle; + delete rxDmaHandle; + if (mspCfg != nullptr) { + delete mspCfg; + } } ReturnValue_t GyroL3GD20H::initialize() { - // Configure the SPI peripheral - spiHandle->Instance = SPI1; - spiHandle->Init.BaudRatePrescaler = spi::getPrescaler(HAL_RCC_GetHCLKFreq(), 3900000); - spiHandle->Init.Direction = SPI_DIRECTION_2LINES; - spi::assignSpiMode(spi::SpiModes::MODE_3, *spiHandle); - spiHandle->Init.DataSize = SPI_DATASIZE_8BIT; - spiHandle->Init.FirstBit = SPI_FIRSTBIT_MSB; - spiHandle->Init.TIMode = SPI_TIMODE_DISABLE; - spiHandle->Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; - spiHandle->Init.CRCPolynomial = 7; - spiHandle->Init.CRCLength = SPI_CRC_LENGTH_8BIT; - spiHandle->Init.NSS = SPI_NSS_SOFT; - spiHandle->Init.NSSPMode = SPI_NSS_PULSE_DISABLE; - // Recommended setting to avoid glitches - spiHandle->Init.MasterKeepIOState = SPI_MASTER_KEEP_IO_STATE_ENABLE; - spiHandle->Init.Mode = SPI_MODE_MASTER; - if(HAL_SPI_Init(spiHandle) != HAL_OK) { - sif::printWarning("Error initializing SPI\n"); - return HasReturnvaluesIF::RETURN_FAILED; + // Configure the SPI peripheral + spiHandle->Instance = SPI1; + spiHandle->Init.BaudRatePrescaler = spi::getPrescaler(HAL_RCC_GetHCLKFreq(), 3900000); + spiHandle->Init.Direction = SPI_DIRECTION_2LINES; + spi::assignSpiMode(spi::SpiModes::MODE_3, *spiHandle); + spiHandle->Init.DataSize = SPI_DATASIZE_8BIT; + spiHandle->Init.FirstBit = SPI_FIRSTBIT_MSB; + spiHandle->Init.TIMode = SPI_TIMODE_DISABLE; + spiHandle->Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; + spiHandle->Init.CRCPolynomial = 7; + spiHandle->Init.CRCLength = SPI_CRC_LENGTH_8BIT; + spiHandle->Init.NSS = SPI_NSS_SOFT; + spiHandle->Init.NSSPMode = SPI_NSS_PULSE_DISABLE; + // Recommended setting to avoid glitches + spiHandle->Init.MasterKeepIOState = SPI_MASTER_KEEP_IO_STATE_ENABLE; + spiHandle->Init.Mode = SPI_MODE_MASTER; + if (HAL_SPI_Init(spiHandle) != HAL_OK) { + sif::printWarning("Error initializing SPI\n"); + return HasReturnvaluesIF::RETURN_FAILED; + } + + delete mspCfg; + transferState = TransferStates::WAIT; + + sif::printInfo("GyroL3GD20H::performOperation: Reading WHO AM I register\n"); + + txBuffer[0] = WHO_AM_I_REG | STM_READ_MASK; + txBuffer[1] = 0; + + switch (transferMode) { + case (spi::TransferModes::DMA): { + return handleDmaTransferInit(); } - - delete mspCfg; - transferState = TransferStates::WAIT; - - sif::printInfo("GyroL3GD20H::performOperation: Reading WHO AM I register\n"); - - txBuffer[0] = WHO_AM_I_REG | STM_READ_MASK; - txBuffer[1] = 0; - - switch(transferMode) { - case(spi::TransferModes::DMA): { - return handleDmaTransferInit(); + case (spi::TransferModes::INTERRUPT): { + return handleInterruptTransferInit(); } - case(spi::TransferModes::INTERRUPT): { - return handleInterruptTransferInit(); - } - case(spi::TransferModes::POLLING): { - return handlePollingTransferInit(); + case (spi::TransferModes::POLLING): { + return handlePollingTransferInit(); } default: { - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; } + } - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t GyroL3GD20H::performOperation() { - switch(transferMode) { - case(spi::TransferModes::DMA): { - return handleDmaSensorRead(); + switch (transferMode) { + case (spi::TransferModes::DMA): { + return handleDmaSensorRead(); } - case(spi::TransferModes::POLLING): { - return handlePollingSensorRead(); + case (spi::TransferModes::POLLING): { + return handlePollingSensorRead(); } - case(spi::TransferModes::INTERRUPT): { - return handleInterruptSensorRead(); + case (spi::TransferModes::INTERRUPT): { + return handleInterruptSensorRead(); } default: { - return HasReturnvaluesIF::RETURN_FAILED; + return HasReturnvaluesIF::RETURN_FAILED; } - } - return HasReturnvaluesIF::RETURN_OK; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t GyroL3GD20H::handleDmaTransferInit() { - /* Clean D-cache */ - /* Make sure the address is 32-byte aligned and add 32-bytes to length, - in case it overlaps cacheline */ - // See https://community.st.com/s/article/FAQ-DMA-is-not-working-on-STM32H7-devices - HAL_StatusTypeDef result = performDmaTransfer(2); - if(result != HAL_OK) { - // Transfer error in transmission process - sif::printWarning("GyroL3GD20H::initialize: Error transmitting SPI with DMA\n"); - } + /* Clean D-cache */ + /* Make sure the address is 32-byte aligned and add 32-bytes to length, + in case it overlaps cacheline */ + // See https://community.st.com/s/article/FAQ-DMA-is-not-working-on-STM32H7-devices + HAL_StatusTypeDef result = performDmaTransfer(2); + if (result != HAL_OK) { + // Transfer error in transmission process + sif::printWarning("GyroL3GD20H::initialize: Error transmitting SPI with DMA\n"); + } - // Wait for the transfer to complete - while (transferState == TransferStates::WAIT) { - TaskFactory::delayTask(1); - } + // Wait for the transfer to complete + while (transferState == TransferStates::WAIT) { + TaskFactory::delayTask(1); + } - switch(transferState) { - case(TransferStates::SUCCESS): { - uint8_t whoAmIVal = rxBuffer[1]; - if(whoAmIVal != EXPECTED_WHO_AM_I_VAL) { - sif::printDebug("GyroL3GD20H::initialize: " - "Read WHO AM I value %d not equal to expected value!\n", whoAmIVal); - } - transferState = TransferStates::IDLE; - break; + switch (transferState) { + case (TransferStates::SUCCESS): { + uint8_t whoAmIVal = rxBuffer[1]; + if (whoAmIVal != EXPECTED_WHO_AM_I_VAL) { + sif::printDebug( + "GyroL3GD20H::initialize: " + "Read WHO AM I value %d not equal to expected value!\n", + whoAmIVal); + } + transferState = TransferStates::IDLE; + break; } - case(TransferStates::FAILURE): { - sif::printWarning("Transfer failure\n"); - transferState = TransferStates::FAILURE; - return HasReturnvaluesIF::RETURN_FAILED; + case (TransferStates::FAILURE): { + sif::printWarning("Transfer failure\n"); + transferState = TransferStates::FAILURE; + return HasReturnvaluesIF::RETURN_FAILED; } default: { - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; } + } - sif::printInfo("GyroL3GD20H::initialize: Configuring device\n"); - // Configure the 5 configuration registers - uint8_t configRegs[5]; - prepareConfigRegs(configRegs); + sif::printInfo("GyroL3GD20H::initialize: Configuring device\n"); + // Configure the 5 configuration registers + uint8_t configRegs[5]; + prepareConfigRegs(configRegs); - result = performDmaTransfer(6); - if(result != HAL_OK) { - // Transfer error in transmission process - sif::printWarning("Error transmitting SPI with DMA\n"); - } + result = performDmaTransfer(6); + if (result != HAL_OK) { + // Transfer error in transmission process + sif::printWarning("Error transmitting SPI with DMA\n"); + } - // Wait for the transfer to complete - while (transferState == TransferStates::WAIT) { - TaskFactory::delayTask(1); - } + // Wait for the transfer to complete + while (transferState == TransferStates::WAIT) { + TaskFactory::delayTask(1); + } - switch(transferState) { - case(TransferStates::SUCCESS): { - sif::printInfo("GyroL3GD20H::initialize: Configuration transfer success\n"); - transferState = TransferStates::IDLE; - break; + switch (transferState) { + case (TransferStates::SUCCESS): { + sif::printInfo("GyroL3GD20H::initialize: Configuration transfer success\n"); + transferState = TransferStates::IDLE; + break; } - case(TransferStates::FAILURE): { - sif::printWarning("GyroL3GD20H::initialize: Configuration transfer failure\n"); - transferState = TransferStates::FAILURE; - return HasReturnvaluesIF::RETURN_FAILED; + case (TransferStates::FAILURE): { + sif::printWarning("GyroL3GD20H::initialize: Configuration transfer failure\n"); + transferState = TransferStates::FAILURE; + return HasReturnvaluesIF::RETURN_FAILED; } default: { - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; } + } + txBuffer[0] = CTRL_REG_1 | STM_AUTO_INCREMENT_MASK | STM_READ_MASK; + std::memset(txBuffer.data() + 1, 0, 5); + result = performDmaTransfer(6); + if (result != HAL_OK) { + // Transfer error in transmission process + sif::printWarning("Error transmitting SPI with DMA\n"); + } + // Wait for the transfer to complete + while (transferState == TransferStates::WAIT) { + TaskFactory::delayTask(1); + } - txBuffer[0] = CTRL_REG_1 | STM_AUTO_INCREMENT_MASK | STM_READ_MASK; - std::memset(txBuffer.data() + 1, 0 , 5); - result = performDmaTransfer(6); - if(result != HAL_OK) { - // Transfer error in transmission process - sif::printWarning("Error transmitting SPI with DMA\n"); + switch (transferState) { + case (TransferStates::SUCCESS): { + if (rxBuffer[1] != configRegs[0] or rxBuffer[2] != configRegs[1] or + rxBuffer[3] != configRegs[2] or rxBuffer[4] != configRegs[3] or + rxBuffer[5] != configRegs[4]) { + sif::printWarning("GyroL3GD20H::initialize: Configuration failure\n"); + } else { + sif::printInfo("GyroL3GD20H::initialize: Configuration success\n"); + } + transferState = TransferStates::IDLE; + break; } - // Wait for the transfer to complete - while (transferState == TransferStates::WAIT) { - TaskFactory::delayTask(1); - } - - switch(transferState) { - case(TransferStates::SUCCESS): { - if(rxBuffer[1] != configRegs[0] or rxBuffer[2] != configRegs[1] or - rxBuffer[3] != configRegs[2] or rxBuffer[4] != configRegs[3] or - rxBuffer[5] != configRegs[4]) { - sif::printWarning("GyroL3GD20H::initialize: Configuration failure\n"); - } - else { - sif::printInfo("GyroL3GD20H::initialize: Configuration success\n"); - } - transferState = TransferStates::IDLE; - break; - } - case(TransferStates::FAILURE): { - sif::printWarning("GyroL3GD20H::initialize: Configuration transfer failure\n"); - transferState = TransferStates::FAILURE; - return HasReturnvaluesIF::RETURN_FAILED; + case (TransferStates::FAILURE): { + sif::printWarning("GyroL3GD20H::initialize: Configuration transfer failure\n"); + transferState = TransferStates::FAILURE; + return HasReturnvaluesIF::RETURN_FAILED; } default: { - return HasReturnvaluesIF::RETURN_FAILED; + return HasReturnvaluesIF::RETURN_FAILED; } - } - return HasReturnvaluesIF::RETURN_OK; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t GyroL3GD20H::handleDmaSensorRead() { - txBuffer[0] = CTRL_REG_1 | STM_AUTO_INCREMENT_MASK | STM_READ_MASK; - std::memset(txBuffer.data() + 1, 0 , 14); + txBuffer[0] = CTRL_REG_1 | STM_AUTO_INCREMENT_MASK | STM_READ_MASK; + std::memset(txBuffer.data() + 1, 0, 14); - HAL_StatusTypeDef result = performDmaTransfer(15); - if(result != HAL_OK) { - // Transfer error in transmission process - sif::printDebug("GyroL3GD20H::handleDmaSensorRead: Error transmitting SPI with DMA\n"); - } - // Wait for the transfer to complete - while (transferState == TransferStates::WAIT) { - TaskFactory::delayTask(1); - } + HAL_StatusTypeDef result = performDmaTransfer(15); + if (result != HAL_OK) { + // Transfer error in transmission process + sif::printDebug("GyroL3GD20H::handleDmaSensorRead: Error transmitting SPI with DMA\n"); + } + // Wait for the transfer to complete + while (transferState == TransferStates::WAIT) { + TaskFactory::delayTask(1); + } - switch(transferState) { - case(TransferStates::SUCCESS): { - handleSensorReadout(); - break; + switch (transferState) { + case (TransferStates::SUCCESS): { + handleSensorReadout(); + break; } - case(TransferStates::FAILURE): { - sif::printWarning("GyroL3GD20H::handleDmaSensorRead: Sensor read failure\n"); - transferState = TransferStates::FAILURE; - return HasReturnvaluesIF::RETURN_FAILED; + case (TransferStates::FAILURE): { + sif::printWarning("GyroL3GD20H::handleDmaSensorRead: Sensor read failure\n"); + transferState = TransferStates::FAILURE; + return HasReturnvaluesIF::RETURN_FAILED; } default: { - return HasReturnvaluesIF::RETURN_FAILED; + return HasReturnvaluesIF::RETURN_FAILED; } - } - return HasReturnvaluesIF::RETURN_OK; + } + return HasReturnvaluesIF::RETURN_OK; } HAL_StatusTypeDef GyroL3GD20H::performDmaTransfer(size_t sendSize) { - transferState = TransferStates::WAIT; + transferState = TransferStates::WAIT; #if STM_USE_PERIPHERAL_TX_BUFFER_MPU_PROTECTION == 0 - SCB_CleanDCache_by_Addr((uint32_t*)(((uint32_t)txBuffer.data()) & ~(uint32_t)0x1F), - txBuffer.size()+32); + SCB_CleanDCache_by_Addr((uint32_t *)(((uint32_t)txBuffer.data()) & ~(uint32_t)0x1F), + txBuffer.size() + 32); #endif - // Start SPI transfer via DMA - HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_RESET); - return HAL_SPI_TransmitReceive_DMA(spiHandle, txBuffer.data(), rxBuffer.data(), sendSize); + // Start SPI transfer via DMA + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_RESET); + return HAL_SPI_TransmitReceive_DMA(spiHandle, txBuffer.data(), rxBuffer.data(), sendSize); } ReturnValue_t GyroL3GD20H::handlePollingTransferInit() { - HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_RESET); - auto result = HAL_SPI_TransmitReceive(spiHandle, txBuffer.data(), rxBuffer.data(), 2, 1000); - HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_SET); - switch(result) { - case(HAL_OK): { - sif::printInfo("GyroL3GD20H::initialize: Polling transfer success\n"); - uint8_t whoAmIVal = rxBuffer[1]; - if(whoAmIVal != EXPECTED_WHO_AM_I_VAL) { - sif::printDebug("GyroL3GD20H::performOperation: " - "Read WHO AM I value %d not equal to expected value!\n", whoAmIVal); - } - break; + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_RESET); + auto result = HAL_SPI_TransmitReceive(spiHandle, txBuffer.data(), rxBuffer.data(), 2, 1000); + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_SET); + switch (result) { + case (HAL_OK): { + sif::printInfo("GyroL3GD20H::initialize: Polling transfer success\n"); + uint8_t whoAmIVal = rxBuffer[1]; + if (whoAmIVal != EXPECTED_WHO_AM_I_VAL) { + sif::printDebug( + "GyroL3GD20H::performOperation: " + "Read WHO AM I value %d not equal to expected value!\n", + whoAmIVal); + } + break; } - case(HAL_TIMEOUT): { - sif::printDebug("GyroL3GD20H::initialize: Polling transfer timeout\n"); - return HasReturnvaluesIF::RETURN_FAILED; + case (HAL_TIMEOUT): { + sif::printDebug("GyroL3GD20H::initialize: Polling transfer timeout\n"); + return HasReturnvaluesIF::RETURN_FAILED; } - case(HAL_ERROR): { - sif::printDebug("GyroL3GD20H::initialize: Polling transfer failure\n"); - return HasReturnvaluesIF::RETURN_FAILED; + case (HAL_ERROR): { + sif::printDebug("GyroL3GD20H::initialize: Polling transfer failure\n"); + return HasReturnvaluesIF::RETURN_FAILED; } default: { - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; } + } - sif::printInfo("GyroL3GD20H::initialize: Configuring device\n"); - // Configure the 5 configuration registers - uint8_t configRegs[5]; - prepareConfigRegs(configRegs); + sif::printInfo("GyroL3GD20H::initialize: Configuring device\n"); + // Configure the 5 configuration registers + uint8_t configRegs[5]; + prepareConfigRegs(configRegs); - HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_RESET); - result = HAL_SPI_TransmitReceive(spiHandle, txBuffer.data(), rxBuffer.data(), 6, 1000); - HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_SET); - switch(result) { - case(HAL_OK): { - break; + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_RESET); + result = HAL_SPI_TransmitReceive(spiHandle, txBuffer.data(), rxBuffer.data(), 6, 1000); + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_SET); + switch (result) { + case (HAL_OK): { + break; } - case(HAL_TIMEOUT): { - sif::printDebug("GyroL3GD20H::initialize: Polling transfer timeout\n"); - return HasReturnvaluesIF::RETURN_FAILED; + case (HAL_TIMEOUT): { + sif::printDebug("GyroL3GD20H::initialize: Polling transfer timeout\n"); + return HasReturnvaluesIF::RETURN_FAILED; } - case(HAL_ERROR): { - sif::printDebug("GyroL3GD20H::initialize: Polling transfer failure\n"); - return HasReturnvaluesIF::RETURN_FAILED; + case (HAL_ERROR): { + sif::printDebug("GyroL3GD20H::initialize: Polling transfer failure\n"); + return HasReturnvaluesIF::RETURN_FAILED; } default: { - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; } + } - txBuffer[0] = CTRL_REG_1 | STM_AUTO_INCREMENT_MASK | STM_READ_MASK; - std::memset(txBuffer.data() + 1, 0 , 5); + txBuffer[0] = CTRL_REG_1 | STM_AUTO_INCREMENT_MASK | STM_READ_MASK; + std::memset(txBuffer.data() + 1, 0, 5); - HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_RESET); - result = HAL_SPI_TransmitReceive(spiHandle, txBuffer.data(), rxBuffer.data(), 6, 1000); - HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_SET); - switch(result) { - case(HAL_OK): { - if(rxBuffer[1] != configRegs[0] or rxBuffer[2] != configRegs[1] or - rxBuffer[3] != configRegs[2] or rxBuffer[4] != configRegs[3] or - rxBuffer[5] != configRegs[4]) { - sif::printWarning("GyroL3GD20H::initialize: Configuration failure\n"); - } - else { - sif::printInfo("GyroL3GD20H::initialize: Configuration success\n"); - } - break; + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_RESET); + result = HAL_SPI_TransmitReceive(spiHandle, txBuffer.data(), rxBuffer.data(), 6, 1000); + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_SET); + switch (result) { + case (HAL_OK): { + if (rxBuffer[1] != configRegs[0] or rxBuffer[2] != configRegs[1] or + rxBuffer[3] != configRegs[2] or rxBuffer[4] != configRegs[3] or + rxBuffer[5] != configRegs[4]) { + sif::printWarning("GyroL3GD20H::initialize: Configuration failure\n"); + } else { + sif::printInfo("GyroL3GD20H::initialize: Configuration success\n"); + } + break; } - case(HAL_TIMEOUT): { - sif::printDebug("GyroL3GD20H::initialize: Polling transfer timeout\n"); - return HasReturnvaluesIF::RETURN_FAILED; + case (HAL_TIMEOUT): { + sif::printDebug("GyroL3GD20H::initialize: Polling transfer timeout\n"); + return HasReturnvaluesIF::RETURN_FAILED; } - case(HAL_ERROR): { - sif::printDebug("GyroL3GD20H::initialize: Polling transfer failure\n"); - return HasReturnvaluesIF::RETURN_FAILED; + case (HAL_ERROR): { + sif::printDebug("GyroL3GD20H::initialize: Polling transfer failure\n"); + return HasReturnvaluesIF::RETURN_FAILED; } default: { - return HasReturnvaluesIF::RETURN_FAILED; + return HasReturnvaluesIF::RETURN_FAILED; } - } - return HasReturnvaluesIF::RETURN_OK; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t GyroL3GD20H::handlePollingSensorRead() { - txBuffer[0] = CTRL_REG_1 | STM_AUTO_INCREMENT_MASK | STM_READ_MASK; - std::memset(txBuffer.data() + 1, 0 , 14); - HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_RESET); - auto result = HAL_SPI_TransmitReceive(spiHandle, txBuffer.data(), rxBuffer.data(), 15, 1000); - HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_SET); + txBuffer[0] = CTRL_REG_1 | STM_AUTO_INCREMENT_MASK | STM_READ_MASK; + std::memset(txBuffer.data() + 1, 0, 14); + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_RESET); + auto result = HAL_SPI_TransmitReceive(spiHandle, txBuffer.data(), rxBuffer.data(), 15, 1000); + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_SET); - switch(result) { - case(HAL_OK): { - handleSensorReadout(); - break; + switch (result) { + case (HAL_OK): { + handleSensorReadout(); + break; } - case(HAL_TIMEOUT): { - sif::printDebug("GyroL3GD20H::initialize: Polling transfer timeout\n"); - return HasReturnvaluesIF::RETURN_FAILED; + case (HAL_TIMEOUT): { + sif::printDebug("GyroL3GD20H::initialize: Polling transfer timeout\n"); + return HasReturnvaluesIF::RETURN_FAILED; } - case(HAL_ERROR): { - sif::printDebug("GyroL3GD20H::initialize: Polling transfer failure\n"); - return HasReturnvaluesIF::RETURN_FAILED; + case (HAL_ERROR): { + sif::printDebug("GyroL3GD20H::initialize: Polling transfer failure\n"); + return HasReturnvaluesIF::RETURN_FAILED; } default: { - return HasReturnvaluesIF::RETURN_FAILED; + return HasReturnvaluesIF::RETURN_FAILED; } - } - return HasReturnvaluesIF::RETURN_OK; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t GyroL3GD20H::handleInterruptTransferInit() { - HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_RESET); - switch(HAL_SPI_TransmitReceive_IT(spiHandle, txBuffer.data(), rxBuffer.data(), 2)) { - case(HAL_OK): { - sif::printInfo("GyroL3GD20H::initialize: Interrupt transfer success\n"); - // Wait for the transfer to complete - while (transferState == TransferStates::WAIT) { - TaskFactory::delayTask(1); - } + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_RESET); + switch (HAL_SPI_TransmitReceive_IT(spiHandle, txBuffer.data(), rxBuffer.data(), 2)) { + case (HAL_OK): { + sif::printInfo("GyroL3GD20H::initialize: Interrupt transfer success\n"); + // Wait for the transfer to complete + while (transferState == TransferStates::WAIT) { + TaskFactory::delayTask(1); + } - uint8_t whoAmIVal = rxBuffer[1]; - if(whoAmIVal != EXPECTED_WHO_AM_I_VAL) { - sif::printDebug("GyroL3GD20H::initialize: " - "Read WHO AM I value %d not equal to expected value!\n", whoAmIVal); - } - break; - } - case(HAL_BUSY): - case(HAL_ERROR): - case(HAL_TIMEOUT): { - sif::printDebug("GyroL3GD20H::initialize: Initialization failure using interrupts\n"); - return HasReturnvaluesIF::RETURN_FAILED; + uint8_t whoAmIVal = rxBuffer[1]; + if (whoAmIVal != EXPECTED_WHO_AM_I_VAL) { + sif::printDebug( + "GyroL3GD20H::initialize: " + "Read WHO AM I value %d not equal to expected value!\n", + whoAmIVal); + } + break; } + case (HAL_BUSY): + case (HAL_ERROR): + case (HAL_TIMEOUT): { + sif::printDebug("GyroL3GD20H::initialize: Initialization failure using interrupts\n"); + return HasReturnvaluesIF::RETURN_FAILED; } + } - sif::printInfo("GyroL3GD20H::initialize: Configuring device\n"); - transferState = TransferStates::WAIT; - // Configure the 5 configuration registers - uint8_t configRegs[5]; - prepareConfigRegs(configRegs); - HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_RESET); - switch(HAL_SPI_TransmitReceive_IT(spiHandle, txBuffer.data(), rxBuffer.data(), 6)) { - case(HAL_OK): { - // Wait for the transfer to complete - while (transferState == TransferStates::WAIT) { - TaskFactory::delayTask(1); - } - break; - } - case(HAL_BUSY): - case(HAL_ERROR): - case(HAL_TIMEOUT): { - sif::printDebug("GyroL3GD20H::initialize: Initialization failure using interrupts\n"); - return HasReturnvaluesIF::RETURN_FAILED; + sif::printInfo("GyroL3GD20H::initialize: Configuring device\n"); + transferState = TransferStates::WAIT; + // Configure the 5 configuration registers + uint8_t configRegs[5]; + prepareConfigRegs(configRegs); + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_RESET); + switch (HAL_SPI_TransmitReceive_IT(spiHandle, txBuffer.data(), rxBuffer.data(), 6)) { + case (HAL_OK): { + // Wait for the transfer to complete + while (transferState == TransferStates::WAIT) { + TaskFactory::delayTask(1); + } + break; } + case (HAL_BUSY): + case (HAL_ERROR): + case (HAL_TIMEOUT): { + sif::printDebug("GyroL3GD20H::initialize: Initialization failure using interrupts\n"); + return HasReturnvaluesIF::RETURN_FAILED; } + } - txBuffer[0] = CTRL_REG_1 | STM_AUTO_INCREMENT_MASK | STM_READ_MASK; - std::memset(txBuffer.data() + 1, 0 , 5); - transferState = TransferStates::WAIT; - HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_RESET); - switch(HAL_SPI_TransmitReceive_IT(spiHandle, txBuffer.data(), rxBuffer.data(), 6)) { - case(HAL_OK): { - // Wait for the transfer to complete - while (transferState == TransferStates::WAIT) { - TaskFactory::delayTask(1); - } - if(rxBuffer[1] != configRegs[0] or rxBuffer[2] != configRegs[1] or - rxBuffer[3] != configRegs[2] or rxBuffer[4] != configRegs[3] or - rxBuffer[5] != configRegs[4]) { - sif::printWarning("GyroL3GD20H::initialize: Configuration failure\n"); - } - else { - sif::printInfo("GyroL3GD20H::initialize: Configuration success\n"); - } - break; + txBuffer[0] = CTRL_REG_1 | STM_AUTO_INCREMENT_MASK | STM_READ_MASK; + std::memset(txBuffer.data() + 1, 0, 5); + transferState = TransferStates::WAIT; + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_RESET); + switch (HAL_SPI_TransmitReceive_IT(spiHandle, txBuffer.data(), rxBuffer.data(), 6)) { + case (HAL_OK): { + // Wait for the transfer to complete + while (transferState == TransferStates::WAIT) { + TaskFactory::delayTask(1); + } + if (rxBuffer[1] != configRegs[0] or rxBuffer[2] != configRegs[1] or + rxBuffer[3] != configRegs[2] or rxBuffer[4] != configRegs[3] or + rxBuffer[5] != configRegs[4]) { + sif::printWarning("GyroL3GD20H::initialize: Configuration failure\n"); + } else { + sif::printInfo("GyroL3GD20H::initialize: Configuration success\n"); + } + break; } - case(HAL_BUSY): - case(HAL_ERROR): - case(HAL_TIMEOUT): { - sif::printDebug("GyroL3GD20H::initialize: Initialization failure using interrupts\n"); - return HasReturnvaluesIF::RETURN_FAILED; + case (HAL_BUSY): + case (HAL_ERROR): + case (HAL_TIMEOUT): { + sif::printDebug("GyroL3GD20H::initialize: Initialization failure using interrupts\n"); + return HasReturnvaluesIF::RETURN_FAILED; } - } - return HasReturnvaluesIF::RETURN_OK; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t GyroL3GD20H::handleInterruptSensorRead() { - transferState = TransferStates::WAIT; - txBuffer[0] = CTRL_REG_1 | STM_AUTO_INCREMENT_MASK | STM_READ_MASK; - std::memset(txBuffer.data() + 1, 0 , 14); - HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_RESET); - switch(HAL_SPI_TransmitReceive_IT(spiHandle, txBuffer.data(), rxBuffer.data(), 15)) { - case(HAL_OK): { - // Wait for the transfer to complete - while (transferState == TransferStates::WAIT) { - TaskFactory::delayTask(1); - } - handleSensorReadout(); - break; + transferState = TransferStates::WAIT; + txBuffer[0] = CTRL_REG_1 | STM_AUTO_INCREMENT_MASK | STM_READ_MASK; + std::memset(txBuffer.data() + 1, 0, 14); + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_RESET); + switch (HAL_SPI_TransmitReceive_IT(spiHandle, txBuffer.data(), rxBuffer.data(), 15)) { + case (HAL_OK): { + // Wait for the transfer to complete + while (transferState == TransferStates::WAIT) { + TaskFactory::delayTask(1); + } + handleSensorReadout(); + break; } - case(HAL_BUSY): - case(HAL_ERROR): - case(HAL_TIMEOUT): { - sif::printDebug("GyroL3GD20H::initialize: Sensor read failure using interrupts\n"); - return HasReturnvaluesIF::RETURN_FAILED; + case (HAL_BUSY): + case (HAL_ERROR): + case (HAL_TIMEOUT): { + sif::printDebug("GyroL3GD20H::initialize: Sensor read failure using interrupts\n"); + return HasReturnvaluesIF::RETURN_FAILED; } - } - return HasReturnvaluesIF::RETURN_OK; + } + return HasReturnvaluesIF::RETURN_OK; } -void GyroL3GD20H::prepareConfigRegs(uint8_t* configRegs) { - // Enable sensor - configRegs[0] = 0b00001111; - configRegs[1] = 0b00000000; - configRegs[2] = 0b00000000; - // Big endian select - configRegs[3] = 0b01000000; - configRegs[4] = 0b00000000; +void GyroL3GD20H::prepareConfigRegs(uint8_t *configRegs) { + // Enable sensor + configRegs[0] = 0b00001111; + configRegs[1] = 0b00000000; + configRegs[2] = 0b00000000; + // Big endian select + configRegs[3] = 0b01000000; + configRegs[4] = 0b00000000; - txBuffer[0] = CTRL_REG_1 | STM_AUTO_INCREMENT_MASK; - std::memcpy(txBuffer.data() + 1, configRegs, 5); + txBuffer[0] = CTRL_REG_1 | STM_AUTO_INCREMENT_MASK; + std::memcpy(txBuffer.data() + 1, configRegs, 5); } uint8_t GyroL3GD20H::readRegPolling(uint8_t reg) { - uint8_t rxBuf[2] = {}; - uint8_t txBuf[2] = {}; - txBuf[0] = reg | STM_READ_MASK; - HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_RESET); - auto result = HAL_SPI_TransmitReceive(spiHandle, txBuf, rxBuf, 2, 1000); - if(result) {}; - HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_SET); - return rxBuf[1]; + uint8_t rxBuf[2] = {}; + uint8_t txBuf[2] = {}; + txBuf[0] = reg | STM_READ_MASK; + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_RESET); + auto result = HAL_SPI_TransmitReceive(spiHandle, txBuf, rxBuf, 2, 1000); + if (result) { + }; + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_SET); + return rxBuf[1]; } void GyroL3GD20H::handleSensorReadout() { - uint8_t statusReg = rxBuffer[8]; - int16_t gyroXRaw = rxBuffer[9] << 8 | rxBuffer[10]; - float gyroX = static_cast(gyroXRaw) * 0.00875; - int16_t gyroYRaw = rxBuffer[11] << 8 | rxBuffer[12]; - float gyroY = static_cast(gyroYRaw) * 0.00875; - int16_t gyroZRaw = rxBuffer[13] << 8 | rxBuffer[14]; - float gyroZ = static_cast(gyroZRaw) * 0.00875; - sif::printInfo("Status register: 0b" BYTE_TO_BINARY_PATTERN "\n", BYTE_TO_BINARY(statusReg)); - sif::printInfo("Gyro X: %f\n", gyroX); - sif::printInfo("Gyro Y: %f\n", gyroY); - sif::printInfo("Gyro Z: %f\n", gyroZ); + uint8_t statusReg = rxBuffer[8]; + int16_t gyroXRaw = rxBuffer[9] << 8 | rxBuffer[10]; + float gyroX = static_cast(gyroXRaw) * 0.00875; + int16_t gyroYRaw = rxBuffer[11] << 8 | rxBuffer[12]; + float gyroY = static_cast(gyroYRaw) * 0.00875; + int16_t gyroZRaw = rxBuffer[13] << 8 | rxBuffer[14]; + float gyroZ = static_cast(gyroZRaw) * 0.00875; + sif::printInfo("Status register: 0b" BYTE_TO_BINARY_PATTERN "\n", BYTE_TO_BINARY(statusReg)); + sif::printInfo("Gyro X: %f\n", gyroX); + sif::printInfo("Gyro Y: %f\n", gyroY); + sif::printInfo("Gyro Z: %f\n", gyroZ); } - -void GyroL3GD20H::spiTransferCompleteCallback(SPI_HandleTypeDef *hspi, void* args) { - transferState = TransferStates::SUCCESS; - HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_SET); - if(GyroL3GD20H::transferMode == spi::TransferModes::DMA) { - // Invalidate cache prior to access by CPU - SCB_InvalidateDCache_by_Addr ((uint32_t *)GyroL3GD20H::rxBuffer.data(), - GyroL3GD20H::recvBufferSize); - } +void GyroL3GD20H::spiTransferCompleteCallback(SPI_HandleTypeDef *hspi, void *args) { + transferState = TransferStates::SUCCESS; + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_SET); + if (GyroL3GD20H::transferMode == spi::TransferModes::DMA) { + // Invalidate cache prior to access by CPU + SCB_InvalidateDCache_by_Addr((uint32_t *)GyroL3GD20H::rxBuffer.data(), + GyroL3GD20H::recvBufferSize); + } } /** @@ -553,6 +551,6 @@ void GyroL3GD20H::spiTransferCompleteCallback(SPI_HandleTypeDef *hspi, void* arg * add your own implementation. * @retval None */ -void GyroL3GD20H::spiTransferErrorCallback(SPI_HandleTypeDef *hspi, void* args) { - transferState = TransferStates::FAILURE; +void GyroL3GD20H::spiTransferErrorCallback(SPI_HandleTypeDef *hspi, void *args) { + transferState = TransferStates::FAILURE; } diff --git a/hal/src/fsfw_hal/stm32h7/devicetest/GyroL3GD20H.h b/hal/src/fsfw_hal/stm32h7/devicetest/GyroL3GD20H.h index b65654de..a6c3376a 100644 --- a/hal/src/fsfw_hal/stm32h7/devicetest/GyroL3GD20H.h +++ b/hal/src/fsfw_hal/stm32h7/devicetest/GyroL3GD20H.h @@ -1,70 +1,61 @@ #ifndef FSFW_HAL_STM32H7_DEVICETEST_GYRO_L3GD20H_H_ #define FSFW_HAL_STM32H7_DEVICETEST_GYRO_L3GD20H_H_ -#include "stm32h7xx_hal.h" -#include "stm32h7xx_hal_spi.h" +#include +#include + #include "../spi/mspInit.h" #include "../spi/spiDefinitions.h" - #include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "stm32h7xx_hal.h" +#include "stm32h7xx_hal_spi.h" -#include -#include - -enum class TransferStates { - IDLE, - WAIT, - SUCCESS, - FAILURE -}; +enum class TransferStates { IDLE, WAIT, SUCCESS, FAILURE }; class GyroL3GD20H { -public: - GyroL3GD20H(SPI_HandleTypeDef* spiHandle, spi::TransferModes transferMode); - ~GyroL3GD20H(); + public: + GyroL3GD20H(SPI_HandleTypeDef* spiHandle, spi::TransferModes transferMode); + ~GyroL3GD20H(); - ReturnValue_t initialize(); - ReturnValue_t performOperation(); + ReturnValue_t initialize(); + ReturnValue_t performOperation(); -private: + private: + const uint8_t WHO_AM_I_REG = 0b00001111; + const uint8_t STM_READ_MASK = 0b10000000; + const uint8_t STM_AUTO_INCREMENT_MASK = 0b01000000; + const uint8_t EXPECTED_WHO_AM_I_VAL = 0b11010111; + const uint8_t CTRL_REG_1 = 0b00100000; + const uint32_t L3G_RANGE = 245; - const uint8_t WHO_AM_I_REG = 0b00001111; - const uint8_t STM_READ_MASK = 0b10000000; - const uint8_t STM_AUTO_INCREMENT_MASK = 0b01000000; - const uint8_t EXPECTED_WHO_AM_I_VAL = 0b11010111; - const uint8_t CTRL_REG_1 = 0b00100000; - const uint32_t L3G_RANGE = 245; + SPI_HandleTypeDef* spiHandle; - SPI_HandleTypeDef* spiHandle; + static spi::TransferModes transferMode; + static constexpr size_t recvBufferSize = 32 * 10; + static std::array rxBuffer; + static constexpr size_t txBufferSize = 32; + static std::array txBuffer; - static spi::TransferModes transferMode; - static constexpr size_t recvBufferSize = 32 * 10; - static std::array rxBuffer; - static constexpr size_t txBufferSize = 32; - static std::array txBuffer; + ReturnValue_t handleDmaTransferInit(); + ReturnValue_t handlePollingTransferInit(); + ReturnValue_t handleInterruptTransferInit(); - ReturnValue_t handleDmaTransferInit(); - ReturnValue_t handlePollingTransferInit(); - ReturnValue_t handleInterruptTransferInit(); + ReturnValue_t handleDmaSensorRead(); + HAL_StatusTypeDef performDmaTransfer(size_t sendSize); + ReturnValue_t handlePollingSensorRead(); + ReturnValue_t handleInterruptSensorRead(); - ReturnValue_t handleDmaSensorRead(); - HAL_StatusTypeDef performDmaTransfer(size_t sendSize); - ReturnValue_t handlePollingSensorRead(); - ReturnValue_t handleInterruptSensorRead(); + uint8_t readRegPolling(uint8_t reg); - uint8_t readRegPolling(uint8_t reg); + static void spiTransferCompleteCallback(SPI_HandleTypeDef* hspi, void* args); + static void spiTransferErrorCallback(SPI_HandleTypeDef* hspi, void* args); - static void spiTransferCompleteCallback(SPI_HandleTypeDef *hspi, void* args); - static void spiTransferErrorCallback(SPI_HandleTypeDef *hspi, void* args); + void prepareConfigRegs(uint8_t* configRegs); + void handleSensorReadout(); - - void prepareConfigRegs(uint8_t* configRegs); - void handleSensorReadout(); - - - DMA_HandleTypeDef* txDmaHandle = {}; - DMA_HandleTypeDef* rxDmaHandle = {}; - spi::MspCfgBase* mspCfg = {}; + DMA_HandleTypeDef* txDmaHandle = {}; + DMA_HandleTypeDef* rxDmaHandle = {}; + spi::MspCfgBase* mspCfg = {}; }; #endif /* FSFW_HAL_STM32H7_DEVICETEST_GYRO_L3GD20H_H_ */ diff --git a/hal/src/fsfw_hal/stm32h7/dma.cpp b/hal/src/fsfw_hal/stm32h7/dma.cpp index bedf4aa4..0e5ca272 100644 --- a/hal/src/fsfw_hal/stm32h7/dma.cpp +++ b/hal/src/fsfw_hal/stm32h7/dma.cpp @@ -1,7 +1,7 @@ #include -#include #include +#include user_handler_t DMA_1_USER_HANDLERS[8]; user_args_t DMA_1_USER_ARGS[8]; @@ -10,15 +10,14 @@ user_handler_t DMA_2_USER_HANDLERS[8]; user_args_t DMA_2_USER_ARGS[8]; void dma::assignDmaUserHandler(DMAIndexes dma_idx, DMAStreams stream_idx, - user_handler_t user_handler, user_args_t user_args) { - if(dma_idx == DMA_1) { - DMA_1_USER_HANDLERS[stream_idx] = user_handler; - DMA_1_USER_ARGS[stream_idx] = user_args; - } - else if(dma_idx == DMA_2) { - DMA_2_USER_HANDLERS[stream_idx] = user_handler; - DMA_2_USER_ARGS[stream_idx] = user_args; - } + user_handler_t user_handler, user_args_t user_args) { + if (dma_idx == DMA_1) { + DMA_1_USER_HANDLERS[stream_idx] = user_handler; + DMA_1_USER_ARGS[stream_idx] = user_args; + } else if (dma_idx == DMA_2) { + DMA_2_USER_HANDLERS[stream_idx] = user_handler; + DMA_2_USER_ARGS[stream_idx] = user_args; + } } // The interrupt handlers in the format required for the IRQ vector table @@ -26,59 +25,27 @@ void dma::assignDmaUserHandler(DMAIndexes dma_idx, DMAStreams stream_idx, /* Do not change these function names! They need to be exactly equal to the name of the functions defined in the startup_stm32h743xx.s files! */ -#define GENERIC_DMA_IRQ_HANDLER(DMA_IDX, STREAM_IDX) \ - if(DMA_##DMA_IDX##_USER_HANDLERS[STREAM_IDX] != NULL) { \ - DMA_##DMA_IDX##_USER_HANDLERS[STREAM_IDX](DMA_##DMA_IDX##_USER_ARGS[STREAM_IDX]); \ - return; \ - } \ - Default_Handler() \ +#define GENERIC_DMA_IRQ_HANDLER(DMA_IDX, STREAM_IDX) \ + if (DMA_##DMA_IDX##_USER_HANDLERS[STREAM_IDX] != NULL) { \ + DMA_##DMA_IDX##_USER_HANDLERS[STREAM_IDX](DMA_##DMA_IDX##_USER_ARGS[STREAM_IDX]); \ + return; \ + } \ + Default_Handler() -extern"C" void DMA1_Stream0_IRQHandler() { - GENERIC_DMA_IRQ_HANDLER(1, 0); -} -extern"C" void DMA1_Stream1_IRQHandler() { - GENERIC_DMA_IRQ_HANDLER(1, 1); -} -extern"C" void DMA1_Stream2_IRQHandler() { - GENERIC_DMA_IRQ_HANDLER(1, 2); -} -extern"C" void DMA1_Stream3_IRQHandler() { - GENERIC_DMA_IRQ_HANDLER(1, 3); -} -extern"C" void DMA1_Stream4_IRQHandler() { - GENERIC_DMA_IRQ_HANDLER(1, 4); -} -extern"C" void DMA1_Stream5_IRQHandler() { - GENERIC_DMA_IRQ_HANDLER(1, 5); -} -extern"C" void DMA1_Stream6_IRQHandler() { - GENERIC_DMA_IRQ_HANDLER(1, 6); -} -extern"C" void DMA1_Stream7_IRQHandler() { - GENERIC_DMA_IRQ_HANDLER(1, 7); -} +extern "C" void DMA1_Stream0_IRQHandler() { GENERIC_DMA_IRQ_HANDLER(1, 0); } +extern "C" void DMA1_Stream1_IRQHandler() { GENERIC_DMA_IRQ_HANDLER(1, 1); } +extern "C" void DMA1_Stream2_IRQHandler() { GENERIC_DMA_IRQ_HANDLER(1, 2); } +extern "C" void DMA1_Stream3_IRQHandler() { GENERIC_DMA_IRQ_HANDLER(1, 3); } +extern "C" void DMA1_Stream4_IRQHandler() { GENERIC_DMA_IRQ_HANDLER(1, 4); } +extern "C" void DMA1_Stream5_IRQHandler() { GENERIC_DMA_IRQ_HANDLER(1, 5); } +extern "C" void DMA1_Stream6_IRQHandler() { GENERIC_DMA_IRQ_HANDLER(1, 6); } +extern "C" void DMA1_Stream7_IRQHandler() { GENERIC_DMA_IRQ_HANDLER(1, 7); } -extern"C" void DMA2_Stream0_IRQHandler() { - GENERIC_DMA_IRQ_HANDLER(2, 0); -} -extern"C" void DMA2_Stream1_IRQHandler() { - GENERIC_DMA_IRQ_HANDLER(2, 1); -} -extern"C" void DMA2_Stream2_IRQHandler() { - GENERIC_DMA_IRQ_HANDLER(2, 2); -} -extern"C" void DMA2_Stream3_IRQHandler() { - GENERIC_DMA_IRQ_HANDLER(2, 3); -} -extern"C" void DMA2_Stream4_IRQHandler() { - GENERIC_DMA_IRQ_HANDLER(2, 4); -} -extern"C" void DMA2_Stream5_IRQHandler() { - GENERIC_DMA_IRQ_HANDLER(2, 5); -} -extern"C" void DMA2_Stream6_IRQHandler() { - GENERIC_DMA_IRQ_HANDLER(2, 6); -} -extern"C" void DMA2_Stream7_IRQHandler() { - GENERIC_DMA_IRQ_HANDLER(2, 7); -} +extern "C" void DMA2_Stream0_IRQHandler() { GENERIC_DMA_IRQ_HANDLER(2, 0); } +extern "C" void DMA2_Stream1_IRQHandler() { GENERIC_DMA_IRQ_HANDLER(2, 1); } +extern "C" void DMA2_Stream2_IRQHandler() { GENERIC_DMA_IRQ_HANDLER(2, 2); } +extern "C" void DMA2_Stream3_IRQHandler() { GENERIC_DMA_IRQ_HANDLER(2, 3); } +extern "C" void DMA2_Stream4_IRQHandler() { GENERIC_DMA_IRQ_HANDLER(2, 4); } +extern "C" void DMA2_Stream5_IRQHandler() { GENERIC_DMA_IRQ_HANDLER(2, 5); } +extern "C" void DMA2_Stream6_IRQHandler() { GENERIC_DMA_IRQ_HANDLER(2, 6); } +extern "C" void DMA2_Stream7_IRQHandler() { GENERIC_DMA_IRQ_HANDLER(2, 7); } diff --git a/hal/src/fsfw_hal/stm32h7/dma.h b/hal/src/fsfw_hal/stm32h7/dma.h index 779a64cb..cba2dd46 100644 --- a/hal/src/fsfw_hal/stm32h7/dma.h +++ b/hal/src/fsfw_hal/stm32h7/dma.h @@ -5,31 +5,26 @@ extern "C" { #endif -#include "interrupts.h" #include +#include "interrupts.h" + namespace dma { -enum DMAType { - TX = 0, - RX = 1 -}; +enum DMAType { TX = 0, RX = 1 }; -enum DMAIndexes: uint8_t { - DMA_1 = 1, - DMA_2 = 2 -}; +enum DMAIndexes : uint8_t { DMA_1 = 1, DMA_2 = 2 }; enum DMAStreams { - STREAM_0 = 0, - STREAM_1 = 1, - STREAM_2 = 2, - STREAM_3 = 3, - STREAM_4 = 4, - STREAM_5 = 5, - STREAM_6 = 6, - STREAM_7 = 7, -} ; + STREAM_0 = 0, + STREAM_1 = 1, + STREAM_2 = 2, + STREAM_3 = 3, + STREAM_4 = 4, + STREAM_5 = 5, + STREAM_6 = 6, + STREAM_7 = 7, +}; /** * Assign user interrupt handlers for DMA streams, allowing to pass an @@ -37,10 +32,10 @@ enum DMAStreams { * @param user_handler * @param user_args */ -void assignDmaUserHandler(DMAIndexes dma_idx, DMAStreams stream_idx, - user_handler_t user_handler, user_args_t user_args); +void assignDmaUserHandler(DMAIndexes dma_idx, DMAStreams stream_idx, user_handler_t user_handler, + user_args_t user_args); -} +} // namespace dma #ifdef __cplusplus } diff --git a/hal/src/fsfw_hal/stm32h7/gpio/gpio.cpp b/hal/src/fsfw_hal/stm32h7/gpio/gpio.cpp index 5a890d7f..28f5c44b 100644 --- a/hal/src/fsfw_hal/stm32h7/gpio/gpio.cpp +++ b/hal/src/fsfw_hal/stm32h7/gpio/gpio.cpp @@ -4,68 +4,68 @@ void gpio::initializeGpioClock(GPIO_TypeDef* gpioPort) { #ifdef GPIOA - if(gpioPort == GPIOA) { - __HAL_RCC_GPIOA_CLK_ENABLE(); - } + if (gpioPort == GPIOA) { + __HAL_RCC_GPIOA_CLK_ENABLE(); + } #endif #ifdef GPIOB - if(gpioPort == GPIOB) { - __HAL_RCC_GPIOB_CLK_ENABLE(); - } + if (gpioPort == GPIOB) { + __HAL_RCC_GPIOB_CLK_ENABLE(); + } #endif #ifdef GPIOC - if(gpioPort == GPIOC) { - __HAL_RCC_GPIOC_CLK_ENABLE(); - } + if (gpioPort == GPIOC) { + __HAL_RCC_GPIOC_CLK_ENABLE(); + } #endif #ifdef GPIOD - if(gpioPort == GPIOD) { - __HAL_RCC_GPIOD_CLK_ENABLE(); - } + if (gpioPort == GPIOD) { + __HAL_RCC_GPIOD_CLK_ENABLE(); + } #endif #ifdef GPIOE - if(gpioPort == GPIOE) { - __HAL_RCC_GPIOE_CLK_ENABLE(); - } + if (gpioPort == GPIOE) { + __HAL_RCC_GPIOE_CLK_ENABLE(); + } #endif #ifdef GPIOF - if(gpioPort == GPIOF) { - __HAL_RCC_GPIOF_CLK_ENABLE(); - } + if (gpioPort == GPIOF) { + __HAL_RCC_GPIOF_CLK_ENABLE(); + } #endif #ifdef GPIOG - if(gpioPort == GPIOG) { - __HAL_RCC_GPIOG_CLK_ENABLE(); - } + if (gpioPort == GPIOG) { + __HAL_RCC_GPIOG_CLK_ENABLE(); + } #endif #ifdef GPIOH - if(gpioPort == GPIOH) { - __HAL_RCC_GPIOH_CLK_ENABLE(); - } + if (gpioPort == GPIOH) { + __HAL_RCC_GPIOH_CLK_ENABLE(); + } #endif #ifdef GPIOI - if(gpioPort == GPIOI) { - __HAL_RCC_GPIOI_CLK_ENABLE(); - } + if (gpioPort == GPIOI) { + __HAL_RCC_GPIOI_CLK_ENABLE(); + } #endif #ifdef GPIOJ - if(gpioPort == GPIOJ) { - __HAL_RCC_GPIOJ_CLK_ENABLE(); - } + if (gpioPort == GPIOJ) { + __HAL_RCC_GPIOJ_CLK_ENABLE(); + } #endif #ifdef GPIOK - if(gpioPort == GPIOK) { - __HAL_RCC_GPIOK_CLK_ENABLE(); - } + if (gpioPort == GPIOK) { + __HAL_RCC_GPIOK_CLK_ENABLE(); + } #endif } diff --git a/hal/src/fsfw_hal/stm32h7/interrupts.h b/hal/src/fsfw_hal/stm32h7/interrupts.h index aef60bf7..e4a332f3 100644 --- a/hal/src/fsfw_hal/stm32h7/interrupts.h +++ b/hal/src/fsfw_hal/stm32h7/interrupts.h @@ -12,14 +12,10 @@ extern "C" { */ extern void Default_Handler(); -typedef void (*user_handler_t) (void*); +typedef void (*user_handler_t)(void*); typedef void* user_args_t; -enum IrqPriorities: uint8_t { - HIGHEST = 0, - HIGHEST_FREERTOS = 6, - LOWEST = 15 -}; +enum IrqPriorities : uint8_t { HIGHEST = 0, HIGHEST_FREERTOS = 6, LOWEST = 15 }; #ifdef __cplusplus } diff --git a/hal/src/fsfw_hal/stm32h7/spi/SpiComIF.cpp b/hal/src/fsfw_hal/stm32h7/spi/SpiComIF.cpp index 4c4f7744..49e4670d 100644 --- a/hal/src/fsfw_hal/stm32h7/spi/SpiComIF.cpp +++ b/hal/src/fsfw_hal/stm32h7/spi/SpiComIF.cpp @@ -1,11 +1,11 @@ #include "fsfw_hal/stm32h7/spi/SpiComIF.h" -#include "fsfw_hal/stm32h7/spi/SpiCookie.h" #include "fsfw/tasks/SemaphoreFactory.h" +#include "fsfw_hal/stm32h7/gpio/gpio.h" +#include "fsfw_hal/stm32h7/spi/SpiCookie.h" +#include "fsfw_hal/stm32h7/spi/mspInit.h" #include "fsfw_hal/stm32h7/spi/spiCore.h" #include "fsfw_hal/stm32h7/spi/spiInterrupts.h" -#include "fsfw_hal/stm32h7/spi/mspInit.h" -#include "fsfw_hal/stm32h7/gpio/gpio.h" // FreeRTOS required special Semaphore handling from an ISR. Therefore, we use the concrete // instance here, because RTEMS and FreeRTOS are the only relevant OSALs currently @@ -13,468 +13,462 @@ #if defined FSFW_OSAL_RTEMS #include "fsfw/osal/rtems/BinarySemaphore.h" #elif defined FSFW_OSAL_FREERTOS -#include "fsfw/osal/freertos/TaskManagement.h" #include "fsfw/osal/freertos/BinarySemaphore.h" +#include "fsfw/osal/freertos/TaskManagement.h" #endif #include "stm32h7xx_hal_gpio.h" -SpiComIF::SpiComIF(object_id_t objectId): SystemObject(objectId) { - void* irqArgsVoided = reinterpret_cast(&irqArgs); - spi::assignTransferRxTxCompleteCallback(&spiTransferCompleteCallback, irqArgsVoided); - spi::assignTransferRxCompleteCallback(&spiTransferRxCompleteCallback, irqArgsVoided); - spi::assignTransferTxCompleteCallback(&spiTransferTxCompleteCallback, irqArgsVoided); - spi::assignTransferErrorCallback(&spiTransferErrorCallback, irqArgsVoided); +SpiComIF::SpiComIF(object_id_t objectId) : SystemObject(objectId) { + void *irqArgsVoided = reinterpret_cast(&irqArgs); + spi::assignTransferRxTxCompleteCallback(&spiTransferCompleteCallback, irqArgsVoided); + spi::assignTransferRxCompleteCallback(&spiTransferRxCompleteCallback, irqArgsVoided); + spi::assignTransferTxCompleteCallback(&spiTransferTxCompleteCallback, irqArgsVoided); + spi::assignTransferErrorCallback(&spiTransferErrorCallback, irqArgsVoided); } void SpiComIF::configureCacheMaintenanceOnTxBuffer(bool enable) { - this->cacheMaintenanceOnTxBuffer = enable; + this->cacheMaintenanceOnTxBuffer = enable; } void SpiComIF::addDmaHandles(DMA_HandleTypeDef *txHandle, DMA_HandleTypeDef *rxHandle) { - spi::setDmaHandles(txHandle, rxHandle); + spi::setDmaHandles(txHandle, rxHandle); } -ReturnValue_t SpiComIF::initialize() { - return HasReturnvaluesIF::RETURN_OK; -} +ReturnValue_t SpiComIF::initialize() { return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t SpiComIF::initializeInterface(CookieIF *cookie) { - SpiCookie* spiCookie = dynamic_cast(cookie); - if(spiCookie == nullptr) { + SpiCookie *spiCookie = dynamic_cast(cookie); + if (spiCookie == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error < "SpiComIF::initializeInterface: Invalid cookie" << std::endl; + sif::error < "SpiComIF::initializeInterface: Invalid cookie" << std::endl; #else - sif::printError("SpiComIF::initializeInterface: Invalid cookie\n"); + sif::printError("SpiComIF::initializeInterface: Invalid cookie\n"); #endif - return NULLPOINTER; - } - auto transferMode = spiCookie->getTransferMode(); + return NULLPOINTER; + } + auto transferMode = spiCookie->getTransferMode(); - if(transferMode == spi::TransferModes::DMA) { - DMA_HandleTypeDef *txHandle = nullptr; - DMA_HandleTypeDef *rxHandle = nullptr; - spi::getDmaHandles(&txHandle, &rxHandle); - if(txHandle == nullptr or rxHandle == nullptr) { - sif::printError("SpiComIF::initialize: DMA handles not set!\n"); - return HasReturnvaluesIF::RETURN_FAILED; - } + if (transferMode == spi::TransferModes::DMA) { + DMA_HandleTypeDef *txHandle = nullptr; + DMA_HandleTypeDef *rxHandle = nullptr; + spi::getDmaHandles(&txHandle, &rxHandle); + if (txHandle == nullptr or rxHandle == nullptr) { + sif::printError("SpiComIF::initialize: DMA handles not set!\n"); + return HasReturnvaluesIF::RETURN_FAILED; } - // This semaphore ensures thread-safety for a given bus - spiSemaphore = dynamic_cast( - SemaphoreFactory::instance()->createBinarySemaphore()); - address_t spiAddress = spiCookie->getDeviceAddress(); + } + // This semaphore ensures thread-safety for a given bus + spiSemaphore = + dynamic_cast(SemaphoreFactory::instance()->createBinarySemaphore()); + address_t spiAddress = spiCookie->getDeviceAddress(); - auto iter = spiDeviceMap.find(spiAddress); - if(iter == spiDeviceMap.end()) { - size_t bufferSize = spiCookie->getMaxRecvSize(); - auto statusPair = spiDeviceMap.emplace(spiAddress, SpiInstance(bufferSize)); - if (not statusPair.second) { + auto iter = spiDeviceMap.find(spiAddress); + if (iter == spiDeviceMap.end()) { + size_t bufferSize = spiCookie->getMaxRecvSize(); + auto statusPair = spiDeviceMap.emplace(spiAddress, SpiInstance(bufferSize)); + if (not statusPair.second) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "SpiComIF::initializeInterface: Failed to insert device with address " << - spiAddress << "to SPI device map" << std::endl; + sif::error << "SpiComIF::initializeInterface: Failed to insert device with address " + << spiAddress << "to SPI device map" << std::endl; #else - sif::printError("SpiComIF::initializeInterface: Failed to insert device with address " - "%lu to SPI device map\n", static_cast(spiAddress)); + sif::printError( + "SpiComIF::initializeInterface: Failed to insert device with address " + "%lu to SPI device map\n", + static_cast(spiAddress)); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; } - auto gpioPin = spiCookie->getChipSelectGpioPin(); - auto gpioPort = spiCookie->getChipSelectGpioPort(); + } + auto gpioPin = spiCookie->getChipSelectGpioPin(); + auto gpioPort = spiCookie->getChipSelectGpioPort(); - SPI_HandleTypeDef& spiHandle = spiCookie->getSpiHandle(); + SPI_HandleTypeDef &spiHandle = spiCookie->getSpiHandle(); - auto spiIdx = spiCookie->getSpiIdx(); - if(spiIdx == spi::SpiBus::SPI_1) { + auto spiIdx = spiCookie->getSpiIdx(); + if (spiIdx == spi::SpiBus::SPI_1) { #ifdef SPI1 - spiHandle.Instance = SPI1; + spiHandle.Instance = SPI1; #endif - } - else if(spiIdx == spi::SpiBus::SPI_2) { + } else if (spiIdx == spi::SpiBus::SPI_2) { #ifdef SPI2 - spiHandle.Instance = SPI2; + spiHandle.Instance = SPI2; #endif - } - else { - printCfgError("SPI Bus Index"); - return HasReturnvaluesIF::RETURN_FAILED; - } + } else { + printCfgError("SPI Bus Index"); + return HasReturnvaluesIF::RETURN_FAILED; + } - auto mspCfg = spiCookie->getMspCfg(); + auto mspCfg = spiCookie->getMspCfg(); - if(transferMode == spi::TransferModes::POLLING) { - auto typedCfg = dynamic_cast(mspCfg); - if(typedCfg == nullptr) { - printCfgError("Polling MSP"); - return HasReturnvaluesIF::RETURN_FAILED; - } - spi::setSpiPollingMspFunctions(typedCfg); + if (transferMode == spi::TransferModes::POLLING) { + auto typedCfg = dynamic_cast(mspCfg); + if (typedCfg == nullptr) { + printCfgError("Polling MSP"); + return HasReturnvaluesIF::RETURN_FAILED; } - else if(transferMode == spi::TransferModes::INTERRUPT) { - auto typedCfg = dynamic_cast(mspCfg); - if(typedCfg == nullptr) { - printCfgError("IRQ MSP"); - return HasReturnvaluesIF::RETURN_FAILED; - } - spi::setSpiIrqMspFunctions(typedCfg); + spi::setSpiPollingMspFunctions(typedCfg); + } else if (transferMode == spi::TransferModes::INTERRUPT) { + auto typedCfg = dynamic_cast(mspCfg); + if (typedCfg == nullptr) { + printCfgError("IRQ MSP"); + return HasReturnvaluesIF::RETURN_FAILED; } - else if(transferMode == spi::TransferModes::DMA) { - auto typedCfg = dynamic_cast(mspCfg); - if(typedCfg == nullptr) { - printCfgError("DMA MSP"); - return HasReturnvaluesIF::RETURN_FAILED; - } - // Check DMA handles - DMA_HandleTypeDef* txHandle = nullptr; - DMA_HandleTypeDef* rxHandle = nullptr; - spi::getDmaHandles(&txHandle, &rxHandle); - if(txHandle == nullptr or rxHandle == nullptr) { - printCfgError("DMA Handle"); - return HasReturnvaluesIF::RETURN_FAILED; - } - spi::setSpiDmaMspFunctions(typedCfg); + spi::setSpiIrqMspFunctions(typedCfg); + } else if (transferMode == spi::TransferModes::DMA) { + auto typedCfg = dynamic_cast(mspCfg); + if (typedCfg == nullptr) { + printCfgError("DMA MSP"); + return HasReturnvaluesIF::RETURN_FAILED; } + // Check DMA handles + DMA_HandleTypeDef *txHandle = nullptr; + DMA_HandleTypeDef *rxHandle = nullptr; + spi::getDmaHandles(&txHandle, &rxHandle); + if (txHandle == nullptr or rxHandle == nullptr) { + printCfgError("DMA Handle"); + return HasReturnvaluesIF::RETURN_FAILED; + } + spi::setSpiDmaMspFunctions(typedCfg); + } - if(gpioPort != nullptr) { - gpio::initializeGpioClock(gpioPort); - GPIO_InitTypeDef chipSelect = {}; - chipSelect.Pin = gpioPin; - chipSelect.Mode = GPIO_MODE_OUTPUT_PP; - HAL_GPIO_Init(gpioPort, &chipSelect); - HAL_GPIO_WritePin(gpioPort, gpioPin, GPIO_PIN_SET); - } + if (gpioPort != nullptr) { + gpio::initializeGpioClock(gpioPort); + GPIO_InitTypeDef chipSelect = {}; + chipSelect.Pin = gpioPin; + chipSelect.Mode = GPIO_MODE_OUTPUT_PP; + HAL_GPIO_Init(gpioPort, &chipSelect); + HAL_GPIO_WritePin(gpioPort, gpioPin, GPIO_PIN_SET); + } - if(HAL_SPI_Init(&spiHandle) != HAL_OK) { - sif::printWarning("SpiComIF::initialize: Error initializing SPI\n"); - return HasReturnvaluesIF::RETURN_FAILED; - } - // The MSP configuration struct is not required anymore - spiCookie->deleteMspCfg(); + if (HAL_SPI_Init(&spiHandle) != HAL_OK) { + sif::printWarning("SpiComIF::initialize: Error initializing SPI\n"); + return HasReturnvaluesIF::RETURN_FAILED; + } + // The MSP configuration struct is not required anymore + spiCookie->deleteMspCfg(); - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t SpiComIF::sendMessage(CookieIF *cookie, const uint8_t *sendData, size_t sendLen) { - SpiCookie* spiCookie = dynamic_cast(cookie); - if(spiCookie == nullptr) { - return NULLPOINTER; - } + SpiCookie *spiCookie = dynamic_cast(cookie); + if (spiCookie == nullptr) { + return NULLPOINTER; + } - SPI_HandleTypeDef& spiHandle = spiCookie->getSpiHandle(); + SPI_HandleTypeDef &spiHandle = spiCookie->getSpiHandle(); - auto iter = spiDeviceMap.find(spiCookie->getDeviceAddress()); - if(iter == spiDeviceMap.end()) { - return HasReturnvaluesIF::RETURN_FAILED; - } - iter->second.currentTransferLen = sendLen; + auto iter = spiDeviceMap.find(spiCookie->getDeviceAddress()); + if (iter == spiDeviceMap.end()) { + return HasReturnvaluesIF::RETURN_FAILED; + } + iter->second.currentTransferLen = sendLen; - auto transferMode = spiCookie->getTransferMode(); - switch(spiCookie->getTransferState()) { - case(spi::TransferStates::IDLE): { - break; + auto transferMode = spiCookie->getTransferMode(); + switch (spiCookie->getTransferState()) { + case (spi::TransferStates::IDLE): { + break; } - case(spi::TransferStates::WAIT): - case(spi::TransferStates::FAILURE): - case(spi::TransferStates::SUCCESS): + case (spi::TransferStates::WAIT): + case (spi::TransferStates::FAILURE): + case (spi::TransferStates::SUCCESS): default: { - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; } + } - switch(transferMode) { - case(spi::TransferModes::POLLING): { - return handlePollingSendOperation(iter->second.replyBuffer.data(), spiHandle, *spiCookie, - sendData, sendLen); + switch (transferMode) { + case (spi::TransferModes::POLLING): { + return handlePollingSendOperation(iter->second.replyBuffer.data(), spiHandle, *spiCookie, + sendData, sendLen); } - case(spi::TransferModes::INTERRUPT): { - return handleInterruptSendOperation(iter->second.replyBuffer.data(), spiHandle, *spiCookie, - sendData, sendLen); + case (spi::TransferModes::INTERRUPT): { + return handleInterruptSendOperation(iter->second.replyBuffer.data(), spiHandle, *spiCookie, + sendData, sendLen); } - case(spi::TransferModes::DMA): { - return handleDmaSendOperation(iter->second.replyBuffer.data(), spiHandle, *spiCookie, - sendData, sendLen); + case (spi::TransferModes::DMA): { + return handleDmaSendOperation(iter->second.replyBuffer.data(), spiHandle, *spiCookie, + sendData, sendLen); } - } - return HasReturnvaluesIF::RETURN_OK; + } + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t SpiComIF::getSendSuccess(CookieIF *cookie) { - return HasReturnvaluesIF::RETURN_OK; -} +ReturnValue_t SpiComIF::getSendSuccess(CookieIF *cookie) { return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t SpiComIF::requestReceiveMessage(CookieIF *cookie, size_t requestLen) { - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t SpiComIF::readReceivedMessage(CookieIF *cookie, uint8_t **buffer, size_t *size) { - SpiCookie* spiCookie = dynamic_cast(cookie); - if(spiCookie == nullptr) { - return NULLPOINTER; + SpiCookie *spiCookie = dynamic_cast(cookie); + if (spiCookie == nullptr) { + return NULLPOINTER; + } + switch (spiCookie->getTransferState()) { + case (spi::TransferStates::SUCCESS): { + auto iter = spiDeviceMap.find(spiCookie->getDeviceAddress()); + if (iter == spiDeviceMap.end()) { + return HasReturnvaluesIF::RETURN_FAILED; + } + *buffer = iter->second.replyBuffer.data(); + *size = iter->second.currentTransferLen; + spiCookie->setTransferState(spi::TransferStates::IDLE); + break; } - switch(spiCookie->getTransferState()) { - case(spi::TransferStates::SUCCESS): { - auto iter = spiDeviceMap.find(spiCookie->getDeviceAddress()); - if(iter == spiDeviceMap.end()) { - return HasReturnvaluesIF::RETURN_FAILED; - } - *buffer = iter->second.replyBuffer.data(); - *size = iter->second.currentTransferLen; - spiCookie->setTransferState(spi::TransferStates::IDLE); - break; - } - case(spi::TransferStates::FAILURE): { + case (spi::TransferStates::FAILURE): { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "SpiComIF::readReceivedMessage: Transfer failure" << std::endl; + sif::warning << "SpiComIF::readReceivedMessage: Transfer failure" << std::endl; #else - sif::printWarning("SpiComIF::readReceivedMessage: Transfer failure\n"); + sif::printWarning("SpiComIF::readReceivedMessage: Transfer failure\n"); #endif #endif - spiCookie->setTransferState(spi::TransferStates::IDLE); - return HasReturnvaluesIF::RETURN_FAILED; + spiCookie->setTransferState(spi::TransferStates::IDLE); + return HasReturnvaluesIF::RETURN_FAILED; } - case(spi::TransferStates::WAIT): - case(spi::TransferStates::IDLE): { - break; + case (spi::TransferStates::WAIT): + case (spi::TransferStates::IDLE): { + break; } default: { - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; } + } - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } void SpiComIF::setDefaultPollingTimeout(dur_millis_t timeout) { - this->defaultPollingTimeout = timeout; + this->defaultPollingTimeout = timeout; } -ReturnValue_t SpiComIF::handlePollingSendOperation(uint8_t* recvPtr, SPI_HandleTypeDef& spiHandle, - SpiCookie& spiCookie, const uint8_t *sendData, size_t sendLen) { - auto gpioPort = spiCookie.getChipSelectGpioPort(); - auto gpioPin = spiCookie.getChipSelectGpioPin(); - auto returnval = spiSemaphore->acquire(timeoutType, timeoutMs); - if(returnval != HasReturnvaluesIF::RETURN_OK) { - return returnval; - } - spiCookie.setTransferState(spi::TransferStates::WAIT); - if(gpioPort != nullptr) { - HAL_GPIO_WritePin(gpioPort, gpioPin, GPIO_PIN_RESET); - } +ReturnValue_t SpiComIF::handlePollingSendOperation(uint8_t *recvPtr, SPI_HandleTypeDef &spiHandle, + SpiCookie &spiCookie, const uint8_t *sendData, + size_t sendLen) { + auto gpioPort = spiCookie.getChipSelectGpioPort(); + auto gpioPin = spiCookie.getChipSelectGpioPin(); + auto returnval = spiSemaphore->acquire(timeoutType, timeoutMs); + if (returnval != HasReturnvaluesIF::RETURN_OK) { + return returnval; + } + spiCookie.setTransferState(spi::TransferStates::WAIT); + if (gpioPort != nullptr) { + HAL_GPIO_WritePin(gpioPort, gpioPin, GPIO_PIN_RESET); + } - auto result = HAL_SPI_TransmitReceive(&spiHandle, const_cast(sendData), - recvPtr, sendLen, defaultPollingTimeout); - if(gpioPort != nullptr) { - HAL_GPIO_WritePin(gpioPort, gpioPin, GPIO_PIN_SET); + auto result = HAL_SPI_TransmitReceive(&spiHandle, const_cast(sendData), recvPtr, + sendLen, defaultPollingTimeout); + if (gpioPort != nullptr) { + HAL_GPIO_WritePin(gpioPort, gpioPin, GPIO_PIN_SET); + } + spiSemaphore->release(); + switch (result) { + case (HAL_OK): { + spiCookie.setTransferState(spi::TransferStates::SUCCESS); + break; } - spiSemaphore->release(); - switch(result) { - case(HAL_OK): { - spiCookie.setTransferState(spi::TransferStates::SUCCESS); - break; - } - case(HAL_TIMEOUT): { + case (HAL_TIMEOUT): { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "SpiComIF::sendMessage: Polling Mode | Timeout for SPI device" << - spiCookie->getDeviceAddress() << std::endl; + sif::warning << "SpiComIF::sendMessage: Polling Mode | Timeout for SPI device" + << spiCookie->getDeviceAddress() << std::endl; #else - sif::printWarning("SpiComIF::sendMessage: Polling Mode | Timeout for SPI device %d\n", - spiCookie.getDeviceAddress()); + sif::printWarning("SpiComIF::sendMessage: Polling Mode | Timeout for SPI device %d\n", + spiCookie.getDeviceAddress()); #endif #endif - spiCookie.setTransferState(spi::TransferStates::FAILURE); - return spi::HAL_TIMEOUT_RETVAL; + spiCookie.setTransferState(spi::TransferStates::FAILURE); + return spi::HAL_TIMEOUT_RETVAL; } - case(HAL_ERROR): + case (HAL_ERROR): default: { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "SpiComIF::sendMessage: Polling Mode | HAL error for SPI device" << - spiCookie->getDeviceAddress() << std::endl; + sif::warning << "SpiComIF::sendMessage: Polling Mode | HAL error for SPI device" + << spiCookie->getDeviceAddress() << std::endl; #else - sif::printWarning("SpiComIF::sendMessage: Polling Mode | HAL error for SPI device %d\n", - spiCookie.getDeviceAddress()); + sif::printWarning("SpiComIF::sendMessage: Polling Mode | HAL error for SPI device %d\n", + spiCookie.getDeviceAddress()); #endif #endif - spiCookie.setTransferState(spi::TransferStates::FAILURE); - return spi::HAL_ERROR_RETVAL; + spiCookie.setTransferState(spi::TransferStates::FAILURE); + return spi::HAL_ERROR_RETVAL; } - } - return HasReturnvaluesIF::RETURN_OK; + } + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t SpiComIF::handleInterruptSendOperation(uint8_t* recvPtr, SPI_HandleTypeDef& spiHandle, - SpiCookie& spiCookie, const uint8_t * sendData, size_t sendLen) { - return handleIrqSendOperation(recvPtr, spiHandle, spiCookie, sendData, sendLen); +ReturnValue_t SpiComIF::handleInterruptSendOperation(uint8_t *recvPtr, SPI_HandleTypeDef &spiHandle, + SpiCookie &spiCookie, const uint8_t *sendData, + size_t sendLen) { + return handleIrqSendOperation(recvPtr, spiHandle, spiCookie, sendData, sendLen); } -ReturnValue_t SpiComIF::handleDmaSendOperation(uint8_t* recvPtr, SPI_HandleTypeDef& spiHandle, - SpiCookie& spiCookie, const uint8_t * sendData, size_t sendLen) { - return handleIrqSendOperation(recvPtr, spiHandle, spiCookie, sendData, sendLen); +ReturnValue_t SpiComIF::handleDmaSendOperation(uint8_t *recvPtr, SPI_HandleTypeDef &spiHandle, + SpiCookie &spiCookie, const uint8_t *sendData, + size_t sendLen) { + return handleIrqSendOperation(recvPtr, spiHandle, spiCookie, sendData, sendLen); } -ReturnValue_t SpiComIF::handleIrqSendOperation(uint8_t *recvPtr, SPI_HandleTypeDef& spiHandle, - SpiCookie& spiCookie, const uint8_t *sendData, size_t sendLen) { - ReturnValue_t result = genericIrqSendSetup(recvPtr, spiHandle, spiCookie, sendData, sendLen); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - // yet another HAL driver which is not const-correct.. - HAL_StatusTypeDef status = HAL_OK; - auto transferMode = spiCookie.getTransferMode(); - if(transferMode == spi::TransferModes::DMA) { - if(cacheMaintenanceOnTxBuffer) { - /* Clean D-cache. Make sure the address is 32-byte aligned and add 32-bytes to length, - in case it overlaps cacheline */ - SCB_CleanDCache_by_Addr((uint32_t*)(((uint32_t) sendData ) & ~(uint32_t)0x1F), - sendLen + 32); - } - status = HAL_SPI_TransmitReceive_DMA(&spiHandle, const_cast(sendData), - currentRecvPtr, sendLen); - } - else { - status = HAL_SPI_TransmitReceive_IT(&spiHandle, const_cast(sendData), - currentRecvPtr, sendLen); - } - switch(status) { - case(HAL_OK): { - break; - } - default: { - return halErrorHandler(status, transferMode); - } - } +ReturnValue_t SpiComIF::handleIrqSendOperation(uint8_t *recvPtr, SPI_HandleTypeDef &spiHandle, + SpiCookie &spiCookie, const uint8_t *sendData, + size_t sendLen) { + ReturnValue_t result = genericIrqSendSetup(recvPtr, spiHandle, spiCookie, sendData, sendLen); + if (result != HasReturnvaluesIF::RETURN_OK) { return result; + } + // yet another HAL driver which is not const-correct.. + HAL_StatusTypeDef status = HAL_OK; + auto transferMode = spiCookie.getTransferMode(); + if (transferMode == spi::TransferModes::DMA) { + if (cacheMaintenanceOnTxBuffer) { + /* Clean D-cache. Make sure the address is 32-byte aligned and add 32-bytes to length, + in case it overlaps cacheline */ + SCB_CleanDCache_by_Addr((uint32_t *)(((uint32_t)sendData) & ~(uint32_t)0x1F), sendLen + 32); + } + status = HAL_SPI_TransmitReceive_DMA(&spiHandle, const_cast(sendData), + currentRecvPtr, sendLen); + } else { + status = HAL_SPI_TransmitReceive_IT(&spiHandle, const_cast(sendData), currentRecvPtr, + sendLen); + } + switch (status) { + case (HAL_OK): { + break; + } + default: { + return halErrorHandler(status, transferMode); + } + } + return result; } ReturnValue_t SpiComIF::halErrorHandler(HAL_StatusTypeDef status, spi::TransferModes transferMode) { - char modeString[10]; - if(transferMode == spi::TransferModes::DMA) { - std::snprintf(modeString, sizeof(modeString), "Dma"); + char modeString[10]; + if (transferMode == spi::TransferModes::DMA) { + std::snprintf(modeString, sizeof(modeString), "Dma"); + } else { + std::snprintf(modeString, sizeof(modeString), "Interrupt"); + } + sif::printWarning("SpiComIF::handle%sSendOperation: HAL error %d occured\n", modeString, status); + switch (status) { + case (HAL_BUSY): { + return spi::HAL_BUSY_RETVAL; } - else { - std::snprintf(modeString, sizeof(modeString), "Interrupt"); + case (HAL_ERROR): { + return spi::HAL_ERROR_RETVAL; } - sif::printWarning("SpiComIF::handle%sSendOperation: HAL error %d occured\n", modeString, - status); - switch(status) { - case(HAL_BUSY): { - return spi::HAL_BUSY_RETVAL; - } - case(HAL_ERROR): { - return spi::HAL_ERROR_RETVAL; - } - case(HAL_TIMEOUT): { - return spi::HAL_TIMEOUT_RETVAL; + case (HAL_TIMEOUT): { + return spi::HAL_TIMEOUT_RETVAL; } default: { - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; } + } } +ReturnValue_t SpiComIF::genericIrqSendSetup(uint8_t *recvPtr, SPI_HandleTypeDef &spiHandle, + SpiCookie &spiCookie, const uint8_t *sendData, + size_t sendLen) { + currentRecvPtr = recvPtr; + currentRecvBuffSize = sendLen; -ReturnValue_t SpiComIF::genericIrqSendSetup(uint8_t *recvPtr, SPI_HandleTypeDef& spiHandle, - SpiCookie& spiCookie, const uint8_t *sendData, size_t sendLen) { - currentRecvPtr = recvPtr; - currentRecvBuffSize = sendLen; - - // Take the semaphore which will be released by a callback when the transfer is complete - ReturnValue_t result = spiSemaphore->acquire(SemaphoreIF::TimeoutType::WAITING, timeoutMs); - if(result != HasReturnvaluesIF::RETURN_OK) { - // Configuration error - sif::printWarning("SpiComIF::handleInterruptSendOperation: Semaphore " - "could not be acquired after %d ms\n", timeoutMs); - return result; - } - // Cache the current SPI handle in any case - spi::setSpiHandle(&spiHandle); - // Assign the IRQ arguments for the user callbacks - irqArgs.comIF = this; - irqArgs.spiCookie = &spiCookie; - // The SPI handle is passed to the default SPI callback as a void argument. This callback - // is different from the user callbacks specified above! - spi::assignSpiUserArgs(spiCookie.getSpiIdx(), reinterpret_cast(&spiHandle)); - if(spiCookie.getChipSelectGpioPort() != nullptr) { - HAL_GPIO_WritePin(spiCookie.getChipSelectGpioPort(), spiCookie.getChipSelectGpioPin(), - GPIO_PIN_RESET); - } - return HasReturnvaluesIF::RETURN_OK; + // Take the semaphore which will be released by a callback when the transfer is complete + ReturnValue_t result = spiSemaphore->acquire(SemaphoreIF::TimeoutType::WAITING, timeoutMs); + if (result != HasReturnvaluesIF::RETURN_OK) { + // Configuration error + sif::printWarning( + "SpiComIF::handleInterruptSendOperation: Semaphore " + "could not be acquired after %d ms\n", + timeoutMs); + return result; + } + // Cache the current SPI handle in any case + spi::setSpiHandle(&spiHandle); + // Assign the IRQ arguments for the user callbacks + irqArgs.comIF = this; + irqArgs.spiCookie = &spiCookie; + // The SPI handle is passed to the default SPI callback as a void argument. This callback + // is different from the user callbacks specified above! + spi::assignSpiUserArgs(spiCookie.getSpiIdx(), reinterpret_cast(&spiHandle)); + if (spiCookie.getChipSelectGpioPort() != nullptr) { + HAL_GPIO_WritePin(spiCookie.getChipSelectGpioPort(), spiCookie.getChipSelectGpioPin(), + GPIO_PIN_RESET); + } + return HasReturnvaluesIF::RETURN_OK; } void SpiComIF::spiTransferTxCompleteCallback(SPI_HandleTypeDef *hspi, void *args) { - genericIrqHandler(args, spi::TransferStates::SUCCESS); + genericIrqHandler(args, spi::TransferStates::SUCCESS); } void SpiComIF::spiTransferRxCompleteCallback(SPI_HandleTypeDef *hspi, void *args) { - genericIrqHandler(args, spi::TransferStates::SUCCESS); + genericIrqHandler(args, spi::TransferStates::SUCCESS); } void SpiComIF::spiTransferCompleteCallback(SPI_HandleTypeDef *hspi, void *args) { - genericIrqHandler(args, spi::TransferStates::SUCCESS); + genericIrqHandler(args, spi::TransferStates::SUCCESS); } void SpiComIF::spiTransferErrorCallback(SPI_HandleTypeDef *hspi, void *args) { - genericIrqHandler(args, spi::TransferStates::FAILURE); + genericIrqHandler(args, spi::TransferStates::FAILURE); } void SpiComIF::genericIrqHandler(void *irqArgsVoid, spi::TransferStates targetState) { - IrqArgs* irqArgs = reinterpret_cast(irqArgsVoid); - if(irqArgs == nullptr) { - return; - } - SpiCookie* spiCookie = irqArgs->spiCookie; - SpiComIF* comIF = irqArgs->comIF; - if(spiCookie == nullptr or comIF == nullptr) { - return; - } + IrqArgs *irqArgs = reinterpret_cast(irqArgsVoid); + if (irqArgs == nullptr) { + return; + } + SpiCookie *spiCookie = irqArgs->spiCookie; + SpiComIF *comIF = irqArgs->comIF; + if (spiCookie == nullptr or comIF == nullptr) { + return; + } - spiCookie->setTransferState(targetState); - - if(spiCookie->getChipSelectGpioPort() != nullptr) { - // Pull CS pin high again - HAL_GPIO_WritePin(spiCookie->getChipSelectGpioPort(), spiCookie->getChipSelectGpioPin(), - GPIO_PIN_SET); - } + spiCookie->setTransferState(targetState); + if (spiCookie->getChipSelectGpioPort() != nullptr) { + // Pull CS pin high again + HAL_GPIO_WritePin(spiCookie->getChipSelectGpioPort(), spiCookie->getChipSelectGpioPin(), + GPIO_PIN_SET); + } #if defined FSFW_OSAL_FREERTOS - // Release the task semaphore - BaseType_t taskWoken = pdFALSE; - ReturnValue_t result = BinarySemaphore::releaseFromISR(comIF->spiSemaphore->getSemaphore(), - &taskWoken); + // Release the task semaphore + BaseType_t taskWoken = pdFALSE; + ReturnValue_t result = + BinarySemaphore::releaseFromISR(comIF->spiSemaphore->getSemaphore(), &taskWoken); #elif defined FSFW_OSAL_RTEMS - ReturnValue_t result = comIF->spiSemaphore->release(); + ReturnValue_t result = comIF->spiSemaphore->release(); #endif - if(result != HasReturnvaluesIF::RETURN_OK) { - // Configuration error - printf("SpiComIF::genericIrqHandler: Failure releasing Semaphore!\n"); - } + if (result != HasReturnvaluesIF::RETURN_OK) { + // Configuration error + printf("SpiComIF::genericIrqHandler: Failure releasing Semaphore!\n"); + } - // Perform cache maintenance operation for DMA transfers - if(spiCookie->getTransferMode() == spi::TransferModes::DMA) { - // Invalidate cache prior to access by CPU - SCB_InvalidateDCache_by_Addr ((uint32_t *) comIF->currentRecvPtr, - comIF->currentRecvBuffSize); - } + // Perform cache maintenance operation for DMA transfers + if (spiCookie->getTransferMode() == spi::TransferModes::DMA) { + // Invalidate cache prior to access by CPU + SCB_InvalidateDCache_by_Addr((uint32_t *)comIF->currentRecvPtr, comIF->currentRecvBuffSize); + } #if defined FSFW_OSAL_FREERTOS - /* Request a context switch if the SPI ComIF task was woken up and has a higher priority - than the currently running task */ - if(taskWoken == pdTRUE) { - TaskManagement::requestContextSwitch(CallContext::ISR); - } + /* Request a context switch if the SPI ComIF task was woken up and has a higher priority + than the currently running task */ + if (taskWoken == pdTRUE) { + TaskManagement::requestContextSwitch(CallContext::ISR); + } #endif } void SpiComIF::printCfgError(const char *const type) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "SpiComIF::initializeInterface: Invalid " << type << " configuration" - << std::endl; + sif::warning << "SpiComIF::initializeInterface: Invalid " << type << " configuration" + << std::endl; #else - sif::printWarning("SpiComIF::initializeInterface: Invalid %s configuration\n", type); + sif::printWarning("SpiComIF::initializeInterface: Invalid %s configuration\n", type); #endif } diff --git a/hal/src/fsfw_hal/stm32h7/spi/SpiComIF.h b/hal/src/fsfw_hal/stm32h7/spi/SpiComIF.h index cb6c4cf8..d8530201 100644 --- a/hal/src/fsfw_hal/stm32h7/spi/SpiComIF.h +++ b/hal/src/fsfw_hal/stm32h7/spi/SpiComIF.h @@ -1,16 +1,15 @@ #ifndef FSFW_HAL_STM32H7_SPI_SPICOMIF_H_ #define FSFW_HAL_STM32H7_SPI_SPICOMIF_H_ -#include "fsfw/tasks/SemaphoreIF.h" +#include +#include + #include "fsfw/devicehandlers/DeviceCommunicationIF.h" #include "fsfw/objectmanager/SystemObject.h" - +#include "fsfw/tasks/SemaphoreIF.h" #include "fsfw_hal/stm32h7/spi/spiDefinitions.h" -#include "stm32h7xx_hal_spi.h" #include "stm32h743xx.h" - -#include -#include +#include "stm32h7xx_hal_spi.h" class SpiCookie; class BinarySemaphore; @@ -28,102 +27,100 @@ class BinarySemaphore; * implementation limits the transfer mode for a given SPI bus. * @author R. Mueller */ -class SpiComIF: - public SystemObject, - public DeviceCommunicationIF { -public: - /** - * Create a SPI communication interface for the given SPI peripheral (spiInstance) - * @param objectId - * @param spiInstance - * @param spiHandle - * @param transferMode - */ - SpiComIF(object_id_t objectId); +class SpiComIF : public SystemObject, public DeviceCommunicationIF { + public: + /** + * Create a SPI communication interface for the given SPI peripheral (spiInstance) + * @param objectId + * @param spiInstance + * @param spiHandle + * @param transferMode + */ + SpiComIF(object_id_t objectId); - /** - * Allows the user to disable cache maintenance on the TX buffer. This can be done if the - * TX buffers are places and MPU protected properly like specified in this link: - * https://community.st.com/s/article/FAQ-DMA-is-not-working-on-STM32H7-devices - * The cache maintenace is enabled by default. - * @param enable - */ - void configureCacheMaintenanceOnTxBuffer(bool enable); + /** + * Allows the user to disable cache maintenance on the TX buffer. This can be done if the + * TX buffers are places and MPU protected properly like specified in this link: + * https://community.st.com/s/article/FAQ-DMA-is-not-working-on-STM32H7-devices + * The cache maintenace is enabled by default. + * @param enable + */ + void configureCacheMaintenanceOnTxBuffer(bool enable); - void setDefaultPollingTimeout(dur_millis_t timeout); + void setDefaultPollingTimeout(dur_millis_t timeout); - /** - * Add the DMA handles. These need to be set in the DMA transfer mode is used. - * @param txHandle - * @param rxHandle - */ - void addDmaHandles(DMA_HandleTypeDef* txHandle, DMA_HandleTypeDef* rxHandle); + /** + * Add the DMA handles. These need to be set in the DMA transfer mode is used. + * @param txHandle + * @param rxHandle + */ + void addDmaHandles(DMA_HandleTypeDef* txHandle, DMA_HandleTypeDef* rxHandle); - ReturnValue_t initialize() override; + ReturnValue_t initialize() override; - // DeviceCommunicationIF overrides - virtual ReturnValue_t initializeInterface(CookieIF * cookie) override; - virtual ReturnValue_t sendMessage(CookieIF *cookie, - const uint8_t * sendData, size_t sendLen) override; - virtual ReturnValue_t getSendSuccess(CookieIF *cookie) override; - virtual ReturnValue_t requestReceiveMessage(CookieIF *cookie, - size_t requestLen) override; - virtual ReturnValue_t readReceivedMessage(CookieIF *cookie, - uint8_t **buffer, size_t *size) override; + // DeviceCommunicationIF overrides + virtual ReturnValue_t initializeInterface(CookieIF* cookie) override; + virtual ReturnValue_t sendMessage(CookieIF* cookie, const uint8_t* sendData, + size_t sendLen) override; + virtual ReturnValue_t getSendSuccess(CookieIF* cookie) override; + virtual ReturnValue_t requestReceiveMessage(CookieIF* cookie, size_t requestLen) override; + virtual ReturnValue_t readReceivedMessage(CookieIF* cookie, uint8_t** buffer, + size_t* size) override; -protected: + protected: + struct SpiInstance { + SpiInstance(size_t maxRecvSize) : replyBuffer(std::vector(maxRecvSize)) {} + std::vector replyBuffer; + size_t currentTransferLen = 0; + }; - struct SpiInstance { - SpiInstance(size_t maxRecvSize): replyBuffer(std::vector(maxRecvSize)) {} - std::vector replyBuffer; - size_t currentTransferLen = 0; - }; + struct IrqArgs { + SpiComIF* comIF = nullptr; + SpiCookie* spiCookie = nullptr; + }; - struct IrqArgs { - SpiComIF* comIF = nullptr; - SpiCookie* spiCookie = nullptr; - }; + IrqArgs irqArgs; - IrqArgs irqArgs; + uint32_t defaultPollingTimeout = 50; - uint32_t defaultPollingTimeout = 50; + SemaphoreIF::TimeoutType timeoutType = SemaphoreIF::TimeoutType::WAITING; + dur_millis_t timeoutMs = 20; - SemaphoreIF::TimeoutType timeoutType = SemaphoreIF::TimeoutType::WAITING; - dur_millis_t timeoutMs = 20; + BinarySemaphore* spiSemaphore = nullptr; + bool cacheMaintenanceOnTxBuffer = true; - BinarySemaphore* spiSemaphore = nullptr; - bool cacheMaintenanceOnTxBuffer = true; + using SpiDeviceMap = std::map; + using SpiDeviceMapIter = SpiDeviceMap::iterator; - using SpiDeviceMap = std::map; - using SpiDeviceMapIter = SpiDeviceMap::iterator; + uint8_t* currentRecvPtr = nullptr; + size_t currentRecvBuffSize = 0; - uint8_t* currentRecvPtr = nullptr; - size_t currentRecvBuffSize = 0; + SpiDeviceMap spiDeviceMap; - SpiDeviceMap spiDeviceMap; + ReturnValue_t handlePollingSendOperation(uint8_t* recvPtr, SPI_HandleTypeDef& spiHandle, + SpiCookie& spiCookie, const uint8_t* sendData, + size_t sendLen); + ReturnValue_t handleInterruptSendOperation(uint8_t* recvPtr, SPI_HandleTypeDef& spiHandle, + SpiCookie& spiCookie, const uint8_t* sendData, + size_t sendLen); + ReturnValue_t handleDmaSendOperation(uint8_t* recvPtr, SPI_HandleTypeDef& spiHandle, + SpiCookie& spiCookie, const uint8_t* sendData, + size_t sendLen); + ReturnValue_t handleIrqSendOperation(uint8_t* recvPtr, SPI_HandleTypeDef& spiHandle, + SpiCookie& spiCookie, const uint8_t* sendData, + size_t sendLen); + ReturnValue_t genericIrqSendSetup(uint8_t* recvPtr, SPI_HandleTypeDef& spiHandle, + SpiCookie& spiCookie, const uint8_t* sendData, size_t sendLen); + ReturnValue_t halErrorHandler(HAL_StatusTypeDef status, spi::TransferModes transferMode); - ReturnValue_t handlePollingSendOperation(uint8_t* recvPtr, SPI_HandleTypeDef& spiHandle, - SpiCookie& spiCookie, const uint8_t * sendData, size_t sendLen); - ReturnValue_t handleInterruptSendOperation(uint8_t* recvPtr, SPI_HandleTypeDef& spiHandle, - SpiCookie& spiCookie, const uint8_t * sendData, size_t sendLen); - ReturnValue_t handleDmaSendOperation(uint8_t* recvPtr, SPI_HandleTypeDef& spiHandle, - SpiCookie& spiCookie, const uint8_t * sendData, size_t sendLen); - ReturnValue_t handleIrqSendOperation(uint8_t* recvPtr, SPI_HandleTypeDef& spiHandle, - SpiCookie& spiCookie, const uint8_t * sendData, size_t sendLen); - ReturnValue_t genericIrqSendSetup(uint8_t* recvPtr, SPI_HandleTypeDef& spiHandle, - SpiCookie& spiCookie, const uint8_t * sendData, size_t sendLen); - ReturnValue_t halErrorHandler(HAL_StatusTypeDef status, spi::TransferModes transferMode); + static void spiTransferTxCompleteCallback(SPI_HandleTypeDef* hspi, void* args); + static void spiTransferRxCompleteCallback(SPI_HandleTypeDef* hspi, void* args); + static void spiTransferCompleteCallback(SPI_HandleTypeDef* hspi, void* args); + static void spiTransferErrorCallback(SPI_HandleTypeDef* hspi, void* args); - static void spiTransferTxCompleteCallback(SPI_HandleTypeDef *hspi, void* args); - static void spiTransferRxCompleteCallback(SPI_HandleTypeDef *hspi, void* args); - static void spiTransferCompleteCallback(SPI_HandleTypeDef *hspi, void* args); - static void spiTransferErrorCallback(SPI_HandleTypeDef *hspi, void* args); + static void genericIrqHandler(void* irqArgs, spi::TransferStates targetState); - static void genericIrqHandler(void* irqArgs, spi::TransferStates targetState); - - void printCfgError(const char* const type); + void printCfgError(const char* const type); }; - - #endif /* FSFW_HAL_STM32H7_SPI_SPICOMIF_H_ */ diff --git a/hal/src/fsfw_hal/stm32h7/spi/SpiCookie.cpp b/hal/src/fsfw_hal/stm32h7/spi/SpiCookie.cpp index 200d4651..6b8773ec 100644 --- a/hal/src/fsfw_hal/stm32h7/spi/SpiCookie.cpp +++ b/hal/src/fsfw_hal/stm32h7/spi/SpiCookie.cpp @@ -1,78 +1,60 @@ #include "fsfw_hal/stm32h7/spi/SpiCookie.h" - SpiCookie::SpiCookie(address_t deviceAddress, spi::SpiBus spiIdx, spi::TransferModes transferMode, - spi::MspCfgBase* mspCfg, uint32_t spiSpeed, spi::SpiModes spiMode, - size_t maxRecvSize, stm32h7::GpioCfg csGpio): - deviceAddress(deviceAddress), spiIdx(spiIdx), spiSpeed(spiSpeed), spiMode(spiMode), - transferMode(transferMode), csGpio(csGpio), - mspCfg(mspCfg), maxRecvSize(maxRecvSize) { - spiHandle.Init.DataSize = SPI_DATASIZE_8BIT; - spiHandle.Init.FirstBit = SPI_FIRSTBIT_MSB; - spiHandle.Init.TIMode = SPI_TIMODE_DISABLE; - spiHandle.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; - spiHandle.Init.CRCPolynomial = 7; - spiHandle.Init.CRCLength = SPI_CRC_LENGTH_8BIT; - spiHandle.Init.NSS = SPI_NSS_SOFT; - spiHandle.Init.NSSPMode = SPI_NSS_PULSE_DISABLE; - spiHandle.Init.Direction = SPI_DIRECTION_2LINES; - // Recommended setting to avoid glitches - spiHandle.Init.MasterKeepIOState = SPI_MASTER_KEEP_IO_STATE_ENABLE; - spiHandle.Init.Mode = SPI_MODE_MASTER; - spi::assignSpiMode(spiMode, spiHandle); - spiHandle.Init.BaudRatePrescaler = spi::getPrescaler(HAL_RCC_GetHCLKFreq(), spiSpeed); + spi::MspCfgBase* mspCfg, uint32_t spiSpeed, spi::SpiModes spiMode, + size_t maxRecvSize, stm32h7::GpioCfg csGpio) + : deviceAddress(deviceAddress), + spiIdx(spiIdx), + spiSpeed(spiSpeed), + spiMode(spiMode), + transferMode(transferMode), + csGpio(csGpio), + mspCfg(mspCfg), + maxRecvSize(maxRecvSize) { + spiHandle.Init.DataSize = SPI_DATASIZE_8BIT; + spiHandle.Init.FirstBit = SPI_FIRSTBIT_MSB; + spiHandle.Init.TIMode = SPI_TIMODE_DISABLE; + spiHandle.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; + spiHandle.Init.CRCPolynomial = 7; + spiHandle.Init.CRCLength = SPI_CRC_LENGTH_8BIT; + spiHandle.Init.NSS = SPI_NSS_SOFT; + spiHandle.Init.NSSPMode = SPI_NSS_PULSE_DISABLE; + spiHandle.Init.Direction = SPI_DIRECTION_2LINES; + // Recommended setting to avoid glitches + spiHandle.Init.MasterKeepIOState = SPI_MASTER_KEEP_IO_STATE_ENABLE; + spiHandle.Init.Mode = SPI_MODE_MASTER; + spi::assignSpiMode(spiMode, spiHandle); + spiHandle.Init.BaudRatePrescaler = spi::getPrescaler(HAL_RCC_GetHCLKFreq(), spiSpeed); } -uint16_t SpiCookie::getChipSelectGpioPin() const { - return csGpio.pin; -} +uint16_t SpiCookie::getChipSelectGpioPin() const { return csGpio.pin; } -GPIO_TypeDef* SpiCookie::getChipSelectGpioPort() { - return csGpio.port; -} +GPIO_TypeDef* SpiCookie::getChipSelectGpioPort() { return csGpio.port; } -address_t SpiCookie::getDeviceAddress() const { - return deviceAddress; -} +address_t SpiCookie::getDeviceAddress() const { return deviceAddress; } -spi::SpiBus SpiCookie::getSpiIdx() const { - return spiIdx; -} +spi::SpiBus SpiCookie::getSpiIdx() const { return spiIdx; } -spi::SpiModes SpiCookie::getSpiMode() const { - return spiMode; -} +spi::SpiModes SpiCookie::getSpiMode() const { return spiMode; } -uint32_t SpiCookie::getSpiSpeed() const { - return spiSpeed; -} +uint32_t SpiCookie::getSpiSpeed() const { return spiSpeed; } -size_t SpiCookie::getMaxRecvSize() const { - return maxRecvSize; -} +size_t SpiCookie::getMaxRecvSize() const { return maxRecvSize; } -SPI_HandleTypeDef& SpiCookie::getSpiHandle() { - return spiHandle; -} +SPI_HandleTypeDef& SpiCookie::getSpiHandle() { return spiHandle; } -spi::MspCfgBase* SpiCookie::getMspCfg() { - return mspCfg; -} +spi::MspCfgBase* SpiCookie::getMspCfg() { return mspCfg; } void SpiCookie::deleteMspCfg() { - if(mspCfg != nullptr) { - delete mspCfg; - } + if (mspCfg != nullptr) { + delete mspCfg; + } } -spi::TransferModes SpiCookie::getTransferMode() const { - return transferMode; -} +spi::TransferModes SpiCookie::getTransferMode() const { return transferMode; } void SpiCookie::setTransferState(spi::TransferStates transferState) { - this->transferState = transferState; + this->transferState = transferState; } -spi::TransferStates SpiCookie::getTransferState() const { - return this->transferState; -} +spi::TransferStates SpiCookie::getTransferState() const { return this->transferState; } diff --git a/hal/src/fsfw_hal/stm32h7/spi/SpiCookie.h b/hal/src/fsfw_hal/stm32h7/spi/SpiCookie.h index 56c6e800..7c894bea 100644 --- a/hal/src/fsfw_hal/stm32h7/spi/SpiCookie.h +++ b/hal/src/fsfw_hal/stm32h7/spi/SpiCookie.h @@ -1,16 +1,14 @@ #ifndef FSFW_HAL_STM32H7_SPI_SPICOOKIE_H_ #define FSFW_HAL_STM32H7_SPI_SPICOOKIE_H_ -#include "spiDefinitions.h" -#include "mspInit.h" -#include "../definitions.h" - -#include "fsfw/devicehandlers/CookieIF.h" - -#include "stm32h743xx.h" - #include +#include "../definitions.h" +#include "fsfw/devicehandlers/CookieIF.h" +#include "mspInit.h" +#include "spiDefinitions.h" +#include "stm32h743xx.h" + /** * @brief SPI cookie implementation for the STM32H7 device family * @details @@ -18,63 +16,61 @@ * SPI communication interface * @author R. Mueller */ -class SpiCookie: public CookieIF { - friend class SpiComIF; -public: +class SpiCookie : public CookieIF { + friend class SpiComIF; - /** - * Allows construction of a SPI cookie for a connected SPI device - * @param deviceAddress - * @param spiIdx SPI bus, e.g. SPI1 or SPI2 - * @param transferMode - * @param mspCfg This is the MSP configuration. The user is expected to supply - * a valid MSP configuration. See mspInit.h for functions - * to create one. - * @param spiSpeed - * @param spiMode - * @param chipSelectGpioPin GPIO port. Don't use a number here, use the 16 bit type - * definitions supplied in the MCU header file! (e.g. GPIO_PIN_X) - * @param chipSelectGpioPort GPIO port (e.g. GPIOA) - * @param maxRecvSize Maximum expected receive size. Chose as small as possible. - * @param csGpio Optional CS GPIO definition. - */ - SpiCookie(address_t deviceAddress, spi::SpiBus spiIdx, spi::TransferModes transferMode, - spi::MspCfgBase* mspCfg, uint32_t spiSpeed, spi::SpiModes spiMode, - size_t maxRecvSize, stm32h7::GpioCfg csGpio = stm32h7::GpioCfg(nullptr, 0, 0)); + public: + /** + * Allows construction of a SPI cookie for a connected SPI device + * @param deviceAddress + * @param spiIdx SPI bus, e.g. SPI1 or SPI2 + * @param transferMode + * @param mspCfg This is the MSP configuration. The user is expected to supply + * a valid MSP configuration. See mspInit.h for functions + * to create one. + * @param spiSpeed + * @param spiMode + * @param chipSelectGpioPin GPIO port. Don't use a number here, use the 16 bit type + * definitions supplied in the MCU header file! (e.g. GPIO_PIN_X) + * @param chipSelectGpioPort GPIO port (e.g. GPIOA) + * @param maxRecvSize Maximum expected receive size. Chose as small as possible. + * @param csGpio Optional CS GPIO definition. + */ + SpiCookie(address_t deviceAddress, spi::SpiBus spiIdx, spi::TransferModes transferMode, + spi::MspCfgBase* mspCfg, uint32_t spiSpeed, spi::SpiModes spiMode, size_t maxRecvSize, + stm32h7::GpioCfg csGpio = stm32h7::GpioCfg(nullptr, 0, 0)); - uint16_t getChipSelectGpioPin() const; - GPIO_TypeDef* getChipSelectGpioPort(); - address_t getDeviceAddress() const; - spi::SpiBus getSpiIdx() const; - spi::SpiModes getSpiMode() const; - spi::TransferModes getTransferMode() const; - uint32_t getSpiSpeed() const; - size_t getMaxRecvSize() const; - SPI_HandleTypeDef& getSpiHandle(); + uint16_t getChipSelectGpioPin() const; + GPIO_TypeDef* getChipSelectGpioPort(); + address_t getDeviceAddress() const; + spi::SpiBus getSpiIdx() const; + spi::SpiModes getSpiMode() const; + spi::TransferModes getTransferMode() const; + uint32_t getSpiSpeed() const; + size_t getMaxRecvSize() const; + SPI_HandleTypeDef& getSpiHandle(); -private: - address_t deviceAddress; - SPI_HandleTypeDef spiHandle = {}; - spi::SpiBus spiIdx; - uint32_t spiSpeed; - spi::SpiModes spiMode; - spi::TransferModes transferMode; - volatile spi::TransferStates transferState = spi::TransferStates::IDLE; - stm32h7::GpioCfg csGpio; + private: + address_t deviceAddress; + SPI_HandleTypeDef spiHandle = {}; + spi::SpiBus spiIdx; + uint32_t spiSpeed; + spi::SpiModes spiMode; + spi::TransferModes transferMode; + volatile spi::TransferStates transferState = spi::TransferStates::IDLE; + stm32h7::GpioCfg csGpio; - // The MSP configuration is cached here. Be careful when using this, it is automatically - // deleted by the SPI communication interface if it is not required anymore! - spi::MspCfgBase* mspCfg = nullptr; - const size_t maxRecvSize; + // The MSP configuration is cached here. Be careful when using this, it is automatically + // deleted by the SPI communication interface if it is not required anymore! + spi::MspCfgBase* mspCfg = nullptr; + const size_t maxRecvSize; - // Only the SpiComIF is allowed to use this to prevent dangling pointers issues - spi::MspCfgBase* getMspCfg(); - void deleteMspCfg(); + // Only the SpiComIF is allowed to use this to prevent dangling pointers issues + spi::MspCfgBase* getMspCfg(); + void deleteMspCfg(); - void setTransferState(spi::TransferStates transferState); - spi::TransferStates getTransferState() const; + void setTransferState(spi::TransferStates transferState); + spi::TransferStates getTransferState() const; }; - - #endif /* FSFW_HAL_STM32H7_SPI_SPICOOKIE_H_ */ diff --git a/hal/src/fsfw_hal/stm32h7/spi/mspInit.cpp b/hal/src/fsfw_hal/stm32h7/spi/mspInit.cpp index b7ff2f70..2b6eb5d7 100644 --- a/hal/src/fsfw_hal/stm32h7/spi/mspInit.cpp +++ b/hal/src/fsfw_hal/stm32h7/spi/mspInit.cpp @@ -1,15 +1,15 @@ -#include "fsfw_hal/stm32h7/dma.h" #include "fsfw_hal/stm32h7/spi/mspInit.h" -#include "fsfw_hal/stm32h7/spi/spiCore.h" -#include "fsfw_hal/stm32h7/spi/spiInterrupts.h" - -#include "stm32h743xx.h" -#include "stm32h7xx_hal_spi.h" -#include "stm32h7xx_hal_dma.h" -#include "stm32h7xx_hal_def.h" #include +#include "fsfw_hal/stm32h7/dma.h" +#include "fsfw_hal/stm32h7/spi/spiCore.h" +#include "fsfw_hal/stm32h7/spi/spiInterrupts.h" +#include "stm32h743xx.h" +#include "stm32h7xx_hal_def.h" +#include "stm32h7xx_hal_dma.h" +#include "stm32h7xx_hal_spi.h" + spi::msp_func_t mspInitFunc = nullptr; spi::MspCfgBase* mspInitArgs = nullptr; @@ -27,56 +27,55 @@ spi::MspCfgBase* mspDeinitArgs = nullptr; * @retval None */ void spi::halMspInitDma(SPI_HandleTypeDef* hspi, MspCfgBase* cfgBase) { - auto cfg = dynamic_cast(cfgBase); - if(hspi == nullptr or cfg == nullptr) { - return; - } - setSpiHandle(hspi); + auto cfg = dynamic_cast(cfgBase); + if (hspi == nullptr or cfg == nullptr) { + return; + } + setSpiHandle(hspi); - DMA_HandleTypeDef* hdma_tx = nullptr; - DMA_HandleTypeDef* hdma_rx = nullptr; - spi::getDmaHandles(&hdma_tx, &hdma_rx); - if(hdma_tx == nullptr or hdma_rx == nullptr) { - printf("HAL_SPI_MspInit: Invalid DMA handles. Make sure to call setDmaHandles!\n"); - return; - } + DMA_HandleTypeDef* hdma_tx = nullptr; + DMA_HandleTypeDef* hdma_rx = nullptr; + spi::getDmaHandles(&hdma_tx, &hdma_rx); + if (hdma_tx == nullptr or hdma_rx == nullptr) { + printf("HAL_SPI_MspInit: Invalid DMA handles. Make sure to call setDmaHandles!\n"); + return; + } - spi::halMspInitInterrupt(hspi, cfg); + spi::halMspInitInterrupt(hspi, cfg); - // DMA setup - if(cfg->dmaClkEnableWrapper == nullptr) { - mspErrorHandler("spi::halMspInitDma", "DMA Clock init invalid"); - } - cfg->dmaClkEnableWrapper(); + // DMA setup + if (cfg->dmaClkEnableWrapper == nullptr) { + mspErrorHandler("spi::halMspInitDma", "DMA Clock init invalid"); + } + cfg->dmaClkEnableWrapper(); - // Configure the DMA - /* Configure the DMA handler for Transmission process */ - if(hdma_tx->Instance == nullptr) { - // Assume it was not configured properly - mspErrorHandler("spi::halMspInitDma", "DMA TX handle invalid"); - } + // Configure the DMA + /* Configure the DMA handler for Transmission process */ + if (hdma_tx->Instance == nullptr) { + // Assume it was not configured properly + mspErrorHandler("spi::halMspInitDma", "DMA TX handle invalid"); + } - HAL_DMA_Init(hdma_tx); - /* Associate the initialized DMA handle to the the SPI handle */ - __HAL_LINKDMA(hspi, hdmatx, *hdma_tx); + HAL_DMA_Init(hdma_tx); + /* Associate the initialized DMA handle to the the SPI handle */ + __HAL_LINKDMA(hspi, hdmatx, *hdma_tx); - HAL_DMA_Init(hdma_rx); - /* Associate the initialized DMA handle to the the SPI handle */ - __HAL_LINKDMA(hspi, hdmarx, *hdma_rx); + HAL_DMA_Init(hdma_rx); + /* Associate the initialized DMA handle to the the SPI handle */ + __HAL_LINKDMA(hspi, hdmarx, *hdma_rx); - /*##-4- Configure the NVIC for DMA #########################################*/ - /* NVIC configuration for DMA transfer complete interrupt (SPI1_RX) */ - // Assign the interrupt handler - dma::assignDmaUserHandler(cfg->rxDmaIndex, cfg->rxDmaStream, &spi::dmaRxIrqHandler, hdma_rx); - HAL_NVIC_SetPriority(cfg->rxDmaIrqNumber, cfg->rxPreEmptPriority, cfg->rxSubpriority); - HAL_NVIC_EnableIRQ(cfg->rxDmaIrqNumber); + /*##-4- Configure the NVIC for DMA #########################################*/ + /* NVIC configuration for DMA transfer complete interrupt (SPI1_RX) */ + // Assign the interrupt handler + dma::assignDmaUserHandler(cfg->rxDmaIndex, cfg->rxDmaStream, &spi::dmaRxIrqHandler, hdma_rx); + HAL_NVIC_SetPriority(cfg->rxDmaIrqNumber, cfg->rxPreEmptPriority, cfg->rxSubpriority); + HAL_NVIC_EnableIRQ(cfg->rxDmaIrqNumber); - /* NVIC configuration for DMA transfer complete interrupt (SPI1_TX) */ - // Assign the interrupt handler - dma::assignDmaUserHandler(cfg->txDmaIndex, cfg->txDmaStream, - &spi::dmaTxIrqHandler, hdma_tx); - HAL_NVIC_SetPriority(cfg->txDmaIrqNumber, cfg->txPreEmptPriority, cfg->txSubpriority); - HAL_NVIC_EnableIRQ(cfg->txDmaIrqNumber); + /* NVIC configuration for DMA transfer complete interrupt (SPI1_TX) */ + // Assign the interrupt handler + dma::assignDmaUserHandler(cfg->txDmaIndex, cfg->txDmaStream, &spi::dmaTxIrqHandler, hdma_tx); + HAL_NVIC_SetPriority(cfg->txDmaIrqNumber, cfg->txPreEmptPriority, cfg->txSubpriority); + HAL_NVIC_EnableIRQ(cfg->txDmaIrqNumber); } /** @@ -88,128 +87,126 @@ void spi::halMspInitDma(SPI_HandleTypeDef* hspi, MspCfgBase* cfgBase) { * @retval None */ void spi::halMspDeinitDma(SPI_HandleTypeDef* hspi, MspCfgBase* cfgBase) { - auto cfg = dynamic_cast(cfgBase); - if(hspi == nullptr or cfg == nullptr) { - return; - } - spi::halMspDeinitInterrupt(hspi, cfgBase); - DMA_HandleTypeDef* hdma_tx = NULL; - DMA_HandleTypeDef* hdma_rx = NULL; - spi::getDmaHandles(&hdma_tx, &hdma_rx); - if(hdma_tx == NULL || hdma_rx == NULL) { - printf("HAL_SPI_MspInit: Invalid DMA handles. Make sure to call setDmaHandles!\n"); - } - else { - // Disable the DMA - /* De-Initialize the DMA associated to transmission process */ - HAL_DMA_DeInit(hdma_tx); - /* De-Initialize the DMA associated to reception process */ - HAL_DMA_DeInit(hdma_rx); - } - - // Disable the NVIC for DMA - HAL_NVIC_DisableIRQ(cfg->txDmaIrqNumber); - HAL_NVIC_DisableIRQ(cfg->rxDmaIrqNumber); + auto cfg = dynamic_cast(cfgBase); + if (hspi == nullptr or cfg == nullptr) { + return; + } + spi::halMspDeinitInterrupt(hspi, cfgBase); + DMA_HandleTypeDef* hdma_tx = NULL; + DMA_HandleTypeDef* hdma_rx = NULL; + spi::getDmaHandles(&hdma_tx, &hdma_rx); + if (hdma_tx == NULL || hdma_rx == NULL) { + printf("HAL_SPI_MspInit: Invalid DMA handles. Make sure to call setDmaHandles!\n"); + } else { + // Disable the DMA + /* De-Initialize the DMA associated to transmission process */ + HAL_DMA_DeInit(hdma_tx); + /* De-Initialize the DMA associated to reception process */ + HAL_DMA_DeInit(hdma_rx); + } + // Disable the NVIC for DMA + HAL_NVIC_DisableIRQ(cfg->txDmaIrqNumber); + HAL_NVIC_DisableIRQ(cfg->rxDmaIrqNumber); } void spi::halMspInitPolling(SPI_HandleTypeDef* hspi, MspCfgBase* cfgBase) { - auto cfg = dynamic_cast(cfgBase); - GPIO_InitTypeDef GPIO_InitStruct = {}; - /*##-1- Enable peripherals and GPIO Clocks #################################*/ - /* Enable GPIO TX/RX clock */ - cfg->setupCb(); + auto cfg = dynamic_cast(cfgBase); + GPIO_InitTypeDef GPIO_InitStruct = {}; + /*##-1- Enable peripherals and GPIO Clocks #################################*/ + /* Enable GPIO TX/RX clock */ + cfg->setupCb(); - /*##-2- Configure peripheral GPIO ##########################################*/ - /* SPI SCK GPIO pin configuration */ - GPIO_InitStruct.Pin = cfg->sck.pin; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_PULLDOWN; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStruct.Alternate = cfg->sck.altFnc; - HAL_GPIO_Init(cfg->sck.port, &GPIO_InitStruct); + /*##-2- Configure peripheral GPIO ##########################################*/ + /* SPI SCK GPIO pin configuration */ + GPIO_InitStruct.Pin = cfg->sck.pin; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_PULLDOWN; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStruct.Alternate = cfg->sck.altFnc; + HAL_GPIO_Init(cfg->sck.port, &GPIO_InitStruct); - /* SPI MISO GPIO pin configuration */ - GPIO_InitStruct.Pin = cfg->miso.pin; - GPIO_InitStruct.Alternate = cfg->miso.altFnc; - HAL_GPIO_Init(cfg->miso.port, &GPIO_InitStruct); + /* SPI MISO GPIO pin configuration */ + GPIO_InitStruct.Pin = cfg->miso.pin; + GPIO_InitStruct.Alternate = cfg->miso.altFnc; + HAL_GPIO_Init(cfg->miso.port, &GPIO_InitStruct); - /* SPI MOSI GPIO pin configuration */ - GPIO_InitStruct.Pin = cfg->mosi.pin; - GPIO_InitStruct.Alternate = cfg->mosi.altFnc; - HAL_GPIO_Init(cfg->mosi.port, &GPIO_InitStruct); + /* SPI MOSI GPIO pin configuration */ + GPIO_InitStruct.Pin = cfg->mosi.pin; + GPIO_InitStruct.Alternate = cfg->mosi.altFnc; + HAL_GPIO_Init(cfg->mosi.port, &GPIO_InitStruct); } void spi::halMspDeinitPolling(SPI_HandleTypeDef* hspi, MspCfgBase* cfgBase) { - auto cfg = reinterpret_cast(cfgBase); - // Reset peripherals - cfg->cleanupCb(); + auto cfg = reinterpret_cast(cfgBase); + // Reset peripherals + cfg->cleanupCb(); - // Disable peripherals and GPIO Clocks - /* Configure SPI SCK as alternate function */ - HAL_GPIO_DeInit(cfg->sck.port, cfg->sck.pin); - /* Configure SPI MISO as alternate function */ - HAL_GPIO_DeInit(cfg->miso.port, cfg->miso.pin); - /* Configure SPI MOSI as alternate function */ - HAL_GPIO_DeInit(cfg->mosi.port, cfg->mosi.pin); + // Disable peripherals and GPIO Clocks + /* Configure SPI SCK as alternate function */ + HAL_GPIO_DeInit(cfg->sck.port, cfg->sck.pin); + /* Configure SPI MISO as alternate function */ + HAL_GPIO_DeInit(cfg->miso.port, cfg->miso.pin); + /* Configure SPI MOSI as alternate function */ + HAL_GPIO_DeInit(cfg->mosi.port, cfg->mosi.pin); } void spi::halMspInitInterrupt(SPI_HandleTypeDef* hspi, MspCfgBase* cfgBase) { - auto cfg = dynamic_cast(cfgBase); - if(cfg == nullptr or hspi == nullptr) { - return; - } + auto cfg = dynamic_cast(cfgBase); + if (cfg == nullptr or hspi == nullptr) { + return; + } - spi::halMspInitPolling(hspi, cfg); - // Configure the NVIC for SPI - spi::assignSpiUserHandler(cfg->spiBus, cfg->spiIrqHandler, cfg->spiUserArgs); - HAL_NVIC_SetPriority(cfg->spiIrqNumber, cfg->preEmptPriority, cfg->subpriority); - HAL_NVIC_EnableIRQ(cfg->spiIrqNumber); + spi::halMspInitPolling(hspi, cfg); + // Configure the NVIC for SPI + spi::assignSpiUserHandler(cfg->spiBus, cfg->spiIrqHandler, cfg->spiUserArgs); + HAL_NVIC_SetPriority(cfg->spiIrqNumber, cfg->preEmptPriority, cfg->subpriority); + HAL_NVIC_EnableIRQ(cfg->spiIrqNumber); } void spi::halMspDeinitInterrupt(SPI_HandleTypeDef* hspi, MspCfgBase* cfgBase) { - auto cfg = dynamic_cast(cfgBase); - spi::halMspDeinitPolling(hspi, cfg); - // Disable the NVIC for SPI - HAL_NVIC_DisableIRQ(cfg->spiIrqNumber); + auto cfg = dynamic_cast(cfgBase); + spi::halMspDeinitPolling(hspi, cfg); + // Disable the NVIC for SPI + HAL_NVIC_DisableIRQ(cfg->spiIrqNumber); } void spi::getMspInitFunction(msp_func_t* init_func, MspCfgBase** args) { - if(init_func != NULL && args != NULL) { - *init_func = mspInitFunc; - *args = mspInitArgs; - } + if (init_func != NULL && args != NULL) { + *init_func = mspInitFunc; + *args = mspInitArgs; + } } void spi::getMspDeinitFunction(msp_func_t* deinit_func, MspCfgBase** args) { - if(deinit_func != NULL && args != NULL) { - *deinit_func = mspDeinitFunc; - *args = mspDeinitArgs; - } + if (deinit_func != NULL && args != NULL) { + *deinit_func = mspDeinitFunc; + *args = mspDeinitArgs; + } } -void spi::setSpiDmaMspFunctions(MspDmaConfigStruct* cfg, - msp_func_t initFunc, msp_func_t deinitFunc) { - mspInitFunc = initFunc; - mspDeinitFunc = deinitFunc; - mspInitArgs = cfg; - mspDeinitArgs = cfg; +void spi::setSpiDmaMspFunctions(MspDmaConfigStruct* cfg, msp_func_t initFunc, + msp_func_t deinitFunc) { + mspInitFunc = initFunc; + mspDeinitFunc = deinitFunc; + mspInitArgs = cfg; + mspDeinitArgs = cfg; } -void spi::setSpiIrqMspFunctions(MspIrqConfigStruct *cfg, msp_func_t initFunc, - msp_func_t deinitFunc) { - mspInitFunc = initFunc; - mspDeinitFunc = deinitFunc; - mspInitArgs = cfg; - mspDeinitArgs = cfg; +void spi::setSpiIrqMspFunctions(MspIrqConfigStruct* cfg, msp_func_t initFunc, + msp_func_t deinitFunc) { + mspInitFunc = initFunc; + mspDeinitFunc = deinitFunc; + mspInitArgs = cfg; + mspDeinitArgs = cfg; } -void spi::setSpiPollingMspFunctions(MspPollingConfigStruct *cfg, msp_func_t initFunc, - msp_func_t deinitFunc) { - mspInitFunc = initFunc; - mspDeinitFunc = deinitFunc; - mspInitArgs = cfg; - mspDeinitArgs = cfg; +void spi::setSpiPollingMspFunctions(MspPollingConfigStruct* cfg, msp_func_t initFunc, + msp_func_t deinitFunc) { + mspInitFunc = initFunc; + mspDeinitFunc = deinitFunc; + mspInitArgs = cfg; + mspDeinitArgs = cfg; } /** @@ -222,13 +219,12 @@ void spi::setSpiPollingMspFunctions(MspPollingConfigStruct *cfg, msp_func_t init * @param hspi: SPI handle pointer * @retval None */ -extern "C" void HAL_SPI_MspInit(SPI_HandleTypeDef *hspi) { - if(mspInitFunc != NULL) { - mspInitFunc(hspi, mspInitArgs); - } - else { - printf("HAL_SPI_MspInit: Please call set_msp_functions to assign SPI MSP functions\n"); - } +extern "C" void HAL_SPI_MspInit(SPI_HandleTypeDef* hspi) { + if (mspInitFunc != NULL) { + mspInitFunc(hspi, mspInitArgs); + } else { + printf("HAL_SPI_MspInit: Please call set_msp_functions to assign SPI MSP functions\n"); + } } /** @@ -239,15 +235,14 @@ extern "C" void HAL_SPI_MspInit(SPI_HandleTypeDef *hspi) { * @param hspi: SPI handle pointer * @retval None */ -extern "C" void HAL_SPI_MspDeInit(SPI_HandleTypeDef *hspi) { - if(mspDeinitFunc != NULL) { - mspDeinitFunc(hspi, mspDeinitArgs); - } - else { - printf("HAL_SPI_MspDeInit: Please call set_msp_functions to assign SPI MSP functions\n"); - } +extern "C" void HAL_SPI_MspDeInit(SPI_HandleTypeDef* hspi) { + if (mspDeinitFunc != NULL) { + mspDeinitFunc(hspi, mspDeinitArgs); + } else { + printf("HAL_SPI_MspDeInit: Please call set_msp_functions to assign SPI MSP functions\n"); + } } -void spi::mspErrorHandler(const char* const function, const char *const message) { - printf("%s failure: %s\n", function, message); +void spi::mspErrorHandler(const char* const function, const char* const message) { + printf("%s failure: %s\n", function, message); } diff --git a/hal/src/fsfw_hal/stm32h7/spi/mspInit.h b/hal/src/fsfw_hal/stm32h7/spi/mspInit.h index 0fb553f7..00c68017 100644 --- a/hal/src/fsfw_hal/stm32h7/spi/mspInit.h +++ b/hal/src/fsfw_hal/stm32h7/spi/mspInit.h @@ -1,19 +1,18 @@ #ifndef FSFW_HAL_STM32H7_SPI_MSPINIT_H_ #define FSFW_HAL_STM32H7_SPI_MSPINIT_H_ -#include "spiDefinitions.h" +#include + #include "../definitions.h" #include "../dma.h" - +#include "spiDefinitions.h" #include "stm32h7xx_hal_spi.h" -#include - #ifdef __cplusplus extern "C" { #endif -using mspCb = void (*) (void); +using mspCb = void (*)(void); /** * @brief This file provides MSP implementation for DMA, IRQ and Polling mode for the @@ -22,74 +21,72 @@ using mspCb = void (*) (void); namespace spi { struct MspCfgBase { - MspCfgBase(); - MspCfgBase(stm32h7::GpioCfg sck, stm32h7::GpioCfg mosi, stm32h7::GpioCfg miso, - mspCb cleanupCb = nullptr, mspCb setupCb = nullptr): - sck(sck), mosi(mosi), miso(miso), cleanupCb(cleanupCb), - setupCb(setupCb) {} + MspCfgBase(); + MspCfgBase(stm32h7::GpioCfg sck, stm32h7::GpioCfg mosi, stm32h7::GpioCfg miso, + mspCb cleanupCb = nullptr, mspCb setupCb = nullptr) + : sck(sck), mosi(mosi), miso(miso), cleanupCb(cleanupCb), setupCb(setupCb) {} - virtual ~MspCfgBase() = default; + virtual ~MspCfgBase() = default; - stm32h7::GpioCfg sck; - stm32h7::GpioCfg mosi; - stm32h7::GpioCfg miso; + stm32h7::GpioCfg sck; + stm32h7::GpioCfg mosi; + stm32h7::GpioCfg miso; - mspCb cleanupCb = nullptr; - mspCb setupCb = nullptr; + mspCb cleanupCb = nullptr; + mspCb setupCb = nullptr; }; -struct MspPollingConfigStruct: public MspCfgBase { - MspPollingConfigStruct(): MspCfgBase() {}; - MspPollingConfigStruct(stm32h7::GpioCfg sck, stm32h7::GpioCfg mosi, stm32h7::GpioCfg miso, - mspCb cleanupCb = nullptr, mspCb setupCb = nullptr): - MspCfgBase(sck, mosi, miso, cleanupCb, setupCb) {} +struct MspPollingConfigStruct : public MspCfgBase { + MspPollingConfigStruct() : MspCfgBase(){}; + MspPollingConfigStruct(stm32h7::GpioCfg sck, stm32h7::GpioCfg mosi, stm32h7::GpioCfg miso, + mspCb cleanupCb = nullptr, mspCb setupCb = nullptr) + : MspCfgBase(sck, mosi, miso, cleanupCb, setupCb) {} }; /* A valid instance of this struct must be passed to the MSP initialization function as a void* argument */ -struct MspIrqConfigStruct: public MspPollingConfigStruct { - MspIrqConfigStruct(): MspPollingConfigStruct() {}; - MspIrqConfigStruct(stm32h7::GpioCfg sck, stm32h7::GpioCfg mosi, stm32h7::GpioCfg miso, - mspCb cleanupCb = nullptr, mspCb setupCb = nullptr): - MspPollingConfigStruct(sck, mosi, miso, cleanupCb, setupCb) {} +struct MspIrqConfigStruct : public MspPollingConfigStruct { + MspIrqConfigStruct() : MspPollingConfigStruct(){}; + MspIrqConfigStruct(stm32h7::GpioCfg sck, stm32h7::GpioCfg mosi, stm32h7::GpioCfg miso, + mspCb cleanupCb = nullptr, mspCb setupCb = nullptr) + : MspPollingConfigStruct(sck, mosi, miso, cleanupCb, setupCb) {} - SpiBus spiBus = SpiBus::SPI_1; - user_handler_t spiIrqHandler = nullptr; - user_args_t spiUserArgs = nullptr; - IRQn_Type spiIrqNumber = SPI1_IRQn; - // Priorities for NVIC - // Pre-Empt priority ranging from 0 to 15. If FreeRTOS calls are used, only 5-15 are allowed - IrqPriorities preEmptPriority = IrqPriorities::LOWEST; - IrqPriorities subpriority = IrqPriorities::LOWEST; + SpiBus spiBus = SpiBus::SPI_1; + user_handler_t spiIrqHandler = nullptr; + user_args_t spiUserArgs = nullptr; + IRQn_Type spiIrqNumber = SPI1_IRQn; + // Priorities for NVIC + // Pre-Empt priority ranging from 0 to 15. If FreeRTOS calls are used, only 5-15 are allowed + IrqPriorities preEmptPriority = IrqPriorities::LOWEST; + IrqPriorities subpriority = IrqPriorities::LOWEST; }; /* A valid instance of this struct must be passed to the MSP initialization function as a void* argument */ -struct MspDmaConfigStruct: public MspIrqConfigStruct { - MspDmaConfigStruct(): MspIrqConfigStruct() {}; - MspDmaConfigStruct(stm32h7::GpioCfg sck, stm32h7::GpioCfg mosi, stm32h7::GpioCfg miso, - mspCb cleanupCb = nullptr, mspCb setupCb = nullptr): - MspIrqConfigStruct(sck, mosi, miso, cleanupCb, setupCb) {} - void (* dmaClkEnableWrapper) (void) = nullptr; +struct MspDmaConfigStruct : public MspIrqConfigStruct { + MspDmaConfigStruct() : MspIrqConfigStruct(){}; + MspDmaConfigStruct(stm32h7::GpioCfg sck, stm32h7::GpioCfg mosi, stm32h7::GpioCfg miso, + mspCb cleanupCb = nullptr, mspCb setupCb = nullptr) + : MspIrqConfigStruct(sck, mosi, miso, cleanupCb, setupCb) {} + void (*dmaClkEnableWrapper)(void) = nullptr; - dma::DMAIndexes txDmaIndex = dma::DMAIndexes::DMA_1; - dma::DMAIndexes rxDmaIndex = dma::DMAIndexes::DMA_1; - dma::DMAStreams txDmaStream = dma::DMAStreams::STREAM_0; - dma::DMAStreams rxDmaStream = dma::DMAStreams::STREAM_0; - IRQn_Type txDmaIrqNumber = DMA1_Stream0_IRQn; - IRQn_Type rxDmaIrqNumber = DMA1_Stream1_IRQn; - // Priorities for NVIC - IrqPriorities txPreEmptPriority = IrqPriorities::LOWEST; - IrqPriorities rxPreEmptPriority = IrqPriorities::LOWEST; - IrqPriorities txSubpriority = IrqPriorities::LOWEST; - IrqPriorities rxSubpriority = IrqPriorities::LOWEST; + dma::DMAIndexes txDmaIndex = dma::DMAIndexes::DMA_1; + dma::DMAIndexes rxDmaIndex = dma::DMAIndexes::DMA_1; + dma::DMAStreams txDmaStream = dma::DMAStreams::STREAM_0; + dma::DMAStreams rxDmaStream = dma::DMAStreams::STREAM_0; + IRQn_Type txDmaIrqNumber = DMA1_Stream0_IRQn; + IRQn_Type rxDmaIrqNumber = DMA1_Stream1_IRQn; + // Priorities for NVIC + IrqPriorities txPreEmptPriority = IrqPriorities::LOWEST; + IrqPriorities rxPreEmptPriority = IrqPriorities::LOWEST; + IrqPriorities txSubpriority = IrqPriorities::LOWEST; + IrqPriorities rxSubpriority = IrqPriorities::LOWEST; }; -using msp_func_t = void (*) (SPI_HandleTypeDef* hspi, MspCfgBase* cfg); +using msp_func_t = void (*)(SPI_HandleTypeDef* hspi, MspCfgBase* cfg); - -void getMspInitFunction(msp_func_t* init_func, MspCfgBase **args); -void getMspDeinitFunction(msp_func_t* deinit_func, MspCfgBase **args); +void getMspInitFunction(msp_func_t* init_func, MspCfgBase** args); +void getMspDeinitFunction(msp_func_t* deinit_func, MspCfgBase** args); void halMspInitDma(SPI_HandleTypeDef* hspi, MspCfgBase* cfg); void halMspDeinitDma(SPI_HandleTypeDef* hspi, MspCfgBase* cfg); @@ -107,23 +104,17 @@ void halMspDeinitPolling(SPI_HandleTypeDef* hspi, MspCfgBase* cfg); * @param deinit_func * @param deinit_args */ -void setSpiDmaMspFunctions(MspDmaConfigStruct* cfg, - msp_func_t initFunc = &spi::halMspInitDma, - msp_func_t deinitFunc= &spi::halMspDeinitDma -); -void setSpiIrqMspFunctions(MspIrqConfigStruct* cfg, - msp_func_t initFunc = &spi::halMspInitInterrupt, - msp_func_t deinitFunc= &spi::halMspDeinitInterrupt -); +void setSpiDmaMspFunctions(MspDmaConfigStruct* cfg, msp_func_t initFunc = &spi::halMspInitDma, + msp_func_t deinitFunc = &spi::halMspDeinitDma); +void setSpiIrqMspFunctions(MspIrqConfigStruct* cfg, msp_func_t initFunc = &spi::halMspInitInterrupt, + msp_func_t deinitFunc = &spi::halMspDeinitInterrupt); void setSpiPollingMspFunctions(MspPollingConfigStruct* cfg, - msp_func_t initFunc = &spi::halMspInitPolling, - msp_func_t deinitFunc= &spi::halMspDeinitPolling -); + msp_func_t initFunc = &spi::halMspInitPolling, + msp_func_t deinitFunc = &spi::halMspDeinitPolling); -void mspErrorHandler(const char* const function, const char *const message); - -} +void mspErrorHandler(const char* const function, const char* const message); +} // namespace spi #ifdef __cplusplus } diff --git a/hal/src/fsfw_hal/stm32h7/spi/spiCore.cpp b/hal/src/fsfw_hal/stm32h7/spi/spiCore.cpp index e569c9f4..2677b62b 100644 --- a/hal/src/fsfw_hal/stm32h7/spi/spiCore.cpp +++ b/hal/src/fsfw_hal/stm32h7/spi/spiCore.cpp @@ -1,8 +1,9 @@ #include "fsfw_hal/stm32h7/spi/spiCore.h" -#include "fsfw_hal/stm32h7/spi/spiDefinitions.h" #include +#include "fsfw_hal/stm32h7/spi/spiDefinitions.h" + SPI_HandleTypeDef* spiHandle = nullptr; DMA_HandleTypeDef* hdmaTx = nullptr; DMA_HandleTypeDef* hdmaRx = nullptr; @@ -17,117 +18,109 @@ spi_transfer_cb_t errorCb = nullptr; void* errorArgs = nullptr; void mapIndexAndStream(DMA_HandleTypeDef* handle, dma::DMAType dmaType, dma::DMAIndexes dmaIdx, - dma::DMAStreams dmaStream, IRQn_Type* dmaIrqNumber); -void mapSpiBus(DMA_HandleTypeDef *handle, dma::DMAType dmaType, spi::SpiBus spiBus); + dma::DMAStreams dmaStream, IRQn_Type* dmaIrqNumber); +void mapSpiBus(DMA_HandleTypeDef* handle, dma::DMAType dmaType, spi::SpiBus spiBus); -void spi::configureDmaHandle(DMA_HandleTypeDef *handle, spi::SpiBus spiBus, dma::DMAType dmaType, - dma::DMAIndexes dmaIdx, dma::DMAStreams dmaStream, IRQn_Type* dmaIrqNumber, - uint32_t dmaMode, uint32_t dmaPriority) { - using namespace dma; - mapIndexAndStream(handle, dmaType, dmaIdx, dmaStream, dmaIrqNumber); - mapSpiBus(handle, dmaType, spiBus); +void spi::configureDmaHandle(DMA_HandleTypeDef* handle, spi::SpiBus spiBus, dma::DMAType dmaType, + dma::DMAIndexes dmaIdx, dma::DMAStreams dmaStream, + IRQn_Type* dmaIrqNumber, uint32_t dmaMode, uint32_t dmaPriority) { + using namespace dma; + mapIndexAndStream(handle, dmaType, dmaIdx, dmaStream, dmaIrqNumber); + mapSpiBus(handle, dmaType, spiBus); - if(dmaType == DMAType::TX) { - handle->Init.Direction = DMA_MEMORY_TO_PERIPH; - } - else { - handle->Init.Direction = DMA_PERIPH_TO_MEMORY; - } + if (dmaType == DMAType::TX) { + handle->Init.Direction = DMA_MEMORY_TO_PERIPH; + } else { + handle->Init.Direction = DMA_PERIPH_TO_MEMORY; + } - handle->Init.Priority = dmaPriority; - handle->Init.Mode = dmaMode; + handle->Init.Priority = dmaPriority; + handle->Init.Mode = dmaMode; - // Standard settings for the rest for now - handle->Init.FIFOMode = DMA_FIFOMODE_DISABLE; - handle->Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL; - handle->Init.MemBurst = DMA_MBURST_INC4; - handle->Init.PeriphBurst = DMA_PBURST_INC4; - handle->Init.PeriphInc = DMA_PINC_DISABLE; - handle->Init.MemInc = DMA_MINC_ENABLE; - handle->Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; - handle->Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; + // Standard settings for the rest for now + handle->Init.FIFOMode = DMA_FIFOMODE_DISABLE; + handle->Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL; + handle->Init.MemBurst = DMA_MBURST_INC4; + handle->Init.PeriphBurst = DMA_PBURST_INC4; + handle->Init.PeriphInc = DMA_PINC_DISABLE; + handle->Init.MemInc = DMA_MINC_ENABLE; + handle->Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; + handle->Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; } void spi::setDmaHandles(DMA_HandleTypeDef* txHandle, DMA_HandleTypeDef* rxHandle) { - hdmaTx = txHandle; - hdmaRx = rxHandle; + hdmaTx = txHandle; + hdmaRx = rxHandle; } void spi::getDmaHandles(DMA_HandleTypeDef** txHandle, DMA_HandleTypeDef** rxHandle) { - *txHandle = hdmaTx; - *rxHandle = hdmaRx; + *txHandle = hdmaTx; + *rxHandle = hdmaRx; } -void spi::setSpiHandle(SPI_HandleTypeDef *spiHandle_) { - if(spiHandle_ == NULL) { - return; - } - spiHandle = spiHandle_; +void spi::setSpiHandle(SPI_HandleTypeDef* spiHandle_) { + if (spiHandle_ == NULL) { + return; + } + spiHandle = spiHandle_; } -void spi::assignTransferRxTxCompleteCallback(spi_transfer_cb_t callback, void *userArgs) { - rxTxCb = callback; - rxTxArgs = userArgs; +void spi::assignTransferRxTxCompleteCallback(spi_transfer_cb_t callback, void* userArgs) { + rxTxCb = callback; + rxTxArgs = userArgs; } -void spi::assignTransferRxCompleteCallback(spi_transfer_cb_t callback, void *userArgs) { - rxCb = callback; - rxArgs = userArgs; +void spi::assignTransferRxCompleteCallback(spi_transfer_cb_t callback, void* userArgs) { + rxCb = callback; + rxArgs = userArgs; } -void spi::assignTransferTxCompleteCallback(spi_transfer_cb_t callback, void *userArgs) { - txCb = callback; - txArgs = userArgs; +void spi::assignTransferTxCompleteCallback(spi_transfer_cb_t callback, void* userArgs) { + txCb = callback; + txArgs = userArgs; } -void spi::assignTransferErrorCallback(spi_transfer_cb_t callback, void *userArgs) { - errorCb = callback; - errorArgs = userArgs; +void spi::assignTransferErrorCallback(spi_transfer_cb_t callback, void* userArgs) { + errorCb = callback; + errorArgs = userArgs; } -SPI_HandleTypeDef* spi::getSpiHandle() { - return spiHandle; -} - - +SPI_HandleTypeDef* spi::getSpiHandle() { return spiHandle; } /** * @brief TxRx Transfer completed callback. * @param hspi: SPI handle */ -extern "C" void HAL_SPI_TxRxCpltCallback(SPI_HandleTypeDef *hspi) { - if(rxTxCb != NULL) { - rxTxCb(hspi, rxTxArgs); - } - else { - printf("HAL_SPI_TxRxCpltCallback: No user callback specified\n"); - } +extern "C" void HAL_SPI_TxRxCpltCallback(SPI_HandleTypeDef* hspi) { + if (rxTxCb != NULL) { + rxTxCb(hspi, rxTxArgs); + } else { + printf("HAL_SPI_TxRxCpltCallback: No user callback specified\n"); + } } /** * @brief TxRx Transfer completed callback. * @param hspi: SPI handle */ -extern "C" void HAL_SPI_TxCpltCallback(SPI_HandleTypeDef *hspi) { - if(txCb != NULL) { - txCb(hspi, txArgs); - } - else { - printf("HAL_SPI_TxCpltCallback: No user callback specified\n"); - } +extern "C" void HAL_SPI_TxCpltCallback(SPI_HandleTypeDef* hspi) { + if (txCb != NULL) { + txCb(hspi, txArgs); + } else { + printf("HAL_SPI_TxCpltCallback: No user callback specified\n"); + } } /** * @brief TxRx Transfer completed callback. * @param hspi: SPI handle */ -extern "C" void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef *hspi) { - if(rxCb != nullptr) { - rxCb(hspi, rxArgs); - } - else { - printf("HAL_SPI_RxCpltCallback: No user callback specified\n"); - } +extern "C" void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef* hspi) { + if (rxCb != nullptr) { + rxCb(hspi, rxArgs); + } else { + printf("HAL_SPI_RxCpltCallback: No user callback specified\n"); + } } /** @@ -137,205 +130,200 @@ extern "C" void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef *hspi) { * add your own implementation. * @retval None */ -extern "C" void HAL_SPI_ErrorCallback(SPI_HandleTypeDef *hspi) { - if(errorCb != nullptr) { - errorCb(hspi, rxArgs); - } - else { - printf("HAL_SPI_ErrorCallback: No user callback specified\n"); - } +extern "C" void HAL_SPI_ErrorCallback(SPI_HandleTypeDef* hspi) { + if (errorCb != nullptr) { + errorCb(hspi, rxArgs); + } else { + printf("HAL_SPI_ErrorCallback: No user callback specified\n"); + } } void mapIndexAndStream(DMA_HandleTypeDef* handle, dma::DMAType dmaType, dma::DMAIndexes dmaIdx, - dma::DMAStreams dmaStream, IRQn_Type* dmaIrqNumber) { - using namespace dma; - if(dmaIdx == DMAIndexes::DMA_1) { + dma::DMAStreams dmaStream, IRQn_Type* dmaIrqNumber) { + using namespace dma; + if (dmaIdx == DMAIndexes::DMA_1) { #ifdef DMA1 - switch(dmaStream) { - case(DMAStreams::STREAM_0): { + switch (dmaStream) { + case (DMAStreams::STREAM_0): { #ifdef DMA1_Stream0 - handle->Instance = DMA1_Stream0; - if(dmaIrqNumber != nullptr) { - *dmaIrqNumber = DMA1_Stream0_IRQn; - } -#endif - break; + handle->Instance = DMA1_Stream0; + if (dmaIrqNumber != nullptr) { + *dmaIrqNumber = DMA1_Stream0_IRQn; } - case(DMAStreams::STREAM_1): { +#endif + break; + } + case (DMAStreams::STREAM_1): { #ifdef DMA1_Stream1 - handle->Instance = DMA1_Stream1; - if(dmaIrqNumber != nullptr) { - *dmaIrqNumber = DMA1_Stream1_IRQn; - } -#endif - break; + handle->Instance = DMA1_Stream1; + if (dmaIrqNumber != nullptr) { + *dmaIrqNumber = DMA1_Stream1_IRQn; } - case(DMAStreams::STREAM_2): { +#endif + break; + } + case (DMAStreams::STREAM_2): { #ifdef DMA1_Stream2 - handle->Instance = DMA1_Stream2; - if(dmaIrqNumber != nullptr) { - *dmaIrqNumber = DMA1_Stream2_IRQn; - } -#endif - break; + handle->Instance = DMA1_Stream2; + if (dmaIrqNumber != nullptr) { + *dmaIrqNumber = DMA1_Stream2_IRQn; } - case(DMAStreams::STREAM_3): { +#endif + break; + } + case (DMAStreams::STREAM_3): { #ifdef DMA1_Stream3 - handle->Instance = DMA1_Stream3; - if(dmaIrqNumber != nullptr) { - *dmaIrqNumber = DMA1_Stream3_IRQn; - } -#endif - break; + handle->Instance = DMA1_Stream3; + if (dmaIrqNumber != nullptr) { + *dmaIrqNumber = DMA1_Stream3_IRQn; } - case(DMAStreams::STREAM_4): { +#endif + break; + } + case (DMAStreams::STREAM_4): { #ifdef DMA1_Stream4 - handle->Instance = DMA1_Stream4; - if(dmaIrqNumber != nullptr) { - *dmaIrqNumber = DMA1_Stream4_IRQn; - } -#endif - break; + handle->Instance = DMA1_Stream4; + if (dmaIrqNumber != nullptr) { + *dmaIrqNumber = DMA1_Stream4_IRQn; } - case(DMAStreams::STREAM_5): { +#endif + break; + } + case (DMAStreams::STREAM_5): { #ifdef DMA1_Stream5 - handle->Instance = DMA1_Stream5; - if(dmaIrqNumber != nullptr) { - *dmaIrqNumber = DMA1_Stream5_IRQn; - } -#endif - break; + handle->Instance = DMA1_Stream5; + if (dmaIrqNumber != nullptr) { + *dmaIrqNumber = DMA1_Stream5_IRQn; } - case(DMAStreams::STREAM_6): { +#endif + break; + } + case (DMAStreams::STREAM_6): { #ifdef DMA1_Stream6 - handle->Instance = DMA1_Stream6; - if(dmaIrqNumber != nullptr) { - *dmaIrqNumber = DMA1_Stream6_IRQn; - } -#endif - break; + handle->Instance = DMA1_Stream6; + if (dmaIrqNumber != nullptr) { + *dmaIrqNumber = DMA1_Stream6_IRQn; } - case(DMAStreams::STREAM_7): { +#endif + break; + } + case (DMAStreams::STREAM_7): { #ifdef DMA1_Stream7 - handle->Instance = DMA1_Stream7; - if(dmaIrqNumber != nullptr) { - *dmaIrqNumber = DMA1_Stream7_IRQn; - } + handle->Instance = DMA1_Stream7; + if (dmaIrqNumber != nullptr) { + *dmaIrqNumber = DMA1_Stream7_IRQn; + } #endif - break; - } - } - if(dmaType == DMAType::TX) { - handle->Init.Request = DMA_REQUEST_SPI1_TX; - } - else { - handle->Init.Request = DMA_REQUEST_SPI1_RX; - } + break; + } + } + if (dmaType == DMAType::TX) { + handle->Init.Request = DMA_REQUEST_SPI1_TX; + } else { + handle->Init.Request = DMA_REQUEST_SPI1_RX; + } #endif /* DMA1 */ - } - if(dmaIdx == DMAIndexes::DMA_2) { + } + if (dmaIdx == DMAIndexes::DMA_2) { #ifdef DMA2 - switch(dmaStream) { - case(DMAStreams::STREAM_0): { + switch (dmaStream) { + case (DMAStreams::STREAM_0): { #ifdef DMA2_Stream0 - handle->Instance = DMA2_Stream0; - if(dmaIrqNumber != nullptr) { - *dmaIrqNumber = DMA2_Stream0_IRQn; - } -#endif - break; + handle->Instance = DMA2_Stream0; + if (dmaIrqNumber != nullptr) { + *dmaIrqNumber = DMA2_Stream0_IRQn; } - case(DMAStreams::STREAM_1): { +#endif + break; + } + case (DMAStreams::STREAM_1): { #ifdef DMA2_Stream1 - handle->Instance = DMA2_Stream1; - if(dmaIrqNumber != nullptr) { - *dmaIrqNumber = DMA2_Stream1_IRQn; - } -#endif - break; + handle->Instance = DMA2_Stream1; + if (dmaIrqNumber != nullptr) { + *dmaIrqNumber = DMA2_Stream1_IRQn; } - case(DMAStreams::STREAM_2): { +#endif + break; + } + case (DMAStreams::STREAM_2): { #ifdef DMA2_Stream2 - handle->Instance = DMA2_Stream2; - if(dmaIrqNumber != nullptr) { - *dmaIrqNumber = DMA2_Stream2_IRQn; - } -#endif - break; + handle->Instance = DMA2_Stream2; + if (dmaIrqNumber != nullptr) { + *dmaIrqNumber = DMA2_Stream2_IRQn; } - case(DMAStreams::STREAM_3): { +#endif + break; + } + case (DMAStreams::STREAM_3): { #ifdef DMA2_Stream3 - handle->Instance = DMA2_Stream3; - if(dmaIrqNumber != nullptr) { - *dmaIrqNumber = DMA2_Stream3_IRQn; - } -#endif - break; + handle->Instance = DMA2_Stream3; + if (dmaIrqNumber != nullptr) { + *dmaIrqNumber = DMA2_Stream3_IRQn; } - case(DMAStreams::STREAM_4): { +#endif + break; + } + case (DMAStreams::STREAM_4): { #ifdef DMA2_Stream4 - handle->Instance = DMA2_Stream4; - if(dmaIrqNumber != nullptr) { - *dmaIrqNumber = DMA2_Stream4_IRQn; - } -#endif - break; + handle->Instance = DMA2_Stream4; + if (dmaIrqNumber != nullptr) { + *dmaIrqNumber = DMA2_Stream4_IRQn; } - case(DMAStreams::STREAM_5): { +#endif + break; + } + case (DMAStreams::STREAM_5): { #ifdef DMA2_Stream5 - handle->Instance = DMA2_Stream5; - if(dmaIrqNumber != nullptr) { - *dmaIrqNumber = DMA2_Stream5_IRQn; - } -#endif - break; + handle->Instance = DMA2_Stream5; + if (dmaIrqNumber != nullptr) { + *dmaIrqNumber = DMA2_Stream5_IRQn; } - case(DMAStreams::STREAM_6): { +#endif + break; + } + case (DMAStreams::STREAM_6): { #ifdef DMA2_Stream6 - handle->Instance = DMA2_Stream6; - if(dmaIrqNumber != nullptr) { - *dmaIrqNumber = DMA2_Stream6_IRQn; - } -#endif - break; + handle->Instance = DMA2_Stream6; + if (dmaIrqNumber != nullptr) { + *dmaIrqNumber = DMA2_Stream6_IRQn; } - case(DMAStreams::STREAM_7): { +#endif + break; + } + case (DMAStreams::STREAM_7): { #ifdef DMA2_Stream7 - handle->Instance = DMA2_Stream7; - if(dmaIrqNumber != nullptr) { - *dmaIrqNumber = DMA2_Stream7_IRQn; - } + handle->Instance = DMA2_Stream7; + if (dmaIrqNumber != nullptr) { + *dmaIrqNumber = DMA2_Stream7_IRQn; + } #endif - break; - } - } -#endif /* DMA2 */ + break; + } } +#endif /* DMA2 */ + } } -void mapSpiBus(DMA_HandleTypeDef *handle, dma::DMAType dmaType, spi::SpiBus spiBus) { - if(dmaType == dma::DMAType::TX) { - if(spiBus == spi::SpiBus::SPI_1) { +void mapSpiBus(DMA_HandleTypeDef* handle, dma::DMAType dmaType, spi::SpiBus spiBus) { + if (dmaType == dma::DMAType::TX) { + if (spiBus == spi::SpiBus::SPI_1) { #ifdef DMA_REQUEST_SPI1_TX - handle->Init.Request = DMA_REQUEST_SPI1_TX; + handle->Init.Request = DMA_REQUEST_SPI1_TX; #endif - } - else if(spiBus == spi::SpiBus::SPI_2) { + } else if (spiBus == spi::SpiBus::SPI_2) { #ifdef DMA_REQUEST_SPI2_TX - handle->Init.Request = DMA_REQUEST_SPI2_TX; + handle->Init.Request = DMA_REQUEST_SPI2_TX; #endif - } } - else { - if(spiBus == spi::SpiBus::SPI_1) { + } else { + if (spiBus == spi::SpiBus::SPI_1) { #ifdef DMA_REQUEST_SPI1_RX - handle->Init.Request = DMA_REQUEST_SPI1_RX; + handle->Init.Request = DMA_REQUEST_SPI1_RX; #endif - } - else if(spiBus == spi::SpiBus::SPI_2) { + } else if (spiBus == spi::SpiBus::SPI_2) { #ifdef DMA_REQUEST_SPI2_RX - handle->Init.Request = DMA_REQUEST_SPI2_RX; + handle->Init.Request = DMA_REQUEST_SPI2_RX; #endif - } } + } } diff --git a/hal/src/fsfw_hal/stm32h7/spi/spiCore.h b/hal/src/fsfw_hal/stm32h7/spi/spiCore.h index 1ad5c693..14ea29fe 100644 --- a/hal/src/fsfw_hal/stm32h7/spi/spiCore.h +++ b/hal/src/fsfw_hal/stm32h7/spi/spiCore.h @@ -3,7 +3,6 @@ #include "fsfw_hal/stm32h7/dma.h" #include "fsfw_hal/stm32h7/spi/spiDefinitions.h" - #include "stm32h7xx_hal.h" #include "stm32h7xx_hal_dma.h" @@ -11,14 +10,13 @@ extern "C" { #endif -using spi_transfer_cb_t = void (*) (SPI_HandleTypeDef *hspi, void* userArgs); +using spi_transfer_cb_t = void (*)(SPI_HandleTypeDef* hspi, void* userArgs); namespace spi { -void configureDmaHandle(DMA_HandleTypeDef* handle, spi::SpiBus spiBus, - dma::DMAType dmaType, dma::DMAIndexes dmaIdx, - dma::DMAStreams dmaStream, IRQn_Type* dmaIrqNumber, uint32_t dmaMode = DMA_NORMAL, - uint32_t dmaPriority = DMA_PRIORITY_LOW); +void configureDmaHandle(DMA_HandleTypeDef* handle, spi::SpiBus spiBus, dma::DMAType dmaType, + dma::DMAIndexes dmaIdx, dma::DMAStreams dmaStream, IRQn_Type* dmaIrqNumber, + uint32_t dmaMode = DMA_NORMAL, uint32_t dmaPriority = DMA_PRIORITY_LOW); /** * Assign DMA handles. Required to use DMA for SPI transfers. @@ -32,7 +30,7 @@ void getDmaHandles(DMA_HandleTypeDef** txHandle, DMA_HandleTypeDef** rxHandle); * Assign SPI handle. Needs to be done before using the SPI * @param spiHandle */ -void setSpiHandle(SPI_HandleTypeDef *spiHandle); +void setSpiHandle(SPI_HandleTypeDef* spiHandle); void assignTransferRxTxCompleteCallback(spi_transfer_cb_t callback, void* userArgs); void assignTransferRxCompleteCallback(spi_transfer_cb_t callback, void* userArgs); @@ -45,7 +43,7 @@ void assignTransferErrorCallback(spi_transfer_cb_t callback, void* userArgs); */ SPI_HandleTypeDef* getSpiHandle(); -} +} // namespace spi #ifdef __cplusplus } diff --git a/hal/src/fsfw_hal/stm32h7/spi/spiDefinitions.cpp b/hal/src/fsfw_hal/stm32h7/spi/spiDefinitions.cpp index 11655f5e..3da4ef53 100644 --- a/hal/src/fsfw_hal/stm32h7/spi/spiDefinitions.cpp +++ b/hal/src/fsfw_hal/stm32h7/spi/spiDefinitions.cpp @@ -1,52 +1,46 @@ #include "fsfw_hal/stm32h7/spi/spiDefinitions.h" void spi::assignSpiMode(SpiModes spiMode, SPI_HandleTypeDef& spiHandle) { - switch(spiMode) { - case(SpiModes::MODE_0): { - spiHandle.Init.CLKPolarity = SPI_POLARITY_LOW; - spiHandle.Init.CLKPhase = SPI_PHASE_1EDGE; - break; + switch (spiMode) { + case (SpiModes::MODE_0): { + spiHandle.Init.CLKPolarity = SPI_POLARITY_LOW; + spiHandle.Init.CLKPhase = SPI_PHASE_1EDGE; + break; } - case(SpiModes::MODE_1): { - spiHandle.Init.CLKPolarity = SPI_POLARITY_LOW; - spiHandle.Init.CLKPhase = SPI_PHASE_2EDGE; - break; + case (SpiModes::MODE_1): { + spiHandle.Init.CLKPolarity = SPI_POLARITY_LOW; + spiHandle.Init.CLKPhase = SPI_PHASE_2EDGE; + break; } - case(SpiModes::MODE_2): { - spiHandle.Init.CLKPolarity = SPI_POLARITY_HIGH; - spiHandle.Init.CLKPhase = SPI_PHASE_1EDGE; - break; - } - case(SpiModes::MODE_3): { - spiHandle.Init.CLKPolarity = SPI_POLARITY_HIGH; - spiHandle.Init.CLKPhase = SPI_PHASE_2EDGE; - break; + case (SpiModes::MODE_2): { + spiHandle.Init.CLKPolarity = SPI_POLARITY_HIGH; + spiHandle.Init.CLKPhase = SPI_PHASE_1EDGE; + break; } + case (SpiModes::MODE_3): { + spiHandle.Init.CLKPolarity = SPI_POLARITY_HIGH; + spiHandle.Init.CLKPhase = SPI_PHASE_2EDGE; + break; } + } } uint32_t spi::getPrescaler(uint32_t clock_src_freq, uint32_t baudrate_mbps) { - uint32_t divisor = 0; - uint32_t spi_clk = clock_src_freq; - uint32_t presc = 0; - static const uint32_t baudrate[] = { - SPI_BAUDRATEPRESCALER_2, - SPI_BAUDRATEPRESCALER_4, - SPI_BAUDRATEPRESCALER_8, - SPI_BAUDRATEPRESCALER_16, - SPI_BAUDRATEPRESCALER_32, - SPI_BAUDRATEPRESCALER_64, - SPI_BAUDRATEPRESCALER_128, - SPI_BAUDRATEPRESCALER_256, - }; + uint32_t divisor = 0; + uint32_t spi_clk = clock_src_freq; + uint32_t presc = 0; + static const uint32_t baudrate[] = { + SPI_BAUDRATEPRESCALER_2, SPI_BAUDRATEPRESCALER_4, SPI_BAUDRATEPRESCALER_8, + SPI_BAUDRATEPRESCALER_16, SPI_BAUDRATEPRESCALER_32, SPI_BAUDRATEPRESCALER_64, + SPI_BAUDRATEPRESCALER_128, SPI_BAUDRATEPRESCALER_256, + }; - while( spi_clk > baudrate_mbps) { - presc = baudrate[divisor]; - if (++divisor > 7) - break; + while (spi_clk > baudrate_mbps) { + presc = baudrate[divisor]; + if (++divisor > 7) break; - spi_clk = ( spi_clk >> 1); - } + spi_clk = (spi_clk >> 1); + } - return presc; + return presc; } diff --git a/hal/src/fsfw_hal/stm32h7/spi/spiDefinitions.h b/hal/src/fsfw_hal/stm32h7/spi/spiDefinitions.h index 772bf32d..12c3bf4e 100644 --- a/hal/src/fsfw_hal/stm32h7/spi/spiDefinitions.h +++ b/hal/src/fsfw_hal/stm32h7/spi/spiDefinitions.h @@ -2,37 +2,24 @@ #define FSFW_HAL_STM32H7_SPI_SPIDEFINITIONS_H_ #include "../../common/spi/spiCommon.h" - #include "fsfw/returnvalues/FwClassIds.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" - #include "stm32h7xx_hal.h" #include "stm32h7xx_hal_spi.h" namespace spi { static constexpr uint8_t HAL_SPI_ID = CLASS_ID::HAL_SPI; -static constexpr ReturnValue_t HAL_TIMEOUT_RETVAL = HasReturnvaluesIF::makeReturnCode(HAL_SPI_ID, 0); +static constexpr ReturnValue_t HAL_TIMEOUT_RETVAL = + HasReturnvaluesIF::makeReturnCode(HAL_SPI_ID, 0); static constexpr ReturnValue_t HAL_BUSY_RETVAL = HasReturnvaluesIF::makeReturnCode(HAL_SPI_ID, 1); static constexpr ReturnValue_t HAL_ERROR_RETVAL = HasReturnvaluesIF::makeReturnCode(HAL_SPI_ID, 2); -enum class TransferStates { - IDLE, - WAIT, - SUCCESS, - FAILURE -}; +enum class TransferStates { IDLE, WAIT, SUCCESS, FAILURE }; -enum SpiBus { - SPI_1, - SPI_2 -}; +enum SpiBus { SPI_1, SPI_2 }; -enum TransferModes { - POLLING, - INTERRUPT, - DMA -}; +enum TransferModes { POLLING, INTERRUPT, DMA }; void assignSpiMode(SpiModes spiMode, SPI_HandleTypeDef& spiHandle); @@ -44,7 +31,6 @@ void assignSpiMode(SpiModes spiMode, SPI_HandleTypeDef& spiHandle); */ uint32_t getPrescaler(uint32_t clock_src_freq, uint32_t baudrate_mbps); -} - +} // namespace spi #endif /* FSFW_HAL_STM32H7_SPI_SPIDEFINITIONS_H_ */ diff --git a/hal/src/fsfw_hal/stm32h7/spi/spiInterrupts.cpp b/hal/src/fsfw_hal/stm32h7/spi/spiInterrupts.cpp index 5d84208d..bd1c06dd 100644 --- a/hal/src/fsfw_hal/stm32h7/spi/spiInterrupts.cpp +++ b/hal/src/fsfw_hal/stm32h7/spi/spiInterrupts.cpp @@ -1,12 +1,12 @@ #include "fsfw_hal/stm32h7/spi/spiInterrupts.h" -#include "fsfw_hal/stm32h7/spi/spiCore.h" +#include + +#include "fsfw_hal/stm32h7/spi/spiCore.h" #include "stm32h7xx_hal.h" #include "stm32h7xx_hal_dma.h" #include "stm32h7xx_hal_spi.h" -#include - user_handler_t spi1UserHandler = &spi::spiIrqHandler; user_args_t spi1UserArgs = nullptr; @@ -18,11 +18,11 @@ user_args_t spi2UserArgs = nullptr; * @param None * @retval None */ -void spi::dmaRxIrqHandler(void* dmaHandle) { - if(dmaHandle == nullptr) { - return; - } - HAL_DMA_IRQHandler((DMA_HandleTypeDef *) dmaHandle); +void spi::dmaRxIrqHandler(void *dmaHandle) { + if (dmaHandle == nullptr) { + return; + } + HAL_DMA_IRQHandler((DMA_HandleTypeDef *)dmaHandle); } /** @@ -30,11 +30,11 @@ void spi::dmaRxIrqHandler(void* dmaHandle) { * @param None * @retval None */ -void spi::dmaTxIrqHandler(void* dmaHandle) { - if(dmaHandle == nullptr) { - return; - } - HAL_DMA_IRQHandler((DMA_HandleTypeDef *) dmaHandle); +void spi::dmaTxIrqHandler(void *dmaHandle) { + if (dmaHandle == nullptr) { + return; + } + HAL_DMA_IRQHandler((DMA_HandleTypeDef *)dmaHandle); } /** @@ -42,65 +42,62 @@ void spi::dmaTxIrqHandler(void* dmaHandle) { * @param None * @retval None */ -void spi::spiIrqHandler(void* spiHandle) { - if(spiHandle == nullptr) { - return; - } - //auto currentSpiHandle = spi::getSpiHandle(); - HAL_SPI_IRQHandler((SPI_HandleTypeDef *) spiHandle); +void spi::spiIrqHandler(void *spiHandle) { + if (spiHandle == nullptr) { + return; + } + // auto currentSpiHandle = spi::getSpiHandle(); + HAL_SPI_IRQHandler((SPI_HandleTypeDef *)spiHandle); } void spi::assignSpiUserHandler(spi::SpiBus spiIdx, user_handler_t userHandler, - user_args_t userArgs) { - if(spiIdx == spi::SpiBus::SPI_1) { - spi1UserHandler = userHandler; - spi1UserArgs = userArgs; - } - else { - spi2UserHandler = userHandler; - spi2UserArgs = userArgs; - } + user_args_t userArgs) { + if (spiIdx == spi::SpiBus::SPI_1) { + spi1UserHandler = userHandler; + spi1UserArgs = userArgs; + } else { + spi2UserHandler = userHandler; + spi2UserArgs = userArgs; + } } void spi::getSpiUserHandler(spi::SpiBus spiBus, user_handler_t *userHandler, - user_args_t *userArgs) { - if(userHandler == nullptr or userArgs == nullptr) { - return; - } - if(spiBus == spi::SpiBus::SPI_1) { - *userArgs = spi1UserArgs; - *userHandler = spi1UserHandler; - } - else { - *userArgs = spi2UserArgs; - *userHandler = spi2UserHandler; - } + user_args_t *userArgs) { + if (userHandler == nullptr or userArgs == nullptr) { + return; + } + if (spiBus == spi::SpiBus::SPI_1) { + *userArgs = spi1UserArgs; + *userHandler = spi1UserHandler; + } else { + *userArgs = spi2UserArgs; + *userHandler = spi2UserHandler; + } } void spi::assignSpiUserArgs(spi::SpiBus spiBus, user_args_t userArgs) { - if(spiBus == spi::SpiBus::SPI_1) { - spi1UserArgs = userArgs; - } - else { - spi2UserArgs = userArgs; - } + if (spiBus == spi::SpiBus::SPI_1) { + spi1UserArgs = userArgs; + } else { + spi2UserArgs = userArgs; + } } /* Do not change these function names! They need to be exactly equal to the name of the functions defined in the startup_stm32h743xx.s files! */ extern "C" void SPI1_IRQHandler() { - if(spi1UserHandler != NULL) { - spi1UserHandler(spi1UserArgs); - return; - } - Default_Handler(); + if (spi1UserHandler != NULL) { + spi1UserHandler(spi1UserArgs); + return; + } + Default_Handler(); } -extern "C" void SPI2_IRQHandler() { - if(spi2UserHandler != nullptr) { - spi2UserHandler(spi2UserArgs); - return; - } - Default_Handler(); +extern "C" void SPI2_IRQHandler() { + if (spi2UserHandler != nullptr) { + spi2UserHandler(spi2UserArgs); + return; + } + Default_Handler(); } diff --git a/hal/src/fsfw_hal/stm32h7/spi/spiInterrupts.h b/hal/src/fsfw_hal/stm32h7/spi/spiInterrupts.h index 0b53f48b..ec93be4d 100644 --- a/hal/src/fsfw_hal/stm32h7/spi/spiInterrupts.h +++ b/hal/src/fsfw_hal/stm32h7/spi/spiInterrupts.h @@ -18,10 +18,8 @@ void assignSpiUserArgs(spi::SpiBus spiBus, user_args_t userArgs); * @param user_handler * @param user_args */ -void assignSpiUserHandler(spi::SpiBus spiBus, user_handler_t user_handler, - user_args_t user_args); -void getSpiUserHandler(spi::SpiBus spiBus, user_handler_t* user_handler, - user_args_t* user_args); +void assignSpiUserHandler(spi::SpiBus spiBus, user_handler_t user_handler, user_args_t user_args); +void getSpiUserHandler(spi::SpiBus spiBus, user_handler_t* user_handler, user_args_t* user_args); /** * Generic interrupt handlers supplied for convenience. Do not call these directly! Set them @@ -32,7 +30,7 @@ void dmaRxIrqHandler(void* dma_handle); void dmaTxIrqHandler(void* dma_handle); void spiIrqHandler(void* spi_handle); -} +} // namespace spi #ifdef __cplusplus } diff --git a/hal/src/fsfw_hal/stm32h7/spi/stm32h743zi.cpp b/hal/src/fsfw_hal/stm32h7/spi/stm32h743zi.cpp index 1bafccd5..7bd8b184 100644 --- a/hal/src/fsfw_hal/stm32h7/spi/stm32h743zi.cpp +++ b/hal/src/fsfw_hal/stm32h7/spi/stm32h743zi.cpp @@ -1,82 +1,81 @@ #include "fsfw_hal/stm32h7/spi/stm32h743zi.h" -#include "fsfw_hal/stm32h7/spi/spiCore.h" -#include "fsfw_hal/stm32h7/spi/spiInterrupts.h" - -#include "stm32h7xx_hal.h" -#include "stm32h7xx_hal_rcc.h" #include +#include "fsfw_hal/stm32h7/spi/spiCore.h" +#include "fsfw_hal/stm32h7/spi/spiInterrupts.h" +#include "stm32h7xx_hal.h" +#include "stm32h7xx_hal_rcc.h" + void spiSetupWrapper() { - __HAL_RCC_GPIOA_CLK_ENABLE(); - __HAL_RCC_GPIOB_CLK_ENABLE(); - __HAL_RCC_SPI1_CLK_ENABLE(); + __HAL_RCC_GPIOA_CLK_ENABLE(); + __HAL_RCC_GPIOB_CLK_ENABLE(); + __HAL_RCC_SPI1_CLK_ENABLE(); } void spiCleanUpWrapper() { - __HAL_RCC_SPI1_FORCE_RESET(); - __HAL_RCC_SPI1_RELEASE_RESET(); + __HAL_RCC_SPI1_FORCE_RESET(); + __HAL_RCC_SPI1_RELEASE_RESET(); } -void spiDmaClockEnableWrapper() { - __HAL_RCC_DMA2_CLK_ENABLE(); -} +void spiDmaClockEnableWrapper() { __HAL_RCC_DMA2_CLK_ENABLE(); } void stm32h7::h743zi::standardPollingCfg(spi::MspPollingConfigStruct& cfg) { - cfg.setupCb = &spiSetupWrapper; - cfg.cleanupCb = &spiCleanUpWrapper; - cfg.sck.port = GPIOA; - cfg.sck.pin = GPIO_PIN_5; - cfg.miso.port = GPIOA; - cfg.miso.pin = GPIO_PIN_6; - cfg.mosi.port = GPIOA; - cfg.mosi.pin = GPIO_PIN_7; - cfg.sck.altFnc = GPIO_AF5_SPI1; - cfg.mosi.altFnc = GPIO_AF5_SPI1; - cfg.miso.altFnc = GPIO_AF5_SPI1; + cfg.setupCb = &spiSetupWrapper; + cfg.cleanupCb = &spiCleanUpWrapper; + cfg.sck.port = GPIOA; + cfg.sck.pin = GPIO_PIN_5; + cfg.miso.port = GPIOA; + cfg.miso.pin = GPIO_PIN_6; + cfg.mosi.port = GPIOA; + cfg.mosi.pin = GPIO_PIN_7; + cfg.sck.altFnc = GPIO_AF5_SPI1; + cfg.mosi.altFnc = GPIO_AF5_SPI1; + cfg.miso.altFnc = GPIO_AF5_SPI1; } void stm32h7::h743zi::standardInterruptCfg(spi::MspIrqConfigStruct& cfg, IrqPriorities spiIrqPrio, - IrqPriorities spiSubprio) { - // High, but works on FreeRTOS as well (priorities range from 0 to 15) - cfg.preEmptPriority = spiIrqPrio; - cfg.subpriority = spiSubprio; - cfg.spiIrqNumber = SPI1_IRQn; - cfg.spiBus = spi::SpiBus::SPI_1; - user_handler_t spiUserHandler = nullptr; - user_args_t spiUserArgs = nullptr; - getSpiUserHandler(spi::SpiBus::SPI_1, &spiUserHandler, &spiUserArgs); - if(spiUserHandler == nullptr) { - printf("spi::h743zi::standardInterruptCfg: Invalid SPI user handlers\n"); - return; - } - cfg.spiUserArgs = spiUserArgs; - cfg.spiIrqHandler = spiUserHandler; - standardPollingCfg(cfg); + IrqPriorities spiSubprio) { + // High, but works on FreeRTOS as well (priorities range from 0 to 15) + cfg.preEmptPriority = spiIrqPrio; + cfg.subpriority = spiSubprio; + cfg.spiIrqNumber = SPI1_IRQn; + cfg.spiBus = spi::SpiBus::SPI_1; + user_handler_t spiUserHandler = nullptr; + user_args_t spiUserArgs = nullptr; + getSpiUserHandler(spi::SpiBus::SPI_1, &spiUserHandler, &spiUserArgs); + if (spiUserHandler == nullptr) { + printf("spi::h743zi::standardInterruptCfg: Invalid SPI user handlers\n"); + return; + } + cfg.spiUserArgs = spiUserArgs; + cfg.spiIrqHandler = spiUserHandler; + standardPollingCfg(cfg); } void stm32h7::h743zi::standardDmaCfg(spi::MspDmaConfigStruct& cfg, IrqPriorities spiIrqPrio, - IrqPriorities txIrqPrio, IrqPriorities rxIrqPrio, IrqPriorities spiSubprio, - IrqPriorities txSubprio, IrqPriorities rxSubprio) { - cfg.dmaClkEnableWrapper = &spiDmaClockEnableWrapper; - cfg.rxDmaIndex = dma::DMAIndexes::DMA_2; - cfg.txDmaIndex = dma::DMAIndexes::DMA_2; - cfg.txDmaStream = dma::DMAStreams::STREAM_3; - cfg.rxDmaStream = dma::DMAStreams::STREAM_2; - DMA_HandleTypeDef* txHandle; - DMA_HandleTypeDef* rxHandle; - spi::getDmaHandles(&txHandle, &rxHandle); - if(txHandle == nullptr or rxHandle == nullptr) { - printf("spi::h743zi::standardDmaCfg: Invalid DMA handles\n"); - return; - } - spi::configureDmaHandle(txHandle, spi::SpiBus::SPI_1, dma::DMAType::TX, cfg.txDmaIndex, - cfg.txDmaStream, &cfg.txDmaIrqNumber); - spi::configureDmaHandle(rxHandle, spi::SpiBus::SPI_1, dma::DMAType::RX, cfg.rxDmaIndex, - cfg.rxDmaStream, &cfg.rxDmaIrqNumber, DMA_NORMAL, DMA_PRIORITY_HIGH); - cfg.txPreEmptPriority = txIrqPrio; - cfg.rxPreEmptPriority = txSubprio; - cfg.txSubpriority = rxIrqPrio; - cfg.rxSubpriority = rxSubprio; - standardInterruptCfg(cfg, spiIrqPrio, spiSubprio); + IrqPriorities txIrqPrio, IrqPriorities rxIrqPrio, + IrqPriorities spiSubprio, IrqPriorities txSubprio, + IrqPriorities rxSubprio) { + cfg.dmaClkEnableWrapper = &spiDmaClockEnableWrapper; + cfg.rxDmaIndex = dma::DMAIndexes::DMA_2; + cfg.txDmaIndex = dma::DMAIndexes::DMA_2; + cfg.txDmaStream = dma::DMAStreams::STREAM_3; + cfg.rxDmaStream = dma::DMAStreams::STREAM_2; + DMA_HandleTypeDef* txHandle; + DMA_HandleTypeDef* rxHandle; + spi::getDmaHandles(&txHandle, &rxHandle); + if (txHandle == nullptr or rxHandle == nullptr) { + printf("spi::h743zi::standardDmaCfg: Invalid DMA handles\n"); + return; + } + spi::configureDmaHandle(txHandle, spi::SpiBus::SPI_1, dma::DMAType::TX, cfg.txDmaIndex, + cfg.txDmaStream, &cfg.txDmaIrqNumber); + spi::configureDmaHandle(rxHandle, spi::SpiBus::SPI_1, dma::DMAType::RX, cfg.rxDmaIndex, + cfg.rxDmaStream, &cfg.rxDmaIrqNumber, DMA_NORMAL, DMA_PRIORITY_HIGH); + cfg.txPreEmptPriority = txIrqPrio; + cfg.rxPreEmptPriority = txSubprio; + cfg.txSubpriority = rxIrqPrio; + cfg.rxSubpriority = rxSubprio; + standardInterruptCfg(cfg, spiIrqPrio, spiSubprio); } diff --git a/hal/src/fsfw_hal/stm32h7/spi/stm32h743zi.h b/hal/src/fsfw_hal/stm32h7/spi/stm32h743zi.h index daa95554..e70f9853 100644 --- a/hal/src/fsfw_hal/stm32h7/spi/stm32h743zi.h +++ b/hal/src/fsfw_hal/stm32h7/spi/stm32h743zi.h @@ -9,14 +9,12 @@ namespace h743zi { void standardPollingCfg(spi::MspPollingConfigStruct& cfg); void standardInterruptCfg(spi::MspIrqConfigStruct& cfg, IrqPriorities spiIrqPrio, - IrqPriorities spiSubprio = HIGHEST); -void standardDmaCfg(spi::MspDmaConfigStruct& cfg, IrqPriorities spiIrqPrio, - IrqPriorities txIrqPrio, IrqPriorities rxIrqPrio, - IrqPriorities spiSubprio = HIGHEST, IrqPriorities txSubPrio = HIGHEST, - IrqPriorities rxSubprio = HIGHEST); + IrqPriorities spiSubprio = HIGHEST); +void standardDmaCfg(spi::MspDmaConfigStruct& cfg, IrqPriorities spiIrqPrio, IrqPriorities txIrqPrio, + IrqPriorities rxIrqPrio, IrqPriorities spiSubprio = HIGHEST, + IrqPriorities txSubPrio = HIGHEST, IrqPriorities rxSubprio = HIGHEST); - -} -} +} // namespace h743zi +} // namespace stm32h7 #endif /* FSFW_HAL_STM32H7_SPI_STM32H743ZISPI_H_ */ diff --git a/src/fsfw/action.h b/src/fsfw/action.h index 1300cf17..ba9151e3 100644 --- a/src/fsfw/action.h +++ b/src/fsfw/action.h @@ -4,8 +4,8 @@ #include "fsfw/action/ActionHelper.h" #include "fsfw/action/ActionMessage.h" #include "fsfw/action/CommandActionHelper.h" -#include "fsfw/action/HasActionsIF.h" #include "fsfw/action/CommandsActionsIF.h" +#include "fsfw/action/HasActionsIF.h" #include "fsfw/action/SimpleActionHelper.h" #endif /* FSFW_INC_FSFW_ACTION_H_ */ diff --git a/src/fsfw/action/ActionHelper.cpp b/src/fsfw/action/ActionHelper.cpp index bebd55a7..d41c78b4 100644 --- a/src/fsfw/action/ActionHelper.cpp +++ b/src/fsfw/action/ActionHelper.cpp @@ -1,177 +1,165 @@ #include "fsfw/action.h" - #include "fsfw/ipc/MessageQueueSenderIF.h" #include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/serviceinterface/ServiceInterface.h" -ActionHelper::ActionHelper(HasActionsIF* setOwner, - MessageQueueIF* useThisQueue) : - owner(setOwner), queueToUse(useThisQueue) { -} +ActionHelper::ActionHelper(HasActionsIF* setOwner, MessageQueueIF* useThisQueue) + : owner(setOwner), queueToUse(useThisQueue) {} -ActionHelper::~ActionHelper() { -} +ActionHelper::~ActionHelper() {} ReturnValue_t ActionHelper::handleActionMessage(CommandMessage* command) { - if (command->getCommand() == ActionMessage::EXECUTE_ACTION) { - ActionId_t currentAction = ActionMessage::getActionId(command); - prepareExecution(command->getSender(), currentAction, - ActionMessage::getStoreId(command)); - return HasReturnvaluesIF::RETURN_OK; - } else { - return CommandMessage::UNKNOWN_COMMAND; - } + if (command->getCommand() == ActionMessage::EXECUTE_ACTION) { + ActionId_t currentAction = ActionMessage::getActionId(command); + prepareExecution(command->getSender(), currentAction, ActionMessage::getStoreId(command)); + return HasReturnvaluesIF::RETURN_OK; + } else { + return CommandMessage::UNKNOWN_COMMAND; + } } ReturnValue_t ActionHelper::initialize(MessageQueueIF* queueToUse_) { - ipcStore = ObjectManager::instance()->get(objects::IPC_STORE); - if (ipcStore == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - if(queueToUse_ != nullptr) { - setQueueToUse(queueToUse_); - } + ipcStore = ObjectManager::instance()->get(objects::IPC_STORE); + if (ipcStore == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if (queueToUse_ != nullptr) { + setQueueToUse(queueToUse_); + } - if(queueToUse == nullptr) { + if (queueToUse == nullptr) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "ActionHelper::initialize: No queue set" << std::endl; + sif::warning << "ActionHelper::initialize: No queue set" << std::endl; #else - sif::printWarning("ActionHelper::initialize: No queue set\n"); + sif::printWarning("ActionHelper::initialize: No queue set\n"); #endif #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; + } - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } -void ActionHelper::step(uint8_t step, MessageQueueId_t reportTo, - ActionId_t commandId, ReturnValue_t result) { - CommandMessage reply; - ActionMessage::setStepReply(&reply, commandId, step + STEP_OFFSET, result); - queueToUse->sendMessage(reportTo, &reply); +void ActionHelper::step(uint8_t step, MessageQueueId_t reportTo, ActionId_t commandId, + ReturnValue_t result) { + CommandMessage reply; + ActionMessage::setStepReply(&reply, commandId, step + STEP_OFFSET, result); + queueToUse->sendMessage(reportTo, &reply); } void ActionHelper::finish(bool success, MessageQueueId_t reportTo, ActionId_t commandId, - ReturnValue_t result) { + ReturnValue_t result) { + CommandMessage reply; + ActionMessage::setCompletionReply(&reply, commandId, success, result); + queueToUse->sendMessage(reportTo, &reply); +} + +void ActionHelper::setQueueToUse(MessageQueueIF* queue) { queueToUse = queue; } + +void ActionHelper::prepareExecution(MessageQueueId_t commandedBy, ActionId_t actionId, + store_address_t dataAddress) { + const uint8_t* dataPtr = NULL; + size_t size = 0; + ReturnValue_t result = ipcStore->getData(dataAddress, &dataPtr, &size); + if (result != HasReturnvaluesIF::RETURN_OK) { CommandMessage reply; - ActionMessage::setCompletionReply(&reply, commandId, success, result); - queueToUse->sendMessage(reportTo, &reply); -} - -void ActionHelper::setQueueToUse(MessageQueueIF* queue) { - queueToUse = queue; -} - -void ActionHelper::prepareExecution(MessageQueueId_t commandedBy, - ActionId_t actionId, store_address_t dataAddress) { - const uint8_t* dataPtr = NULL; - size_t size = 0; - ReturnValue_t result = ipcStore->getData(dataAddress, &dataPtr, &size); - if (result != HasReturnvaluesIF::RETURN_OK) { - CommandMessage reply; - ActionMessage::setStepReply(&reply, actionId, 0, result); - queueToUse->sendMessage(commandedBy, &reply); - return; - } - result = owner->executeAction(actionId, commandedBy, dataPtr, size); - ipcStore->deleteData(dataAddress); - if(result == HasActionsIF::EXECUTION_FINISHED) { - CommandMessage reply; - ActionMessage::setCompletionReply(&reply, actionId, true, result); - queueToUse->sendMessage(commandedBy, &reply); - } - if (result != HasReturnvaluesIF::RETURN_OK) { - CommandMessage reply; - ActionMessage::setStepReply(&reply, actionId, 0, result); - queueToUse->sendMessage(commandedBy, &reply); - return; - } -} - -ReturnValue_t ActionHelper::reportData(MessageQueueId_t reportTo, - ActionId_t replyId, SerializeIF* data, bool hideSender) { + ActionMessage::setStepReply(&reply, actionId, 0, result); + queueToUse->sendMessage(commandedBy, &reply); + return; + } + result = owner->executeAction(actionId, commandedBy, dataPtr, size); + ipcStore->deleteData(dataAddress); + if (result == HasActionsIF::EXECUTION_FINISHED) { CommandMessage reply; - store_address_t storeAddress; - uint8_t *dataPtr; - size_t maxSize = data->getSerializedSize(); - if (maxSize == 0) { - /* No error, there's simply nothing to report. */ - return HasReturnvaluesIF::RETURN_OK; - } - size_t size = 0; - ReturnValue_t result = ipcStore->getFreeElement(&storeAddress, maxSize, - &dataPtr); - if (result != HasReturnvaluesIF::RETURN_OK) { + ActionMessage::setCompletionReply(&reply, actionId, true, result); + queueToUse->sendMessage(commandedBy, &reply); + } + if (result != HasReturnvaluesIF::RETURN_OK) { + CommandMessage reply; + ActionMessage::setStepReply(&reply, actionId, 0, result); + queueToUse->sendMessage(commandedBy, &reply); + return; + } +} + +ReturnValue_t ActionHelper::reportData(MessageQueueId_t reportTo, ActionId_t replyId, + SerializeIF* data, bool hideSender) { + CommandMessage reply; + store_address_t storeAddress; + uint8_t* dataPtr; + size_t maxSize = data->getSerializedSize(); + if (maxSize == 0) { + /* No error, there's simply nothing to report. */ + return HasReturnvaluesIF::RETURN_OK; + } + size_t size = 0; + ReturnValue_t result = ipcStore->getFreeElement(&storeAddress, maxSize, &dataPtr); + if (result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "ActionHelper::reportData: Getting free element from IPC store failed!" << - std::endl; + sif::warning << "ActionHelper::reportData: Getting free element from IPC store failed!" + << std::endl; #else - sif::printWarning("ActionHelper::reportData: Getting free element from IPC " - "store failed!\n"); + sif::printWarning( + "ActionHelper::reportData: Getting free element from IPC " + "store failed!\n"); #endif - return result; - } - result = data->serialize(&dataPtr, &size, maxSize, - SerializeIF::Endianness::BIG); - if (result != HasReturnvaluesIF::RETURN_OK) { - ipcStore->deleteData(storeAddress); - return result; - } - - /* We don't need to report the objectId, as we receive REQUESTED data before the completion - success message. True aperiodic replies need to be reported with another dedicated message. */ - ActionMessage::setDataReply(&reply, replyId, storeAddress); - - /* If the sender needs to be hidden, for example to handle packet - as unrequested reply, this will be done here. */ - if (hideSender) { - result = MessageQueueSenderIF::sendMessage(reportTo, &reply); - } - else { - result = queueToUse->sendMessage(reportTo, &reply); - } - - if (result != HasReturnvaluesIF::RETURN_OK){ - ipcStore->deleteData(storeAddress); - } return result; + } + result = data->serialize(&dataPtr, &size, maxSize, SerializeIF::Endianness::BIG); + if (result != HasReturnvaluesIF::RETURN_OK) { + ipcStore->deleteData(storeAddress); + return result; + } + + /* We don't need to report the objectId, as we receive REQUESTED data before the completion + success message. True aperiodic replies need to be reported with another dedicated message. */ + ActionMessage::setDataReply(&reply, replyId, storeAddress); + + /* If the sender needs to be hidden, for example to handle packet + as unrequested reply, this will be done here. */ + if (hideSender) { + result = MessageQueueSenderIF::sendMessage(reportTo, &reply); + } else { + result = queueToUse->sendMessage(reportTo, &reply); + } + + if (result != HasReturnvaluesIF::RETURN_OK) { + ipcStore->deleteData(storeAddress); + } + return result; } -void ActionHelper::resetHelper() { -} +void ActionHelper::resetHelper() {} -ReturnValue_t ActionHelper::reportData(MessageQueueId_t reportTo, - ActionId_t replyId, const uint8_t *data, size_t dataSize, - bool hideSender) { - CommandMessage reply; - store_address_t storeAddress; - ReturnValue_t result = ipcStore->addData(&storeAddress, data, dataSize); - if (result != HasReturnvaluesIF::RETURN_OK) { +ReturnValue_t ActionHelper::reportData(MessageQueueId_t reportTo, ActionId_t replyId, + const uint8_t* data, size_t dataSize, bool hideSender) { + CommandMessage reply; + store_address_t storeAddress; + ReturnValue_t result = ipcStore->addData(&storeAddress, data, dataSize); + if (result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "ActionHelper::reportData: Adding data to IPC store failed!" << std::endl; + sif::warning << "ActionHelper::reportData: Adding data to IPC store failed!" << std::endl; #else - sif::printWarning("ActionHelper::reportData: Adding data to IPC store failed!\n"); + sif::printWarning("ActionHelper::reportData: Adding data to IPC store failed!\n"); #endif - return result; - } - - /* We don't need to report the objectId, as we receive REQUESTED data before the completion - success message. True aperiodic replies need to be reported with another dedicated message. */ - ActionMessage::setDataReply(&reply, replyId, storeAddress); - - /* If the sender needs to be hidden, for example to handle packet - as unrequested reply, this will be done here. */ - if (hideSender) { - result = MessageQueueSenderIF::sendMessage(reportTo, &reply); - } - else { - result = queueToUse->sendMessage(reportTo, &reply); - } - - if (result != HasReturnvaluesIF::RETURN_OK) { - ipcStore->deleteData(storeAddress); - } return result; + } + + /* We don't need to report the objectId, as we receive REQUESTED data before the completion + success message. True aperiodic replies need to be reported with another dedicated message. */ + ActionMessage::setDataReply(&reply, replyId, storeAddress); + + /* If the sender needs to be hidden, for example to handle packet + as unrequested reply, this will be done here. */ + if (hideSender) { + result = MessageQueueSenderIF::sendMessage(reportTo, &reply); + } else { + result = queueToUse->sendMessage(reportTo, &reply); + } + + if (result != HasReturnvaluesIF::RETURN_OK) { + ipcStore->deleteData(storeAddress); + } + return result; } diff --git a/src/fsfw/action/ActionHelper.h b/src/fsfw/action/ActionHelper.h index c9024747..d86e87d2 100644 --- a/src/fsfw/action/ActionHelper.h +++ b/src/fsfw/action/ActionHelper.h @@ -1,9 +1,9 @@ #ifndef FSFW_ACTION_ACTIONHELPER_H_ #define FSFW_ACTION_ACTIONHELPER_H_ -#include "ActionMessage.h" -#include "../serialize/SerializeIF.h" #include "../ipc/MessageQueueIF.h" +#include "../serialize/SerializeIF.h" +#include "ActionMessage.h" /** * @brief Action Helper is a helper class which handles action messages * @@ -17,110 +17,110 @@ class HasActionsIF; class ActionHelper { -public: - /** - * Constructor of the action helper - * @param setOwner Pointer to the owner of the interface - * @param useThisQueue messageQueue to be used, can be set during - * initialize function as well. - */ - ActionHelper(HasActionsIF* setOwner, MessageQueueIF* useThisQueue); + public: + /** + * Constructor of the action helper + * @param setOwner Pointer to the owner of the interface + * @param useThisQueue messageQueue to be used, can be set during + * initialize function as well. + */ + ActionHelper(HasActionsIF* setOwner, MessageQueueIF* useThisQueue); - virtual ~ActionHelper(); - /** - * Function to be called from the owner with a new command message - * - * If the message is a valid action message the helper will use the - * executeAction function from HasActionsIF. - * If the message is invalid or the callback fails a message reply will be - * send to the sender of the message automatically. - * - * @param command Pointer to a command message received by the owner - * @return HasReturnvaluesIF::RETURN_OK if the message is a action message, - * CommandMessage::UNKNOW_COMMAND if this message ID is unkown - */ - ReturnValue_t handleActionMessage(CommandMessage* command); - /** - * Helper initialize function. Must be called before use of any other - * helper function - * @param queueToUse_ Pointer to the messageQueue to be used, optional - * if queue was set in constructor - * @return Returns RETURN_OK if successful - */ - ReturnValue_t initialize(MessageQueueIF* queueToUse_ = nullptr); - /** - * Function to be called from the owner to send a step message. - * Success or failure will be determined by the result value. - * - * @param step Number of steps already done - * @param reportTo The messageQueueId to report the step message to - * @param commandId ID of the executed command - * @param result Result of the execution - */ - void step(uint8_t step, MessageQueueId_t reportTo, - ActionId_t commandId, + virtual ~ActionHelper(); + /** + * Function to be called from the owner with a new command message + * + * If the message is a valid action message the helper will use the + * executeAction function from HasActionsIF. + * If the message is invalid or the callback fails a message reply will be + * send to the sender of the message automatically. + * + * @param command Pointer to a command message received by the owner + * @return HasReturnvaluesIF::RETURN_OK if the message is a action message, + * CommandMessage::UNKNOW_COMMAND if this message ID is unkown + */ + ReturnValue_t handleActionMessage(CommandMessage* command); + /** + * Helper initialize function. Must be called before use of any other + * helper function + * @param queueToUse_ Pointer to the messageQueue to be used, optional + * if queue was set in constructor + * @return Returns RETURN_OK if successful + */ + ReturnValue_t initialize(MessageQueueIF* queueToUse_ = nullptr); + /** + * Function to be called from the owner to send a step message. + * Success or failure will be determined by the result value. + * + * @param step Number of steps already done + * @param reportTo The messageQueueId to report the step message to + * @param commandId ID of the executed command + * @param result Result of the execution + */ + void step(uint8_t step, MessageQueueId_t reportTo, ActionId_t commandId, ReturnValue_t result = HasReturnvaluesIF::RETURN_OK); - /** - * Function to be called by the owner to send a action completion message - * @param success Specify whether action was completed successfully or not. - * @param reportTo MessageQueueId_t to report the action completion message to - * @param commandId ID of the executed command - * @param result Result of the execution - */ - void finish(bool success, MessageQueueId_t reportTo, ActionId_t commandId, - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK); - /** - * Function to be called by the owner if an action does report data. - * Takes a SerializeIF* pointer and serializes it into the IPC store. - * @param reportTo MessageQueueId_t to report the action completion - * message to - * @param replyId ID of the executed command - * @param data Pointer to the data - * @return Returns RETURN_OK if successful, otherwise failure code - */ - ReturnValue_t reportData(MessageQueueId_t reportTo, ActionId_t replyId, - SerializeIF* data, bool hideSender = false); - /** - * Function to be called by the owner if an action does report data. - * Takes the raw data and writes it into the IPC store. - * @param reportTo MessageQueueId_t to report the action completion - * message to - * @param replyId ID of the executed command - * @param data Pointer to the data - * @return Returns RETURN_OK if successful, otherwise failure code - */ - ReturnValue_t reportData(MessageQueueId_t reportTo, ActionId_t replyId, - const uint8_t* data, size_t dataSize, bool hideSender = false); - /** - * Function to setup the MessageQueueIF* of the helper. Can be used to - * set the MessageQueueIF* if message queue is unavailable at construction - * and initialize but must be setup before first call of other functions. - * @param queue Queue to be used by the helper - */ - void setQueueToUse(MessageQueueIF *queue); -protected: - //! Increase of value of this per step - static const uint8_t STEP_OFFSET = 1; - //! Pointer to the owner - HasActionsIF* owner; - //! Queue to be used as response sender, has to be set in ctor or with - //! setQueueToUse - MessageQueueIF* queueToUse; - //! Pointer to an IPC Store, initialized during construction or - StorageManagerIF* ipcStore = nullptr; + /** + * Function to be called by the owner to send a action completion message + * @param success Specify whether action was completed successfully or not. + * @param reportTo MessageQueueId_t to report the action completion message to + * @param commandId ID of the executed command + * @param result Result of the execution + */ + void finish(bool success, MessageQueueId_t reportTo, ActionId_t commandId, + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK); + /** + * Function to be called by the owner if an action does report data. + * Takes a SerializeIF* pointer and serializes it into the IPC store. + * @param reportTo MessageQueueId_t to report the action completion + * message to + * @param replyId ID of the executed command + * @param data Pointer to the data + * @return Returns RETURN_OK if successful, otherwise failure code + */ + ReturnValue_t reportData(MessageQueueId_t reportTo, ActionId_t replyId, SerializeIF* data, + bool hideSender = false); + /** + * Function to be called by the owner if an action does report data. + * Takes the raw data and writes it into the IPC store. + * @param reportTo MessageQueueId_t to report the action completion + * message to + * @param replyId ID of the executed command + * @param data Pointer to the data + * @return Returns RETURN_OK if successful, otherwise failure code + */ + ReturnValue_t reportData(MessageQueueId_t reportTo, ActionId_t replyId, const uint8_t* data, + size_t dataSize, bool hideSender = false); + /** + * Function to setup the MessageQueueIF* of the helper. Can be used to + * set the MessageQueueIF* if message queue is unavailable at construction + * and initialize but must be setup before first call of other functions. + * @param queue Queue to be used by the helper + */ + void setQueueToUse(MessageQueueIF* queue); - /** - * Internal function called by handleActionMessage - * @param commandedBy MessageQueueID of Commander - * @param actionId ID of action to be done - * @param dataAddress Address of additional data in IPC Store - */ - virtual void prepareExecution(MessageQueueId_t commandedBy, - ActionId_t actionId, store_address_t dataAddress); - /** - * @brief Default implementation is empty. - */ - virtual void resetHelper(); + protected: + //! Increase of value of this per step + static const uint8_t STEP_OFFSET = 1; + //! Pointer to the owner + HasActionsIF* owner; + //! Queue to be used as response sender, has to be set in ctor or with + //! setQueueToUse + MessageQueueIF* queueToUse; + //! Pointer to an IPC Store, initialized during construction or + StorageManagerIF* ipcStore = nullptr; + + /** + * Internal function called by handleActionMessage + * @param commandedBy MessageQueueID of Commander + * @param actionId ID of action to be done + * @param dataAddress Address of additional data in IPC Store + */ + virtual void prepareExecution(MessageQueueId_t commandedBy, ActionId_t actionId, + store_address_t dataAddress); + /** + * @brief Default implementation is empty. + */ + virtual void resetHelper(); }; #endif /* FSFW_ACTION_ACTIONHELPER_H_ */ diff --git a/src/fsfw/action/ActionMessage.cpp b/src/fsfw/action/ActionMessage.cpp index 7d66c57f..40a516b1 100644 --- a/src/fsfw/action/ActionMessage.cpp +++ b/src/fsfw/action/ActionMessage.cpp @@ -1,81 +1,77 @@ #include "fsfw/action.h" - #include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/storagemanager/StorageManagerIF.h" -ActionMessage::ActionMessage() { -} +ActionMessage::ActionMessage() {} -ActionMessage::~ActionMessage() { -} +ActionMessage::~ActionMessage() {} void ActionMessage::setCommand(CommandMessage* message, ActionId_t fid, - store_address_t parameters) { - message->setCommand(EXECUTE_ACTION); - message->setParameter(fid); - message->setParameter2(parameters.raw); + store_address_t parameters) { + message->setCommand(EXECUTE_ACTION); + message->setParameter(fid); + message->setParameter2(parameters.raw); } ActionId_t ActionMessage::getActionId(const CommandMessage* message) { - return ActionId_t(message->getParameter()); + return ActionId_t(message->getParameter()); } store_address_t ActionMessage::getStoreId(const CommandMessage* message) { - store_address_t temp; - temp.raw = message->getParameter2(); - return temp; + store_address_t temp; + temp.raw = message->getParameter2(); + return temp; } void ActionMessage::setStepReply(CommandMessage* message, ActionId_t fid, uint8_t step, - ReturnValue_t result) { - if (result == HasReturnvaluesIF::RETURN_OK) { - message->setCommand(STEP_SUCCESS); - } else { - message->setCommand(STEP_FAILED); - } - message->setParameter(fid); - message->setParameter2((step << 16) + result); + ReturnValue_t result) { + if (result == HasReturnvaluesIF::RETURN_OK) { + message->setCommand(STEP_SUCCESS); + } else { + message->setCommand(STEP_FAILED); + } + message->setParameter(fid); + message->setParameter2((step << 16) + result); } uint8_t ActionMessage::getStep(const CommandMessage* message) { - return uint8_t((message->getParameter2() >> 16) & 0xFF); + return uint8_t((message->getParameter2() >> 16) & 0xFF); } ReturnValue_t ActionMessage::getReturnCode(const CommandMessage* message) { - return message->getParameter2() & 0xFFFF; + return message->getParameter2() & 0xFFFF; } void ActionMessage::setDataReply(CommandMessage* message, ActionId_t actionId, - store_address_t data) { - message->setCommand(DATA_REPLY); - message->setParameter(actionId); - message->setParameter2(data.raw); + store_address_t data) { + message->setCommand(DATA_REPLY); + message->setParameter(actionId); + message->setParameter2(data.raw); } -void ActionMessage::setCompletionReply(CommandMessage* message, - ActionId_t fid, bool success, ReturnValue_t result) { - if (success) { - message->setCommand(COMPLETION_SUCCESS); - } - else { - message->setCommand(COMPLETION_FAILED); - } - message->setParameter(fid); - message->setParameter2(result); +void ActionMessage::setCompletionReply(CommandMessage* message, ActionId_t fid, bool success, + ReturnValue_t result) { + if (success) { + message->setCommand(COMPLETION_SUCCESS); + } else { + message->setCommand(COMPLETION_FAILED); + } + message->setParameter(fid); + message->setParameter2(result); } void ActionMessage::clear(CommandMessage* message) { - switch(message->getCommand()) { + switch (message->getCommand()) { case EXECUTE_ACTION: case DATA_REPLY: { - StorageManagerIF *ipcStore = ObjectManager::instance()->get( - objects::IPC_STORE); - if (ipcStore != NULL) { - ipcStore->deleteData(getStoreId(message)); - } - break; + StorageManagerIF* ipcStore = + ObjectManager::instance()->get(objects::IPC_STORE); + if (ipcStore != NULL) { + ipcStore->deleteData(getStoreId(message)); + } + break; } default: - break; - } + break; + } } diff --git a/src/fsfw/action/ActionMessage.h b/src/fsfw/action/ActionMessage.h index c7570c9d..bd12cc19 100644 --- a/src/fsfw/action/ActionMessage.h +++ b/src/fsfw/action/ActionMessage.h @@ -14,34 +14,33 @@ using ActionId_t = uint32_t; * ActionHelper are able to process these messages. */ class ActionMessage { -private: - ActionMessage(); -public: - static const uint8_t MESSAGE_ID = messagetypes::ACTION; - static const Command_t EXECUTE_ACTION = MAKE_COMMAND_ID(1); - static const Command_t STEP_SUCCESS = MAKE_COMMAND_ID(2); - static const Command_t STEP_FAILED = MAKE_COMMAND_ID(3); - static const Command_t DATA_REPLY = MAKE_COMMAND_ID(4); - static const Command_t COMPLETION_SUCCESS = MAKE_COMMAND_ID(5); - static const Command_t COMPLETION_FAILED = MAKE_COMMAND_ID(6); + private: + ActionMessage(); - virtual ~ActionMessage(); - static void setCommand(CommandMessage* message, ActionId_t fid, - store_address_t parameters); + public: + static const uint8_t MESSAGE_ID = messagetypes::ACTION; + static const Command_t EXECUTE_ACTION = MAKE_COMMAND_ID(1); + static const Command_t STEP_SUCCESS = MAKE_COMMAND_ID(2); + static const Command_t STEP_FAILED = MAKE_COMMAND_ID(3); + static const Command_t DATA_REPLY = MAKE_COMMAND_ID(4); + static const Command_t COMPLETION_SUCCESS = MAKE_COMMAND_ID(5); + static const Command_t COMPLETION_FAILED = MAKE_COMMAND_ID(6); - static ActionId_t getActionId(const CommandMessage* message ); - static store_address_t getStoreId(const CommandMessage* message); + virtual ~ActionMessage(); + static void setCommand(CommandMessage* message, ActionId_t fid, store_address_t parameters); - static void setStepReply(CommandMessage* message, ActionId_t fid, - uint8_t step, ReturnValue_t result = HasReturnvaluesIF::RETURN_OK); - static uint8_t getStep(const CommandMessage* message ); - static ReturnValue_t getReturnCode(const CommandMessage* message ); - static void setDataReply(CommandMessage* message, ActionId_t actionId, - store_address_t data); - static void setCompletionReply(CommandMessage* message, ActionId_t fid, - bool success, ReturnValue_t result = HasReturnvaluesIF::RETURN_OK); + static ActionId_t getActionId(const CommandMessage* message); + static store_address_t getStoreId(const CommandMessage* message); - static void clear(CommandMessage* message); + static void setStepReply(CommandMessage* message, ActionId_t fid, uint8_t step, + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK); + static uint8_t getStep(const CommandMessage* message); + static ReturnValue_t getReturnCode(const CommandMessage* message); + static void setDataReply(CommandMessage* message, ActionId_t actionId, store_address_t data); + static void setCompletionReply(CommandMessage* message, ActionId_t fid, bool success, + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK); + + static void clear(CommandMessage* message); }; #endif /* FSFW_ACTION_ACTIONMESSAGE_H_ */ diff --git a/src/fsfw/action/CommandActionHelper.cpp b/src/fsfw/action/CommandActionHelper.cpp index b46dcceb..19d8e9b8 100644 --- a/src/fsfw/action/CommandActionHelper.cpp +++ b/src/fsfw/action/CommandActionHelper.cpp @@ -1,125 +1,115 @@ #include "fsfw/action.h" - #include "fsfw/objectmanager/ObjectManager.h" -CommandActionHelper::CommandActionHelper(CommandsActionsIF *setOwner) : - owner(setOwner), queueToUse(NULL), ipcStore( - NULL), commandCount(0), lastTarget(0) { -} +CommandActionHelper::CommandActionHelper(CommandsActionsIF *setOwner) + : owner(setOwner), queueToUse(NULL), ipcStore(NULL), commandCount(0), lastTarget(0) {} -CommandActionHelper::~CommandActionHelper() { -} +CommandActionHelper::~CommandActionHelper() {} -ReturnValue_t CommandActionHelper::commandAction(object_id_t commandTo, - ActionId_t actionId, SerializeIF *data) { - HasActionsIF *receiver = ObjectManager::instance()->get(commandTo); - if (receiver == NULL) { - return CommandsActionsIF::OBJECT_HAS_NO_FUNCTIONS; - } - store_address_t storeId; - uint8_t *storePointer; - size_t maxSize = data->getSerializedSize(); - ReturnValue_t result = ipcStore->getFreeElement(&storeId, maxSize, - &storePointer); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - size_t size = 0; - result = data->serialize(&storePointer, &size, maxSize, - SerializeIF::Endianness::BIG); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return sendCommand(receiver->getCommandQueue(), actionId, storeId); -} - -ReturnValue_t CommandActionHelper::commandAction(object_id_t commandTo, - ActionId_t actionId, const uint8_t *data, uint32_t size) { -// if (commandCount != 0) { -// return CommandsFunctionsIF::ALREADY_COMMANDING; -// } - HasActionsIF *receiver = ObjectManager::instance()->get(commandTo); - if (receiver == NULL) { - return CommandsActionsIF::OBJECT_HAS_NO_FUNCTIONS; - } - store_address_t storeId; - ReturnValue_t result = ipcStore->addData(&storeId, data, size); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return sendCommand(receiver->getCommandQueue(), actionId, storeId); -} - -ReturnValue_t CommandActionHelper::sendCommand(MessageQueueId_t queueId, - ActionId_t actionId, store_address_t storeId) { - CommandMessage command; - ActionMessage::setCommand(&command, actionId, storeId); - ReturnValue_t result = queueToUse->sendMessage(queueId, &command); - if (result != HasReturnvaluesIF::RETURN_OK) { - ipcStore->deleteData(storeId); - } - lastTarget = queueId; - commandCount++; +ReturnValue_t CommandActionHelper::commandAction(object_id_t commandTo, ActionId_t actionId, + SerializeIF *data) { + HasActionsIF *receiver = ObjectManager::instance()->get(commandTo); + if (receiver == NULL) { + return CommandsActionsIF::OBJECT_HAS_NO_FUNCTIONS; + } + store_address_t storeId; + uint8_t *storePointer; + size_t maxSize = data->getSerializedSize(); + ReturnValue_t result = ipcStore->getFreeElement(&storeId, maxSize, &storePointer); + if (result != HasReturnvaluesIF::RETURN_OK) { return result; + } + size_t size = 0; + result = data->serialize(&storePointer, &size, maxSize, SerializeIF::Endianness::BIG); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return sendCommand(receiver->getCommandQueue(), actionId, storeId); +} + +ReturnValue_t CommandActionHelper::commandAction(object_id_t commandTo, ActionId_t actionId, + const uint8_t *data, uint32_t size) { + // if (commandCount != 0) { + // return CommandsFunctionsIF::ALREADY_COMMANDING; + // } + HasActionsIF *receiver = ObjectManager::instance()->get(commandTo); + if (receiver == NULL) { + return CommandsActionsIF::OBJECT_HAS_NO_FUNCTIONS; + } + store_address_t storeId; + ReturnValue_t result = ipcStore->addData(&storeId, data, size); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return sendCommand(receiver->getCommandQueue(), actionId, storeId); +} + +ReturnValue_t CommandActionHelper::sendCommand(MessageQueueId_t queueId, ActionId_t actionId, + store_address_t storeId) { + CommandMessage command; + ActionMessage::setCommand(&command, actionId, storeId); + ReturnValue_t result = queueToUse->sendMessage(queueId, &command); + if (result != HasReturnvaluesIF::RETURN_OK) { + ipcStore->deleteData(storeId); + } + lastTarget = queueId; + commandCount++; + return result; } ReturnValue_t CommandActionHelper::initialize() { - ipcStore = ObjectManager::instance()->get(objects::IPC_STORE); - if (ipcStore == NULL) { - return HasReturnvaluesIF::RETURN_FAILED; - } + ipcStore = ObjectManager::instance()->get(objects::IPC_STORE); + if (ipcStore == NULL) { + return HasReturnvaluesIF::RETURN_FAILED; + } - queueToUse = owner->getCommandQueuePtr(); - if (queueToUse == NULL) { - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + queueToUse = owner->getCommandQueuePtr(); + if (queueToUse == NULL) { + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t CommandActionHelper::handleReply(CommandMessage *reply) { - if (reply->getSender() != lastTarget) { - return HasReturnvaluesIF::RETURN_FAILED; - } - switch (reply->getCommand()) { + if (reply->getSender() != lastTarget) { + return HasReturnvaluesIF::RETURN_FAILED; + } + switch (reply->getCommand()) { case ActionMessage::COMPLETION_SUCCESS: - commandCount--; - owner->completionSuccessfulReceived(ActionMessage::getActionId(reply)); - return HasReturnvaluesIF::RETURN_OK; + commandCount--; + owner->completionSuccessfulReceived(ActionMessage::getActionId(reply)); + return HasReturnvaluesIF::RETURN_OK; case ActionMessage::COMPLETION_FAILED: - commandCount--; - owner->completionFailedReceived(ActionMessage::getActionId(reply), - ActionMessage::getReturnCode(reply)); - return HasReturnvaluesIF::RETURN_OK; + commandCount--; + owner->completionFailedReceived(ActionMessage::getActionId(reply), + ActionMessage::getReturnCode(reply)); + return HasReturnvaluesIF::RETURN_OK; case ActionMessage::STEP_SUCCESS: - owner->stepSuccessfulReceived(ActionMessage::getActionId(reply), - ActionMessage::getStep(reply)); - return HasReturnvaluesIF::RETURN_OK; + owner->stepSuccessfulReceived(ActionMessage::getActionId(reply), + ActionMessage::getStep(reply)); + return HasReturnvaluesIF::RETURN_OK; case ActionMessage::STEP_FAILED: - commandCount--; - owner->stepFailedReceived(ActionMessage::getActionId(reply), - ActionMessage::getStep(reply), - ActionMessage::getReturnCode(reply)); - return HasReturnvaluesIF::RETURN_OK; + commandCount--; + owner->stepFailedReceived(ActionMessage::getActionId(reply), ActionMessage::getStep(reply), + ActionMessage::getReturnCode(reply)); + return HasReturnvaluesIF::RETURN_OK; case ActionMessage::DATA_REPLY: - extractDataForOwner(ActionMessage::getActionId(reply), - ActionMessage::getStoreId(reply)); - return HasReturnvaluesIF::RETURN_OK; + extractDataForOwner(ActionMessage::getActionId(reply), ActionMessage::getStoreId(reply)); + return HasReturnvaluesIF::RETURN_OK; default: - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; + } } -uint8_t CommandActionHelper::getCommandCount() const { - return commandCount; -} +uint8_t CommandActionHelper::getCommandCount() const { return commandCount; } void CommandActionHelper::extractDataForOwner(ActionId_t actionId, store_address_t storeId) { - const uint8_t * data = NULL; - size_t size = 0; - ReturnValue_t result = ipcStore->getData(storeId, &data, &size); - if (result != HasReturnvaluesIF::RETURN_OK) { - return; - } - owner->dataReceived(actionId, data, size); - ipcStore->deleteData(storeId); + const uint8_t *data = NULL; + size_t size = 0; + ReturnValue_t result = ipcStore->getData(storeId, &data, &size); + if (result != HasReturnvaluesIF::RETURN_OK) { + return; + } + owner->dataReceived(actionId, data, size); + ipcStore->deleteData(storeId); } diff --git a/src/fsfw/action/CommandActionHelper.h b/src/fsfw/action/CommandActionHelper.h index ce297e66..dd8ad7f1 100644 --- a/src/fsfw/action/CommandActionHelper.h +++ b/src/fsfw/action/CommandActionHelper.h @@ -2,35 +2,35 @@ #define COMMANDACTIONHELPER_H_ #include "ActionMessage.h" +#include "fsfw/ipc/MessageQueueIF.h" #include "fsfw/objectmanager/ObjectManagerIF.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" #include "fsfw/serialize/SerializeIF.h" #include "fsfw/storagemanager/StorageManagerIF.h" -#include "fsfw/ipc/MessageQueueIF.h" class CommandsActionsIF; class CommandActionHelper { - friend class CommandsActionsIF; -public: - CommandActionHelper(CommandsActionsIF* owner); - virtual ~CommandActionHelper(); - ReturnValue_t commandAction(object_id_t commandTo, - ActionId_t actionId, const uint8_t* data, uint32_t size); - ReturnValue_t commandAction(object_id_t commandTo, - ActionId_t actionId, SerializeIF* data); - ReturnValue_t initialize(); - ReturnValue_t handleReply(CommandMessage* reply); - uint8_t getCommandCount() const; -private: - CommandsActionsIF* owner; - MessageQueueIF* queueToUse; - StorageManagerIF* ipcStore; - uint8_t commandCount; - MessageQueueId_t lastTarget; - void extractDataForOwner(ActionId_t actionId, store_address_t storeId); - ReturnValue_t sendCommand(MessageQueueId_t queueId, ActionId_t actionId, - store_address_t storeId); + friend class CommandsActionsIF; + + public: + CommandActionHelper(CommandsActionsIF* owner); + virtual ~CommandActionHelper(); + ReturnValue_t commandAction(object_id_t commandTo, ActionId_t actionId, const uint8_t* data, + uint32_t size); + ReturnValue_t commandAction(object_id_t commandTo, ActionId_t actionId, SerializeIF* data); + ReturnValue_t initialize(); + ReturnValue_t handleReply(CommandMessage* reply); + uint8_t getCommandCount() const; + + private: + CommandsActionsIF* owner; + MessageQueueIF* queueToUse; + StorageManagerIF* ipcStore; + uint8_t commandCount; + MessageQueueId_t lastTarget; + void extractDataForOwner(ActionId_t actionId, store_address_t storeId); + ReturnValue_t sendCommand(MessageQueueId_t queueId, ActionId_t actionId, store_address_t storeId); }; #endif /* COMMANDACTIONHELPER_H_ */ diff --git a/src/fsfw/action/CommandsActionsIF.h b/src/fsfw/action/CommandsActionsIF.h index fe7e856c..5870a9f2 100644 --- a/src/fsfw/action/CommandsActionsIF.h +++ b/src/fsfw/action/CommandsActionsIF.h @@ -1,9 +1,9 @@ #ifndef FSFW_ACTION_COMMANDSACTIONSIF_H_ #define FSFW_ACTION_COMMANDSACTIONSIF_H_ -#include "CommandActionHelper.h" -#include "../returnvalues/HasReturnvaluesIF.h" #include "../ipc/MessageQueueIF.h" +#include "../returnvalues/HasReturnvaluesIF.h" +#include "CommandActionHelper.h" /** * Interface to separate commanding actions of other objects. @@ -15,23 +15,21 @@ * - replyReceived(id, step, cause) (if cause == OK, it's a success). */ class CommandsActionsIF { - friend class CommandActionHelper; -public: - static const uint8_t INTERFACE_ID = CLASS_ID::COMMANDS_ACTIONS_IF; - static const ReturnValue_t OBJECT_HAS_NO_FUNCTIONS = MAKE_RETURN_CODE(1); - static const ReturnValue_t ALREADY_COMMANDING = MAKE_RETURN_CODE(2); - virtual ~CommandsActionsIF() {} - virtual MessageQueueIF* getCommandQueuePtr() = 0; -protected: - virtual void stepSuccessfulReceived(ActionId_t actionId, uint8_t step) = 0; - virtual void stepFailedReceived(ActionId_t actionId, uint8_t step, - ReturnValue_t returnCode) = 0; - virtual void dataReceived(ActionId_t actionId, const uint8_t* data, - uint32_t size) = 0; - virtual void completionSuccessfulReceived(ActionId_t actionId) = 0; - virtual void completionFailedReceived(ActionId_t actionId, - ReturnValue_t returnCode) = 0; + friend class CommandActionHelper; + + public: + static const uint8_t INTERFACE_ID = CLASS_ID::COMMANDS_ACTIONS_IF; + static const ReturnValue_t OBJECT_HAS_NO_FUNCTIONS = MAKE_RETURN_CODE(1); + static const ReturnValue_t ALREADY_COMMANDING = MAKE_RETURN_CODE(2); + virtual ~CommandsActionsIF() {} + virtual MessageQueueIF* getCommandQueuePtr() = 0; + + protected: + virtual void stepSuccessfulReceived(ActionId_t actionId, uint8_t step) = 0; + virtual void stepFailedReceived(ActionId_t actionId, uint8_t step, ReturnValue_t returnCode) = 0; + virtual void dataReceived(ActionId_t actionId, const uint8_t* data, uint32_t size) = 0; + virtual void completionSuccessfulReceived(ActionId_t actionId) = 0; + virtual void completionFailedReceived(ActionId_t actionId, ReturnValue_t returnCode) = 0; }; - #endif /* FSFW_ACTION_COMMANDSACTIONSIF_H_ */ diff --git a/src/fsfw/action/HasActionsIF.h b/src/fsfw/action/HasActionsIF.h index 056e674c..acc502d7 100644 --- a/src/fsfw/action/HasActionsIF.h +++ b/src/fsfw/action/HasActionsIF.h @@ -1,11 +1,11 @@ #ifndef FSFW_ACTION_HASACTIONSIF_H_ #define FSFW_ACTION_HASACTIONSIF_H_ +#include "../ipc/MessageQueueIF.h" +#include "../returnvalues/HasReturnvaluesIF.h" #include "ActionHelper.h" #include "ActionMessage.h" #include "SimpleActionHelper.h" -#include "../returnvalues/HasReturnvaluesIF.h" -#include "../ipc/MessageQueueIF.h" /** * @brief @@ -34,30 +34,29 @@ * @ingroup interfaces */ class HasActionsIF { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::HAS_ACTIONS_IF; - static const ReturnValue_t IS_BUSY = MAKE_RETURN_CODE(1); - static const ReturnValue_t INVALID_PARAMETERS = MAKE_RETURN_CODE(2); - static const ReturnValue_t EXECUTION_FINISHED = MAKE_RETURN_CODE(3); - static const ReturnValue_t INVALID_ACTION_ID = MAKE_RETURN_CODE(4); - virtual ~HasActionsIF() { } - /** - * Function to get the MessageQueueId_t of the implementing object - * @return MessageQueueId_t of the object - */ - virtual MessageQueueId_t getCommandQueue() const = 0; - /** - * Execute or initialize the execution of a certain function. - * The ActionHelpers will execute this function and behave differently - * depending on the returnvalue. - * - * @return - * -@c EXECUTION_FINISHED Finish reply will be generated - * -@c Not RETURN_OK Step failure reply will be generated - */ - virtual ReturnValue_t executeAction(ActionId_t actionId, - MessageQueueId_t commandedBy, const uint8_t* data, size_t size) = 0; + public: + static const uint8_t INTERFACE_ID = CLASS_ID::HAS_ACTIONS_IF; + static const ReturnValue_t IS_BUSY = MAKE_RETURN_CODE(1); + static const ReturnValue_t INVALID_PARAMETERS = MAKE_RETURN_CODE(2); + static const ReturnValue_t EXECUTION_FINISHED = MAKE_RETURN_CODE(3); + static const ReturnValue_t INVALID_ACTION_ID = MAKE_RETURN_CODE(4); + virtual ~HasActionsIF() {} + /** + * Function to get the MessageQueueId_t of the implementing object + * @return MessageQueueId_t of the object + */ + virtual MessageQueueId_t getCommandQueue() const = 0; + /** + * Execute or initialize the execution of a certain function. + * The ActionHelpers will execute this function and behave differently + * depending on the returnvalue. + * + * @return + * -@c EXECUTION_FINISHED Finish reply will be generated + * -@c Not RETURN_OK Step failure reply will be generated + */ + virtual ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, + const uint8_t* data, size_t size) = 0; }; - #endif /* FSFW_ACTION_HASACTIONSIF_H_ */ diff --git a/src/fsfw/action/SimpleActionHelper.cpp b/src/fsfw/action/SimpleActionHelper.cpp index 7135ea62..894f0df6 100644 --- a/src/fsfw/action/SimpleActionHelper.cpp +++ b/src/fsfw/action/SimpleActionHelper.cpp @@ -1,74 +1,67 @@ #include "fsfw/action.h" -SimpleActionHelper::SimpleActionHelper(HasActionsIF* setOwner, - MessageQueueIF* useThisQueue) : - ActionHelper(setOwner, useThisQueue), isExecuting(false) { -} +SimpleActionHelper::SimpleActionHelper(HasActionsIF* setOwner, MessageQueueIF* useThisQueue) + : ActionHelper(setOwner, useThisQueue), isExecuting(false) {} -SimpleActionHelper::~SimpleActionHelper() { -} +SimpleActionHelper::~SimpleActionHelper() {} void SimpleActionHelper::step(ReturnValue_t result) { - // STEP_OFFESET is subtracted to compensate for adding offset in base - // method, which is not necessary here. - ActionHelper::step(stepCount - STEP_OFFSET, lastCommander, lastAction, - result); - if (result != HasReturnvaluesIF::RETURN_OK) { - resetHelper(); - } + // STEP_OFFESET is subtracted to compensate for adding offset in base + // method, which is not necessary here. + ActionHelper::step(stepCount - STEP_OFFSET, lastCommander, lastAction, result); + if (result != HasReturnvaluesIF::RETURN_OK) { + resetHelper(); + } } void SimpleActionHelper::finish(ReturnValue_t result) { - ActionHelper::finish(lastCommander, lastAction, result); - resetHelper(); + ActionHelper::finish(lastCommander, lastAction, result); + resetHelper(); } ReturnValue_t SimpleActionHelper::reportData(SerializeIF* data) { - return ActionHelper::reportData(lastCommander, lastAction, data); + return ActionHelper::reportData(lastCommander, lastAction, data); } void SimpleActionHelper::resetHelper() { - stepCount = 0; - isExecuting = false; - lastAction = 0; - lastCommander = 0; + stepCount = 0; + isExecuting = false; + lastAction = 0; + lastCommander = 0; } -void SimpleActionHelper::prepareExecution(MessageQueueId_t commandedBy, - ActionId_t actionId, store_address_t dataAddress) { - CommandMessage reply; - if (isExecuting) { - ipcStore->deleteData(dataAddress); - ActionMessage::setStepReply(&reply, actionId, 0, - HasActionsIF::IS_BUSY); - queueToUse->sendMessage(commandedBy, &reply); - } - const uint8_t* dataPtr = NULL; - size_t size = 0; - ReturnValue_t result = ipcStore->getData(dataAddress, &dataPtr, &size); - if (result != HasReturnvaluesIF::RETURN_OK) { - ActionMessage::setStepReply(&reply, actionId, 0, result); - queueToUse->sendMessage(commandedBy, &reply); - return; - } - lastCommander = commandedBy; - lastAction = actionId; - result = owner->executeAction(actionId, commandedBy, dataPtr, size); +void SimpleActionHelper::prepareExecution(MessageQueueId_t commandedBy, ActionId_t actionId, + store_address_t dataAddress) { + CommandMessage reply; + if (isExecuting) { ipcStore->deleteData(dataAddress); - switch (result) { + ActionMessage::setStepReply(&reply, actionId, 0, HasActionsIF::IS_BUSY); + queueToUse->sendMessage(commandedBy, &reply); + } + const uint8_t* dataPtr = NULL; + size_t size = 0; + ReturnValue_t result = ipcStore->getData(dataAddress, &dataPtr, &size); + if (result != HasReturnvaluesIF::RETURN_OK) { + ActionMessage::setStepReply(&reply, actionId, 0, result); + queueToUse->sendMessage(commandedBy, &reply); + return; + } + lastCommander = commandedBy; + lastAction = actionId; + result = owner->executeAction(actionId, commandedBy, dataPtr, size); + ipcStore->deleteData(dataAddress); + switch (result) { case HasReturnvaluesIF::RETURN_OK: - isExecuting = true; - stepCount++; - break; + isExecuting = true; + stepCount++; + break; case HasActionsIF::EXECUTION_FINISHED: - ActionMessage::setCompletionReply(&reply, actionId, - true, HasReturnvaluesIF::RETURN_OK); - queueToUse->sendMessage(commandedBy, &reply); - break; + ActionMessage::setCompletionReply(&reply, actionId, true, HasReturnvaluesIF::RETURN_OK); + queueToUse->sendMessage(commandedBy, &reply); + break; default: - ActionMessage::setStepReply(&reply, actionId, 0, result); - queueToUse->sendMessage(commandedBy, &reply); - break; - } - + ActionMessage::setStepReply(&reply, actionId, 0, result); + queueToUse->sendMessage(commandedBy, &reply); + break; + } } diff --git a/src/fsfw/action/SimpleActionHelper.h b/src/fsfw/action/SimpleActionHelper.h index 7c6c4e00..5cb85fbd 100644 --- a/src/fsfw/action/SimpleActionHelper.h +++ b/src/fsfw/action/SimpleActionHelper.h @@ -8,23 +8,24 @@ * at a time but remembers last commander and last action which * simplifies usage */ -class SimpleActionHelper: public ActionHelper { -public: - SimpleActionHelper(HasActionsIF* setOwner, MessageQueueIF* useThisQueue); - virtual ~SimpleActionHelper(); - void step(ReturnValue_t result = HasReturnvaluesIF::RETURN_OK); - void finish(ReturnValue_t result = HasReturnvaluesIF::RETURN_OK); - ReturnValue_t reportData(SerializeIF* data); +class SimpleActionHelper : public ActionHelper { + public: + SimpleActionHelper(HasActionsIF* setOwner, MessageQueueIF* useThisQueue); + virtual ~SimpleActionHelper(); + void step(ReturnValue_t result = HasReturnvaluesIF::RETURN_OK); + void finish(ReturnValue_t result = HasReturnvaluesIF::RETURN_OK); + ReturnValue_t reportData(SerializeIF* data); -protected: - void prepareExecution(MessageQueueId_t commandedBy, ActionId_t actionId, - store_address_t dataAddress); - virtual void resetHelper(); -private: - bool isExecuting; - MessageQueueId_t lastCommander = MessageQueueIF::NO_QUEUE; - ActionId_t lastAction = 0; - uint8_t stepCount = 0; + protected: + void prepareExecution(MessageQueueId_t commandedBy, ActionId_t actionId, + store_address_t dataAddress); + virtual void resetHelper(); + + private: + bool isExecuting; + MessageQueueId_t lastCommander = MessageQueueIF::NO_QUEUE; + ActionId_t lastAction = 0; + uint8_t stepCount = 0; }; #endif /* SIMPLEACTIONHELPER_H_ */ diff --git a/src/fsfw/cfdp/CFDPHandler.cpp b/src/fsfw/cfdp/CFDPHandler.cpp index 79712bf2..96baa98c 100644 --- a/src/fsfw/cfdp/CFDPHandler.cpp +++ b/src/fsfw/cfdp/CFDPHandler.cpp @@ -1,60 +1,57 @@ -#include "fsfw/ipc/CommandMessage.h" -#include "fsfw/storagemanager/storeAddress.h" #include "fsfw/cfdp/CFDPHandler.h" -#include "fsfw/cfdp/CFDPMessage.h" -#include "fsfw/tmtcservices/AcceptsTelemetryIF.h" +#include "fsfw/cfdp/CFDPMessage.h" +#include "fsfw/ipc/CommandMessage.h" #include "fsfw/ipc/QueueFactory.h" #include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/storagemanager/storeAddress.h" +#include "fsfw/tmtcservices/AcceptsTelemetryIF.h" object_id_t CFDPHandler::packetSource = 0; object_id_t CFDPHandler::packetDestination = 0; -CFDPHandler::CFDPHandler(object_id_t setObjectId, CFDPDistributor* dist) : SystemObject(setObjectId) { - requestQueue = QueueFactory::instance()->createMessageQueue(CFDP_HANDLER_MAX_RECEPTION); - distributor = dist; +CFDPHandler::CFDPHandler(object_id_t setObjectId, CFDPDistributor* dist) + : SystemObject(setObjectId) { + requestQueue = QueueFactory::instance()->createMessageQueue(CFDP_HANDLER_MAX_RECEPTION); + distributor = dist; } CFDPHandler::~CFDPHandler() {} ReturnValue_t CFDPHandler::initialize() { - ReturnValue_t result = SystemObject::initialize(); - if (result != RETURN_OK) { - return result; - } - this->distributor->registerHandler(this); - return HasReturnvaluesIF::RETURN_OK; + ReturnValue_t result = SystemObject::initialize(); + if (result != RETURN_OK) { + return result; + } + this->distributor->registerHandler(this); + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t CFDPHandler::handleRequest(store_address_t storeId) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "CFDPHandler::handleRequest" << std::endl; + sif::debug << "CFDPHandler::handleRequest" << std::endl; #else - sif::printDebug("CFDPHandler::handleRequest\n"); + sif::printDebug("CFDPHandler::handleRequest\n"); #endif /* !FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif - //TODO read out packet from store using storeId + // TODO read out packet from store using storeId - return RETURN_OK; + return RETURN_OK; } ReturnValue_t CFDPHandler::performOperation(uint8_t opCode) { - ReturnValue_t status = RETURN_OK; - CommandMessage currentMessage; - for (status = this->requestQueue->receiveMessage(¤tMessage); status == RETURN_OK; - status = this->requestQueue->receiveMessage(¤tMessage)) { - store_address_t storeId = CFDPMessage::getStoreId(¤tMessage); - this->handleRequest(storeId); - } - return RETURN_OK; + ReturnValue_t status = RETURN_OK; + CommandMessage currentMessage; + for (status = this->requestQueue->receiveMessage(¤tMessage); status == RETURN_OK; + status = this->requestQueue->receiveMessage(¤tMessage)) { + store_address_t storeId = CFDPMessage::getStoreId(¤tMessage); + this->handleRequest(storeId); + } + return RETURN_OK; } -uint16_t CFDPHandler::getIdentifier() { - return 0; -} +uint16_t CFDPHandler::getIdentifier() { return 0; } -MessageQueueId_t CFDPHandler::getRequestQueue() { - return this->requestQueue->getId(); -} +MessageQueueId_t CFDPHandler::getRequestQueue() { return this->requestQueue->getId(); } diff --git a/src/fsfw/cfdp/CFDPHandler.h b/src/fsfw/cfdp/CFDPHandler.h index 2f11eee3..abbac6b6 100644 --- a/src/fsfw/cfdp/CFDPHandler.h +++ b/src/fsfw/cfdp/CFDPHandler.h @@ -1,62 +1,63 @@ #ifndef FSFW_CFDP_CFDPHANDLER_H_ #define FSFW_CFDP_CFDPHANDLER_H_ -#include "fsfw/tmtcservices/AcceptsTelecommandsIF.h" +#include "fsfw/ipc/MessageQueueIF.h" #include "fsfw/objectmanager/SystemObject.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" #include "fsfw/tasks/ExecutableObjectIF.h" #include "fsfw/tcdistribution/CFDPDistributor.h" +#include "fsfw/tmtcservices/AcceptsTelecommandsIF.h" -#include "fsfw/ipc/MessageQueueIF.h" - -namespace Factory{ +namespace Factory { void setStaticFrameworkObjectIds(); } -class CFDPHandler : - public ExecutableObjectIF, - public AcceptsTelecommandsIF, - public SystemObject, - public HasReturnvaluesIF { - friend void (Factory::setStaticFrameworkObjectIds)(); -public: - CFDPHandler(object_id_t setObjectId, CFDPDistributor* distributor); - /** - * The destructor is empty. - */ - virtual ~CFDPHandler(); +class CFDPHandler : public ExecutableObjectIF, + public AcceptsTelecommandsIF, + public SystemObject, + public HasReturnvaluesIF { + friend void(Factory::setStaticFrameworkObjectIds)(); - virtual ReturnValue_t handleRequest(store_address_t storeId); + public: + CFDPHandler(object_id_t setObjectId, CFDPDistributor* distributor); + /** + * The destructor is empty. + */ + virtual ~CFDPHandler(); - virtual ReturnValue_t initialize() override; - virtual uint16_t getIdentifier() override; - MessageQueueId_t getRequestQueue() override; - ReturnValue_t performOperation(uint8_t opCode) override; - protected: - /** - * This is a complete instance of the telecommand reception queue - * of the class. It is initialized on construction of the class. - */ - MessageQueueIF* requestQueue = nullptr; + virtual ReturnValue_t handleRequest(store_address_t storeId); - CFDPDistributor* distributor = nullptr; + virtual ReturnValue_t initialize() override; + virtual uint16_t getIdentifier() override; + MessageQueueId_t getRequestQueue() override; + ReturnValue_t performOperation(uint8_t opCode) override; - /** - * The current CFDP packet to be processed. - * It is deleted after handleRequest was executed. - */ - CFDPPacketStored currentPacket; + protected: + /** + * This is a complete instance of the telecommand reception queue + * of the class. It is initialized on construction of the class. + */ + MessageQueueIF* requestQueue = nullptr; - static object_id_t packetSource; + CFDPDistributor* distributor = nullptr; - static object_id_t packetDestination; - private: - /** - * This constant sets the maximum number of packets accepted per call. - * Remember that one packet must be completely handled in one - * #handleRequest call. - */ - static const uint8_t CFDP_HANDLER_MAX_RECEPTION = 100; + /** + * The current CFDP packet to be processed. + * It is deleted after handleRequest was executed. + */ + CFDPPacketStored currentPacket; + + static object_id_t packetSource; + + static object_id_t packetDestination; + + private: + /** + * This constant sets the maximum number of packets accepted per call. + * Remember that one packet must be completely handled in one + * #handleRequest call. + */ + static const uint8_t CFDP_HANDLER_MAX_RECEPTION = 100; }; #endif /* FSFW_CFDP_CFDPHANDLER_H_ */ diff --git a/src/fsfw/cfdp/CFDPMessage.cpp b/src/fsfw/cfdp/CFDPMessage.cpp index c75b6b2c..fee55715 100644 --- a/src/fsfw/cfdp/CFDPMessage.cpp +++ b/src/fsfw/cfdp/CFDPMessage.cpp @@ -1,21 +1,17 @@ #include "CFDPMessage.h" -CFDPMessage::CFDPMessage() { -} +CFDPMessage::CFDPMessage() {} -CFDPMessage::~CFDPMessage() { -} +CFDPMessage::~CFDPMessage() {} -void CFDPMessage::setCommand(CommandMessage *message, - store_address_t cfdpPacket) { - message->setParameter(cfdpPacket.raw); +void CFDPMessage::setCommand(CommandMessage *message, store_address_t cfdpPacket) { + message->setParameter(cfdpPacket.raw); } store_address_t CFDPMessage::getStoreId(const CommandMessage *message) { - store_address_t storeAddressCFDPPacket; - storeAddressCFDPPacket = message->getParameter(); - return storeAddressCFDPPacket; + store_address_t storeAddressCFDPPacket; + storeAddressCFDPPacket = message->getParameter(); + return storeAddressCFDPPacket; } -void CFDPMessage::clear(CommandMessage *message) { -} +void CFDPMessage::clear(CommandMessage *message) {} diff --git a/src/fsfw/cfdp/CFDPMessage.h b/src/fsfw/cfdp/CFDPMessage.h index 5b321975..3de723eb 100644 --- a/src/fsfw/cfdp/CFDPMessage.h +++ b/src/fsfw/cfdp/CFDPMessage.h @@ -6,18 +6,18 @@ #include "fsfw/storagemanager/StorageManagerIF.h" class CFDPMessage { -private: - CFDPMessage(); -public: - static const uint8_t MESSAGE_ID = messagetypes::CFDP; + private: + CFDPMessage(); - virtual ~CFDPMessage(); - static void setCommand(CommandMessage* message, - store_address_t cfdpPacket); + public: + static const uint8_t MESSAGE_ID = messagetypes::CFDP; - static store_address_t getStoreId(const CommandMessage* message); + virtual ~CFDPMessage(); + static void setCommand(CommandMessage* message, store_address_t cfdpPacket); - static void clear(CommandMessage* message); + static store_address_t getStoreId(const CommandMessage* message); + + static void clear(CommandMessage* message); }; #endif /* FSFW_CFDP_CFDPMESSAGE_H_ */ diff --git a/src/fsfw/cfdp/FileSize.h b/src/fsfw/cfdp/FileSize.h index 3997d5a4..6dae9683 100644 --- a/src/fsfw/cfdp/FileSize.h +++ b/src/fsfw/cfdp/FileSize.h @@ -6,78 +6,73 @@ namespace cfdp { -struct FileSize: public SerializeIF { -public: - FileSize(): largeFile(false) {}; +struct FileSize : public SerializeIF { + public: + FileSize() : largeFile(false){}; - FileSize(uint64_t fileSize, bool isLarge = false) { - setFileSize(fileSize, isLarge); - }; + FileSize(uint64_t fileSize, bool isLarge = false) { setFileSize(fileSize, isLarge); }; - ReturnValue_t serialize(bool isLarge, uint8_t **buffer, size_t *size,size_t maxSize, - Endianness streamEndianness) { - this->largeFile = isLarge; - return serialize(buffer, size, maxSize, streamEndianness); + ReturnValue_t serialize(bool isLarge, uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) { + this->largeFile = isLarge; + return serialize(buffer, size, maxSize, streamEndianness); + } + + ReturnValue_t serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const override { + if (not largeFile) { + uint32_t fileSizeTyped = fileSize; + return SerializeAdapter::serialize(&fileSizeTyped, buffer, size, maxSize, streamEndianness); } + return SerializeAdapter::serialize(&fileSize, buffer, size, maxSize, streamEndianness); + } - ReturnValue_t serialize(uint8_t **buffer, size_t *size,size_t maxSize, - Endianness streamEndianness) const override { - if(not largeFile) { - uint32_t fileSizeTyped = fileSize; - return SerializeAdapter::serialize(&fileSizeTyped, buffer, size, maxSize, - streamEndianness); + size_t getSerializedSize() const override { + if (largeFile) { + return 8; + } else { + return 4; + } + } - } - return SerializeAdapter::serialize(&fileSize, buffer, size, maxSize, streamEndianness); + ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) override { + if (largeFile) { + return SerializeAdapter::deSerialize(&size, buffer, size, streamEndianness); + } else { + uint32_t sizeTmp = 0; + ReturnValue_t result = + SerializeAdapter::deSerialize(&sizeTmp, buffer, size, streamEndianness); + if (result == HasReturnvaluesIF::RETURN_OK) { + fileSize = sizeTmp; + } + return result; } + } - size_t getSerializedSize() const override { - if (largeFile) { - return 8; - } else { - return 4; - } + ReturnValue_t setFileSize(uint64_t fileSize, bool largeFile) { + if (not largeFile and fileSize > UINT32_MAX) { + // TODO: emit warning here + return HasReturnvaluesIF::RETURN_FAILED; } + this->fileSize = fileSize; + this->largeFile = largeFile; + return HasReturnvaluesIF::RETURN_OK; + } - ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) override { - if(largeFile) { - return SerializeAdapter::deSerialize(&size, buffer, size, streamEndianness); - } else { - uint32_t sizeTmp = 0; - ReturnValue_t result = SerializeAdapter::deSerialize(&sizeTmp, buffer, size, - streamEndianness); - if(result == HasReturnvaluesIF::RETURN_OK) { - fileSize = sizeTmp; - } - return result; - } + bool isLargeFile() const { return largeFile; } + uint64_t getSize(bool *largeFile = nullptr) const { + if (largeFile != nullptr) { + *largeFile = this->largeFile; } + return fileSize; + } - ReturnValue_t setFileSize(uint64_t fileSize, bool largeFile) { - if (not largeFile and fileSize > UINT32_MAX) { - // TODO: emit warning here - return HasReturnvaluesIF::RETURN_FAILED; - } - this->fileSize = fileSize; - this->largeFile = largeFile; - return HasReturnvaluesIF::RETURN_OK; - } - - bool isLargeFile() const { - return largeFile; - } - uint64_t getSize(bool* largeFile = nullptr) const { - if(largeFile != nullptr) { - *largeFile = this->largeFile; - } - return fileSize; - } -private: - uint64_t fileSize = 0; - bool largeFile = false; + private: + uint64_t fileSize = 0; + bool largeFile = false; }; -} +} // namespace cfdp #endif /* FSFW_SRC_FSFW_CFDP_FILESIZE_H_ */ diff --git a/src/fsfw/cfdp/definitions.h b/src/fsfw/cfdp/definitions.h index ffcbca97..eb21f5bf 100644 --- a/src/fsfw/cfdp/definitions.h +++ b/src/fsfw/cfdp/definitions.h @@ -2,10 +2,12 @@ #define FSFW_SRC_FSFW_CFDP_PDU_DEFINITIONS_H_ #include -#include + #include -#include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include + #include "fsfw/returnvalues/FwClassIds.h" +#include "fsfw/returnvalues/HasReturnvaluesIF.h" namespace cfdp { @@ -14,140 +16,122 @@ static constexpr uint8_t VERSION_BITS = 0b00100000; static constexpr uint8_t CFDP_CLASS_ID = CLASS_ID::CFDP; static constexpr ReturnValue_t INVALID_TLV_TYPE = - HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 1); + HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 1); static constexpr ReturnValue_t INVALID_DIRECTIVE_FIELDS = - HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 2); + HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 2); static constexpr ReturnValue_t INVALID_PDU_DATAFIELD_LEN = - HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 3); + HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 3); static constexpr ReturnValue_t INVALID_ACK_DIRECTIVE_FIELDS = - HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 4); + HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 4); //! Can not parse options. This can also occur because there are options //! available but the user did not pass a valid options array static constexpr ReturnValue_t METADATA_CANT_PARSE_OPTIONS = - HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 5); + HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 5); static constexpr ReturnValue_t NAK_CANT_PARSE_OPTIONS = - HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 6); + HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 6); static constexpr ReturnValue_t FINISHED_CANT_PARSE_FS_RESPONSES = - HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 6); + HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 6); static constexpr ReturnValue_t FILESTORE_REQUIRES_SECOND_FILE = - HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 8); + HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 8); //! Can not parse filestore response because user did not pass a valid instance //! or remaining size is invalid static constexpr ReturnValue_t FILESTORE_RESPONSE_CANT_PARSE_FS_MESSAGE = - HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 9); + HasReturnvaluesIF::makeReturnCode(CFDP_CLASS_ID, 9); //! Checksum types according to the SANA Checksum Types registry //! https://sanaregistry.org/r/checksum_identifiers/ enum ChecksumType { - // Modular legacy checksum - MODULAR = 0, - CRC_32_PROXIMITY_1 = 1, - CRC_32C = 2, - CRC_32 = 3, - NULL_CHECKSUM = 15 + // Modular legacy checksum + MODULAR = 0, + CRC_32_PROXIMITY_1 = 1, + CRC_32C = 2, + CRC_32 = 3, + NULL_CHECKSUM = 15 }; -enum PduType: bool { - FILE_DIRECTIVE = 0, - FILE_DATA = 1 +enum PduType : bool { FILE_DIRECTIVE = 0, FILE_DATA = 1 }; + +enum TransmissionModes : bool { ACKNOWLEDGED = 0, UNACKNOWLEDGED = 1 }; + +enum SegmentMetadataFlag : bool { NOT_PRESENT = 0, PRESENT = 1 }; + +enum Direction : bool { TOWARDS_RECEIVER = 0, TOWARDS_SENDER = 1 }; + +enum SegmentationControl : bool { + NO_RECORD_BOUNDARIES_PRESERVATION = 0, + RECORD_BOUNDARIES_PRESERVATION = 1 }; -enum TransmissionModes: bool { - ACKNOWLEDGED = 0, - UNACKNOWLEDGED = 1 +enum WidthInBytes : uint8_t { + // Only those are supported for now + ONE_BYTE = 1, + TWO_BYTES = 2, + FOUR_BYTES = 4, }; -enum SegmentMetadataFlag: bool { - NOT_PRESENT = 0, - PRESENT = 1 +enum FileDirectives : uint8_t { + INVALID_DIRECTIVE = 0x0f, + EOF_DIRECTIVE = 0x04, + FINISH = 0x05, + ACK = 0x06, + METADATA = 0x07, + NAK = 0x08, + PROMPT = 0x09, + KEEP_ALIVE = 0x0c }; -enum Direction: bool { - TOWARDS_RECEIVER = 0, - TOWARDS_SENDER = 1 -}; - -enum SegmentationControl: bool { - NO_RECORD_BOUNDARIES_PRESERVATION = 0, - RECORD_BOUNDARIES_PRESERVATION = 1 -}; - -enum WidthInBytes: uint8_t { - // Only those are supported for now - ONE_BYTE = 1, - TWO_BYTES = 2, - FOUR_BYTES = 4, -}; - -enum FileDirectives: uint8_t { - INVALID_DIRECTIVE = 0x0f, - EOF_DIRECTIVE = 0x04, - FINISH = 0x05, - ACK = 0x06, - METADATA = 0x07, - NAK = 0x08, - PROMPT = 0x09, - KEEP_ALIVE = 0x0c -}; - -enum ConditionCode: uint8_t { - NO_CONDITION_FIELD = 0xff, - NO_ERROR = 0b0000, - POSITIVE_ACK_LIMIT_REACHED = 0b0001, - KEEP_ALIVE_LIMIT_REACHED = 0b0010, - INVALID_TRANSMISSION_MODE = 0b0011, - FILESTORE_REJECTION = 0b0100, - FILE_CHECKSUM_FAILURE = 0b0101, - FILE_SIZE_ERROR = 0b0110, - NAK_LIMIT_REACHED = 0b0111, - INACTIVITY_DETECTED = 0b1000, - CHECK_LIMIT_REACHED = 0b1010, - UNSUPPORTED_CHECKSUM_TYPE = 0b1011, - SUSPEND_REQUEST_RECEIVED = 0b1110, - CANCEL_REQUEST_RECEIVED = 0b1111 +enum ConditionCode : uint8_t { + NO_CONDITION_FIELD = 0xff, + NO_ERROR = 0b0000, + POSITIVE_ACK_LIMIT_REACHED = 0b0001, + KEEP_ALIVE_LIMIT_REACHED = 0b0010, + INVALID_TRANSMISSION_MODE = 0b0011, + FILESTORE_REJECTION = 0b0100, + FILE_CHECKSUM_FAILURE = 0b0101, + FILE_SIZE_ERROR = 0b0110, + NAK_LIMIT_REACHED = 0b0111, + INACTIVITY_DETECTED = 0b1000, + CHECK_LIMIT_REACHED = 0b1010, + UNSUPPORTED_CHECKSUM_TYPE = 0b1011, + SUSPEND_REQUEST_RECEIVED = 0b1110, + CANCEL_REQUEST_RECEIVED = 0b1111 }; enum AckTransactionStatus { - UNDEFINED = 0b00, - ACTIVE = 0b01, - TERMINATED = 0b10, - UNRECOGNIZED = 0b11 + UNDEFINED = 0b00, + ACTIVE = 0b01, + TERMINATED = 0b10, + UNRECOGNIZED = 0b11 }; -enum FinishedDeliveryCode { - DATA_COMPLETE = 0, - DATA_INCOMPLETE = 1 -}; +enum FinishedDeliveryCode { DATA_COMPLETE = 0, DATA_INCOMPLETE = 1 }; enum FinishedFileStatus { - DISCARDED_DELIBERATELY = 0, - DISCARDED_FILESTORE_REJECTION = 1, - RETAINED_IN_FILESTORE = 2, - FILE_STATUS_UNREPORTED = 3 + DISCARDED_DELIBERATELY = 0, + DISCARDED_FILESTORE_REJECTION = 1, + RETAINED_IN_FILESTORE = 2, + FILE_STATUS_UNREPORTED = 3 }; -enum PromptResponseRequired: bool { - PROMPT_NAK = 0, - PROMPT_KEEP_ALIVE = 1 -}; +enum PromptResponseRequired : bool { PROMPT_NAK = 0, PROMPT_KEEP_ALIVE = 1 }; -enum TlvTypes: uint8_t { - FILESTORE_REQUEST = 0x00, - FILESTORE_RESPONSE = 0x01, - MSG_TO_USER = 0x02, - FAULT_HANDLER = 0x04, - FLOW_LABEL = 0x05, - ENTITY_ID = 0x06, - INVALID_TLV = 0xff, +enum TlvTypes : uint8_t { + FILESTORE_REQUEST = 0x00, + FILESTORE_RESPONSE = 0x01, + MSG_TO_USER = 0x02, + FAULT_HANDLER = 0x04, + FLOW_LABEL = 0x05, + ENTITY_ID = 0x06, + INVALID_TLV = 0xff, }; enum RecordContinuationState { - NO_START_NO_END = 0b00, - CONTAINS_START_NO_END = 0b01, - CONTAINS_END_NO_START = 0b10, - CONTAINS_START_AND_END = 0b11 + NO_START_NO_END = 0b00, + CONTAINS_START_NO_END = 0b01, + CONTAINS_END_NO_START = 0b10, + CONTAINS_START_AND_END = 0b11 }; -} +} // namespace cfdp #endif /* FSFW_SRC_FSFW_CFDP_PDU_DEFINITIONS_H_ */ diff --git a/src/fsfw/cfdp/pdu/AckInfo.cpp b/src/fsfw/cfdp/pdu/AckInfo.cpp index 4095e8bf..f35cfbb1 100644 --- a/src/fsfw/cfdp/pdu/AckInfo.cpp +++ b/src/fsfw/cfdp/pdu/AckInfo.cpp @@ -1,52 +1,45 @@ #include "AckInfo.h" AckInfo::AckInfo(cfdp::FileDirectives ackedDirective, cfdp::ConditionCode ackedConditionCode, - cfdp::AckTransactionStatus transactionStatus, uint8_t directiveSubtypeCode): - ackedDirective(ackedDirective), ackedConditionCode(ackedConditionCode), - transactionStatus(transactionStatus), directiveSubtypeCode(directiveSubtypeCode) { - if (ackedDirective == cfdp::FileDirectives::FINISH) { - this->directiveSubtypeCode = 0b0001; - } else { - this->directiveSubtypeCode = 0b0000; - } + cfdp::AckTransactionStatus transactionStatus, uint8_t directiveSubtypeCode) + : ackedDirective(ackedDirective), + ackedConditionCode(ackedConditionCode), + transactionStatus(transactionStatus), + directiveSubtypeCode(directiveSubtypeCode) { + if (ackedDirective == cfdp::FileDirectives::FINISH) { + this->directiveSubtypeCode = 0b0001; + } else { + this->directiveSubtypeCode = 0b0000; + } } -cfdp::ConditionCode AckInfo::getAckedConditionCode() const { - return ackedConditionCode; -} +cfdp::ConditionCode AckInfo::getAckedConditionCode() const { return ackedConditionCode; } void AckInfo::setAckedConditionCode(cfdp::ConditionCode ackedConditionCode) { - this->ackedConditionCode = ackedConditionCode; - if (ackedDirective == cfdp::FileDirectives::FINISH) { - this->directiveSubtypeCode = 0b0001; - } else { - this->directiveSubtypeCode = 0b0000; - } + this->ackedConditionCode = ackedConditionCode; + if (ackedDirective == cfdp::FileDirectives::FINISH) { + this->directiveSubtypeCode = 0b0001; + } else { + this->directiveSubtypeCode = 0b0000; + } } -cfdp::FileDirectives AckInfo::getAckedDirective() const { - return ackedDirective; -} +cfdp::FileDirectives AckInfo::getAckedDirective() const { return ackedDirective; } void AckInfo::setAckedDirective(cfdp::FileDirectives ackedDirective) { - this->ackedDirective = ackedDirective; + this->ackedDirective = ackedDirective; } -uint8_t AckInfo::getDirectiveSubtypeCode() const { - return directiveSubtypeCode; -} +uint8_t AckInfo::getDirectiveSubtypeCode() const { return directiveSubtypeCode; } void AckInfo::setDirectiveSubtypeCode(uint8_t directiveSubtypeCode) { - this->directiveSubtypeCode = directiveSubtypeCode; + this->directiveSubtypeCode = directiveSubtypeCode; } -cfdp::AckTransactionStatus AckInfo::getTransactionStatus() const { - return transactionStatus; -} +cfdp::AckTransactionStatus AckInfo::getTransactionStatus() const { return transactionStatus; } -AckInfo::AckInfo() { -} +AckInfo::AckInfo() {} void AckInfo::setTransactionStatus(cfdp::AckTransactionStatus transactionStatus) { - this->transactionStatus = transactionStatus; + this->transactionStatus = transactionStatus; } diff --git a/src/fsfw/cfdp/pdu/AckInfo.h b/src/fsfw/cfdp/pdu/AckInfo.h index 2d54c535..572fc59f 100644 --- a/src/fsfw/cfdp/pdu/AckInfo.h +++ b/src/fsfw/cfdp/pdu/AckInfo.h @@ -4,30 +4,28 @@ #include "../definitions.h" class AckInfo { -public: - AckInfo(); - AckInfo(cfdp::FileDirectives ackedDirective, cfdp::ConditionCode ackedConditionCode, - cfdp::AckTransactionStatus transactionStatus, uint8_t directiveSubtypeCode = 0); + public: + AckInfo(); + AckInfo(cfdp::FileDirectives ackedDirective, cfdp::ConditionCode ackedConditionCode, + cfdp::AckTransactionStatus transactionStatus, uint8_t directiveSubtypeCode = 0); - cfdp::ConditionCode getAckedConditionCode() const; - void setAckedConditionCode(cfdp::ConditionCode ackedConditionCode); + cfdp::ConditionCode getAckedConditionCode() const; + void setAckedConditionCode(cfdp::ConditionCode ackedConditionCode); - cfdp::FileDirectives getAckedDirective() const; - void setAckedDirective(cfdp::FileDirectives ackedDirective); + cfdp::FileDirectives getAckedDirective() const; + void setAckedDirective(cfdp::FileDirectives ackedDirective); - uint8_t getDirectiveSubtypeCode() const; - void setDirectiveSubtypeCode(uint8_t directiveSubtypeCode); + uint8_t getDirectiveSubtypeCode() const; + void setDirectiveSubtypeCode(uint8_t directiveSubtypeCode); - cfdp::AckTransactionStatus getTransactionStatus() const; - void setTransactionStatus(cfdp::AckTransactionStatus transactionStatus); + cfdp::AckTransactionStatus getTransactionStatus() const; + void setTransactionStatus(cfdp::AckTransactionStatus transactionStatus); -private: - cfdp::FileDirectives ackedDirective = cfdp::FileDirectives::INVALID_DIRECTIVE; - cfdp::ConditionCode ackedConditionCode = cfdp::ConditionCode::NO_CONDITION_FIELD; - cfdp::AckTransactionStatus transactionStatus = cfdp::AckTransactionStatus::UNDEFINED; - uint8_t directiveSubtypeCode = 0; + private: + cfdp::FileDirectives ackedDirective = cfdp::FileDirectives::INVALID_DIRECTIVE; + cfdp::ConditionCode ackedConditionCode = cfdp::ConditionCode::NO_CONDITION_FIELD; + cfdp::AckTransactionStatus transactionStatus = cfdp::AckTransactionStatus::UNDEFINED; + uint8_t directiveSubtypeCode = 0; }; - - #endif /* FSFW_SRC_FSFW_CFDP_PDU_ACKINFO_H_ */ diff --git a/src/fsfw/cfdp/pdu/AckPduDeserializer.cpp b/src/fsfw/cfdp/pdu/AckPduDeserializer.cpp index b4f59a7a..f5babf4b 100644 --- a/src/fsfw/cfdp/pdu/AckPduDeserializer.cpp +++ b/src/fsfw/cfdp/pdu/AckPduDeserializer.cpp @@ -1,38 +1,37 @@ #include "AckPduDeserializer.h" -AckPduDeserializer::AckPduDeserializer(const uint8_t *pduBuf, size_t maxSize, AckInfo& info): - FileDirectiveDeserializer(pduBuf, maxSize), info(info) { -} +AckPduDeserializer::AckPduDeserializer(const uint8_t* pduBuf, size_t maxSize, AckInfo& info) + : FileDirectiveDeserializer(pduBuf, maxSize), info(info) {} ReturnValue_t AckPduDeserializer::parseData() { - ReturnValue_t result = FileDirectiveDeserializer::parseData(); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - size_t currentIdx = FileDirectiveDeserializer::getHeaderSize(); - if (currentIdx + 2 > this->maxSize) { - return SerializeIF::BUFFER_TOO_SHORT; - } - if(not checkAndSetCodes(rawPtr[currentIdx], rawPtr[currentIdx + 1])) { - return cfdp::INVALID_ACK_DIRECTIVE_FIELDS; - } - return HasReturnvaluesIF::RETURN_OK; + ReturnValue_t result = FileDirectiveDeserializer::parseData(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + size_t currentIdx = FileDirectiveDeserializer::getHeaderSize(); + if (currentIdx + 2 > this->maxSize) { + return SerializeIF::BUFFER_TOO_SHORT; + } + if (not checkAndSetCodes(rawPtr[currentIdx], rawPtr[currentIdx + 1])) { + return cfdp::INVALID_ACK_DIRECTIVE_FIELDS; + } + return HasReturnvaluesIF::RETURN_OK; } bool AckPduDeserializer::checkAndSetCodes(uint8_t firstByte, uint8_t secondByte) { - uint8_t ackedDirective = static_cast(firstByte >> 4); + uint8_t ackedDirective = static_cast(firstByte >> 4); - if(ackedDirective != cfdp::FileDirectives::EOF_DIRECTIVE and - ackedDirective != cfdp::FileDirectives::FINISH) { - return false; - } - this->info.setAckedDirective(static_cast(ackedDirective)); - uint8_t directiveSubtypeCode = firstByte & 0x0f; - if(directiveSubtypeCode != 0b0000 and directiveSubtypeCode != 0b0001) { - return false; - } - this->info.setDirectiveSubtypeCode(directiveSubtypeCode); - this->info.setAckedConditionCode(static_cast(secondByte >> 4)); - this->info.setTransactionStatus(static_cast(secondByte & 0x0f)); - return true; + if (ackedDirective != cfdp::FileDirectives::EOF_DIRECTIVE and + ackedDirective != cfdp::FileDirectives::FINISH) { + return false; + } + this->info.setAckedDirective(static_cast(ackedDirective)); + uint8_t directiveSubtypeCode = firstByte & 0x0f; + if (directiveSubtypeCode != 0b0000 and directiveSubtypeCode != 0b0001) { + return false; + } + this->info.setDirectiveSubtypeCode(directiveSubtypeCode); + this->info.setAckedConditionCode(static_cast(secondByte >> 4)); + this->info.setTransactionStatus(static_cast(secondByte & 0x0f)); + return true; } diff --git a/src/fsfw/cfdp/pdu/AckPduDeserializer.h b/src/fsfw/cfdp/pdu/AckPduDeserializer.h index 31f09c92..0bb95071 100644 --- a/src/fsfw/cfdp/pdu/AckPduDeserializer.h +++ b/src/fsfw/cfdp/pdu/AckPduDeserializer.h @@ -1,26 +1,23 @@ #ifndef FSFW_SRC_FSFW_CFDP_PDU_ACKPDUDESERIALIZER_H_ #define FSFW_SRC_FSFW_CFDP_PDU_ACKPDUDESERIALIZER_H_ -#include "fsfw/cfdp/pdu/FileDirectiveDeserializer.h" #include "AckInfo.h" +#include "fsfw/cfdp/pdu/FileDirectiveDeserializer.h" -class AckPduDeserializer: public FileDirectiveDeserializer { -public: - AckPduDeserializer(const uint8_t* pduBuf, size_t maxSize, AckInfo& info); +class AckPduDeserializer : public FileDirectiveDeserializer { + public: + AckPduDeserializer(const uint8_t* pduBuf, size_t maxSize, AckInfo& info); - /** - * - * @return - * - cfdp::INVALID_DIRECTIVE_FIELDS: Invalid fields - */ - ReturnValue_t parseData(); - -private: - bool checkAndSetCodes(uint8_t rawAckedByte, uint8_t rawAckedConditionCode); - AckInfo& info; + /** + * + * @return + * - cfdp::INVALID_DIRECTIVE_FIELDS: Invalid fields + */ + ReturnValue_t parseData(); + private: + bool checkAndSetCodes(uint8_t rawAckedByte, uint8_t rawAckedConditionCode); + AckInfo& info; }; - - #endif /* FSFW_SRC_FSFW_CFDP_PDU_ACKPDUDESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/AckPduSerializer.cpp b/src/fsfw/cfdp/pdu/AckPduSerializer.cpp index 56fe8b33..d19418f1 100644 --- a/src/fsfw/cfdp/pdu/AckPduSerializer.cpp +++ b/src/fsfw/cfdp/pdu/AckPduSerializer.cpp @@ -1,38 +1,36 @@ #include "AckPduSerializer.h" -AckPduSerializer::AckPduSerializer(AckInfo& ackInfo, PduConfig &pduConf): - FileDirectiveSerializer(pduConf, cfdp::FileDirectives::ACK, 2), - ackInfo(ackInfo) { -} +AckPduSerializer::AckPduSerializer(AckInfo &ackInfo, PduConfig &pduConf) + : FileDirectiveSerializer(pduConf, cfdp::FileDirectives::ACK, 2), ackInfo(ackInfo) {} size_t AckPduSerializer::getSerializedSize() const { - return FileDirectiveSerializer::getWholePduSize(); + return FileDirectiveSerializer::getWholePduSize(); } ReturnValue_t AckPduSerializer::serialize(uint8_t **buffer, size_t *size, size_t maxSize, - Endianness streamEndianness) const { - ReturnValue_t result = FileDirectiveSerializer::serialize(buffer, size, maxSize, - streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - cfdp::FileDirectives ackedDirective = ackInfo.getAckedDirective(); - uint8_t directiveSubtypeCode = ackInfo.getDirectiveSubtypeCode(); - cfdp::ConditionCode ackedConditionCode = ackInfo.getAckedConditionCode(); - cfdp::AckTransactionStatus transactionStatus = ackInfo.getTransactionStatus(); - if(ackedDirective != cfdp::FileDirectives::FINISH and - ackedDirective != cfdp::FileDirectives::EOF_DIRECTIVE) { - // TODO: better returncode - return HasReturnvaluesIF::RETURN_FAILED; - } - if(*size + 2 > maxSize) { - return SerializeIF::BUFFER_TOO_SHORT; - } - **buffer = ackedDirective << 4 | directiveSubtypeCode; - *buffer += 1; - *size += 1; - **buffer = ackedConditionCode << 4 | transactionStatus; - *buffer += 1; - *size += 1; - return HasReturnvaluesIF::RETURN_OK; + Endianness streamEndianness) const { + ReturnValue_t result = + FileDirectiveSerializer::serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + cfdp::FileDirectives ackedDirective = ackInfo.getAckedDirective(); + uint8_t directiveSubtypeCode = ackInfo.getDirectiveSubtypeCode(); + cfdp::ConditionCode ackedConditionCode = ackInfo.getAckedConditionCode(); + cfdp::AckTransactionStatus transactionStatus = ackInfo.getTransactionStatus(); + if (ackedDirective != cfdp::FileDirectives::FINISH and + ackedDirective != cfdp::FileDirectives::EOF_DIRECTIVE) { + // TODO: better returncode + return HasReturnvaluesIF::RETURN_FAILED; + } + if (*size + 2 > maxSize) { + return SerializeIF::BUFFER_TOO_SHORT; + } + **buffer = ackedDirective << 4 | directiveSubtypeCode; + *buffer += 1; + *size += 1; + **buffer = ackedConditionCode << 4 | transactionStatus; + *buffer += 1; + *size += 1; + return HasReturnvaluesIF::RETURN_OK; } diff --git a/src/fsfw/cfdp/pdu/AckPduSerializer.h b/src/fsfw/cfdp/pdu/AckPduSerializer.h index de478c69..68a049e2 100644 --- a/src/fsfw/cfdp/pdu/AckPduSerializer.h +++ b/src/fsfw/cfdp/pdu/AckPduSerializer.h @@ -5,26 +5,26 @@ #include "FileDirectiveDeserializer.h" #include "FileDirectiveSerializer.h" -class AckPduSerializer: public FileDirectiveSerializer { -public: - /** - * @brief Serializer to pack ACK PDUs - * @details - * Please note that only Finished PDUs and EOF are acknowledged. - * @param ackedDirective - * @param ackedConditionCode - * @param transactionStatus - * @param pduConf - */ - AckPduSerializer(AckInfo& ackInfo, PduConfig& pduConf); +class AckPduSerializer : public FileDirectiveSerializer { + public: + /** + * @brief Serializer to pack ACK PDUs + * @details + * Please note that only Finished PDUs and EOF are acknowledged. + * @param ackedDirective + * @param ackedConditionCode + * @param transactionStatus + * @param pduConf + */ + AckPduSerializer(AckInfo& ackInfo, PduConfig& pduConf); - size_t getSerializedSize() const override; + size_t getSerializedSize() const override; - ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, - Endianness streamEndianness) const override; + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; -private: - AckInfo& ackInfo; + private: + AckInfo& ackInfo; }; #endif /* FSFW_SRC_FSFW_CFDP_PDU_ACKPDUSERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/EofInfo.cpp b/src/fsfw/cfdp/pdu/EofInfo.cpp index f7c41dbe..98e79df7 100644 --- a/src/fsfw/cfdp/pdu/EofInfo.cpp +++ b/src/fsfw/cfdp/pdu/EofInfo.cpp @@ -1,58 +1,47 @@ #include "EofInfo.h" EofInfo::EofInfo(cfdp::ConditionCode conditionCode, uint32_t checksum, cfdp::FileSize fileSize, - EntityIdTlv* faultLoc): conditionCode(conditionCode), checksum(checksum), - fileSize(fileSize), faultLoc(faultLoc) { -} + EntityIdTlv* faultLoc) + : conditionCode(conditionCode), checksum(checksum), fileSize(fileSize), faultLoc(faultLoc) {} -EofInfo::EofInfo(EntityIdTlv *faultLoc): conditionCode(cfdp::ConditionCode::NO_CONDITION_FIELD), - checksum(0), fileSize(0), faultLoc(faultLoc) { -} +EofInfo::EofInfo(EntityIdTlv* faultLoc) + : conditionCode(cfdp::ConditionCode::NO_CONDITION_FIELD), + checksum(0), + fileSize(0), + faultLoc(faultLoc) {} -uint32_t EofInfo::getChecksum() const { - return checksum; -} +uint32_t EofInfo::getChecksum() const { return checksum; } -cfdp::ConditionCode EofInfo::getConditionCode() const { - return conditionCode; -} +cfdp::ConditionCode EofInfo::getConditionCode() const { return conditionCode; } -EntityIdTlv* EofInfo::getFaultLoc() const { - return faultLoc; -} +EntityIdTlv* EofInfo::getFaultLoc() const { return faultLoc; } -cfdp::FileSize& EofInfo::getFileSize() { - return fileSize; -} +cfdp::FileSize& EofInfo::getFileSize() { return fileSize; } -void EofInfo::setChecksum(uint32_t checksum) { - this->checksum = checksum; -} +void EofInfo::setChecksum(uint32_t checksum) { this->checksum = checksum; } void EofInfo::setConditionCode(cfdp::ConditionCode conditionCode) { - this->conditionCode = conditionCode; + this->conditionCode = conditionCode; } -void EofInfo::setFaultLoc(EntityIdTlv *faultLoc) { - this->faultLoc = faultLoc; -} +void EofInfo::setFaultLoc(EntityIdTlv* faultLoc) { this->faultLoc = faultLoc; } size_t EofInfo::getSerializedSize(bool fssLarge) { - // Condition code + spare + 4 byte checksum - size_t size = 5; - if(fssLarge) { - size += 8; - } else { - size += 4; - } - // Do not account for fault location if the condition code is NO_ERROR. We assume that - // a serializer will not serialize the fault location here. - if(getFaultLoc() != nullptr and getConditionCode() != cfdp::ConditionCode::NO_ERROR) { - size+= faultLoc->getSerializedSize(); - } - return size; + // Condition code + spare + 4 byte checksum + size_t size = 5; + if (fssLarge) { + size += 8; + } else { + size += 4; + } + // Do not account for fault location if the condition code is NO_ERROR. We assume that + // a serializer will not serialize the fault location here. + if (getFaultLoc() != nullptr and getConditionCode() != cfdp::ConditionCode::NO_ERROR) { + size += faultLoc->getSerializedSize(); + } + return size; } ReturnValue_t EofInfo::setFileSize(size_t fileSize, bool isLarge) { - return this->fileSize.setFileSize(fileSize, isLarge); + return this->fileSize.setFileSize(fileSize, isLarge); } diff --git a/src/fsfw/cfdp/pdu/EofInfo.h b/src/fsfw/cfdp/pdu/EofInfo.h index 33feb4fd..fa8adfd9 100644 --- a/src/fsfw/cfdp/pdu/EofInfo.h +++ b/src/fsfw/cfdp/pdu/EofInfo.h @@ -1,33 +1,33 @@ #ifndef FSFW_SRC_FSFW_CFDP_PDU_EOFINFO_H_ #define FSFW_SRC_FSFW_CFDP_PDU_EOFINFO_H_ -#include "fsfw/cfdp/tlv/EntityIdTlv.h" -#include "../definitions.h" #include "../FileSize.h" +#include "../definitions.h" +#include "fsfw/cfdp/tlv/EntityIdTlv.h" struct EofInfo { -public: - EofInfo(EntityIdTlv* faultLoc = nullptr); - EofInfo(cfdp::ConditionCode conditionCode, uint32_t checksum, cfdp::FileSize fileSize, - EntityIdTlv* faultLoc = nullptr); + public: + EofInfo(EntityIdTlv* faultLoc = nullptr); + EofInfo(cfdp::ConditionCode conditionCode, uint32_t checksum, cfdp::FileSize fileSize, + EntityIdTlv* faultLoc = nullptr); - size_t getSerializedSize(bool fssLarge = false); + size_t getSerializedSize(bool fssLarge = false); - uint32_t getChecksum() const; - cfdp::ConditionCode getConditionCode() const; + uint32_t getChecksum() const; + cfdp::ConditionCode getConditionCode() const; - EntityIdTlv* getFaultLoc() const; - cfdp::FileSize& getFileSize(); - void setChecksum(uint32_t checksum); - void setConditionCode(cfdp::ConditionCode conditionCode); - void setFaultLoc(EntityIdTlv *faultLoc); - ReturnValue_t setFileSize(size_t size, bool isLarge); -private: + EntityIdTlv* getFaultLoc() const; + cfdp::FileSize& getFileSize(); + void setChecksum(uint32_t checksum); + void setConditionCode(cfdp::ConditionCode conditionCode); + void setFaultLoc(EntityIdTlv* faultLoc); + ReturnValue_t setFileSize(size_t size, bool isLarge); - cfdp::ConditionCode conditionCode; - uint32_t checksum; - cfdp::FileSize fileSize; - EntityIdTlv* faultLoc = nullptr; + private: + cfdp::ConditionCode conditionCode; + uint32_t checksum; + cfdp::FileSize fileSize; + EntityIdTlv* faultLoc = nullptr; }; #endif /* FSFW_SRC_FSFW_CFDP_PDU_EOFINFO_H_ */ diff --git a/src/fsfw/cfdp/pdu/EofPduDeserializer.cpp b/src/fsfw/cfdp/pdu/EofPduDeserializer.cpp index e5f607bf..e1ab8dc9 100644 --- a/src/fsfw/cfdp/pdu/EofPduDeserializer.cpp +++ b/src/fsfw/cfdp/pdu/EofPduDeserializer.cpp @@ -1,68 +1,69 @@ #include "EofPduDeserializer.h" + #include "fsfw/FSFW.h" #include "fsfw/serviceinterface.h" -EofPduDeserializer::EofPduDeserializer(const uint8_t *pduBuf, size_t maxSize, EofInfo& eofInfo): - FileDirectiveDeserializer(pduBuf, maxSize), info(eofInfo) { -} +EofPduDeserializer::EofPduDeserializer(const uint8_t* pduBuf, size_t maxSize, EofInfo& eofInfo) + : FileDirectiveDeserializer(pduBuf, maxSize), info(eofInfo) {} ReturnValue_t EofPduDeserializer::parseData() { - ReturnValue_t result = FileDirectiveDeserializer::parseData(); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + ReturnValue_t result = FileDirectiveDeserializer::parseData(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - const uint8_t* bufPtr = rawPtr; - size_t expectedFileFieldLen = 4; - if(this->getLargeFileFlag()) { - expectedFileFieldLen = 8; - } - size_t currentIdx = FileDirectiveDeserializer::getHeaderSize(); - size_t deserLen = maxSize; - if(maxSize < currentIdx + 5 + expectedFileFieldLen) { - return SerializeIF::STREAM_TOO_SHORT; - } + const uint8_t* bufPtr = rawPtr; + size_t expectedFileFieldLen = 4; + if (this->getLargeFileFlag()) { + expectedFileFieldLen = 8; + } + size_t currentIdx = FileDirectiveDeserializer::getHeaderSize(); + size_t deserLen = maxSize; + if (maxSize < currentIdx + 5 + expectedFileFieldLen) { + return SerializeIF::STREAM_TOO_SHORT; + } - bufPtr += currentIdx; - deserLen -= currentIdx; - info.setConditionCode(static_cast(*bufPtr >> 4)); - bufPtr += 1; - deserLen -= 1; - uint32_t checksum = 0; - auto endianness = getEndianness(); - result = SerializeAdapter::deSerialize(&checksum, &bufPtr, &deserLen, endianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - info.setChecksum(checksum); - if(this->getLargeFileFlag()) { - uint64_t fileSizeValue = 0; - result = SerializeAdapter::deSerialize(&fileSizeValue, &bufPtr, &deserLen, endianness); - info.setFileSize(fileSizeValue, true); - } - else { - uint32_t fileSizeValue = 0; - result = SerializeAdapter::deSerialize(&fileSizeValue, &bufPtr, &deserLen, endianness); - info.setFileSize(fileSizeValue, false); - } - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if(info.getConditionCode() != cfdp::ConditionCode::NO_ERROR) { - EntityIdTlv* tlvPtr = info.getFaultLoc(); - if(tlvPtr == nullptr) { + bufPtr += currentIdx; + deserLen -= currentIdx; + info.setConditionCode(static_cast(*bufPtr >> 4)); + bufPtr += 1; + deserLen -= 1; + uint32_t checksum = 0; + auto endianness = getEndianness(); + result = SerializeAdapter::deSerialize(&checksum, &bufPtr, &deserLen, endianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + info.setChecksum(checksum); + if (this->getLargeFileFlag()) { + uint64_t fileSizeValue = 0; + result = SerializeAdapter::deSerialize(&fileSizeValue, &bufPtr, &deserLen, endianness); + info.setFileSize(fileSizeValue, true); + } else { + uint32_t fileSizeValue = 0; + result = SerializeAdapter::deSerialize(&fileSizeValue, &bufPtr, &deserLen, endianness); + info.setFileSize(fileSizeValue, false); + } + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (info.getConditionCode() != cfdp::ConditionCode::NO_ERROR) { + EntityIdTlv* tlvPtr = info.getFaultLoc(); + if (tlvPtr == nullptr) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "EofPduDeserializer::parseData: Ca not deserialize fault location," - " given TLV pointer invalid" << std::endl; + sif::warning << "EofPduDeserializer::parseData: Ca not deserialize fault location," + " given TLV pointer invalid" + << std::endl; #else - sif::printWarning("EofPduDeserializer::parseData: Ca not deserialize fault location," - " given TLV pointer invalid"); + sif::printWarning( + "EofPduDeserializer::parseData: Ca not deserialize fault location," + " given TLV pointer invalid"); #endif #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - return HasReturnvaluesIF::RETURN_FAILED; - } - result = tlvPtr->deSerialize(&bufPtr, &deserLen, endianness); + return HasReturnvaluesIF::RETURN_FAILED; } - return result; + result = tlvPtr->deSerialize(&bufPtr, &deserLen, endianness); + } + return result; } diff --git a/src/fsfw/cfdp/pdu/EofPduDeserializer.h b/src/fsfw/cfdp/pdu/EofPduDeserializer.h index fea5f03f..8f62b25a 100644 --- a/src/fsfw/cfdp/pdu/EofPduDeserializer.h +++ b/src/fsfw/cfdp/pdu/EofPduDeserializer.h @@ -1,18 +1,17 @@ #ifndef FSFW_SRC_FSFW_CFDP_PDU_EOFPDUDESERIALIZER_H_ #define FSFW_SRC_FSFW_CFDP_PDU_EOFPDUDESERIALIZER_H_ -#include "fsfw/cfdp/pdu/FileDirectiveDeserializer.h" #include "EofInfo.h" +#include "fsfw/cfdp/pdu/FileDirectiveDeserializer.h" -class EofPduDeserializer: public FileDirectiveDeserializer { -public: - EofPduDeserializer(const uint8_t* pduBuf, size_t maxSize, EofInfo& eofInfo); +class EofPduDeserializer : public FileDirectiveDeserializer { + public: + EofPduDeserializer(const uint8_t* pduBuf, size_t maxSize, EofInfo& eofInfo); - virtual ReturnValue_t parseData() override; -private: - EofInfo& info; + virtual ReturnValue_t parseData() override; + + private: + EofInfo& info; }; - - #endif /* FSFW_SRC_FSFW_CFDP_PDU_EOFPDUDESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/EofPduSerializer.cpp b/src/fsfw/cfdp/pdu/EofPduSerializer.cpp index 81bd98f1..e9fe0ca0 100644 --- a/src/fsfw/cfdp/pdu/EofPduSerializer.cpp +++ b/src/fsfw/cfdp/pdu/EofPduSerializer.cpp @@ -1,46 +1,44 @@ -#include "fsfw/FSFW.h" -#include "fsfw/serviceinterface.h" #include "EofPduSerializer.h" -EofPduSerializer::EofPduSerializer(PduConfig &conf, EofInfo& info): - FileDirectiveSerializer(conf, cfdp::FileDirectives::EOF_DIRECTIVE, 9), info(info) { - setDirectiveDataFieldLen(info.getSerializedSize(getLargeFileFlag())); +#include "fsfw/FSFW.h" +#include "fsfw/serviceinterface.h" + +EofPduSerializer::EofPduSerializer(PduConfig &conf, EofInfo &info) + : FileDirectiveSerializer(conf, cfdp::FileDirectives::EOF_DIRECTIVE, 9), info(info) { + setDirectiveDataFieldLen(info.getSerializedSize(getLargeFileFlag())); } size_t EofPduSerializer::getSerializedSize() const { - return FileDirectiveSerializer::getWholePduSize(); + return FileDirectiveSerializer::getWholePduSize(); } ReturnValue_t EofPduSerializer::serialize(uint8_t **buffer, size_t *size, size_t maxSize, - Endianness streamEndianness) const { - ReturnValue_t result = FileDirectiveSerializer::serialize(buffer, size, maxSize, - streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if(*size + 1 > maxSize) { - return SerializeIF::BUFFER_TOO_SHORT; - } - **buffer = info.getConditionCode() << 4; - *buffer += 1; - *size += 1; - uint32_t checksum = info.getChecksum(); - result = SerializeAdapter::serialize(&checksum, buffer, size, maxSize, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if(info.getFileSize().isLargeFile()) { - uint64_t fileSizeValue = info.getFileSize().getSize(); - result = SerializeAdapter::serialize(&fileSizeValue, buffer, size, - maxSize, streamEndianness); - } - else { - uint32_t fileSizeValue = info.getFileSize().getSize(); - result = SerializeAdapter::serialize(&fileSizeValue, buffer, size, - maxSize, streamEndianness); - } - if(info.getFaultLoc() != nullptr and info.getConditionCode() != cfdp::ConditionCode::NO_ERROR) { - result = info.getFaultLoc()->serialize(buffer, size, maxSize, streamEndianness); - } + Endianness streamEndianness) const { + ReturnValue_t result = + FileDirectiveSerializer::serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { return result; + } + if (*size + 1 > maxSize) { + return SerializeIF::BUFFER_TOO_SHORT; + } + **buffer = info.getConditionCode() << 4; + *buffer += 1; + *size += 1; + uint32_t checksum = info.getChecksum(); + result = SerializeAdapter::serialize(&checksum, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (info.getFileSize().isLargeFile()) { + uint64_t fileSizeValue = info.getFileSize().getSize(); + result = SerializeAdapter::serialize(&fileSizeValue, buffer, size, maxSize, streamEndianness); + } else { + uint32_t fileSizeValue = info.getFileSize().getSize(); + result = SerializeAdapter::serialize(&fileSizeValue, buffer, size, maxSize, streamEndianness); + } + if (info.getFaultLoc() != nullptr and info.getConditionCode() != cfdp::ConditionCode::NO_ERROR) { + result = info.getFaultLoc()->serialize(buffer, size, maxSize, streamEndianness); + } + return result; } diff --git a/src/fsfw/cfdp/pdu/EofPduSerializer.h b/src/fsfw/cfdp/pdu/EofPduSerializer.h index cdc9b0f1..fbdcfe67 100644 --- a/src/fsfw/cfdp/pdu/EofPduSerializer.h +++ b/src/fsfw/cfdp/pdu/EofPduSerializer.h @@ -1,22 +1,21 @@ #ifndef FSFW_SRC_FSFW_CFDP_PDU_EOFPDUSERIALIZER_H_ #define FSFW_SRC_FSFW_CFDP_PDU_EOFPDUSERIALIZER_H_ +#include "EofInfo.h" #include "fsfw/cfdp/pdu/FileDirectiveSerializer.h" #include "fsfw/cfdp/tlv/EntityIdTlv.h" -#include "EofInfo.h" -class EofPduSerializer: public FileDirectiveSerializer { -public: - EofPduSerializer(PduConfig &conf, EofInfo& info); +class EofPduSerializer : public FileDirectiveSerializer { + public: + EofPduSerializer(PduConfig& conf, EofInfo& info); - size_t getSerializedSize() const override; + size_t getSerializedSize() const override; - ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, - Endianness streamEndianness) const override; -private: - EofInfo& info; + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; + + private: + EofInfo& info; }; - - #endif /* FSFW_SRC_FSFW_CFDP_PDU_EOFPDUSERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/FileDataDeserializer.cpp b/src/fsfw/cfdp/pdu/FileDataDeserializer.cpp index 80106edf..240c4188 100644 --- a/src/fsfw/cfdp/pdu/FileDataDeserializer.cpp +++ b/src/fsfw/cfdp/pdu/FileDataDeserializer.cpp @@ -1,52 +1,48 @@ #include "FileDataDeserializer.h" -FileDataDeserializer::FileDataDeserializer(const uint8_t *pduBuf, size_t maxSize, - FileDataInfo& info): - HeaderDeserializer(pduBuf, maxSize), info(info) { -} +FileDataDeserializer::FileDataDeserializer(const uint8_t* pduBuf, size_t maxSize, + FileDataInfo& info) + : HeaderDeserializer(pduBuf, maxSize), info(info) {} ReturnValue_t FileDataDeserializer::parseData() { - ReturnValue_t result = HeaderDeserializer::parseData(); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; + ReturnValue_t result = HeaderDeserializer::parseData(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + size_t currentIdx = HeaderDeserializer::getHeaderSize(); + const uint8_t* buf = rawPtr + currentIdx; + size_t remSize = HeaderDeserializer::getWholePduSize() - currentIdx; + if (remSize < 1) { + return SerializeIF::STREAM_TOO_SHORT; + } + if (hasSegmentMetadataFlag()) { + info.setSegmentMetadataFlag(true); + info.setRecordContinuationState(static_cast((*buf >> 6) & 0b11)); + size_t segmentMetadataLen = *buf & 0b00111111; + info.setSegmentMetadataLen(segmentMetadataLen); + if (remSize < segmentMetadataLen + 1) { + return SerializeIF::STREAM_TOO_SHORT; } - size_t currentIdx = HeaderDeserializer::getHeaderSize(); - const uint8_t* buf = rawPtr + currentIdx; - size_t remSize = HeaderDeserializer::getWholePduSize() - currentIdx; - if (remSize < 1) { - return SerializeIF::STREAM_TOO_SHORT; + if (segmentMetadataLen > 0) { + buf += 1; + remSize -= 1; + info.setSegmentMetadata(buf); + buf += segmentMetadataLen; + remSize -= segmentMetadataLen; } - if(hasSegmentMetadataFlag()) { - info.setSegmentMetadataFlag(true); - info.setRecordContinuationState(static_cast( - (*buf >> 6) & 0b11)); - size_t segmentMetadataLen = *buf & 0b00111111; - info.setSegmentMetadataLen(segmentMetadataLen); - if(remSize < segmentMetadataLen + 1) { - return SerializeIF::STREAM_TOO_SHORT; - } - if(segmentMetadataLen > 0) { - buf += 1; - remSize -= 1; - info.setSegmentMetadata(buf); - buf += segmentMetadataLen; - remSize -= segmentMetadataLen; - } - } - result = info.getOffset().deSerialize(&buf, &remSize, this->getEndianness()); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if(remSize > 0) { - info.setFileData(buf, remSize); - } - return HasReturnvaluesIF::RETURN_OK; + } + result = info.getOffset().deSerialize(&buf, &remSize, this->getEndianness()); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (remSize > 0) { + info.setFileData(buf, remSize); + } + return HasReturnvaluesIF::RETURN_OK; } -SerializeIF::Endianness FileDataDeserializer::getEndianness() const { - return endianness; -} +SerializeIF::Endianness FileDataDeserializer::getEndianness() const { return endianness; } void FileDataDeserializer::setEndianness(SerializeIF::Endianness endianness) { - this->endianness = endianness; + this->endianness = endianness; } diff --git a/src/fsfw/cfdp/pdu/FileDataDeserializer.h b/src/fsfw/cfdp/pdu/FileDataDeserializer.h index 13532d95..833c0561 100644 --- a/src/fsfw/cfdp/pdu/FileDataDeserializer.h +++ b/src/fsfw/cfdp/pdu/FileDataDeserializer.h @@ -1,22 +1,21 @@ #ifndef FSFW_SRC_FSFW_CFDP_PDU_FILEDATADESERIALIZER_H_ #define FSFW_SRC_FSFW_CFDP_PDU_FILEDATADESERIALIZER_H_ +#include "../definitions.h" #include "FileDataInfo.h" #include "HeaderDeserializer.h" -#include "../definitions.h" -class FileDataDeserializer: public HeaderDeserializer { -public: - FileDataDeserializer(const uint8_t* pduBuf, size_t maxSize, FileDataInfo& info); +class FileDataDeserializer : public HeaderDeserializer { + public: + FileDataDeserializer(const uint8_t* pduBuf, size_t maxSize, FileDataInfo& info); - ReturnValue_t parseData(); - SerializeIF::Endianness getEndianness() const; - void setEndianness(SerializeIF::Endianness endianness = SerializeIF::Endianness::NETWORK); + ReturnValue_t parseData(); + SerializeIF::Endianness getEndianness() const; + void setEndianness(SerializeIF::Endianness endianness = SerializeIF::Endianness::NETWORK); -private: - - SerializeIF::Endianness endianness = SerializeIF::Endianness::NETWORK; - FileDataInfo& info; + private: + SerializeIF::Endianness endianness = SerializeIF::Endianness::NETWORK; + FileDataInfo& info; }; #endif /* FSFW_SRC_FSFW_CFDP_PDU_FILEDATADESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/FileDataInfo.cpp b/src/fsfw/cfdp/pdu/FileDataInfo.cpp index 1698f5e0..c410adce 100644 --- a/src/fsfw/cfdp/pdu/FileDataInfo.cpp +++ b/src/fsfw/cfdp/pdu/FileDataInfo.cpp @@ -1,104 +1,93 @@ #include "FileDataInfo.h" -FileDataInfo::FileDataInfo(cfdp::FileSize &offset, const uint8_t *fileData, size_t fileSize): - offset(offset), fileData(fileData), fileSize(fileSize) { -} +FileDataInfo::FileDataInfo(cfdp::FileSize &offset, const uint8_t *fileData, size_t fileSize) + : offset(offset), fileData(fileData), fileSize(fileSize) {} -FileDataInfo::FileDataInfo(cfdp::FileSize &offset): offset(offset) { -} +FileDataInfo::FileDataInfo(cfdp::FileSize &offset) : offset(offset) {} void FileDataInfo::setSegmentMetadataFlag(bool enable) { - if(enable) { - segmentMetadataFlag = cfdp::SegmentMetadataFlag::PRESENT; - } else { - segmentMetadataFlag = cfdp::SegmentMetadataFlag::NOT_PRESENT; - } + if (enable) { + segmentMetadataFlag = cfdp::SegmentMetadataFlag::PRESENT; + } else { + segmentMetadataFlag = cfdp::SegmentMetadataFlag::NOT_PRESENT; + } } size_t FileDataInfo::getSerializedSize(bool largeFile) const { - size_t sz = 0; - if(segmentMetadataFlag == cfdp::SegmentMetadataFlag::PRESENT) { - sz += 1 + segmentMetadataLen; - } - if(largeFile) { - sz += 8; - } else { - sz += 4; - } - sz += fileSize; - return sz; + size_t sz = 0; + if (segmentMetadataFlag == cfdp::SegmentMetadataFlag::PRESENT) { + sz += 1 + segmentMetadataLen; + } + if (largeFile) { + sz += 8; + } else { + sz += 4; + } + sz += fileSize; + return sz; } cfdp::SegmentMetadataFlag FileDataInfo::getSegmentMetadataFlag() const { - return this->segmentMetadataFlag; + return this->segmentMetadataFlag; } bool FileDataInfo::hasSegmentMetadata() const { - if(segmentMetadataFlag == cfdp::SegmentMetadataFlag::PRESENT) { - return true; - } - return false; + if (segmentMetadataFlag == cfdp::SegmentMetadataFlag::PRESENT) { + return true; + } + return false; } cfdp::RecordContinuationState FileDataInfo::getRecordContinuationState() const { - return this->recContState; + return this->recContState; } -size_t FileDataInfo::getSegmentMetadataLen() const { - return segmentMetadataLen; -} +size_t FileDataInfo::getSegmentMetadataLen() const { return segmentMetadataLen; } ReturnValue_t FileDataInfo::addSegmentMetadataInfo(cfdp::RecordContinuationState recContState, - const uint8_t* segmentMetadata, size_t segmentMetadataLen) { - this->segmentMetadataFlag = cfdp::SegmentMetadataFlag::PRESENT; - this->recContState = recContState; - if(segmentMetadataLen > 63) { - return HasReturnvaluesIF::RETURN_FAILED; - } - this->segmentMetadata = segmentMetadata; - this->segmentMetadataLen = segmentMetadataLen; - return HasReturnvaluesIF::RETURN_OK; + const uint8_t *segmentMetadata, + size_t segmentMetadataLen) { + this->segmentMetadataFlag = cfdp::SegmentMetadataFlag::PRESENT; + this->recContState = recContState; + if (segmentMetadataLen > 63) { + return HasReturnvaluesIF::RETURN_FAILED; + } + this->segmentMetadata = segmentMetadata; + this->segmentMetadataLen = segmentMetadataLen; + return HasReturnvaluesIF::RETURN_OK; } -const uint8_t* FileDataInfo::getFileData(size_t *fileSize) const { - if(fileSize != nullptr) { - *fileSize = this->fileSize; - } - return fileData; +const uint8_t *FileDataInfo::getFileData(size_t *fileSize) const { + if (fileSize != nullptr) { + *fileSize = this->fileSize; + } + return fileData; } -const uint8_t* FileDataInfo::getSegmentMetadata(size_t *segmentMetadataLen) { - if(segmentMetadataLen != nullptr) { - *segmentMetadataLen = this->segmentMetadataLen; - } - return segmentMetadata; +const uint8_t *FileDataInfo::getSegmentMetadata(size_t *segmentMetadataLen) { + if (segmentMetadataLen != nullptr) { + *segmentMetadataLen = this->segmentMetadataLen; + } + return segmentMetadata; } -cfdp::FileSize& FileDataInfo::getOffset() { - return offset; -} +cfdp::FileSize &FileDataInfo::getOffset() { return offset; } void FileDataInfo::setRecordContinuationState(cfdp::RecordContinuationState recContState) { - this->recContState = recContState; + this->recContState = recContState; } -void FileDataInfo::setSegmentMetadataLen(size_t len) { - this->segmentMetadataLen = len; -} +void FileDataInfo::setSegmentMetadataLen(size_t len) { this->segmentMetadataLen = len; } -void FileDataInfo::setSegmentMetadata(const uint8_t *ptr) { - this->segmentMetadata = ptr; -} +void FileDataInfo::setSegmentMetadata(const uint8_t *ptr) { this->segmentMetadata = ptr; } void FileDataInfo::setFileData(const uint8_t *fileData, size_t fileSize) { - this->fileData = fileData; - this->fileSize = fileSize; + this->fileData = fileData; + this->fileSize = fileSize; } -cfdp::SegmentationControl FileDataInfo::getSegmentationControl() const { - return segCtrl; -} +cfdp::SegmentationControl FileDataInfo::getSegmentationControl() const { return segCtrl; } void FileDataInfo::setSegmentationControl(cfdp::SegmentationControl segCtrl) { - this->segCtrl = segCtrl; + this->segCtrl = segCtrl; } diff --git a/src/fsfw/cfdp/pdu/FileDataInfo.h b/src/fsfw/cfdp/pdu/FileDataInfo.h index 1fcc6ff0..7fd573db 100644 --- a/src/fsfw/cfdp/pdu/FileDataInfo.h +++ b/src/fsfw/cfdp/pdu/FileDataInfo.h @@ -1,45 +1,44 @@ #ifndef FSFW_SRC_FSFW_CFDP_PDU_FILEDATAINFO_H_ #define FSFW_SRC_FSFW_CFDP_PDU_FILEDATAINFO_H_ -#include #include +#include class FileDataInfo { -public: - FileDataInfo(cfdp::FileSize& offset); - FileDataInfo(cfdp::FileSize& offset, const uint8_t* fileData, size_t fileSize); + public: + FileDataInfo(cfdp::FileSize& offset); + FileDataInfo(cfdp::FileSize& offset, const uint8_t* fileData, size_t fileSize); - size_t getSerializedSize(bool largeFile = false) const; + size_t getSerializedSize(bool largeFile = false) const; - cfdp::FileSize& getOffset(); - const uint8_t* getFileData(size_t* fileSize = nullptr) const; - void setFileData(const uint8_t* fileData, size_t fileSize); + cfdp::FileSize& getOffset(); + const uint8_t* getFileData(size_t* fileSize = nullptr) const; + void setFileData(const uint8_t* fileData, size_t fileSize); - cfdp::SegmentMetadataFlag getSegmentMetadataFlag() const; - cfdp::SegmentationControl getSegmentationControl() const; - cfdp::RecordContinuationState getRecordContinuationState() const; - void setRecordContinuationState(cfdp::RecordContinuationState recContState); - void setSegmentationControl(cfdp::SegmentationControl segCtrl); + cfdp::SegmentMetadataFlag getSegmentMetadataFlag() const; + cfdp::SegmentationControl getSegmentationControl() const; + cfdp::RecordContinuationState getRecordContinuationState() const; + void setRecordContinuationState(cfdp::RecordContinuationState recContState); + void setSegmentationControl(cfdp::SegmentationControl segCtrl); - size_t getSegmentMetadataLen() const; - void setSegmentMetadataLen(size_t len); - void setSegmentMetadata(const uint8_t* ptr); - bool hasSegmentMetadata() const; - void setSegmentMetadataFlag(bool enable); - ReturnValue_t addSegmentMetadataInfo(cfdp::RecordContinuationState recContState, - const uint8_t* segmentMetadata, size_t segmentMetadataLen); - const uint8_t* getSegmentMetadata(size_t* segmentMetadataLen = nullptr); + size_t getSegmentMetadataLen() const; + void setSegmentMetadataLen(size_t len); + void setSegmentMetadata(const uint8_t* ptr); + bool hasSegmentMetadata() const; + void setSegmentMetadataFlag(bool enable); + ReturnValue_t addSegmentMetadataInfo(cfdp::RecordContinuationState recContState, + const uint8_t* segmentMetadata, size_t segmentMetadataLen); + const uint8_t* getSegmentMetadata(size_t* segmentMetadataLen = nullptr); -private: - cfdp::SegmentMetadataFlag segmentMetadataFlag = cfdp::SegmentMetadataFlag::NOT_PRESENT; - cfdp::SegmentationControl segCtrl = - cfdp::SegmentationControl::NO_RECORD_BOUNDARIES_PRESERVATION; - cfdp::FileSize& offset; - const uint8_t* fileData = nullptr; - size_t fileSize = 0; - cfdp::RecordContinuationState recContState = cfdp::RecordContinuationState::NO_START_NO_END; - size_t segmentMetadataLen = 0; - const uint8_t* segmentMetadata = nullptr; + private: + cfdp::SegmentMetadataFlag segmentMetadataFlag = cfdp::SegmentMetadataFlag::NOT_PRESENT; + cfdp::SegmentationControl segCtrl = cfdp::SegmentationControl::NO_RECORD_BOUNDARIES_PRESERVATION; + cfdp::FileSize& offset; + const uint8_t* fileData = nullptr; + size_t fileSize = 0; + cfdp::RecordContinuationState recContState = cfdp::RecordContinuationState::NO_START_NO_END; + size_t segmentMetadataLen = 0; + const uint8_t* segmentMetadata = nullptr; }; #endif /* FSFW_SRC_FSFW_CFDP_PDU_FILEDATAINFO_H_ */ diff --git a/src/fsfw/cfdp/pdu/FileDataSerializer.cpp b/src/fsfw/cfdp/pdu/FileDataSerializer.cpp index 4488e368..837b418b 100644 --- a/src/fsfw/cfdp/pdu/FileDataSerializer.cpp +++ b/src/fsfw/cfdp/pdu/FileDataSerializer.cpp @@ -1,54 +1,55 @@ #include "FileDataSerializer.h" + #include -FileDataSerializer::FileDataSerializer(PduConfig& conf, FileDataInfo& info): - HeaderSerializer(conf, cfdp::PduType::FILE_DATA, 0, info.getSegmentMetadataFlag()), - info(info) { - update(); +FileDataSerializer::FileDataSerializer(PduConfig& conf, FileDataInfo& info) + : HeaderSerializer(conf, cfdp::PduType::FILE_DATA, 0, info.getSegmentMetadataFlag()), + info(info) { + update(); } void FileDataSerializer::update() { - this->setSegmentMetadataFlag(info.getSegmentMetadataFlag()); - this->setSegmentationControl(info.getSegmentationControl()); - setPduDataFieldLen(info.getSerializedSize(this->getLargeFileFlag())); + this->setSegmentMetadataFlag(info.getSegmentMetadataFlag()); + this->setSegmentationControl(info.getSegmentationControl()); + setPduDataFieldLen(info.getSerializedSize(this->getLargeFileFlag())); } -ReturnValue_t FileDataSerializer::serialize(uint8_t **buffer, size_t *size, size_t maxSize, - Endianness streamEndianness) const { - ReturnValue_t result = HeaderSerializer::serialize(buffer, size, maxSize, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if(*size + this->getSerializedSize() > maxSize) { - return SerializeIF::BUFFER_TOO_SHORT; - } - const uint8_t* readOnlyPtr = nullptr; - if (this->hasSegmentMetadataFlag()) { - size_t segmentMetadataLen = info.getSegmentMetadataLen(); - **buffer = info.getRecordContinuationState() << 6 | segmentMetadataLen; - *buffer += 1; - *size += 1; - readOnlyPtr = info.getSegmentMetadata(); - std::memcpy(*buffer, readOnlyPtr, segmentMetadataLen); - *buffer += segmentMetadataLen; - *size += segmentMetadataLen; - } - cfdp::FileSize& offset = info.getOffset(); - result = offset.serialize(this->getLargeFileFlag(), buffer, size, maxSize, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - size_t fileSize = 0; - readOnlyPtr = info.getFileData(&fileSize); - if(*size + fileSize > maxSize) { - return SerializeIF::BUFFER_TOO_SHORT; - } - std::memcpy(*buffer, readOnlyPtr, fileSize); - *buffer += fileSize; - *size += fileSize; - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t FileDataSerializer::serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const { + ReturnValue_t result = HeaderSerializer::serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (*size + this->getSerializedSize() > maxSize) { + return SerializeIF::BUFFER_TOO_SHORT; + } + const uint8_t* readOnlyPtr = nullptr; + if (this->hasSegmentMetadataFlag()) { + size_t segmentMetadataLen = info.getSegmentMetadataLen(); + **buffer = info.getRecordContinuationState() << 6 | segmentMetadataLen; + *buffer += 1; + *size += 1; + readOnlyPtr = info.getSegmentMetadata(); + std::memcpy(*buffer, readOnlyPtr, segmentMetadataLen); + *buffer += segmentMetadataLen; + *size += segmentMetadataLen; + } + cfdp::FileSize& offset = info.getOffset(); + result = offset.serialize(this->getLargeFileFlag(), buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + size_t fileSize = 0; + readOnlyPtr = info.getFileData(&fileSize); + if (*size + fileSize > maxSize) { + return SerializeIF::BUFFER_TOO_SHORT; + } + std::memcpy(*buffer, readOnlyPtr, fileSize); + *buffer += fileSize; + *size += fileSize; + return HasReturnvaluesIF::RETURN_OK; } size_t FileDataSerializer::getSerializedSize() const { - return HeaderSerializer::getSerializedSize() + info.getSerializedSize(this->getLargeFileFlag()); + return HeaderSerializer::getSerializedSize() + info.getSerializedSize(this->getLargeFileFlag()); } diff --git a/src/fsfw/cfdp/pdu/FileDataSerializer.h b/src/fsfw/cfdp/pdu/FileDataSerializer.h index b0153528..662b9b4d 100644 --- a/src/fsfw/cfdp/pdu/FileDataSerializer.h +++ b/src/fsfw/cfdp/pdu/FileDataSerializer.h @@ -1,23 +1,23 @@ #ifndef FSFW_SRC_FSFW_CFDP_PDU_FILEDATASERIALIZER_H_ #define FSFW_SRC_FSFW_CFDP_PDU_FILEDATASERIALIZER_H_ -#include "FileDataInfo.h" #include "../definitions.h" +#include "FileDataInfo.h" #include "HeaderSerializer.h" -class FileDataSerializer: public HeaderSerializer { -public: - FileDataSerializer(PduConfig& conf, FileDataInfo& info); +class FileDataSerializer : public HeaderSerializer { + public: + FileDataSerializer(PduConfig& conf, FileDataInfo& info); - void update(); + void update(); - ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, - Endianness streamEndianness) const override; + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; - size_t getSerializedSize() const override; + size_t getSerializedSize() const override; -private: - FileDataInfo& info; + private: + FileDataInfo& info; }; #endif /* FSFW_SRC_FSFW_CFDP_PDU_FILEDATADESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/FileDirectiveDeserializer.cpp b/src/fsfw/cfdp/pdu/FileDirectiveDeserializer.cpp index b348c5bd..3c0552f7 100644 --- a/src/fsfw/cfdp/pdu/FileDirectiveDeserializer.cpp +++ b/src/fsfw/cfdp/pdu/FileDirectiveDeserializer.cpp @@ -1,55 +1,49 @@ #include "FileDirectiveDeserializer.h" -FileDirectiveDeserializer::FileDirectiveDeserializer(const uint8_t *pduBuf, size_t maxSize): - HeaderDeserializer(pduBuf, maxSize) { -} +FileDirectiveDeserializer::FileDirectiveDeserializer(const uint8_t *pduBuf, size_t maxSize) + : HeaderDeserializer(pduBuf, maxSize) {} -cfdp::FileDirectives FileDirectiveDeserializer::getFileDirective() const { - return fileDirective; -} +cfdp::FileDirectives FileDirectiveDeserializer::getFileDirective() const { return fileDirective; } ReturnValue_t FileDirectiveDeserializer::parseData() { - ReturnValue_t result = HeaderDeserializer::parseData(); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if(this->getPduDataFieldLen() < 1) { - return cfdp::INVALID_PDU_DATAFIELD_LEN; - } - if(FileDirectiveDeserializer::getWholePduSize() > maxSize) { - return SerializeIF::STREAM_TOO_SHORT; - } - size_t currentIdx = HeaderDeserializer::getHeaderSize(); - if(not checkFileDirective(rawPtr[currentIdx])) { - return cfdp::INVALID_DIRECTIVE_FIELDS; - } - setFileDirective(static_cast(rawPtr[currentIdx])); - return HasReturnvaluesIF::RETURN_OK; + ReturnValue_t result = HeaderDeserializer::parseData(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (this->getPduDataFieldLen() < 1) { + return cfdp::INVALID_PDU_DATAFIELD_LEN; + } + if (FileDirectiveDeserializer::getWholePduSize() > maxSize) { + return SerializeIF::STREAM_TOO_SHORT; + } + size_t currentIdx = HeaderDeserializer::getHeaderSize(); + if (not checkFileDirective(rawPtr[currentIdx])) { + return cfdp::INVALID_DIRECTIVE_FIELDS; + } + setFileDirective(static_cast(rawPtr[currentIdx])); + return HasReturnvaluesIF::RETURN_OK; } size_t FileDirectiveDeserializer::getHeaderSize() const { - // return size of header plus the directive byte - return HeaderDeserializer::getHeaderSize() + 1; + // return size of header plus the directive byte + return HeaderDeserializer::getHeaderSize() + 1; } bool FileDirectiveDeserializer::checkFileDirective(uint8_t rawByte) { - if(rawByte < cfdp::FileDirectives::EOF_DIRECTIVE or - (rawByte > cfdp::FileDirectives::PROMPT and - rawByte != cfdp::FileDirectives::KEEP_ALIVE)) { - // Invalid directive field. TODO: Custom returnvalue - return false; - } - return true; + if (rawByte < cfdp::FileDirectives::EOF_DIRECTIVE or + (rawByte > cfdp::FileDirectives::PROMPT and rawByte != cfdp::FileDirectives::KEEP_ALIVE)) { + // Invalid directive field. TODO: Custom returnvalue + return false; + } + return true; } void FileDirectiveDeserializer::setFileDirective(cfdp::FileDirectives fileDirective) { - this->fileDirective = fileDirective; + this->fileDirective = fileDirective; } void FileDirectiveDeserializer::setEndianness(SerializeIF::Endianness endianness) { - this->endianness = endianness; + this->endianness = endianness; } -SerializeIF::Endianness FileDirectiveDeserializer::getEndianness() const { - return endianness; -} +SerializeIF::Endianness FileDirectiveDeserializer::getEndianness() const { return endianness; } diff --git a/src/fsfw/cfdp/pdu/FileDirectiveDeserializer.h b/src/fsfw/cfdp/pdu/FileDirectiveDeserializer.h index 257fb5c0..064cb64a 100644 --- a/src/fsfw/cfdp/pdu/FileDirectiveDeserializer.h +++ b/src/fsfw/cfdp/pdu/FileDirectiveDeserializer.h @@ -11,31 +11,29 @@ * This is a zero-copy implementation and #parseData needs to be called to ensure the data is * valid. */ -class FileDirectiveDeserializer: public HeaderDeserializer { -public: - FileDirectiveDeserializer(const uint8_t* pduBuf, size_t maxSize); +class FileDirectiveDeserializer : public HeaderDeserializer { + public: + FileDirectiveDeserializer(const uint8_t* pduBuf, size_t maxSize); - /** - * This needs to be called before accessing the PDU fields to avoid segmentation faults. - * @return - */ - virtual ReturnValue_t parseData(); - size_t getHeaderSize() const; + /** + * This needs to be called before accessing the PDU fields to avoid segmentation faults. + * @return + */ + virtual ReturnValue_t parseData(); + size_t getHeaderSize() const; - cfdp::FileDirectives getFileDirective() const; + cfdp::FileDirectives getFileDirective() const; - void setEndianness(SerializeIF::Endianness endianness); - SerializeIF::Endianness getEndianness() const; + void setEndianness(SerializeIF::Endianness endianness); + SerializeIF::Endianness getEndianness() const; -protected: - bool checkFileDirective(uint8_t rawByte); + protected: + bool checkFileDirective(uint8_t rawByte); -private: - void setFileDirective(cfdp::FileDirectives fileDirective); - cfdp::FileDirectives fileDirective = cfdp::FileDirectives::INVALID_DIRECTIVE; - SerializeIF::Endianness endianness = SerializeIF::Endianness::NETWORK; + private: + void setFileDirective(cfdp::FileDirectives fileDirective); + cfdp::FileDirectives fileDirective = cfdp::FileDirectives::INVALID_DIRECTIVE; + SerializeIF::Endianness endianness = SerializeIF::Endianness::NETWORK; }; - - #endif /* FSFW_SRC_FSFW_CFDP_PDU_FILEDIRECTIVEDESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/FileDirectiveSerializer.cpp b/src/fsfw/cfdp/pdu/FileDirectiveSerializer.cpp index 89600d1d..98b2d0a2 100644 --- a/src/fsfw/cfdp/pdu/FileDirectiveSerializer.cpp +++ b/src/fsfw/cfdp/pdu/FileDirectiveSerializer.cpp @@ -1,39 +1,38 @@ #include "FileDirectiveSerializer.h" - FileDirectiveSerializer::FileDirectiveSerializer(PduConfig &pduConf, - cfdp::FileDirectives directiveCode, size_t directiveParamFieldLen): - HeaderSerializer(pduConf, cfdp::PduType::FILE_DIRECTIVE, directiveParamFieldLen + 1), - directiveCode(directiveCode) { -} + cfdp::FileDirectives directiveCode, + size_t directiveParamFieldLen) + : HeaderSerializer(pduConf, cfdp::PduType::FILE_DIRECTIVE, directiveParamFieldLen + 1), + directiveCode(directiveCode) {} size_t FileDirectiveSerializer::getSerializedSize() const { - return HeaderSerializer::getSerializedSize() + 1; + return HeaderSerializer::getSerializedSize() + 1; } ReturnValue_t FileDirectiveSerializer::serialize(uint8_t **buffer, size_t *size, size_t maxSize, - Endianness streamEndianness) const { - if(buffer == nullptr or size == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - if(FileDirectiveSerializer::getWholePduSize() > maxSize) { - return BUFFER_TOO_SHORT; - } - ReturnValue_t result = HeaderSerializer::serialize(buffer, size, maxSize, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + Endianness streamEndianness) const { + if (buffer == nullptr or size == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if (FileDirectiveSerializer::getWholePduSize() > maxSize) { + return BUFFER_TOO_SHORT; + } + ReturnValue_t result = HeaderSerializer::serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - if(*size >= maxSize) { - return BUFFER_TOO_SHORT; - } - **buffer = directiveCode; - *buffer += 1; - *size += 1; - return HasReturnvaluesIF::RETURN_OK; + if (*size >= maxSize) { + return BUFFER_TOO_SHORT; + } + **buffer = directiveCode; + *buffer += 1; + *size += 1; + return HasReturnvaluesIF::RETURN_OK; } void FileDirectiveSerializer::setDirectiveDataFieldLen(size_t len) { - // Set length of data field plus 1 byte for the directive octet - HeaderSerializer::setPduDataFieldLen(len + 1); + // Set length of data field plus 1 byte for the directive octet + HeaderSerializer::setPduDataFieldLen(len + 1); } diff --git a/src/fsfw/cfdp/pdu/FileDirectiveSerializer.h b/src/fsfw/cfdp/pdu/FileDirectiveSerializer.h index 75a3582d..8f86a5e1 100644 --- a/src/fsfw/cfdp/pdu/FileDirectiveSerializer.h +++ b/src/fsfw/cfdp/pdu/FileDirectiveSerializer.h @@ -3,26 +3,26 @@ #include "fsfw/cfdp/pdu/HeaderSerializer.h" -class FileDirectiveSerializer: public HeaderSerializer { -public: - FileDirectiveSerializer(PduConfig& pduConf, cfdp::FileDirectives directiveCode, - size_t directiveParamFieldLen); +class FileDirectiveSerializer : public HeaderSerializer { + public: + FileDirectiveSerializer(PduConfig& pduConf, cfdp::FileDirectives directiveCode, + size_t directiveParamFieldLen); - /** - * This only returns the size of the PDU header + 1 for the directive code octet. - * Use FileDirectiveSerializer::getWholePduSize to get the full packet length, assuming - * the length fields was set correctly - * @return - */ - size_t getSerializedSize() const override; + /** + * This only returns the size of the PDU header + 1 for the directive code octet. + * Use FileDirectiveSerializer::getWholePduSize to get the full packet length, assuming + * the length fields was set correctly + * @return + */ + size_t getSerializedSize() const override; - ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, - Endianness streamEndianness) const override; + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; - void setDirectiveDataFieldLen(size_t len); -private: - cfdp::FileDirectives directiveCode = cfdp::FileDirectives::INVALID_DIRECTIVE; + void setDirectiveDataFieldLen(size_t len); + private: + cfdp::FileDirectives directiveCode = cfdp::FileDirectives::INVALID_DIRECTIVE; }; #endif /* FSFW_SRC_FSFW_CFDP_PDU_FILEDIRECTIVESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/FinishedInfo.cpp b/src/fsfw/cfdp/pdu/FinishedInfo.cpp index e6b7e9b4..c32372a1 100644 --- a/src/fsfw/cfdp/pdu/FinishedInfo.cpp +++ b/src/fsfw/cfdp/pdu/FinishedInfo.cpp @@ -1,111 +1,102 @@ #include "FinishedInfo.h" -FinishedInfo::FinishedInfo() { -} - +FinishedInfo::FinishedInfo() {} FinishedInfo::FinishedInfo(cfdp::ConditionCode conditionCode, - cfdp::FinishedDeliveryCode deliveryCode, cfdp::FinishedFileStatus fileStatus): - conditionCode(conditionCode), deliveryCode(deliveryCode), fileStatus(fileStatus) { -} + cfdp::FinishedDeliveryCode deliveryCode, + cfdp::FinishedFileStatus fileStatus) + : conditionCode(conditionCode), deliveryCode(deliveryCode), fileStatus(fileStatus) {} size_t FinishedInfo::getSerializedSize() const { - size_t size = 1; - if(hasFsResponses()) { - for(size_t idx = 0; idx < fsResponsesLen; idx++) { - size += fsResponses[idx]->getSerializedSize(); - } + size_t size = 1; + if (hasFsResponses()) { + for (size_t idx = 0; idx < fsResponsesLen; idx++) { + size += fsResponses[idx]->getSerializedSize(); } - if(this->faultLocation != nullptr) { - size += faultLocation->getSerializedSize(); - } - return size; + } + if (this->faultLocation != nullptr) { + size += faultLocation->getSerializedSize(); + } + return size; } bool FinishedInfo::hasFsResponses() const { - if(fsResponses != nullptr and fsResponsesLen > 0) { - return true; - } - return false; + if (fsResponses != nullptr and fsResponsesLen > 0) { + return true; + } + return false; } bool FinishedInfo::canHoldFsResponses() const { - if(fsResponses != nullptr and fsResponsesMaxLen > 0) { - return true; - } - return false; + if (fsResponses != nullptr and fsResponsesMaxLen > 0) { + return true; + } + return false; } - ReturnValue_t FinishedInfo::setFilestoreResponsesArray(FilestoreResponseTlv** fsResponses, - size_t* fsResponsesLen, const size_t* maxFsResponsesLen) { - this->fsResponses = fsResponses; - if(fsResponsesLen != nullptr) { - this->fsResponsesLen = *fsResponsesLen; - if(this->fsResponsesMaxLen < *fsResponsesLen) { - this->fsResponsesMaxLen = this->fsResponsesLen; - } + size_t* fsResponsesLen, + const size_t* maxFsResponsesLen) { + this->fsResponses = fsResponses; + if (fsResponsesLen != nullptr) { + this->fsResponsesLen = *fsResponsesLen; + if (this->fsResponsesMaxLen < *fsResponsesLen) { + this->fsResponsesMaxLen = this->fsResponsesLen; } - if(maxFsResponsesLen != nullptr) { - this->fsResponsesMaxLen = *maxFsResponsesLen; - } - return HasReturnvaluesIF::RETURN_OK; + } + if (maxFsResponsesLen != nullptr) { + this->fsResponsesMaxLen = *maxFsResponsesLen; + } + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t FinishedInfo::getFilestoreResonses(FilestoreResponseTlv ***fsResponses, - size_t *fsResponsesLen, size_t* fsResponsesMaxLen) { - if(fsResponses == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - *fsResponses = this->fsResponses; - if(fsResponsesLen != nullptr) { - *fsResponsesLen = this->fsResponsesLen; - } - if(fsResponsesMaxLen != nullptr) { - *fsResponsesMaxLen = this->fsResponsesMaxLen; - } - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t FinishedInfo::getFilestoreResonses(FilestoreResponseTlv*** fsResponses, + size_t* fsResponsesLen, + size_t* fsResponsesMaxLen) { + if (fsResponses == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + *fsResponses = this->fsResponses; + if (fsResponsesLen != nullptr) { + *fsResponsesLen = this->fsResponsesLen; + } + if (fsResponsesMaxLen != nullptr) { + *fsResponsesMaxLen = this->fsResponsesMaxLen; + } + return HasReturnvaluesIF::RETURN_OK; } -void FinishedInfo::setFaultLocation(EntityIdTlv *faultLocation) { - this->faultLocation = faultLocation; +void FinishedInfo::setFaultLocation(EntityIdTlv* faultLocation) { + this->faultLocation = faultLocation; } ReturnValue_t FinishedInfo::getFaultLocation(EntityIdTlv** faultLocation) { - if(this->faultLocation == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - *faultLocation = this->faultLocation; - return HasReturnvaluesIF::RETURN_OK; + if (this->faultLocation == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + *faultLocation = this->faultLocation; + return HasReturnvaluesIF::RETURN_OK; } -cfdp::ConditionCode FinishedInfo::getConditionCode() const { - return conditionCode; -} +cfdp::ConditionCode FinishedInfo::getConditionCode() const { return conditionCode; } void FinishedInfo::setConditionCode(cfdp::ConditionCode conditionCode) { - this->conditionCode = conditionCode; + this->conditionCode = conditionCode; } -cfdp::FinishedDeliveryCode FinishedInfo::getDeliveryCode() const { - return deliveryCode; -} +cfdp::FinishedDeliveryCode FinishedInfo::getDeliveryCode() const { return deliveryCode; } void FinishedInfo::setDeliveryCode(cfdp::FinishedDeliveryCode deliveryCode) { - this->deliveryCode = deliveryCode; + this->deliveryCode = deliveryCode; } -cfdp::FinishedFileStatus FinishedInfo::getFileStatus() const { - return fileStatus; -} +cfdp::FinishedFileStatus FinishedInfo::getFileStatus() const { return fileStatus; } void FinishedInfo::setFilestoreResponsesArrayLen(size_t fsResponsesLen) { - this->fsResponsesLen = fsResponsesLen; + this->fsResponsesLen = fsResponsesLen; } -size_t FinishedInfo::getFsResponsesLen() const { - return fsResponsesLen; -} +size_t FinishedInfo::getFsResponsesLen() const { return fsResponsesLen; } void FinishedInfo::setFileStatus(cfdp::FinishedFileStatus fileStatus) { - this->fileStatus = fileStatus; + this->fileStatus = fileStatus; } diff --git a/src/fsfw/cfdp/pdu/FinishedInfo.h b/src/fsfw/cfdp/pdu/FinishedInfo.h index 18552df5..5768a298 100644 --- a/src/fsfw/cfdp/pdu/FinishedInfo.h +++ b/src/fsfw/cfdp/pdu/FinishedInfo.h @@ -1,45 +1,45 @@ #ifndef FSFW_SRC_FSFW_CFDP_PDU_FINISHINFO_H_ #define FSFW_SRC_FSFW_CFDP_PDU_FINISHINFO_H_ +#include "../definitions.h" #include "fsfw/cfdp/tlv/EntityIdTlv.h" #include "fsfw/cfdp/tlv/FilestoreResponseTlv.h" -#include "../definitions.h" class FinishedInfo { -public: - FinishedInfo(); - FinishedInfo(cfdp::ConditionCode conditionCode, cfdp::FinishedDeliveryCode deliveryCode, - cfdp::FinishedFileStatus fileStatus); + public: + FinishedInfo(); + FinishedInfo(cfdp::ConditionCode conditionCode, cfdp::FinishedDeliveryCode deliveryCode, + cfdp::FinishedFileStatus fileStatus); - size_t getSerializedSize() const; + size_t getSerializedSize() const; - bool hasFsResponses() const; - bool canHoldFsResponses() const; + bool hasFsResponses() const; + bool canHoldFsResponses() const; - ReturnValue_t setFilestoreResponsesArray(FilestoreResponseTlv** fsResponses, - size_t* fsResponsesLen, const size_t* maxFsResponseLen); - void setFaultLocation(EntityIdTlv* entityId); + ReturnValue_t setFilestoreResponsesArray(FilestoreResponseTlv** fsResponses, + size_t* fsResponsesLen, const size_t* maxFsResponseLen); + void setFaultLocation(EntityIdTlv* entityId); - ReturnValue_t getFilestoreResonses(FilestoreResponseTlv ***fsResponses, - size_t *fsResponsesLen, size_t* fsResponsesMaxLen); - size_t getFsResponsesLen() const; - void setFilestoreResponsesArrayLen(size_t fsResponsesLen); - ReturnValue_t getFaultLocation(EntityIdTlv** entityId); - cfdp::ConditionCode getConditionCode() const; - void setConditionCode(cfdp::ConditionCode conditionCode); - cfdp::FinishedDeliveryCode getDeliveryCode() const; - void setDeliveryCode(cfdp::FinishedDeliveryCode deliveryCode); - cfdp::FinishedFileStatus getFileStatus() const; - void setFileStatus(cfdp::FinishedFileStatus fileStatus); + ReturnValue_t getFilestoreResonses(FilestoreResponseTlv*** fsResponses, size_t* fsResponsesLen, + size_t* fsResponsesMaxLen); + size_t getFsResponsesLen() const; + void setFilestoreResponsesArrayLen(size_t fsResponsesLen); + ReturnValue_t getFaultLocation(EntityIdTlv** entityId); + cfdp::ConditionCode getConditionCode() const; + void setConditionCode(cfdp::ConditionCode conditionCode); + cfdp::FinishedDeliveryCode getDeliveryCode() const; + void setDeliveryCode(cfdp::FinishedDeliveryCode deliveryCode); + cfdp::FinishedFileStatus getFileStatus() const; + void setFileStatus(cfdp::FinishedFileStatus fileStatus); -private: - cfdp::ConditionCode conditionCode = cfdp::ConditionCode::NO_CONDITION_FIELD; - cfdp::FinishedDeliveryCode deliveryCode = cfdp::FinishedDeliveryCode::DATA_COMPLETE; - cfdp::FinishedFileStatus fileStatus = cfdp::FinishedFileStatus::DISCARDED_DELIBERATELY; - FilestoreResponseTlv** fsResponses = nullptr; - size_t fsResponsesLen = 0; - size_t fsResponsesMaxLen = 0; - EntityIdTlv* faultLocation = nullptr; + private: + cfdp::ConditionCode conditionCode = cfdp::ConditionCode::NO_CONDITION_FIELD; + cfdp::FinishedDeliveryCode deliveryCode = cfdp::FinishedDeliveryCode::DATA_COMPLETE; + cfdp::FinishedFileStatus fileStatus = cfdp::FinishedFileStatus::DISCARDED_DELIBERATELY; + FilestoreResponseTlv** fsResponses = nullptr; + size_t fsResponsesLen = 0; + size_t fsResponsesMaxLen = 0; + EntityIdTlv* faultLocation = nullptr; }; #endif /* FSFW_SRC_FSFW_CFDP_PDU_FINISHINFO_H_ */ diff --git a/src/fsfw/cfdp/pdu/FinishedPduDeserializer.cpp b/src/fsfw/cfdp/pdu/FinishedPduDeserializer.cpp index 55528650..feeca617 100644 --- a/src/fsfw/cfdp/pdu/FinishedPduDeserializer.cpp +++ b/src/fsfw/cfdp/pdu/FinishedPduDeserializer.cpp @@ -1,90 +1,88 @@ #include "FinishedPduDeserializer.h" -FinishPduDeserializer::FinishPduDeserializer(const uint8_t *pduBuf, size_t maxSize, - FinishedInfo &info): FileDirectiveDeserializer(pduBuf, maxSize), finishedInfo(info) { -} +FinishPduDeserializer::FinishPduDeserializer(const uint8_t* pduBuf, size_t maxSize, + FinishedInfo& info) + : FileDirectiveDeserializer(pduBuf, maxSize), finishedInfo(info) {} ReturnValue_t FinishPduDeserializer::parseData() { - ReturnValue_t result = FileDirectiveDeserializer::parseData(); - if(result != HasReturnvaluesIF::RETURN_OK) { + ReturnValue_t result = FileDirectiveDeserializer::parseData(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + size_t currentIdx = FileDirectiveDeserializer::getHeaderSize(); + const uint8_t* buf = rawPtr + currentIdx; + size_t remSize = FileDirectiveDeserializer::getWholePduSize() - currentIdx; + if (remSize < 1) { + return SerializeIF::STREAM_TOO_SHORT; + } + uint8_t firstByte = *buf; + cfdp::ConditionCode condCode = static_cast((firstByte >> 4) & 0x0f); + finishedInfo.setConditionCode(condCode); + finishedInfo.setDeliveryCode(static_cast(firstByte >> 2 & 0b1)); + finishedInfo.setFileStatus(static_cast(firstByte & 0b11)); + buf += 1; + remSize -= 1; + currentIdx += 1; + if (remSize > 0) { + result = parseTlvs(remSize, currentIdx, buf, condCode); + } + return result; +} + +FinishedInfo& FinishPduDeserializer::getInfo() { return finishedInfo; } + +ReturnValue_t FinishPduDeserializer::parseTlvs(size_t remLen, size_t currentIdx, const uint8_t* buf, + cfdp::ConditionCode conditionCode) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + size_t fsResponsesIdx = 0; + auto endianness = getEndianness(); + FilestoreResponseTlv** fsResponseArray = nullptr; + size_t fsResponseMaxArrayLen = 0; + EntityIdTlv* faultLocation = nullptr; + cfdp::TlvTypes nextTlv = cfdp::TlvTypes::INVALID_TLV; + while (remLen > 0) { + // Simply forward parse the TLV type. Every TLV type except the last one must be a Filestore + // Response TLV, and even the last one can be a Filestore Response TLV if the fault + // location is omitted + if (currentIdx + 2 > maxSize) { + return SerializeIF::STREAM_TOO_SHORT; + } + nextTlv = static_cast(*buf); + if (nextTlv == cfdp::TlvTypes::FILESTORE_RESPONSE) { + if (fsResponseArray == nullptr) { + if (not finishedInfo.canHoldFsResponses()) { + return cfdp::FINISHED_CANT_PARSE_FS_RESPONSES; + } + result = + finishedInfo.getFilestoreResonses(&fsResponseArray, nullptr, &fsResponseMaxArrayLen); + } + if (fsResponsesIdx == fsResponseMaxArrayLen) { + return cfdp::FINISHED_CANT_PARSE_FS_RESPONSES; + } + result = fsResponseArray[fsResponsesIdx]->deSerialize(&buf, &remLen, endianness); + if (result != HasReturnvaluesIF::RETURN_OK) { return result; + } + fsResponsesIdx += 1; + } else if (nextTlv == cfdp::TlvTypes::ENTITY_ID) { + // This needs to be the last TLV and it should not be here if the condition code + // is "No Error" or "Unsupported Checksum Type" + if (conditionCode == cfdp::ConditionCode::NO_ERROR or + conditionCode == cfdp::ConditionCode::UNSUPPORTED_CHECKSUM_TYPE) { + return cfdp::INVALID_TLV_TYPE; + } + result = finishedInfo.getFaultLocation(&faultLocation); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = faultLocation->deSerialize(&buf, &remLen, endianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + } else { + return cfdp::INVALID_TLV_TYPE; } - size_t currentIdx = FileDirectiveDeserializer::getHeaderSize(); - const uint8_t* buf = rawPtr + currentIdx; - size_t remSize = FileDirectiveDeserializer::getWholePduSize() - currentIdx; - if (remSize < 1) { - return SerializeIF::STREAM_TOO_SHORT; - } - uint8_t firstByte = *buf; - cfdp::ConditionCode condCode = static_cast((firstByte >> 4) & 0x0f); - finishedInfo.setConditionCode(condCode); - finishedInfo.setDeliveryCode(static_cast(firstByte >> 2 & 0b1)); - finishedInfo.setFileStatus(static_cast(firstByte & 0b11)); - buf += 1; - remSize -= 1; - currentIdx += 1; - if(remSize > 0) { - result = parseTlvs(remSize, currentIdx, buf, condCode); - } - return result; -} - -FinishedInfo& FinishPduDeserializer::getInfo() { - return finishedInfo; -} - -ReturnValue_t FinishPduDeserializer::parseTlvs(size_t remLen, size_t currentIdx, - const uint8_t* buf, cfdp::ConditionCode conditionCode) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - size_t fsResponsesIdx = 0; - auto endianness = getEndianness(); - FilestoreResponseTlv** fsResponseArray = nullptr; - size_t fsResponseMaxArrayLen = 0; - EntityIdTlv* faultLocation = nullptr; - cfdp::TlvTypes nextTlv = cfdp::TlvTypes::INVALID_TLV; - while(remLen > 0) { - // Simply forward parse the TLV type. Every TLV type except the last one must be a Filestore - // Response TLV, and even the last one can be a Filestore Response TLV if the fault - // location is omitted - if (currentIdx + 2 > maxSize) { - return SerializeIF::STREAM_TOO_SHORT; - } - nextTlv = static_cast(*buf); - if (nextTlv == cfdp::TlvTypes::FILESTORE_RESPONSE) { - if(fsResponseArray == nullptr) { - if(not finishedInfo.canHoldFsResponses()) { - return cfdp::FINISHED_CANT_PARSE_FS_RESPONSES; - } - result = finishedInfo.getFilestoreResonses(&fsResponseArray, nullptr, - &fsResponseMaxArrayLen); - } - if(fsResponsesIdx == fsResponseMaxArrayLen) { - return cfdp::FINISHED_CANT_PARSE_FS_RESPONSES; - } - result = fsResponseArray[fsResponsesIdx]->deSerialize(&buf, &remLen, endianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - fsResponsesIdx += 1; - } else if(nextTlv == cfdp::TlvTypes::ENTITY_ID) { - // This needs to be the last TLV and it should not be here if the condition code - // is "No Error" or "Unsupported Checksum Type" - if(conditionCode == cfdp::ConditionCode::NO_ERROR or - conditionCode == cfdp::ConditionCode::UNSUPPORTED_CHECKSUM_TYPE) { - return cfdp::INVALID_TLV_TYPE; - } - result = finishedInfo.getFaultLocation(&faultLocation); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = faultLocation->deSerialize(&buf, &remLen, endianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - } else { - return cfdp::INVALID_TLV_TYPE; - } - } - finishedInfo.setFilestoreResponsesArrayLen(fsResponsesIdx); - return result; + } + finishedInfo.setFilestoreResponsesArrayLen(fsResponsesIdx); + return result; } diff --git a/src/fsfw/cfdp/pdu/FinishedPduDeserializer.h b/src/fsfw/cfdp/pdu/FinishedPduDeserializer.h index dcbc23bd..a34fc4cb 100644 --- a/src/fsfw/cfdp/pdu/FinishedPduDeserializer.h +++ b/src/fsfw/cfdp/pdu/FinishedPduDeserializer.h @@ -1,21 +1,22 @@ #ifndef FSFW_SRC_FSFW_CFDP_PDU_FINISHEDPDUDESERIALIZER_H_ #define FSFW_SRC_FSFW_CFDP_PDU_FINISHEDPDUDESERIALIZER_H_ -#include "fsfw/cfdp/pdu/FinishedInfo.h" #include "fsfw/cfdp/pdu/FileDirectiveDeserializer.h" +#include "fsfw/cfdp/pdu/FinishedInfo.h" -class FinishPduDeserializer: public FileDirectiveDeserializer { -public: - FinishPduDeserializer(const uint8_t *pduBuf, size_t maxSize, FinishedInfo& info); +class FinishPduDeserializer : public FileDirectiveDeserializer { + public: + FinishPduDeserializer(const uint8_t* pduBuf, size_t maxSize, FinishedInfo& info); - ReturnValue_t parseData() override; + ReturnValue_t parseData() override; - FinishedInfo& getInfo(); -private: - FinishedInfo& finishedInfo; + FinishedInfo& getInfo(); - ReturnValue_t parseTlvs(size_t remLen, size_t currentIdx, const uint8_t* buf, - cfdp::ConditionCode conditionCode); + private: + FinishedInfo& finishedInfo; + + ReturnValue_t parseTlvs(size_t remLen, size_t currentIdx, const uint8_t* buf, + cfdp::ConditionCode conditionCode); }; #endif /* FSFW_SRC_FSFW_CFDP_PDU_FINISHEDPDUDESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/FinishedPduSerializer.cpp b/src/fsfw/cfdp/pdu/FinishedPduSerializer.cpp index 98112ce2..115a2c9c 100644 --- a/src/fsfw/cfdp/pdu/FinishedPduSerializer.cpp +++ b/src/fsfw/cfdp/pdu/FinishedPduSerializer.cpp @@ -1,47 +1,47 @@ #include "FinishedPduSerializer.h" -FinishPduSerializer::FinishPduSerializer(PduConfig &conf, FinishedInfo &finishInfo): - FileDirectiveSerializer(conf, cfdp::FileDirectives::FINISH, 0), finishInfo(finishInfo) { - updateDirectiveFieldLen(); +FinishPduSerializer::FinishPduSerializer(PduConfig &conf, FinishedInfo &finishInfo) + : FileDirectiveSerializer(conf, cfdp::FileDirectives::FINISH, 0), finishInfo(finishInfo) { + updateDirectiveFieldLen(); } size_t FinishPduSerializer::getSerializedSize() const { - return FinishPduSerializer::getWholePduSize(); + return FinishPduSerializer::getWholePduSize(); } void FinishPduSerializer::updateDirectiveFieldLen() { - setDirectiveDataFieldLen(finishInfo.getSerializedSize()); + setDirectiveDataFieldLen(finishInfo.getSerializedSize()); } ReturnValue_t FinishPduSerializer::serialize(uint8_t **buffer, size_t *size, size_t maxSize, - Endianness streamEndianness) const { - ReturnValue_t result = FileDirectiveSerializer::serialize(buffer, size, maxSize, - streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if(*size + 1 >= maxSize) { - return SerializeIF::BUFFER_TOO_SHORT; - } - **buffer = finishInfo.getConditionCode() << 4 | finishInfo.getDeliveryCode() << 2 | - finishInfo.getFileStatus(); - *size += 1; - *buffer += 1; - - if(finishInfo.hasFsResponses()) { - FilestoreResponseTlv** fsResponsesArray = nullptr; - size_t fsResponsesArrayLen = 0; - finishInfo.getFilestoreResonses(&fsResponsesArray, &fsResponsesArrayLen, nullptr); - for(size_t idx = 0; idx < fsResponsesArrayLen; idx++) { - result = fsResponsesArray[idx]->serialize(buffer, size, maxSize, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - } - } - EntityIdTlv* entityId = nullptr; - if(finishInfo.getFaultLocation(&entityId) == HasReturnvaluesIF::RETURN_OK) { - result = entityId->serialize(buffer, size, maxSize, streamEndianness); - } + Endianness streamEndianness) const { + ReturnValue_t result = + FileDirectiveSerializer::serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { return result; + } + if (*size + 1 >= maxSize) { + return SerializeIF::BUFFER_TOO_SHORT; + } + **buffer = finishInfo.getConditionCode() << 4 | finishInfo.getDeliveryCode() << 2 | + finishInfo.getFileStatus(); + *size += 1; + *buffer += 1; + + if (finishInfo.hasFsResponses()) { + FilestoreResponseTlv **fsResponsesArray = nullptr; + size_t fsResponsesArrayLen = 0; + finishInfo.getFilestoreResonses(&fsResponsesArray, &fsResponsesArrayLen, nullptr); + for (size_t idx = 0; idx < fsResponsesArrayLen; idx++) { + result = fsResponsesArray[idx]->serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + } + } + EntityIdTlv *entityId = nullptr; + if (finishInfo.getFaultLocation(&entityId) == HasReturnvaluesIF::RETURN_OK) { + result = entityId->serialize(buffer, size, maxSize, streamEndianness); + } + return result; } diff --git a/src/fsfw/cfdp/pdu/FinishedPduSerializer.h b/src/fsfw/cfdp/pdu/FinishedPduSerializer.h index cfb067a5..d66b25f2 100644 --- a/src/fsfw/cfdp/pdu/FinishedPduSerializer.h +++ b/src/fsfw/cfdp/pdu/FinishedPduSerializer.h @@ -1,22 +1,23 @@ #ifndef FSFW_SRC_FSFW_CFDP_PDU_FINISHEDPDUSERIALIZER_H_ #define FSFW_SRC_FSFW_CFDP_PDU_FINISHEDPDUSERIALIZER_H_ -#include "fsfw/cfdp/pdu/FileDirectiveSerializer.h" -#include "fsfw/cfdp/pdu/FileDataSerializer.h" #include "FinishedInfo.h" +#include "fsfw/cfdp/pdu/FileDataSerializer.h" +#include "fsfw/cfdp/pdu/FileDirectiveSerializer.h" -class FinishPduSerializer: public FileDirectiveSerializer { -public: - FinishPduSerializer(PduConfig& pduConf, FinishedInfo& finishInfo); +class FinishPduSerializer : public FileDirectiveSerializer { + public: + FinishPduSerializer(PduConfig& pduConf, FinishedInfo& finishInfo); - void updateDirectiveFieldLen(); + void updateDirectiveFieldLen(); - size_t getSerializedSize() const override; + size_t getSerializedSize() const override; - ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, - Endianness streamEndianness) const override; -private: - FinishedInfo& finishInfo; + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; + + private: + FinishedInfo& finishInfo; }; #endif /* FSFW_SRC_FSFW_CFDP_PDU_FINISHEDPDUSERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/HeaderDeserializer.cpp b/src/fsfw/cfdp/pdu/HeaderDeserializer.cpp index 39994eb5..70f397f8 100644 --- a/src/fsfw/cfdp/pdu/HeaderDeserializer.cpp +++ b/src/fsfw/cfdp/pdu/HeaderDeserializer.cpp @@ -1,136 +1,128 @@ -#include #include "HeaderDeserializer.h" + +#include + #include -HeaderDeserializer::HeaderDeserializer(const uint8_t *pduBuf, size_t maxSize): - rawPtr(pduBuf), maxSize(maxSize) { -} +HeaderDeserializer::HeaderDeserializer(const uint8_t *pduBuf, size_t maxSize) + : rawPtr(pduBuf), maxSize(maxSize) {} ReturnValue_t HeaderDeserializer::parseData() { - if (maxSize < 7) { - return SerializeIF::STREAM_TOO_SHORT; - } - return setData(const_cast(rawPtr), maxSize); + if (maxSize < 7) { + return SerializeIF::STREAM_TOO_SHORT; + } + return setData(const_cast(rawPtr), maxSize); } -ReturnValue_t HeaderDeserializer::setData(uint8_t *dataPtr, size_t maxSize, - void* args) { - if(dataPtr == nullptr) { - // Allowed for now - this->fixedHeader = nullptr; - return HasReturnvaluesIF::RETURN_OK; - } - this->fixedHeader = reinterpret_cast(const_cast(dataPtr)); - sourceIdRaw = static_cast(&fixedHeader->variableFieldsStart); - cfdp::WidthInBytes widthEntityIds = getLenEntityIds(); - cfdp::WidthInBytes widthSeqNum = getLenSeqNum(); - seqNumRaw = static_cast(sourceIdRaw) + static_cast(widthEntityIds); - destIdRaw = static_cast(seqNumRaw) + static_cast(widthSeqNum); - this->maxSize = maxSize; +ReturnValue_t HeaderDeserializer::setData(uint8_t *dataPtr, size_t maxSize, void *args) { + if (dataPtr == nullptr) { + // Allowed for now + this->fixedHeader = nullptr; return HasReturnvaluesIF::RETURN_OK; + } + this->fixedHeader = reinterpret_cast(const_cast(dataPtr)); + sourceIdRaw = static_cast(&fixedHeader->variableFieldsStart); + cfdp::WidthInBytes widthEntityIds = getLenEntityIds(); + cfdp::WidthInBytes widthSeqNum = getLenSeqNum(); + seqNumRaw = static_cast(sourceIdRaw) + static_cast(widthEntityIds); + destIdRaw = static_cast(seqNumRaw) + static_cast(widthSeqNum); + this->maxSize = maxSize; + return HasReturnvaluesIF::RETURN_OK; } size_t HeaderDeserializer::getHeaderSize() const { - if(fixedHeader != nullptr) { - return getLenEntityIds() * 2 + getLenSeqNum() + 4; - } - return 0; + if (fixedHeader != nullptr) { + return getLenEntityIds() * 2 + getLenSeqNum() + 4; + } + return 0; } size_t HeaderDeserializer::getPduDataFieldLen() const { - uint16_t pduFiedlLen = (fixedHeader->pduDataFieldLenH << 8) | fixedHeader->pduDataFieldLenL; - return pduFiedlLen; + uint16_t pduFiedlLen = (fixedHeader->pduDataFieldLenH << 8) | fixedHeader->pduDataFieldLenL; + return pduFiedlLen; } size_t HeaderDeserializer::getWholePduSize() const { - return getPduDataFieldLen() + getHeaderSize(); + return getPduDataFieldLen() + getHeaderSize(); } cfdp::PduType HeaderDeserializer::getPduType() const { - return static_cast((fixedHeader->firstByte >> 4) & 0x01); + return static_cast((fixedHeader->firstByte >> 4) & 0x01); } cfdp::Direction HeaderDeserializer::getDirection() const { - return static_cast((fixedHeader->firstByte >> 3) & 0x01); + return static_cast((fixedHeader->firstByte >> 3) & 0x01); } cfdp::TransmissionModes HeaderDeserializer::getTransmissionMode() const { - return static_cast((fixedHeader->firstByte >> 2) & 0x01); + return static_cast((fixedHeader->firstByte >> 2) & 0x01); } -bool HeaderDeserializer::getCrcFlag() const { - return (fixedHeader->firstByte >> 1) & 0x01; -} +bool HeaderDeserializer::getCrcFlag() const { return (fixedHeader->firstByte >> 1) & 0x01; } -bool HeaderDeserializer::getLargeFileFlag() const { - return fixedHeader->firstByte & 0x01; -} +bool HeaderDeserializer::getLargeFileFlag() const { return fixedHeader->firstByte & 0x01; } cfdp::SegmentationControl HeaderDeserializer::getSegmentationControl() const { - return static_cast((fixedHeader->fourthByte >> 7) & 0x01); + return static_cast((fixedHeader->fourthByte >> 7) & 0x01); } cfdp::WidthInBytes HeaderDeserializer::getLenEntityIds() const { - return static_cast((fixedHeader->fourthByte >> 4) & 0x07); + return static_cast((fixedHeader->fourthByte >> 4) & 0x07); } cfdp::WidthInBytes HeaderDeserializer::getLenSeqNum() const { - return static_cast(fixedHeader->fourthByte & 0x07); + return static_cast(fixedHeader->fourthByte & 0x07); } cfdp::SegmentMetadataFlag HeaderDeserializer::getSegmentMetadataFlag() const { - return static_cast((fixedHeader->fourthByte >> 3) & 0x01); + return static_cast((fixedHeader->fourthByte >> 3) & 0x01); } void HeaderDeserializer::getSourceId(cfdp::EntityId &sourceId) const { - assignVarLenField(dynamic_cast(&sourceId), getLenEntityIds(), - this->sourceIdRaw); + assignVarLenField(dynamic_cast(&sourceId), getLenEntityIds(), + this->sourceIdRaw); } void HeaderDeserializer::getDestId(cfdp::EntityId &destId) const { - assignVarLenField(dynamic_cast(&destId), getLenEntityIds(), - this->destIdRaw); + assignVarLenField(dynamic_cast(&destId), getLenEntityIds(), this->destIdRaw); } void HeaderDeserializer::getTransactionSeqNum(cfdp::TransactionSeqNum &seqNum) const { - assignVarLenField(dynamic_cast(&seqNum), getLenSeqNum(), - this->seqNumRaw); + assignVarLenField(dynamic_cast(&seqNum), getLenSeqNum(), this->seqNumRaw); } -void HeaderDeserializer::assignVarLenField(cfdp::VarLenField* field, cfdp::WidthInBytes width, - void *sourcePtr) const { - switch(width) { - case(cfdp::WidthInBytes::ONE_BYTE): { - uint8_t* fieldTyped = static_cast(sourcePtr); - field->setValue(width, *fieldTyped); - break; +void HeaderDeserializer::assignVarLenField(cfdp::VarLenField *field, cfdp::WidthInBytes width, + void *sourcePtr) const { + switch (width) { + case (cfdp::WidthInBytes::ONE_BYTE): { + uint8_t *fieldTyped = static_cast(sourcePtr); + field->setValue(width, *fieldTyped); + break; } - case(cfdp::WidthInBytes::TWO_BYTES): { - uint16_t fieldTyped = 0; - size_t deserSize = 0; - SerializeAdapter::deSerialize(&fieldTyped, static_cast(sourcePtr), &deserSize, - SerializeIF::Endianness::NETWORK); - field->setValue(width, fieldTyped); - break; - } - case(cfdp::WidthInBytes::FOUR_BYTES): { - uint32_t fieldTyped = 0; - size_t deserSize = 0; - SerializeAdapter::deSerialize(&fieldTyped, static_cast(sourcePtr), &deserSize, - SerializeIF::Endianness::NETWORK); - field->setValue(width, fieldTyped); - break; + case (cfdp::WidthInBytes::TWO_BYTES): { + uint16_t fieldTyped = 0; + size_t deserSize = 0; + SerializeAdapter::deSerialize(&fieldTyped, static_cast(sourcePtr), &deserSize, + SerializeIF::Endianness::NETWORK); + field->setValue(width, fieldTyped); + break; } + case (cfdp::WidthInBytes::FOUR_BYTES): { + uint32_t fieldTyped = 0; + size_t deserSize = 0; + SerializeAdapter::deSerialize(&fieldTyped, static_cast(sourcePtr), &deserSize, + SerializeIF::Endianness::NETWORK); + field->setValue(width, fieldTyped); + break; } + } } -size_t HeaderDeserializer::getMaxSize() const { - return maxSize; -} +size_t HeaderDeserializer::getMaxSize() const { return maxSize; } bool HeaderDeserializer::hasSegmentMetadataFlag() const { - if(this->getSegmentMetadataFlag() == cfdp::SegmentMetadataFlag::PRESENT) { - return true; - } - return false; + if (this->getSegmentMetadataFlag() == cfdp::SegmentMetadataFlag::PRESENT) { + return true; + } + return false; } diff --git a/src/fsfw/cfdp/pdu/HeaderDeserializer.h b/src/fsfw/cfdp/pdu/HeaderDeserializer.h index d44d538f..ed033697 100644 --- a/src/fsfw/cfdp/pdu/HeaderDeserializer.h +++ b/src/fsfw/cfdp/pdu/HeaderDeserializer.h @@ -1,19 +1,20 @@ #ifndef FSFW_SRC_FSFW_CFDP_PDU_HEADERDESERIALIZER_H_ #define FSFW_SRC_FSFW_CFDP_PDU_HEADERDESERIALIZER_H_ +#include +#include + #include "PduConfig.h" #include "PduHeaderIF.h" #include "fsfw/serialize/SerializeIF.h" #include "fsfw/tmtcpacket/RedirectableDataPointerIF.h" -#include -#include struct PduHeaderFixedStruct { - uint8_t firstByte; - uint8_t pduDataFieldLenH; - uint8_t pduDataFieldLenL; - uint8_t fourthByte; - uint8_t variableFieldsStart; + uint8_t firstByte; + uint8_t pduDataFieldLenH; + uint8_t pduDataFieldLenL; + uint8_t fourthByte; + uint8_t variableFieldsStart; }; /** @@ -22,72 +23,68 @@ struct PduHeaderFixedStruct { * This is a zero-copy implementation and #parseData needs to be called to ensure the data is * valid. */ -class HeaderDeserializer: - public RedirectableDataPointerIF, - public PduHeaderIF { -public: - /** - * Initialize a PDU header from raw data. This is a zero-copy implementation and #parseData - * needs to be called to ensure the data is valid - * @param pduBuf - * @param maxSize - */ - HeaderDeserializer(const uint8_t* pduBuf, size_t maxSize); +class HeaderDeserializer : public RedirectableDataPointerIF, public PduHeaderIF { + public: + /** + * Initialize a PDU header from raw data. This is a zero-copy implementation and #parseData + * needs to be called to ensure the data is valid + * @param pduBuf + * @param maxSize + */ + HeaderDeserializer(const uint8_t* pduBuf, size_t maxSize); - /** - * This needs to be called before accessing the PDU fields to avoid segmentation faults. - * @return - * - RETURN_OK on parse success - * - RETURN_FAILED Invalid raw data - * - SerializeIF::BUFFER_TOO_SHORT if buffer is shorter than expected - */ - virtual ReturnValue_t parseData(); - size_t getHeaderSize() const; + /** + * This needs to be called before accessing the PDU fields to avoid segmentation faults. + * @return + * - RETURN_OK on parse success + * - RETURN_FAILED Invalid raw data + * - SerializeIF::BUFFER_TOO_SHORT if buffer is shorter than expected + */ + virtual ReturnValue_t parseData(); + size_t getHeaderSize() const; - size_t getPduDataFieldLen() const override; - size_t getWholePduSize() const override; + size_t getPduDataFieldLen() const override; + size_t getWholePduSize() const override; - cfdp::PduType getPduType() const override; - cfdp::Direction getDirection() const override; - cfdp::TransmissionModes getTransmissionMode() const override; - bool getCrcFlag() const override; - bool getLargeFileFlag() const override; - cfdp::SegmentationControl getSegmentationControl() const override; - cfdp::WidthInBytes getLenEntityIds() const override; - cfdp::WidthInBytes getLenSeqNum() const override; - cfdp::SegmentMetadataFlag getSegmentMetadataFlag() const override; - bool hasSegmentMetadataFlag() const override; + cfdp::PduType getPduType() const override; + cfdp::Direction getDirection() const override; + cfdp::TransmissionModes getTransmissionMode() const override; + bool getCrcFlag() const override; + bool getLargeFileFlag() const override; + cfdp::SegmentationControl getSegmentationControl() const override; + cfdp::WidthInBytes getLenEntityIds() const override; + cfdp::WidthInBytes getLenSeqNum() const override; + cfdp::SegmentMetadataFlag getSegmentMetadataFlag() const override; + bool hasSegmentMetadataFlag() const override; - void getSourceId(cfdp::EntityId& sourceId) const override; - void getDestId(cfdp::EntityId& destId) const override; - void getTransactionSeqNum(cfdp::TransactionSeqNum& seqNum) const override; + void getSourceId(cfdp::EntityId& sourceId) const override; + void getDestId(cfdp::EntityId& destId) const override; + void getTransactionSeqNum(cfdp::TransactionSeqNum& seqNum) const override; - ReturnValue_t deserResult = HasReturnvaluesIF::RETURN_OK; + ReturnValue_t deserResult = HasReturnvaluesIF::RETURN_OK; - /** - * Can also be used to reset the pointer to a nullptr, but the getter functions will not - * perform nullptr checks! - * @param dataPtr - * @param maxSize - * @param args - * @return - */ - ReturnValue_t setData(uint8_t* dataPtr, size_t maxSize, - void* args = nullptr) override; + /** + * Can also be used to reset the pointer to a nullptr, but the getter functions will not + * perform nullptr checks! + * @param dataPtr + * @param maxSize + * @param args + * @return + */ + ReturnValue_t setData(uint8_t* dataPtr, size_t maxSize, void* args = nullptr) override; - size_t getMaxSize() const; -protected: - PduHeaderFixedStruct* fixedHeader = nullptr; - const uint8_t* rawPtr = nullptr; - size_t maxSize = 0; + size_t getMaxSize() const; -private: + protected: + PduHeaderFixedStruct* fixedHeader = nullptr; + const uint8_t* rawPtr = nullptr; + size_t maxSize = 0; - void assignVarLenField(cfdp::VarLenField* field, cfdp::WidthInBytes width, - void* sourcePtr) const; - void* sourceIdRaw = nullptr; - void* seqNumRaw = nullptr; - void* destIdRaw = nullptr; + private: + void assignVarLenField(cfdp::VarLenField* field, cfdp::WidthInBytes width, void* sourcePtr) const; + void* sourceIdRaw = nullptr; + void* seqNumRaw = nullptr; + void* destIdRaw = nullptr; }; #endif /* FSFW_SRC_FSFW_CFDP_PDU_HEADERDESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/HeaderSerializer.cpp b/src/fsfw/cfdp/pdu/HeaderSerializer.cpp index a5163b29..041fb714 100644 --- a/src/fsfw/cfdp/pdu/HeaderSerializer.cpp +++ b/src/fsfw/cfdp/pdu/HeaderSerializer.cpp @@ -1,135 +1,117 @@ #include "HeaderSerializer.h" + #include "HeaderDeserializer.h" -HeaderSerializer::HeaderSerializer(PduConfig& pduConf, cfdp::PduType pduType, - size_t initPduDataFieldLen, cfdp::SegmentMetadataFlag segmentMetadataFlag, - cfdp::SegmentationControl segCtrl): - pduType(pduType), segmentMetadataFlag(segmentMetadataFlag), segmentationCtrl(segCtrl), - pduDataFieldLen(initPduDataFieldLen), pduConf(pduConf) { -} +HeaderSerializer::HeaderSerializer(PduConfig &pduConf, cfdp::PduType pduType, + size_t initPduDataFieldLen, + cfdp::SegmentMetadataFlag segmentMetadataFlag, + cfdp::SegmentationControl segCtrl) + : pduType(pduType), + segmentMetadataFlag(segmentMetadataFlag), + segmentationCtrl(segCtrl), + pduDataFieldLen(initPduDataFieldLen), + pduConf(pduConf) {} ReturnValue_t HeaderSerializer::serialize(uint8_t **buffer, size_t *size, size_t maxSize, - Endianness streamEndianness) const { - if(buffer == nullptr or size == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - if(maxSize < this->getSerializedSize()) { - return BUFFER_TOO_SHORT; - } - **buffer = cfdp::VERSION_BITS | this->pduType << 4 | pduConf.direction << 3 | - pduConf.mode << 2 | pduConf.crcFlag << 1 | pduConf.largeFile; - *buffer += 1; - **buffer = (pduDataFieldLen & 0xff00) >> 8; - *buffer += 1; - **buffer = pduDataFieldLen & 0x00ff; - *buffer += 1; - **buffer = segmentationCtrl << 7 | pduConf.sourceId.getWidth() << 4 | - segmentMetadataFlag << 3 | pduConf.seqNum.getWidth(); - *buffer += 1; - *size += 4; - ReturnValue_t result = pduConf.sourceId.serialize(buffer, size, maxSize, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = pduConf.seqNum.serialize(buffer, size, maxSize, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = pduConf.destId.serialize(buffer, size, maxSize, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + Endianness streamEndianness) const { + if (buffer == nullptr or size == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if (maxSize < this->getSerializedSize()) { + return BUFFER_TOO_SHORT; + } + **buffer = cfdp::VERSION_BITS | this->pduType << 4 | pduConf.direction << 3 | pduConf.mode << 2 | + pduConf.crcFlag << 1 | pduConf.largeFile; + *buffer += 1; + **buffer = (pduDataFieldLen & 0xff00) >> 8; + *buffer += 1; + **buffer = pduDataFieldLen & 0x00ff; + *buffer += 1; + **buffer = segmentationCtrl << 7 | pduConf.sourceId.getWidth() << 4 | segmentMetadataFlag << 3 | + pduConf.seqNum.getWidth(); + *buffer += 1; + *size += 4; + ReturnValue_t result = pduConf.sourceId.serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = pduConf.seqNum.serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = pduConf.destId.serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } size_t HeaderSerializer::getSerializedSize() const { - size_t shit = pduConf.seqNum.getWidth() + pduConf.sourceId.getWidth() * 2 + 4; - return shit; + size_t shit = pduConf.seqNum.getWidth() + pduConf.sourceId.getWidth() * 2 + 4; + return shit; } ReturnValue_t HeaderSerializer::deSerialize(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) { - // We could implement this, but I prefer dedicated classes - return HasReturnvaluesIF::RETURN_FAILED; + Endianness streamEndianness) { + // We could implement this, but I prefer dedicated classes + return HasReturnvaluesIF::RETURN_FAILED; } size_t HeaderSerializer::getWholePduSize() const { - // Return size of header plus the PDU data field length - return pduDataFieldLen + HeaderSerializer::getSerializedSize(); + // Return size of header plus the PDU data field length + return pduDataFieldLen + HeaderSerializer::getSerializedSize(); } -size_t HeaderSerializer::getPduDataFieldLen() const { - return pduDataFieldLen; -} +size_t HeaderSerializer::getPduDataFieldLen() const { return pduDataFieldLen; } void HeaderSerializer::setPduDataFieldLen(size_t pduDataFieldLen) { - this->pduDataFieldLen = pduDataFieldLen; + this->pduDataFieldLen = pduDataFieldLen; } -void HeaderSerializer::setPduType(cfdp::PduType pduType) { - this->pduType = pduType; -} +void HeaderSerializer::setPduType(cfdp::PduType pduType) { this->pduType = pduType; } void HeaderSerializer::setSegmentMetadataFlag(cfdp::SegmentMetadataFlag segmentMetadataFlag) { - this->segmentMetadataFlag = segmentMetadataFlag; + this->segmentMetadataFlag = segmentMetadataFlag; } -cfdp::PduType HeaderSerializer::getPduType() const { - return pduType; -} +cfdp::PduType HeaderSerializer::getPduType() const { return pduType; } -cfdp::Direction HeaderSerializer::getDirection() const { - return pduConf.direction; -} +cfdp::Direction HeaderSerializer::getDirection() const { return pduConf.direction; } -cfdp::TransmissionModes HeaderSerializer::getTransmissionMode() const { - return pduConf.mode; -} +cfdp::TransmissionModes HeaderSerializer::getTransmissionMode() const { return pduConf.mode; } -bool HeaderSerializer::getCrcFlag() const { - return pduConf.crcFlag; -} +bool HeaderSerializer::getCrcFlag() const { return pduConf.crcFlag; } -bool HeaderSerializer::getLargeFileFlag() const { - return pduConf.largeFile; -} +bool HeaderSerializer::getLargeFileFlag() const { return pduConf.largeFile; } cfdp::SegmentationControl HeaderSerializer::getSegmentationControl() const { - return segmentationCtrl; + return segmentationCtrl; } -cfdp::WidthInBytes HeaderSerializer::getLenEntityIds() const { - return pduConf.sourceId.getWidth(); -} +cfdp::WidthInBytes HeaderSerializer::getLenEntityIds() const { return pduConf.sourceId.getWidth(); } -cfdp::WidthInBytes HeaderSerializer::getLenSeqNum() const { - return pduConf.seqNum.getWidth(); -} +cfdp::WidthInBytes HeaderSerializer::getLenSeqNum() const { return pduConf.seqNum.getWidth(); } cfdp::SegmentMetadataFlag HeaderSerializer::getSegmentMetadataFlag() const { - return segmentMetadataFlag; + return segmentMetadataFlag; } -void HeaderSerializer::getSourceId(cfdp::EntityId &sourceId) const { - sourceId = pduConf.sourceId; -} +void HeaderSerializer::getSourceId(cfdp::EntityId &sourceId) const { sourceId = pduConf.sourceId; } -void HeaderSerializer::getDestId(cfdp::EntityId &destId) const { - destId = pduConf.destId; -} +void HeaderSerializer::getDestId(cfdp::EntityId &destId) const { destId = pduConf.destId; } void HeaderSerializer::setSegmentationControl(cfdp::SegmentationControl segmentationControl) { - this->segmentationCtrl = segmentationControl; + this->segmentationCtrl = segmentationControl; } void HeaderSerializer::getTransactionSeqNum(cfdp::TransactionSeqNum &seqNum) const { - seqNum = pduConf.seqNum; + seqNum = pduConf.seqNum; } bool HeaderSerializer::hasSegmentMetadataFlag() const { - if(this->segmentMetadataFlag == cfdp::SegmentMetadataFlag::PRESENT) { - return true; - } - return false; + if (this->segmentMetadataFlag == cfdp::SegmentMetadataFlag::PRESENT) { + return true; + } + return false; } diff --git a/src/fsfw/cfdp/pdu/HeaderSerializer.h b/src/fsfw/cfdp/pdu/HeaderSerializer.h index 61e9d74a..8f2fc3fd 100644 --- a/src/fsfw/cfdp/pdu/HeaderSerializer.h +++ b/src/fsfw/cfdp/pdu/HeaderSerializer.h @@ -1,64 +1,63 @@ #ifndef FSFW_SRC_FSFW_CFDP_PDU_HEADERSERIALIZER_H_ #define FSFW_SRC_FSFW_CFDP_PDU_HEADERSERIALIZER_H_ -#include "PduHeaderIF.h" -#include "fsfw/serialize/SerializeIF.h" #include "../definitions.h" #include "PduConfig.h" +#include "PduHeaderIF.h" +#include "fsfw/serialize/SerializeIF.h" -class HeaderSerializer: public SerializeIF, public PduHeaderIF { -public: +class HeaderSerializer : public SerializeIF, public PduHeaderIF { + public: + HeaderSerializer( + PduConfig& pduConf, cfdp::PduType pduType, size_t initPduDataFieldLen, + cfdp::SegmentMetadataFlag segmentMetadataFlag = cfdp::SegmentMetadataFlag::NOT_PRESENT, + cfdp::SegmentationControl segCtrl = + cfdp::SegmentationControl::NO_RECORD_BOUNDARIES_PRESERVATION); - HeaderSerializer(PduConfig& pduConf, cfdp::PduType pduType, - size_t initPduDataFieldLen, - cfdp::SegmentMetadataFlag segmentMetadataFlag = cfdp::SegmentMetadataFlag::NOT_PRESENT, - cfdp::SegmentationControl segCtrl = - cfdp::SegmentationControl::NO_RECORD_BOUNDARIES_PRESERVATION); + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; - ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, - Endianness streamEndianness) const override; + /** + * This only returns the length of the serialized hader. + * Use #getWholePduSize to get the length of the full packet, assuming that the PDU + * data field length was not properly. + * @return + */ + size_t getSerializedSize() const override; - /** - * This only returns the length of the serialized hader. - * Use #getWholePduSize to get the length of the full packet, assuming that the PDU - * data field length was not properly. - * @return - */ - size_t getSerializedSize() const override; + ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + Endianness streamEndianness) override; - ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) override; + void setPduDataFieldLen(size_t pduDataFieldLen); + void setPduType(cfdp::PduType pduType); + void setSegmentMetadataFlag(cfdp::SegmentMetadataFlag); - void setPduDataFieldLen(size_t pduDataFieldLen); - void setPduType(cfdp::PduType pduType); - void setSegmentMetadataFlag(cfdp::SegmentMetadataFlag); + size_t getPduDataFieldLen() const override; + size_t getWholePduSize() const override; - size_t getPduDataFieldLen() const override; - size_t getWholePduSize() const override; + cfdp::PduType getPduType() const override; + cfdp::Direction getDirection() const override; + cfdp::TransmissionModes getTransmissionMode() const override; + bool getCrcFlag() const override; + bool getLargeFileFlag() const override; + cfdp::SegmentationControl getSegmentationControl() const override; + cfdp::WidthInBytes getLenEntityIds() const override; + cfdp::WidthInBytes getLenSeqNum() const override; + cfdp::SegmentMetadataFlag getSegmentMetadataFlag() const override; + bool hasSegmentMetadataFlag() const; + void setSegmentationControl(cfdp::SegmentationControl); - cfdp::PduType getPduType() const override; - cfdp::Direction getDirection() const override; - cfdp::TransmissionModes getTransmissionMode() const override; - bool getCrcFlag() const override; - bool getLargeFileFlag() const override; - cfdp::SegmentationControl getSegmentationControl() const override; - cfdp::WidthInBytes getLenEntityIds() const override; - cfdp::WidthInBytes getLenSeqNum() const override; - cfdp::SegmentMetadataFlag getSegmentMetadataFlag() const override; - bool hasSegmentMetadataFlag() const; - void setSegmentationControl(cfdp::SegmentationControl); + void getSourceId(cfdp::EntityId& sourceId) const override; + void getDestId(cfdp::EntityId& destId) const override; + void getTransactionSeqNum(cfdp::TransactionSeqNum& seqNum) const override; - void getSourceId(cfdp::EntityId& sourceId) const override; - void getDestId(cfdp::EntityId& destId) const override; - void getTransactionSeqNum(cfdp::TransactionSeqNum& seqNum) const override; -private: - cfdp::PduType pduType; - cfdp::SegmentMetadataFlag segmentMetadataFlag; - cfdp::SegmentationControl segmentationCtrl; - size_t pduDataFieldLen; + private: + cfdp::PduType pduType; + cfdp::SegmentMetadataFlag segmentMetadataFlag; + cfdp::SegmentationControl segmentationCtrl; + size_t pduDataFieldLen; - PduConfig& pduConf; + PduConfig& pduConf; }; - #endif /* FSFW_SRC_FSFW_CFDP_PDU_HEADERSERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/KeepAlivePduDeserializer.cpp b/src/fsfw/cfdp/pdu/KeepAlivePduDeserializer.cpp index f8778224..15f80549 100644 --- a/src/fsfw/cfdp/pdu/KeepAlivePduDeserializer.cpp +++ b/src/fsfw/cfdp/pdu/KeepAlivePduDeserializer.cpp @@ -1,20 +1,18 @@ #include "KeepAlivePduDeserializer.h" -KeepAlivePduDeserializer::KeepAlivePduDeserializer(const uint8_t *pduBuf, size_t maxSize, - cfdp::FileSize &progress): FileDirectiveDeserializer(pduBuf, maxSize), progress(progress) { -} +KeepAlivePduDeserializer::KeepAlivePduDeserializer(const uint8_t* pduBuf, size_t maxSize, + cfdp::FileSize& progress) + : FileDirectiveDeserializer(pduBuf, maxSize), progress(progress) {} ReturnValue_t KeepAlivePduDeserializer::parseData() { - ReturnValue_t result = FileDirectiveDeserializer::parseData(); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - size_t currentIdx = FileDirectiveDeserializer::getHeaderSize(); - size_t remLen = FileDirectiveDeserializer::getWholePduSize() - currentIdx; - const uint8_t* buffer = rawPtr + currentIdx; - return progress.deSerialize(&buffer, &remLen, getEndianness()); + ReturnValue_t result = FileDirectiveDeserializer::parseData(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + size_t currentIdx = FileDirectiveDeserializer::getHeaderSize(); + size_t remLen = FileDirectiveDeserializer::getWholePduSize() - currentIdx; + const uint8_t* buffer = rawPtr + currentIdx; + return progress.deSerialize(&buffer, &remLen, getEndianness()); } -cfdp::FileSize& KeepAlivePduDeserializer::getProgress() { - return progress; -} +cfdp::FileSize& KeepAlivePduDeserializer::getProgress() { return progress; } diff --git a/src/fsfw/cfdp/pdu/KeepAlivePduDeserializer.h b/src/fsfw/cfdp/pdu/KeepAlivePduDeserializer.h index a7016166..e8b83ad6 100644 --- a/src/fsfw/cfdp/pdu/KeepAlivePduDeserializer.h +++ b/src/fsfw/cfdp/pdu/KeepAlivePduDeserializer.h @@ -4,15 +4,16 @@ #include "fsfw/cfdp/FileSize.h" #include "fsfw/cfdp/pdu/FileDirectiveDeserializer.h" -class KeepAlivePduDeserializer: public FileDirectiveDeserializer { -public: - KeepAlivePduDeserializer(const uint8_t *pduBuf, size_t maxSize, cfdp::FileSize& progress); +class KeepAlivePduDeserializer : public FileDirectiveDeserializer { + public: + KeepAlivePduDeserializer(const uint8_t* pduBuf, size_t maxSize, cfdp::FileSize& progress); - ReturnValue_t parseData() override; + ReturnValue_t parseData() override; - cfdp::FileSize& getProgress(); -private: - cfdp::FileSize& progress; + cfdp::FileSize& getProgress(); + + private: + cfdp::FileSize& progress; }; #endif /* FSFW_SRC_FSFW_CFDP_PDU_KEEPALIVEPDUDESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/KeepAlivePduSerializer.cpp b/src/fsfw/cfdp/pdu/KeepAlivePduSerializer.cpp index 7882562b..e635ce06 100644 --- a/src/fsfw/cfdp/pdu/KeepAlivePduSerializer.cpp +++ b/src/fsfw/cfdp/pdu/KeepAlivePduSerializer.cpp @@ -1,26 +1,26 @@ #include "KeepAlivePduSerializer.h" -KeepAlivePduSerializer::KeepAlivePduSerializer(PduConfig &conf, cfdp::FileSize& progress): - FileDirectiveSerializer(conf, cfdp::FileDirectives::KEEP_ALIVE, 4), progress(progress) { - updateDirectiveFieldLen(); +KeepAlivePduSerializer::KeepAlivePduSerializer(PduConfig &conf, cfdp::FileSize &progress) + : FileDirectiveSerializer(conf, cfdp::FileDirectives::KEEP_ALIVE, 4), progress(progress) { + updateDirectiveFieldLen(); } size_t KeepAlivePduSerializer::getSerializedSize() const { - return FileDirectiveSerializer::getWholePduSize(); + return FileDirectiveSerializer::getWholePduSize(); } void KeepAlivePduSerializer::updateDirectiveFieldLen() { - if(this->getLargeFileFlag()) { - this->setDirectiveDataFieldLen(8); - } + if (this->getLargeFileFlag()) { + this->setDirectiveDataFieldLen(8); + } } ReturnValue_t KeepAlivePduSerializer::serialize(uint8_t **buffer, size_t *size, size_t maxSize, - Endianness streamEndianness) const { - ReturnValue_t result = FileDirectiveSerializer::serialize(buffer, size, maxSize, - streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return progress.serialize(this->getLargeFileFlag(), buffer, size, maxSize, streamEndianness); + Endianness streamEndianness) const { + ReturnValue_t result = + FileDirectiveSerializer::serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return progress.serialize(this->getLargeFileFlag(), buffer, size, maxSize, streamEndianness); } diff --git a/src/fsfw/cfdp/pdu/KeepAlivePduSerializer.h b/src/fsfw/cfdp/pdu/KeepAlivePduSerializer.h index 57882d3f..d2499a79 100644 --- a/src/fsfw/cfdp/pdu/KeepAlivePduSerializer.h +++ b/src/fsfw/cfdp/pdu/KeepAlivePduSerializer.h @@ -4,18 +4,19 @@ #include "fsfw/cfdp/FileSize.h" #include "fsfw/cfdp/pdu/FileDirectiveSerializer.h" -class KeepAlivePduSerializer: public FileDirectiveSerializer { -public: - KeepAlivePduSerializer(PduConfig& conf, cfdp::FileSize& progress); +class KeepAlivePduSerializer : public FileDirectiveSerializer { + public: + KeepAlivePduSerializer(PduConfig& conf, cfdp::FileSize& progress); - void updateDirectiveFieldLen(); + void updateDirectiveFieldLen(); - size_t getSerializedSize() const override; + size_t getSerializedSize() const override; - ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, - Endianness streamEndianness) const override; -private: - cfdp::FileSize& progress; + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; + + private: + cfdp::FileSize& progress; }; #endif /* FSFW_SRC_FSFW_CFDP_PDU_KEEPALIVEPDUSERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/MetadataInfo.cpp b/src/fsfw/cfdp/pdu/MetadataInfo.cpp index 04e0d6d1..a2ca6972 100644 --- a/src/fsfw/cfdp/pdu/MetadataInfo.cpp +++ b/src/fsfw/cfdp/pdu/MetadataInfo.cpp @@ -1,115 +1,98 @@ #include "MetadataInfo.h" MetadataInfo::MetadataInfo(bool closureRequested, cfdp::ChecksumType checksumType, - cfdp::FileSize& fileSize, cfdp::Lv& sourceFileName, cfdp::Lv& destFileName): - closureRequested(closureRequested), checksumType(checksumType), fileSize(fileSize), - sourceFileName(sourceFileName), destFileName(destFileName) { -} + cfdp::FileSize& fileSize, cfdp::Lv& sourceFileName, + cfdp::Lv& destFileName) + : closureRequested(closureRequested), + checksumType(checksumType), + fileSize(fileSize), + sourceFileName(sourceFileName), + destFileName(destFileName) {} void MetadataInfo::setOptionsArray(cfdp::Tlv** optionsArray, size_t* optionsLen, - size_t* maxOptionsLen) { - this->optionsArray = optionsArray; - if(maxOptionsLen != nullptr) { - this->maxOptionsLen = *maxOptionsLen; - } - if(optionsLen != nullptr) { - this->optionsLen = *optionsLen; - } + size_t* maxOptionsLen) { + this->optionsArray = optionsArray; + if (maxOptionsLen != nullptr) { + this->maxOptionsLen = *maxOptionsLen; + } + if (optionsLen != nullptr) { + this->optionsLen = *optionsLen; + } } -cfdp::ChecksumType MetadataInfo::getChecksumType() const { - return checksumType; -} +cfdp::ChecksumType MetadataInfo::getChecksumType() const { return checksumType; } void MetadataInfo::setChecksumType(cfdp::ChecksumType checksumType) { - this->checksumType = checksumType; + this->checksumType = checksumType; } -bool MetadataInfo::isClosureRequested() const { - return closureRequested; -} +bool MetadataInfo::isClosureRequested() const { return closureRequested; } void MetadataInfo::setClosureRequested(bool closureRequested) { - this->closureRequested = closureRequested; + this->closureRequested = closureRequested; } -cfdp::Lv& MetadataInfo::getDestFileName() { - return destFileName; -} +cfdp::Lv& MetadataInfo::getDestFileName() { return destFileName; } -cfdp::FileSize& MetadataInfo::getFileSize() { - return fileSize; -} +cfdp::FileSize& MetadataInfo::getFileSize() { return fileSize; } -ReturnValue_t MetadataInfo::getOptions(cfdp::Tlv*** optionsArray, size_t *optionsLen, - size_t* maxOptsLen) { - if(optionsArray == nullptr or this->optionsArray == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - *optionsArray = this->optionsArray; - if(optionsLen != nullptr) { - *optionsLen = this->optionsLen; - } - if(maxOptsLen != nullptr) { - *maxOptsLen = this->maxOptionsLen; - } - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t MetadataInfo::getOptions(cfdp::Tlv*** optionsArray, size_t* optionsLen, + size_t* maxOptsLen) { + if (optionsArray == nullptr or this->optionsArray == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + *optionsArray = this->optionsArray; + if (optionsLen != nullptr) { + *optionsLen = this->optionsLen; + } + if (maxOptsLen != nullptr) { + *maxOptsLen = this->maxOptionsLen; + } + return HasReturnvaluesIF::RETURN_OK; } bool MetadataInfo::hasOptions() const { - if (optionsArray != nullptr and optionsLen > 0) { - return true; - } - return false; + if (optionsArray != nullptr and optionsLen > 0) { + return true; + } + return false; } bool MetadataInfo::canHoldOptions() const { - if (optionsArray != nullptr and maxOptionsLen > 0) { - return true; - } - return false; + if (optionsArray != nullptr and maxOptionsLen > 0) { + return true; + } + return false; } size_t MetadataInfo::getSerializedSize(bool fssLarge) { - // 1 byte + minimal FSS 4 bytes - size_t size = 5; - if(fssLarge) { - size += 4; + // 1 byte + minimal FSS 4 bytes + size_t size = 5; + if (fssLarge) { + size += 4; + } + size += sourceFileName.getSerializedSize(); + size += destFileName.getSerializedSize(); + if (hasOptions()) { + for (size_t idx = 0; idx < optionsLen; idx++) { + size += optionsArray[idx]->getSerializedSize(); } - size += sourceFileName.getSerializedSize(); - size += destFileName.getSerializedSize(); - if(hasOptions()) { - for(size_t idx = 0; idx < optionsLen; idx++) { - size += optionsArray[idx]->getSerializedSize(); - } - } - return size; + } + return size; } -void MetadataInfo::setDestFileName(cfdp::Lv &destFileName) { - this->destFileName = destFileName; +void MetadataInfo::setDestFileName(cfdp::Lv& destFileName) { this->destFileName = destFileName; } + +void MetadataInfo::setSourceFileName(cfdp::Lv& sourceFileName) { + this->sourceFileName = sourceFileName; } -void MetadataInfo::setSourceFileName(cfdp::Lv &sourceFileName) { - this->sourceFileName = sourceFileName; -} +size_t MetadataInfo::getMaxOptionsLen() const { return maxOptionsLen; } -size_t MetadataInfo::getMaxOptionsLen() const { - return maxOptionsLen; -} +void MetadataInfo::setMaxOptionsLen(size_t maxOptionsLen) { this->maxOptionsLen = maxOptionsLen; } -void MetadataInfo::setMaxOptionsLen(size_t maxOptionsLen) { - this->maxOptionsLen = maxOptionsLen; -} +size_t MetadataInfo::getOptionsLen() const { return optionsLen; } -size_t MetadataInfo::getOptionsLen() const { - return optionsLen; -} +void MetadataInfo::setOptionsLen(size_t optionsLen) { this->optionsLen = optionsLen; } -void MetadataInfo::setOptionsLen(size_t optionsLen) { - this->optionsLen = optionsLen; -} - -cfdp::Lv& MetadataInfo::getSourceFileName() { - return sourceFileName; -} +cfdp::Lv& MetadataInfo::getSourceFileName() { return sourceFileName; } diff --git a/src/fsfw/cfdp/pdu/MetadataInfo.h b/src/fsfw/cfdp/pdu/MetadataInfo.h index c5a9a0ef..9b90138c 100644 --- a/src/fsfw/cfdp/pdu/MetadataInfo.h +++ b/src/fsfw/cfdp/pdu/MetadataInfo.h @@ -1,49 +1,49 @@ #ifndef FSFW_SRC_FSFW_CFDP_PDU_METADATAINFO_H_ #define FSFW_SRC_FSFW_CFDP_PDU_METADATAINFO_H_ -#include "fsfw/cfdp/tlv/Tlv.h" -#include "fsfw/cfdp/tlv/Lv.h" #include "fsfw/cfdp/FileSize.h" #include "fsfw/cfdp/definitions.h" +#include "fsfw/cfdp/tlv/Lv.h" +#include "fsfw/cfdp/tlv/Tlv.h" class MetadataInfo { -public: - MetadataInfo(bool closureRequested, cfdp::ChecksumType checksumType, cfdp::FileSize& fileSize, - cfdp::Lv& sourceFileName, cfdp::Lv& destFileName); + public: + MetadataInfo(bool closureRequested, cfdp::ChecksumType checksumType, cfdp::FileSize& fileSize, + cfdp::Lv& sourceFileName, cfdp::Lv& destFileName); - size_t getSerializedSize(bool fssLarge = false); + size_t getSerializedSize(bool fssLarge = false); - void setOptionsArray(cfdp::Tlv** optionsArray, size_t* optionsLen, size_t* maxOptionsLen); - cfdp::ChecksumType getChecksumType() const; - void setChecksumType(cfdp::ChecksumType checksumType); - bool isClosureRequested() const; - void setClosureRequested(bool closureRequested = false); + void setOptionsArray(cfdp::Tlv** optionsArray, size_t* optionsLen, size_t* maxOptionsLen); + cfdp::ChecksumType getChecksumType() const; + void setChecksumType(cfdp::ChecksumType checksumType); + bool isClosureRequested() const; + void setClosureRequested(bool closureRequested = false); - void setDestFileName(cfdp::Lv& destFileName); - void setSourceFileName(cfdp::Lv& sourceFileName); + void setDestFileName(cfdp::Lv& destFileName); + void setSourceFileName(cfdp::Lv& sourceFileName); - cfdp::Lv& getDestFileName(); - cfdp::Lv& getSourceFileName(); - cfdp::FileSize& getFileSize(); + cfdp::Lv& getDestFileName(); + cfdp::Lv& getSourceFileName(); + cfdp::FileSize& getFileSize(); - bool hasOptions() const; - bool canHoldOptions() const; - ReturnValue_t getOptions(cfdp::Tlv*** optionsArray, size_t* optionsLen, size_t* maxOptsLen); - void setOptionsLen(size_t optionsLen); - size_t getOptionsLen() const; - void setMaxOptionsLen(size_t maxOptionsLen); - size_t getMaxOptionsLen() const; + bool hasOptions() const; + bool canHoldOptions() const; + ReturnValue_t getOptions(cfdp::Tlv*** optionsArray, size_t* optionsLen, size_t* maxOptsLen); + void setOptionsLen(size_t optionsLen); + size_t getOptionsLen() const; + void setMaxOptionsLen(size_t maxOptionsLen); + size_t getMaxOptionsLen() const; -private: - bool closureRequested = false; - cfdp::ChecksumType checksumType; - cfdp::FileSize& fileSize; - cfdp::Lv& sourceFileName; - cfdp::Lv& destFileName; + private: + bool closureRequested = false; + cfdp::ChecksumType checksumType; + cfdp::FileSize& fileSize; + cfdp::Lv& sourceFileName; + cfdp::Lv& destFileName; - cfdp::Tlv** optionsArray = nullptr; - size_t optionsLen = 0; - size_t maxOptionsLen = 0; + cfdp::Tlv** optionsArray = nullptr; + size_t optionsLen = 0; + size_t maxOptionsLen = 0; }; #endif /* FSFW_SRC_FSFW_CFDP_PDU_METADATAINFO_H_ */ diff --git a/src/fsfw/cfdp/pdu/MetadataPduDeserializer.cpp b/src/fsfw/cfdp/pdu/MetadataPduDeserializer.cpp index ccfaf2c9..161eb63a 100644 --- a/src/fsfw/cfdp/pdu/MetadataPduDeserializer.cpp +++ b/src/fsfw/cfdp/pdu/MetadataPduDeserializer.cpp @@ -1,58 +1,58 @@ #include "MetadataPduDeserializer.h" -MetadataPduDeserializer::MetadataPduDeserializer(const uint8_t *pduBuf, size_t maxSize, - MetadataInfo &info): FileDirectiveDeserializer(pduBuf, maxSize), info(info) { -} +MetadataPduDeserializer::MetadataPduDeserializer(const uint8_t* pduBuf, size_t maxSize, + MetadataInfo& info) + : FileDirectiveDeserializer(pduBuf, maxSize), info(info) {} ReturnValue_t MetadataPduDeserializer::parseData() { - ReturnValue_t result = FileDirectiveDeserializer::parseData(); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - size_t currentIdx = FileDirectiveDeserializer::getHeaderSize(); - const uint8_t* buf = rawPtr + currentIdx; - size_t remSize = FileDirectiveDeserializer::getWholePduSize() - currentIdx; - if (remSize < 1) { - return SerializeIF::STREAM_TOO_SHORT; - } - info.setClosureRequested((*buf >> 6) & 0x01); - info.setChecksumType(static_cast(*buf & 0x0f)); - remSize -= 1; - buf += 1; - auto endianness = getEndianness(); - result = info.getFileSize().deSerialize(&buf, &remSize, endianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = info.getSourceFileName().deSerialize(&buf, &remSize, endianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = info.getDestFileName().deSerialize(&buf, &remSize, endianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - - info.setOptionsLen(0); - if (remSize > 0) { - if(not info.canHoldOptions()) { - return cfdp::METADATA_CANT_PARSE_OPTIONS; - } - cfdp::Tlv** optionsArray = nullptr; - size_t optsMaxLen = 0; - size_t optsIdx = 0; - info.getOptions(&optionsArray, nullptr, &optsMaxLen); - while(remSize > 0) { - if(optsIdx > optsMaxLen) { - return cfdp::METADATA_CANT_PARSE_OPTIONS; - } - result = optionsArray[optsIdx]->deSerialize(&buf, &remSize, endianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - optsIdx++; - } - info.setOptionsLen(optsIdx); - } + ReturnValue_t result = FileDirectiveDeserializer::parseData(); + if (result != HasReturnvaluesIF::RETURN_OK) { return result; + } + size_t currentIdx = FileDirectiveDeserializer::getHeaderSize(); + const uint8_t* buf = rawPtr + currentIdx; + size_t remSize = FileDirectiveDeserializer::getWholePduSize() - currentIdx; + if (remSize < 1) { + return SerializeIF::STREAM_TOO_SHORT; + } + info.setClosureRequested((*buf >> 6) & 0x01); + info.setChecksumType(static_cast(*buf & 0x0f)); + remSize -= 1; + buf += 1; + auto endianness = getEndianness(); + result = info.getFileSize().deSerialize(&buf, &remSize, endianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = info.getSourceFileName().deSerialize(&buf, &remSize, endianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = info.getDestFileName().deSerialize(&buf, &remSize, endianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + + info.setOptionsLen(0); + if (remSize > 0) { + if (not info.canHoldOptions()) { + return cfdp::METADATA_CANT_PARSE_OPTIONS; + } + cfdp::Tlv** optionsArray = nullptr; + size_t optsMaxLen = 0; + size_t optsIdx = 0; + info.getOptions(&optionsArray, nullptr, &optsMaxLen); + while (remSize > 0) { + if (optsIdx > optsMaxLen) { + return cfdp::METADATA_CANT_PARSE_OPTIONS; + } + result = optionsArray[optsIdx]->deSerialize(&buf, &remSize, endianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + optsIdx++; + } + info.setOptionsLen(optsIdx); + } + return result; } diff --git a/src/fsfw/cfdp/pdu/MetadataPduDeserializer.h b/src/fsfw/cfdp/pdu/MetadataPduDeserializer.h index a3b343b4..1a8f9315 100644 --- a/src/fsfw/cfdp/pdu/MetadataPduDeserializer.h +++ b/src/fsfw/cfdp/pdu/MetadataPduDeserializer.h @@ -4,15 +4,14 @@ #include "fsfw/cfdp/pdu/FileDirectiveDeserializer.h" #include "fsfw/cfdp/pdu/MetadataInfo.h" -class MetadataPduDeserializer: public FileDirectiveDeserializer { -public: - MetadataPduDeserializer(const uint8_t* pduBuf, size_t maxSize, MetadataInfo& info); +class MetadataPduDeserializer : public FileDirectiveDeserializer { + public: + MetadataPduDeserializer(const uint8_t* pduBuf, size_t maxSize, MetadataInfo& info); - ReturnValue_t parseData() override; -private: - MetadataInfo& info; + ReturnValue_t parseData() override; + + private: + MetadataInfo& info; }; - - #endif /* FSFW_SRC_FSFW_CFDP_PDU_METADATAPDUDESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/MetadataPduSerializer.cpp b/src/fsfw/cfdp/pdu/MetadataPduSerializer.cpp index 1d2d67c2..f5c4de0a 100644 --- a/src/fsfw/cfdp/pdu/MetadataPduSerializer.cpp +++ b/src/fsfw/cfdp/pdu/MetadataPduSerializer.cpp @@ -1,54 +1,54 @@ #include "MetadataPduSerializer.h" -MetadataPduSerializer::MetadataPduSerializer(PduConfig &conf, MetadataInfo &info): - FileDirectiveSerializer(conf, cfdp::FileDirectives::METADATA, 5), info(info) { - updateDirectiveFieldLen(); +MetadataPduSerializer::MetadataPduSerializer(PduConfig &conf, MetadataInfo &info) + : FileDirectiveSerializer(conf, cfdp::FileDirectives::METADATA, 5), info(info) { + updateDirectiveFieldLen(); } void MetadataPduSerializer::updateDirectiveFieldLen() { - setDirectiveDataFieldLen(info.getSerializedSize(getLargeFileFlag())); + setDirectiveDataFieldLen(info.getSerializedSize(getLargeFileFlag())); } size_t MetadataPduSerializer::getSerializedSize() const { - return FileDirectiveSerializer::getWholePduSize(); + return FileDirectiveSerializer::getWholePduSize(); } ReturnValue_t MetadataPduSerializer::serialize(uint8_t **buffer, size_t *size, size_t maxSize, - Endianness streamEndianness) const { - ReturnValue_t result = FileDirectiveSerializer::serialize(buffer, size, maxSize, - streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if(*size + 1 >= maxSize) { - return SerializeIF::BUFFER_TOO_SHORT; - } - **buffer = info.isClosureRequested() << 6 | info.getChecksumType(); - *buffer += 1; - *size += 1; - result = info.getFileSize().serialize(buffer, size, maxSize, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = info.getSourceFileName().serialize(buffer, size, maxSize, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = info.getDestFileName().serialize(buffer, size, maxSize, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - - if(info.hasOptions()) { - cfdp::Tlv** optsArray = nullptr; - size_t optsLen = 0; - info.getOptions(&optsArray, &optsLen, nullptr); - for(size_t idx = 0; idx < optsLen; idx++) { - result = optsArray[idx]->serialize(buffer, size, maxSize, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - } - } + Endianness streamEndianness) const { + ReturnValue_t result = + FileDirectiveSerializer::serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { return result; + } + if (*size + 1 >= maxSize) { + return SerializeIF::BUFFER_TOO_SHORT; + } + **buffer = info.isClosureRequested() << 6 | info.getChecksumType(); + *buffer += 1; + *size += 1; + result = info.getFileSize().serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = info.getSourceFileName().serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = info.getDestFileName().serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + + if (info.hasOptions()) { + cfdp::Tlv **optsArray = nullptr; + size_t optsLen = 0; + info.getOptions(&optsArray, &optsLen, nullptr); + for (size_t idx = 0; idx < optsLen; idx++) { + result = optsArray[idx]->serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + } + } + return result; } diff --git a/src/fsfw/cfdp/pdu/MetadataPduSerializer.h b/src/fsfw/cfdp/pdu/MetadataPduSerializer.h index 6cbead49..cacf8a52 100644 --- a/src/fsfw/cfdp/pdu/MetadataPduSerializer.h +++ b/src/fsfw/cfdp/pdu/MetadataPduSerializer.h @@ -1,23 +1,22 @@ #ifndef FSFW_SRC_FSFW_CFDP_PDU_METADATAPDUSERIALIZER_H_ #define FSFW_SRC_FSFW_CFDP_PDU_METADATAPDUSERIALIZER_H_ -#include "fsfw/cfdp/pdu/MetadataInfo.h" #include "fsfw/cfdp/pdu/FileDirectiveSerializer.h" +#include "fsfw/cfdp/pdu/MetadataInfo.h" -class MetadataPduSerializer: public FileDirectiveSerializer { -public: - MetadataPduSerializer(PduConfig &conf, MetadataInfo& info); +class MetadataPduSerializer : public FileDirectiveSerializer { + public: + MetadataPduSerializer(PduConfig& conf, MetadataInfo& info); - void updateDirectiveFieldLen(); + void updateDirectiveFieldLen(); - size_t getSerializedSize() const override; + size_t getSerializedSize() const override; - ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, - Endianness streamEndianness) const override; -private: - MetadataInfo& info; + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; + + private: + MetadataInfo& info; }; - - #endif /* FSFW_SRC_FSFW_CFDP_PDU_METADATAPDUSERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/NakInfo.cpp b/src/fsfw/cfdp/pdu/NakInfo.cpp index d11aabc1..795004a9 100644 --- a/src/fsfw/cfdp/pdu/NakInfo.cpp +++ b/src/fsfw/cfdp/pdu/NakInfo.cpp @@ -1,83 +1,70 @@ #include "NakInfo.h" -NakInfo::NakInfo(cfdp::FileSize startOfScope, cfdp::FileSize endOfScope): - startOfScope(startOfScope), endOfScope(endOfScope) { -} +NakInfo::NakInfo(cfdp::FileSize startOfScope, cfdp::FileSize endOfScope) + : startOfScope(startOfScope), endOfScope(endOfScope) {} size_t NakInfo::getSerializedSize(bool fssLarge) { - size_t size = 8; - if(fssLarge) { - size += 8; + size_t size = 8; + if (fssLarge) { + size += 8; + } + if (hasSegmentRequests()) { + if (fssLarge) { + size += segmentRequestsLen * 16; + } else { + size += segmentRequestsLen * 8; } - if(hasSegmentRequests()) { - if(fssLarge) { - size += segmentRequestsLen * 16; - } else { - size += segmentRequestsLen * 8; - } - } - return size; + } + return size; } bool NakInfo::hasSegmentRequests() const { - if(this->segmentRequests != nullptr and segmentRequestsLen > 0) { - return true; - } - return false; + if (this->segmentRequests != nullptr and segmentRequestsLen > 0) { + return true; + } + return false; } bool NakInfo::canHoldSegmentRequests() const { - if(this->segmentRequests != nullptr and maxSegmentRequestsLen > 0) { - return true; - } - return false; -} - -bool NakInfo::getSegmentRequests(SegmentRequest **segmentRequestPtr, - size_t *segmentRequestLen, size_t* maxSegmentRequestsLen) { - if(this->segmentRequests != nullptr) { - *segmentRequestPtr = this->segmentRequests; - } - if(segmentRequestLen != nullptr) { - *segmentRequestLen = this->segmentRequestsLen; - } - if(maxSegmentRequestsLen != nullptr) { - *maxSegmentRequestsLen = this->maxSegmentRequestsLen; - } + if (this->segmentRequests != nullptr and maxSegmentRequestsLen > 0) { return true; + } + return false; } -void NakInfo::setSegmentRequests(SegmentRequest *segmentRequests, size_t* segmentRequestLen, - size_t* maxSegmentRequestLen) { - this->segmentRequests = segmentRequests; - if(segmentRequestLen != nullptr) { - this->segmentRequestsLen = *segmentRequestLen; - } - if(maxSegmentRequestLen != nullptr) { - this->maxSegmentRequestsLen = *maxSegmentRequestLen; - } +bool NakInfo::getSegmentRequests(SegmentRequest** segmentRequestPtr, size_t* segmentRequestLen, + size_t* maxSegmentRequestsLen) { + if (this->segmentRequests != nullptr) { + *segmentRequestPtr = this->segmentRequests; + } + if (segmentRequestLen != nullptr) { + *segmentRequestLen = this->segmentRequestsLen; + } + if (maxSegmentRequestsLen != nullptr) { + *maxSegmentRequestsLen = this->maxSegmentRequestsLen; + } + return true; } -cfdp::FileSize& NakInfo::getStartOfScope() { - return startOfScope; +void NakInfo::setSegmentRequests(SegmentRequest* segmentRequests, size_t* segmentRequestLen, + size_t* maxSegmentRequestLen) { + this->segmentRequests = segmentRequests; + if (segmentRequestLen != nullptr) { + this->segmentRequestsLen = *segmentRequestLen; + } + if (maxSegmentRequestLen != nullptr) { + this->maxSegmentRequestsLen = *maxSegmentRequestLen; + } } -cfdp::FileSize& NakInfo::getEndOfScope() { - return endOfScope; -} +cfdp::FileSize& NakInfo::getStartOfScope() { return startOfScope; } -size_t NakInfo::getSegmentRequestsLen() const { - return segmentRequestsLen; -} +cfdp::FileSize& NakInfo::getEndOfScope() { return endOfScope; } -size_t NakInfo::getSegmentRequestsMaxLen() const { - return maxSegmentRequestsLen; -} +size_t NakInfo::getSegmentRequestsLen() const { return segmentRequestsLen; } -void NakInfo::setSegmentRequestLen(size_t readLen) { - this->segmentRequestsLen = readLen; -} +size_t NakInfo::getSegmentRequestsMaxLen() const { return maxSegmentRequestsLen; } -void NakInfo::setMaxSegmentRequestLen(size_t maxSize) { - this->maxSegmentRequestsLen = maxSize; -} +void NakInfo::setSegmentRequestLen(size_t readLen) { this->segmentRequestsLen = readLen; } + +void NakInfo::setMaxSegmentRequestLen(size_t maxSize) { this->maxSegmentRequestsLen = maxSize; } diff --git a/src/fsfw/cfdp/pdu/NakInfo.h b/src/fsfw/cfdp/pdu/NakInfo.h index 839484be..02d6b6f4 100644 --- a/src/fsfw/cfdp/pdu/NakInfo.h +++ b/src/fsfw/cfdp/pdu/NakInfo.h @@ -1,40 +1,41 @@ #ifndef FSFW_SRC_FSFW_CFDP_PDU_NAKINFO_H_ #define FSFW_SRC_FSFW_CFDP_PDU_NAKINFO_H_ -#include "fsfw/cfdp/FileSize.h" #include +#include "fsfw/cfdp/FileSize.h" + class NakInfo { -public: - using SegmentRequest = std::pair; + public: + using SegmentRequest = std::pair; - NakInfo(cfdp::FileSize startOfScope, cfdp::FileSize endOfScope); + NakInfo(cfdp::FileSize startOfScope, cfdp::FileSize endOfScope); - void setSegmentRequests(SegmentRequest* segmentRequests, size_t* segmentRequestLen, - size_t* maxSegmentRequestLen); + void setSegmentRequests(SegmentRequest* segmentRequests, size_t* segmentRequestLen, + size_t* maxSegmentRequestLen); - size_t getSerializedSize(bool fssLarge = false); + size_t getSerializedSize(bool fssLarge = false); - cfdp::FileSize& getStartOfScope(); - cfdp::FileSize& getEndOfScope(); + cfdp::FileSize& getStartOfScope(); + cfdp::FileSize& getEndOfScope(); - bool hasSegmentRequests() const; - bool canHoldSegmentRequests() const; - void setMaxSegmentRequestLen(size_t maxSize); - bool getSegmentRequests(SegmentRequest** segmentRequestPtr, size_t* segmentRequestLen, - size_t* maxSegmentRequestsLen); - size_t getSegmentRequestsLen() const; - size_t getSegmentRequestsMaxLen() const; + bool hasSegmentRequests() const; + bool canHoldSegmentRequests() const; + void setMaxSegmentRequestLen(size_t maxSize); + bool getSegmentRequests(SegmentRequest** segmentRequestPtr, size_t* segmentRequestLen, + size_t* maxSegmentRequestsLen); + size_t getSegmentRequestsLen() const; + size_t getSegmentRequestsMaxLen() const; - //! This functions is more relevant for deserializers - void setSegmentRequestLen(size_t readLen); + //! This functions is more relevant for deserializers + void setSegmentRequestLen(size_t readLen); -private: - cfdp::FileSize startOfScope; - cfdp::FileSize endOfScope; - SegmentRequest* segmentRequests = nullptr; - size_t segmentRequestsLen = 0; - size_t maxSegmentRequestsLen = 0; + private: + cfdp::FileSize startOfScope; + cfdp::FileSize endOfScope; + SegmentRequest* segmentRequests = nullptr; + size_t segmentRequestsLen = 0; + size_t maxSegmentRequestsLen = 0; }; #endif /* FSFW_SRC_FSFW_CFDP_PDU_NAKINFO_H_ */ diff --git a/src/fsfw/cfdp/pdu/NakPduDeserializer.cpp b/src/fsfw/cfdp/pdu/NakPduDeserializer.cpp index b2d02322..9d5f074c 100644 --- a/src/fsfw/cfdp/pdu/NakPduDeserializer.cpp +++ b/src/fsfw/cfdp/pdu/NakPduDeserializer.cpp @@ -1,58 +1,56 @@ #include "NakPduDeserializer.h" -NakPduDeserializer::NakPduDeserializer(const uint8_t *pduBuf, size_t maxSize, NakInfo &info): - FileDirectiveDeserializer(pduBuf, maxSize), nakInfo(info) { -} +NakPduDeserializer::NakPduDeserializer(const uint8_t* pduBuf, size_t maxSize, NakInfo& info) + : FileDirectiveDeserializer(pduBuf, maxSize), nakInfo(info) {} ReturnValue_t NakPduDeserializer::parseData() { - ReturnValue_t result = FileDirectiveDeserializer::parseData(); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - size_t currentIdx = FileDirectiveDeserializer::getHeaderSize(); - const uint8_t* buffer = rawPtr + currentIdx; - size_t remSize = FileDirectiveDeserializer::getWholePduSize() - currentIdx; - if (remSize < 1) { - return SerializeIF::STREAM_TOO_SHORT; - } - result = nakInfo.getStartOfScope().deSerialize(&buffer, &remSize, - SerializeIF::Endianness::NETWORK); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = nakInfo.getEndOfScope().deSerialize(&buffer, &remSize, - SerializeIF::Endianness::NETWORK); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - nakInfo.setSegmentRequestLen(0); - if(remSize > 0) { - if(not nakInfo.canHoldSegmentRequests()) { - return cfdp::NAK_CANT_PARSE_OPTIONS; - } - NakInfo::SegmentRequest* segReqs = nullptr; - size_t maxSegReqs = 0; - nakInfo.getSegmentRequests(&segReqs, nullptr, &maxSegReqs); - if(segReqs != nullptr) { - size_t idx = 0; - while(remSize > 0) { - if(idx == maxSegReqs) { - return cfdp::NAK_CANT_PARSE_OPTIONS; - } - result = segReqs[idx].first.deSerialize(&buffer, &remSize, - SerializeIF::Endianness::NETWORK); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = segReqs[idx].second.deSerialize(&buffer, &remSize, - SerializeIF::Endianness::NETWORK); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - idx++; - } - nakInfo.setSegmentRequestLen(idx); - } - } + ReturnValue_t result = FileDirectiveDeserializer::parseData(); + if (result != HasReturnvaluesIF::RETURN_OK) { return result; + } + size_t currentIdx = FileDirectiveDeserializer::getHeaderSize(); + const uint8_t* buffer = rawPtr + currentIdx; + size_t remSize = FileDirectiveDeserializer::getWholePduSize() - currentIdx; + if (remSize < 1) { + return SerializeIF::STREAM_TOO_SHORT; + } + result = + nakInfo.getStartOfScope().deSerialize(&buffer, &remSize, SerializeIF::Endianness::NETWORK); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = nakInfo.getEndOfScope().deSerialize(&buffer, &remSize, SerializeIF::Endianness::NETWORK); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + nakInfo.setSegmentRequestLen(0); + if (remSize > 0) { + if (not nakInfo.canHoldSegmentRequests()) { + return cfdp::NAK_CANT_PARSE_OPTIONS; + } + NakInfo::SegmentRequest* segReqs = nullptr; + size_t maxSegReqs = 0; + nakInfo.getSegmentRequests(&segReqs, nullptr, &maxSegReqs); + if (segReqs != nullptr) { + size_t idx = 0; + while (remSize > 0) { + if (idx == maxSegReqs) { + return cfdp::NAK_CANT_PARSE_OPTIONS; + } + result = + segReqs[idx].first.deSerialize(&buffer, &remSize, SerializeIF::Endianness::NETWORK); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = + segReqs[idx].second.deSerialize(&buffer, &remSize, SerializeIF::Endianness::NETWORK); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + idx++; + } + nakInfo.setSegmentRequestLen(idx); + } + } + return result; } diff --git a/src/fsfw/cfdp/pdu/NakPduDeserializer.h b/src/fsfw/cfdp/pdu/NakPduDeserializer.h index 81726610..f0f43158 100644 --- a/src/fsfw/cfdp/pdu/NakPduDeserializer.h +++ b/src/fsfw/cfdp/pdu/NakPduDeserializer.h @@ -4,19 +4,18 @@ #include "fsfw/cfdp/pdu/FileDirectiveDeserializer.h" #include "fsfw/cfdp/pdu/NakInfo.h" -class NakPduDeserializer: public FileDirectiveDeserializer { -public: - NakPduDeserializer(const uint8_t* pduBuf, size_t maxSize, NakInfo& info); +class NakPduDeserializer : public FileDirectiveDeserializer { + public: + NakPduDeserializer(const uint8_t* pduBuf, size_t maxSize, NakInfo& info); - /** - * This needs to be called before accessing the PDU fields to avoid segmentation faults. - * @return - */ - virtual ReturnValue_t parseData() override; -private: - NakInfo& nakInfo; + /** + * This needs to be called before accessing the PDU fields to avoid segmentation faults. + * @return + */ + virtual ReturnValue_t parseData() override; + + private: + NakInfo& nakInfo; }; - - #endif /* FSFW_SRC_FSFW_CFDP_PDU_NAKPDUDESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/NakPduSerializer.cpp b/src/fsfw/cfdp/pdu/NakPduSerializer.cpp index 9afb80cb..95f1bc98 100644 --- a/src/fsfw/cfdp/pdu/NakPduSerializer.cpp +++ b/src/fsfw/cfdp/pdu/NakPduSerializer.cpp @@ -1,49 +1,47 @@ #include "NakPduSerializer.h" -NakPduSerializer::NakPduSerializer(PduConfig& pduConf, NakInfo& nakInfo): - FileDirectiveSerializer(pduConf, cfdp::FileDirectives::NAK, 0), nakInfo(nakInfo) { - updateDirectiveFieldLen(); +NakPduSerializer::NakPduSerializer(PduConfig &pduConf, NakInfo &nakInfo) + : FileDirectiveSerializer(pduConf, cfdp::FileDirectives::NAK, 0), nakInfo(nakInfo) { + updateDirectiveFieldLen(); } void NakPduSerializer::updateDirectiveFieldLen() { - this->setDirectiveDataFieldLen(nakInfo.getSerializedSize(getLargeFileFlag())); + this->setDirectiveDataFieldLen(nakInfo.getSerializedSize(getLargeFileFlag())); } size_t NakPduSerializer::getSerializedSize() const { - return FileDirectiveSerializer::getWholePduSize(); + return FileDirectiveSerializer::getWholePduSize(); } ReturnValue_t NakPduSerializer::serialize(uint8_t **buffer, size_t *size, size_t maxSize, - Endianness streamEndianness) const { - ReturnValue_t result = FileDirectiveSerializer::serialize(buffer, size, maxSize, - streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = nakInfo.getStartOfScope().serialize(buffer, size, maxSize, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = nakInfo.getEndOfScope().serialize(buffer, size, maxSize, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if(nakInfo.hasSegmentRequests()) { - NakInfo::SegmentRequest *segmentRequests = nullptr; - size_t segmentRequestLen = 0; - nakInfo.getSegmentRequests(&segmentRequests, &segmentRequestLen, nullptr); - for(size_t idx = 0; idx < segmentRequestLen; idx++) { - result = segmentRequests[idx].first.serialize(buffer, size, maxSize, - streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = segmentRequests[idx].second.serialize(buffer, size, maxSize, - streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - } - } + Endianness streamEndianness) const { + ReturnValue_t result = + FileDirectiveSerializer::serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { return result; + } + result = nakInfo.getStartOfScope().serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = nakInfo.getEndOfScope().serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (nakInfo.hasSegmentRequests()) { + NakInfo::SegmentRequest *segmentRequests = nullptr; + size_t segmentRequestLen = 0; + nakInfo.getSegmentRequests(&segmentRequests, &segmentRequestLen, nullptr); + for (size_t idx = 0; idx < segmentRequestLen; idx++) { + result = segmentRequests[idx].first.serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = segmentRequests[idx].second.serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + } + } + return result; } diff --git a/src/fsfw/cfdp/pdu/NakPduSerializer.h b/src/fsfw/cfdp/pdu/NakPduSerializer.h index 556f0037..4009884b 100644 --- a/src/fsfw/cfdp/pdu/NakPduSerializer.h +++ b/src/fsfw/cfdp/pdu/NakPduSerializer.h @@ -1,41 +1,38 @@ #ifndef FSFW_SRC_FSFW_CFDP_PDU_NAKPDUSERIALIZER_H_ #define FSFW_SRC_FSFW_CFDP_PDU_NAKPDUSERIALIZER_H_ -#include "fsfw/cfdp/pdu/FileDirectiveSerializer.h" -#include "fsfw/cfdp/definitions.h" -#include "fsfw/cfdp/FileSize.h" -#include "NakInfo.h" - #include -class NakPduSerializer: public FileDirectiveSerializer { -public: +#include "NakInfo.h" +#include "fsfw/cfdp/FileSize.h" +#include "fsfw/cfdp/definitions.h" +#include "fsfw/cfdp/pdu/FileDirectiveSerializer.h" - /** - * - * @param PduConf - * @param startOfScope - * @param endOfScope - * @param [in] segmentRequests Pointer to the start of a list of segment requests - * @param segmentRequestLen Length of the segment request list to be serialized - */ - NakPduSerializer(PduConfig& PduConf, NakInfo& nakInfo); +class NakPduSerializer : public FileDirectiveSerializer { + public: + /** + * + * @param PduConf + * @param startOfScope + * @param endOfScope + * @param [in] segmentRequests Pointer to the start of a list of segment requests + * @param segmentRequestLen Length of the segment request list to be serialized + */ + NakPduSerializer(PduConfig& PduConf, NakInfo& nakInfo); - size_t getSerializedSize() const override; + size_t getSerializedSize() const override; - ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, - Endianness streamEndianness) const override; + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; - /** - * If you change the info struct, you might need to update the directive field length - * manually - */ - void updateDirectiveFieldLen(); -private: - NakInfo& nakInfo; + /** + * If you change the info struct, you might need to update the directive field length + * manually + */ + void updateDirectiveFieldLen(); + private: + NakInfo& nakInfo; }; - - #endif /* FSFW_SRC_FSFW_CFDP_PDU_NAKPDUSERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/PduConfig.cpp b/src/fsfw/cfdp/pdu/PduConfig.cpp index acf02f5b..d495f864 100644 --- a/src/fsfw/cfdp/pdu/PduConfig.cpp +++ b/src/fsfw/cfdp/pdu/PduConfig.cpp @@ -1,8 +1,12 @@ #include "PduConfig.h" PduConfig::PduConfig(cfdp::TransmissionModes mode, cfdp::TransactionSeqNum seqNum, - cfdp::EntityId sourceId, cfdp::EntityId destId, bool crcFlag, - bool largeFile, cfdp::Direction direction): - mode(mode), seqNum(seqNum), sourceId(sourceId), destId(destId), - crcFlag(crcFlag), largeFile(largeFile), direction(direction) { -} + cfdp::EntityId sourceId, cfdp::EntityId destId, bool crcFlag, bool largeFile, + cfdp::Direction direction) + : mode(mode), + seqNum(seqNum), + sourceId(sourceId), + destId(destId), + crcFlag(crcFlag), + largeFile(largeFile), + direction(direction) {} diff --git a/src/fsfw/cfdp/pdu/PduConfig.h b/src/fsfw/cfdp/pdu/PduConfig.h index 79d14a2e..e5b52e52 100644 --- a/src/fsfw/cfdp/pdu/PduConfig.h +++ b/src/fsfw/cfdp/pdu/PduConfig.h @@ -5,32 +5,32 @@ namespace cfdp { -struct EntityId: public VarLenField { -public: - EntityId(): VarLenField() {} - EntityId(cfdp::WidthInBytes width, size_t entityId): VarLenField(width, entityId) {} +struct EntityId : public VarLenField { + public: + EntityId() : VarLenField() {} + EntityId(cfdp::WidthInBytes width, size_t entityId) : VarLenField(width, entityId) {} }; -struct TransactionSeqNum: public VarLenField { -public: - TransactionSeqNum(): VarLenField() {} - TransactionSeqNum(cfdp::WidthInBytes width, size_t seqNum): VarLenField(width, seqNum) {} +struct TransactionSeqNum : public VarLenField { + public: + TransactionSeqNum() : VarLenField() {} + TransactionSeqNum(cfdp::WidthInBytes width, size_t seqNum) : VarLenField(width, seqNum) {} }; -} +} // namespace cfdp class PduConfig { -public: - PduConfig(cfdp::TransmissionModes mode, cfdp::TransactionSeqNum seqNum, - cfdp::EntityId sourceId, cfdp::EntityId destId, bool crcFlag = false, - bool largeFile = false, cfdp::Direction direction = cfdp::Direction::TOWARDS_RECEIVER); - cfdp::TransmissionModes mode; - cfdp::TransactionSeqNum seqNum; - cfdp::EntityId sourceId; - cfdp::EntityId destId; - bool crcFlag; - bool largeFile; - cfdp::Direction direction; + public: + PduConfig(cfdp::TransmissionModes mode, cfdp::TransactionSeqNum seqNum, cfdp::EntityId sourceId, + cfdp::EntityId destId, bool crcFlag = false, bool largeFile = false, + cfdp::Direction direction = cfdp::Direction::TOWARDS_RECEIVER); + cfdp::TransmissionModes mode; + cfdp::TransactionSeqNum seqNum; + cfdp::EntityId sourceId; + cfdp::EntityId destId; + bool crcFlag; + bool largeFile; + cfdp::Direction direction; }; #endif /* FSFW_SRC_FSFW_CFDP_PDU_PDUCONFIG_H_ */ diff --git a/src/fsfw/cfdp/pdu/PduHeaderIF.h b/src/fsfw/cfdp/pdu/PduHeaderIF.h index 0ea8b4fe..f05d95a4 100644 --- a/src/fsfw/cfdp/pdu/PduHeaderIF.h +++ b/src/fsfw/cfdp/pdu/PduHeaderIF.h @@ -1,37 +1,37 @@ #ifndef FSFW_SRC_FSFW_CFDP_PDU_PDUHEADERIF_H_ #define FSFW_SRC_FSFW_CFDP_PDU_PDUHEADERIF_H_ -#include "PduConfig.h" -#include "../definitions.h" #include +#include "../definitions.h" +#include "PduConfig.h" + /** * @brief Generic interface to access all fields of a PDU header * @details * See CCSDS 727.0-B-5 pp.75 for more information about these fields */ class PduHeaderIF { -public: - virtual~ PduHeaderIF() {}; + public: + virtual ~PduHeaderIF(){}; - virtual size_t getWholePduSize() const = 0; - virtual size_t getPduDataFieldLen() const = 0; - virtual cfdp::PduType getPduType() const = 0; - virtual cfdp::Direction getDirection() const = 0; - virtual cfdp::TransmissionModes getTransmissionMode() const = 0; - virtual bool getCrcFlag() const = 0; - virtual bool getLargeFileFlag() const = 0; - virtual cfdp::SegmentationControl getSegmentationControl() const = 0; - virtual cfdp::WidthInBytes getLenEntityIds() const = 0; - virtual cfdp::WidthInBytes getLenSeqNum() const = 0; - virtual cfdp::SegmentMetadataFlag getSegmentMetadataFlag() const = 0; - virtual bool hasSegmentMetadataFlag() const = 0; - virtual void getSourceId(cfdp::EntityId& sourceId) const = 0; - virtual void getDestId(cfdp::EntityId& destId) const = 0; - virtual void getTransactionSeqNum(cfdp::TransactionSeqNum& seqNum) const = 0; -private: + virtual size_t getWholePduSize() const = 0; + virtual size_t getPduDataFieldLen() const = 0; + virtual cfdp::PduType getPduType() const = 0; + virtual cfdp::Direction getDirection() const = 0; + virtual cfdp::TransmissionModes getTransmissionMode() const = 0; + virtual bool getCrcFlag() const = 0; + virtual bool getLargeFileFlag() const = 0; + virtual cfdp::SegmentationControl getSegmentationControl() const = 0; + virtual cfdp::WidthInBytes getLenEntityIds() const = 0; + virtual cfdp::WidthInBytes getLenSeqNum() const = 0; + virtual cfdp::SegmentMetadataFlag getSegmentMetadataFlag() const = 0; + virtual bool hasSegmentMetadataFlag() const = 0; + virtual void getSourceId(cfdp::EntityId& sourceId) const = 0; + virtual void getDestId(cfdp::EntityId& destId) const = 0; + virtual void getTransactionSeqNum(cfdp::TransactionSeqNum& seqNum) const = 0; + + private: }; - - #endif /* FSFW_SRC_FSFW_CFDP_PDU_PDUHEADERIF_H_ */ diff --git a/src/fsfw/cfdp/pdu/PromptPduDeserializer.cpp b/src/fsfw/cfdp/pdu/PromptPduDeserializer.cpp index abff805e..6a6f5505 100644 --- a/src/fsfw/cfdp/pdu/PromptPduDeserializer.cpp +++ b/src/fsfw/cfdp/pdu/PromptPduDeserializer.cpp @@ -1,22 +1,21 @@ #include "PromptPduDeserializer.h" -PromptPduDeserializer::PromptPduDeserializer(const uint8_t *pduBuf, size_t maxSize): - FileDirectiveDeserializer(pduBuf, maxSize) { -} +PromptPduDeserializer::PromptPduDeserializer(const uint8_t *pduBuf, size_t maxSize) + : FileDirectiveDeserializer(pduBuf, maxSize) {} cfdp::PromptResponseRequired PromptPduDeserializer::getPromptResponseRequired() const { - return responseRequired; + return responseRequired; } ReturnValue_t PromptPduDeserializer::parseData() { - ReturnValue_t result = FileDirectiveDeserializer::parseData(); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - size_t currentIdx = FileDirectiveDeserializer::getHeaderSize(); - if (FileDirectiveDeserializer::getWholePduSize() - currentIdx < 1) { - return SerializeIF::STREAM_TOO_SHORT; - } - responseRequired = static_cast((rawPtr[currentIdx] >> 7) & 0x01); - return HasReturnvaluesIF::RETURN_OK; + ReturnValue_t result = FileDirectiveDeserializer::parseData(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + size_t currentIdx = FileDirectiveDeserializer::getHeaderSize(); + if (FileDirectiveDeserializer::getWholePduSize() - currentIdx < 1) { + return SerializeIF::STREAM_TOO_SHORT; + } + responseRequired = static_cast((rawPtr[currentIdx] >> 7) & 0x01); + return HasReturnvaluesIF::RETURN_OK; } diff --git a/src/fsfw/cfdp/pdu/PromptPduDeserializer.h b/src/fsfw/cfdp/pdu/PromptPduDeserializer.h index 97762243..9441f364 100644 --- a/src/fsfw/cfdp/pdu/PromptPduDeserializer.h +++ b/src/fsfw/cfdp/pdu/PromptPduDeserializer.h @@ -3,16 +3,15 @@ #include "fsfw/cfdp/pdu/FileDirectiveDeserializer.h" -class PromptPduDeserializer: public FileDirectiveDeserializer { -public: - PromptPduDeserializer(const uint8_t *pduBuf, size_t maxSize); +class PromptPduDeserializer : public FileDirectiveDeserializer { + public: + PromptPduDeserializer(const uint8_t *pduBuf, size_t maxSize); - cfdp::PromptResponseRequired getPromptResponseRequired() const; - ReturnValue_t parseData() override; -private: - cfdp::PromptResponseRequired responseRequired = cfdp::PromptResponseRequired::PROMPT_NAK; + cfdp::PromptResponseRequired getPromptResponseRequired() const; + ReturnValue_t parseData() override; + + private: + cfdp::PromptResponseRequired responseRequired = cfdp::PromptResponseRequired::PROMPT_NAK; }; - - #endif /* FSFW_SRC_FSFW_CFDP_PDU_PROMPTPDUDESERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/PromptPduSerializer.cpp b/src/fsfw/cfdp/pdu/PromptPduSerializer.cpp index 599f8072..a7287563 100644 --- a/src/fsfw/cfdp/pdu/PromptPduSerializer.cpp +++ b/src/fsfw/cfdp/pdu/PromptPduSerializer.cpp @@ -1,27 +1,26 @@ #include "PromptPduSerializer.h" PromptPduSerializer::PromptPduSerializer(PduConfig &conf, - cfdp::PromptResponseRequired responseRequired): - FileDirectiveSerializer(conf, cfdp::FileDirectives::PROMPT, 1), - responseRequired(responseRequired) { -} + cfdp::PromptResponseRequired responseRequired) + : FileDirectiveSerializer(conf, cfdp::FileDirectives::PROMPT, 1), + responseRequired(responseRequired) {} size_t PromptPduSerializer::getSerializedSize() const { - return FileDirectiveSerializer::getWholePduSize(); + return FileDirectiveSerializer::getWholePduSize(); } ReturnValue_t PromptPduSerializer::serialize(uint8_t **buffer, size_t *size, size_t maxSize, - Endianness streamEndianness) const { - ReturnValue_t result = FileDirectiveSerializer::serialize(buffer, size, maxSize, - streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if(*size + 1 > maxSize) { - return SerializeIF::BUFFER_TOO_SHORT; - } - **buffer = this->responseRequired << 7; - *buffer += 1; - *size += 1; + Endianness streamEndianness) const { + ReturnValue_t result = + FileDirectiveSerializer::serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { return result; + } + if (*size + 1 > maxSize) { + return SerializeIF::BUFFER_TOO_SHORT; + } + **buffer = this->responseRequired << 7; + *buffer += 1; + *size += 1; + return result; } diff --git a/src/fsfw/cfdp/pdu/PromptPduSerializer.h b/src/fsfw/cfdp/pdu/PromptPduSerializer.h index 79945fd7..51500224 100644 --- a/src/fsfw/cfdp/pdu/PromptPduSerializer.h +++ b/src/fsfw/cfdp/pdu/PromptPduSerializer.h @@ -3,16 +3,17 @@ #include "fsfw/cfdp/pdu/FileDirectiveSerializer.h" -class PromptPduSerializer: public FileDirectiveSerializer { -public: - PromptPduSerializer(PduConfig& conf, cfdp::PromptResponseRequired responseRequired); +class PromptPduSerializer : public FileDirectiveSerializer { + public: + PromptPduSerializer(PduConfig& conf, cfdp::PromptResponseRequired responseRequired); - size_t getSerializedSize() const override; + size_t getSerializedSize() const override; - ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, - Endianness streamEndianness) const override; -private: - cfdp::PromptResponseRequired responseRequired; + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; + + private: + cfdp::PromptResponseRequired responseRequired; }; #endif /* FSFW_SRC_FSFW_CFDP_PDU_PROMPTPDUSERIALIZER_H_ */ diff --git a/src/fsfw/cfdp/pdu/VarLenField.cpp b/src/fsfw/cfdp/pdu/VarLenField.cpp index ac2410c8..b11c3b09 100644 --- a/src/fsfw/cfdp/pdu/VarLenField.cpp +++ b/src/fsfw/cfdp/pdu/VarLenField.cpp @@ -1,127 +1,120 @@ #include "VarLenField.h" -#include "fsfw/FSFW.h" -#include "fsfw/serviceinterface.h" -#include "fsfw/serialize/SerializeAdapter.h" -cfdp::VarLenField::VarLenField(cfdp::WidthInBytes width, size_t value): VarLenField() { - ReturnValue_t result = this->setValue(width, value); - if(result != HasReturnvaluesIF::RETURN_OK) { +#include "fsfw/FSFW.h" +#include "fsfw/serialize/SerializeAdapter.h" +#include "fsfw/serviceinterface.h" + +cfdp::VarLenField::VarLenField(cfdp::WidthInBytes width, size_t value) : VarLenField() { + ReturnValue_t result = this->setValue(width, value); + if (result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_DISABLE_PRINTOUT == 0 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "cfdp::VarLenField: Setting value failed" << std::endl; + sif::warning << "cfdp::VarLenField: Setting value failed" << std::endl; #else - sif::printWarning("cfdp::VarLenField: Setting value failed\n"); + sif::printWarning("cfdp::VarLenField: Setting value failed\n"); #endif #endif - } + } } -cfdp::VarLenField::VarLenField(): width(cfdp::WidthInBytes::ONE_BYTE) { - value.oneByte = 0; -} +cfdp::VarLenField::VarLenField() : width(cfdp::WidthInBytes::ONE_BYTE) { value.oneByte = 0; } -cfdp::WidthInBytes cfdp::VarLenField::getWidth() const { - return width; -} +cfdp::WidthInBytes cfdp::VarLenField::getWidth() const { return width; } ReturnValue_t cfdp::VarLenField::setValue(cfdp::WidthInBytes widthInBytes, size_t value) { - switch(widthInBytes) { - case(cfdp::WidthInBytes::ONE_BYTE): { - if(value > UINT8_MAX) { - return HasReturnvaluesIF::RETURN_FAILED; - } - this->value.oneByte = value; - break; + switch (widthInBytes) { + case (cfdp::WidthInBytes::ONE_BYTE): { + if (value > UINT8_MAX) { + return HasReturnvaluesIF::RETURN_FAILED; + } + this->value.oneByte = value; + break; } - case(cfdp::WidthInBytes::TWO_BYTES): { - if(value > UINT16_MAX) { - return HasReturnvaluesIF::RETURN_FAILED; - } - this->value.twoBytes = value; - break; + case (cfdp::WidthInBytes::TWO_BYTES): { + if (value > UINT16_MAX) { + return HasReturnvaluesIF::RETURN_FAILED; + } + this->value.twoBytes = value; + break; } - case(cfdp::WidthInBytes::FOUR_BYTES): { - if(value > UINT32_MAX) { - return HasReturnvaluesIF::RETURN_FAILED; - } - this->value.fourBytes = value; - break; + case (cfdp::WidthInBytes::FOUR_BYTES): { + if (value > UINT32_MAX) { + return HasReturnvaluesIF::RETURN_FAILED; + } + this->value.fourBytes = value; + break; } default: { - break; + break; } - } - this->width = widthInBytes; - return HasReturnvaluesIF::RETURN_OK; + } + this->width = widthInBytes; + return HasReturnvaluesIF::RETURN_OK; } size_t cfdp::VarLenField::getValue() const { - switch(width) { - case(cfdp::WidthInBytes::ONE_BYTE): { - return value.oneByte; + switch (width) { + case (cfdp::WidthInBytes::ONE_BYTE): { + return value.oneByte; } - case(cfdp::WidthInBytes::TWO_BYTES): { - return value.twoBytes; + case (cfdp::WidthInBytes::TWO_BYTES): { + return value.twoBytes; } - case(cfdp::WidthInBytes::FOUR_BYTES): { - return value.fourBytes; + case (cfdp::WidthInBytes::FOUR_BYTES): { + return value.fourBytes; } - } - return 0; + } + return 0; } ReturnValue_t cfdp::VarLenField::serialize(uint8_t **buffer, size_t *size, size_t maxSize, - Endianness streamEndianness) const { - switch(width) { - case(cfdp::WidthInBytes::ONE_BYTE): { - if (*size + 1 > maxSize) { - return BUFFER_TOO_SHORT; - } - **buffer = value.oneByte; - *size += 1; - *buffer += 1; - return HasReturnvaluesIF::RETURN_OK; + Endianness streamEndianness) const { + switch (width) { + case (cfdp::WidthInBytes::ONE_BYTE): { + if (*size + 1 > maxSize) { + return BUFFER_TOO_SHORT; + } + **buffer = value.oneByte; + *size += 1; + *buffer += 1; + return HasReturnvaluesIF::RETURN_OK; } - case(cfdp::WidthInBytes::TWO_BYTES): { - return SerializeAdapter::serialize(&value.twoBytes, buffer, size, maxSize, - streamEndianness); + case (cfdp::WidthInBytes::TWO_BYTES): { + return SerializeAdapter::serialize(&value.twoBytes, buffer, size, maxSize, streamEndianness); } - case(cfdp::WidthInBytes::FOUR_BYTES): { - return SerializeAdapter::serialize(&value.fourBytes, buffer, size, maxSize, - streamEndianness); + case (cfdp::WidthInBytes::FOUR_BYTES): { + return SerializeAdapter::serialize(&value.fourBytes, buffer, size, maxSize, streamEndianness); } default: { - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; } + } } -size_t cfdp::VarLenField::getSerializedSize() const { - return width; -} +size_t cfdp::VarLenField::getSerializedSize() const { return width; } ReturnValue_t cfdp::VarLenField::deSerialize(cfdp::WidthInBytes width, const uint8_t **buffer, - size_t *size, Endianness streamEndianness) { - this->width = width; - return deSerialize(buffer, size, streamEndianness); + size_t *size, Endianness streamEndianness) { + this->width = width; + return deSerialize(buffer, size, streamEndianness); } ReturnValue_t cfdp::VarLenField::deSerialize(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) { - switch(width) { - case(cfdp::WidthInBytes::ONE_BYTE): { - value.oneByte = **buffer; - *size += 1; - return HasReturnvaluesIF::RETURN_OK; + Endianness streamEndianness) { + switch (width) { + case (cfdp::WidthInBytes::ONE_BYTE): { + value.oneByte = **buffer; + *size += 1; + return HasReturnvaluesIF::RETURN_OK; } - case(cfdp::WidthInBytes::TWO_BYTES): { - return SerializeAdapter::deSerialize(&value.twoBytes, buffer, size, streamEndianness); + case (cfdp::WidthInBytes::TWO_BYTES): { + return SerializeAdapter::deSerialize(&value.twoBytes, buffer, size, streamEndianness); } - case(cfdp::WidthInBytes::FOUR_BYTES): { - return SerializeAdapter::deSerialize(&value.fourBytes, buffer, size, streamEndianness); + case (cfdp::WidthInBytes::FOUR_BYTES): { + return SerializeAdapter::deSerialize(&value.fourBytes, buffer, size, streamEndianness); } default: { - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; } + } } diff --git a/src/fsfw/cfdp/pdu/VarLenField.h b/src/fsfw/cfdp/pdu/VarLenField.h index 01bcfaed..590c2dd5 100644 --- a/src/fsfw/cfdp/pdu/VarLenField.h +++ b/src/fsfw/cfdp/pdu/VarLenField.h @@ -1,45 +1,47 @@ #ifndef FSFW_SRC_FSFW_CFDP_PDU_VARLENFIELD_H_ #define FSFW_SRC_FSFW_CFDP_PDU_VARLENFIELD_H_ -#include "../definitions.h" -#include "fsfw/serialize/SerializeIF.h" #include #include +#include "../definitions.h" +#include "fsfw/serialize/SerializeIF.h" + namespace cfdp { -class VarLenField: public SerializeIF { -public: - union LengthFieldLen { - uint8_t oneByte; - uint16_t twoBytes; - uint32_t fourBytes; - uint64_t eightBytes; - }; +class VarLenField : public SerializeIF { + public: + union LengthFieldLen { + uint8_t oneByte; + uint16_t twoBytes; + uint32_t fourBytes; + uint64_t eightBytes; + }; - VarLenField(); - VarLenField(cfdp::WidthInBytes width, size_t value); + VarLenField(); + VarLenField(cfdp::WidthInBytes width, size_t value); - ReturnValue_t setValue(cfdp::WidthInBytes, size_t value); + ReturnValue_t setValue(cfdp::WidthInBytes, size_t value); - ReturnValue_t serialize(uint8_t **buffer, size_t *size, size_t maxSize, - Endianness streamEndianness) const override; + ReturnValue_t serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const override; - size_t getSerializedSize() const override; + size_t getSerializedSize() const override; - ReturnValue_t deSerialize(cfdp::WidthInBytes width, const uint8_t **buffer, size_t *size, - Endianness streamEndianness); + ReturnValue_t deSerialize(cfdp::WidthInBytes width, const uint8_t **buffer, size_t *size, + Endianness streamEndianness); - cfdp::WidthInBytes getWidth() const; - size_t getValue() const; -private: - ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) override; + cfdp::WidthInBytes getWidth() const; + size_t getValue() const; - cfdp::WidthInBytes width; - LengthFieldLen value; + private: + ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) override; + + cfdp::WidthInBytes width; + LengthFieldLen value; }; -} +} // namespace cfdp #endif /* FSFW_SRC_FSFW_CFDP_PDU_VARLENFIELD_H_ */ diff --git a/src/fsfw/cfdp/tlv/EntityIdTlv.cpp b/src/fsfw/cfdp/tlv/EntityIdTlv.cpp index 98b1094e..87f55db8 100644 --- a/src/fsfw/cfdp/tlv/EntityIdTlv.cpp +++ b/src/fsfw/cfdp/tlv/EntityIdTlv.cpp @@ -1,68 +1,59 @@ #include "EntityIdTlv.h" + #include -EntityIdTlv::EntityIdTlv(cfdp::EntityId& entityId): entityId(entityId) { -} +EntityIdTlv::EntityIdTlv(cfdp::EntityId &entityId) : entityId(entityId) {} -EntityIdTlv::~EntityIdTlv() { -} +EntityIdTlv::~EntityIdTlv() {} ReturnValue_t EntityIdTlv::serialize(uint8_t **buffer, size_t *size, size_t maxSize, - Endianness streamEndianness) const { - if(maxSize < this->getSerializedSize()) { - return BUFFER_TOO_SHORT; - } - **buffer = cfdp::TlvTypes::ENTITY_ID; - *size += 1; - *buffer += 1; - size_t serLen = entityId.getSerializedSize(); - **buffer = serLen; - *size += 1; - *buffer += 1; - return entityId.serialize(buffer, size, maxSize, streamEndianness); + Endianness streamEndianness) const { + if (maxSize < this->getSerializedSize()) { + return BUFFER_TOO_SHORT; + } + **buffer = cfdp::TlvTypes::ENTITY_ID; + *size += 1; + *buffer += 1; + size_t serLen = entityId.getSerializedSize(); + **buffer = serLen; + *size += 1; + *buffer += 1; + return entityId.serialize(buffer, size, maxSize, streamEndianness); } -size_t EntityIdTlv::getSerializedSize() const { - return getLengthField() + 1; -} +size_t EntityIdTlv::getSerializedSize() const { return getLengthField() + 1; } ReturnValue_t EntityIdTlv::deSerialize(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) { - if(*size < 3) { - return STREAM_TOO_SHORT; - } - cfdp::TlvTypes type = static_cast(**buffer); - if(type != cfdp::TlvTypes::ENTITY_ID) { - return cfdp::INVALID_TLV_TYPE; - } - *buffer += 1; - *size -= 1; + Endianness streamEndianness) { + if (*size < 3) { + return STREAM_TOO_SHORT; + } + cfdp::TlvTypes type = static_cast(**buffer); + if (type != cfdp::TlvTypes::ENTITY_ID) { + return cfdp::INVALID_TLV_TYPE; + } + *buffer += 1; + *size -= 1; - cfdp::WidthInBytes width = static_cast(**buffer); - if (*size < static_cast(1 + width)) { - return STREAM_TOO_SHORT; - } - *buffer += 1; - *size -= 1; + cfdp::WidthInBytes width = static_cast(**buffer); + if (*size < static_cast(1 + width)) { + return STREAM_TOO_SHORT; + } + *buffer += 1; + *size -= 1; - return entityId.deSerialize(width, buffer, size, streamEndianness); + return entityId.deSerialize(width, buffer, size, streamEndianness); } ReturnValue_t EntityIdTlv::deSerialize(cfdp::Tlv &tlv, Endianness endianness) { - const uint8_t* ptr = tlv.getValue() + 2; - size_t remSz = tlv.getSerializedSize() - 2; - cfdp::WidthInBytes width = static_cast(remSz); - return entityId.deSerialize(width, &ptr, &remSz, endianness); + const uint8_t *ptr = tlv.getValue() + 2; + size_t remSz = tlv.getSerializedSize() - 2; + cfdp::WidthInBytes width = static_cast(remSz); + return entityId.deSerialize(width, &ptr, &remSz, endianness); } -uint8_t EntityIdTlv::getLengthField() const { - return 1 + entityId.getSerializedSize(); -} +uint8_t EntityIdTlv::getLengthField() const { return 1 + entityId.getSerializedSize(); } -cfdp::TlvTypes EntityIdTlv::getType() const { - return cfdp::TlvTypes::ENTITY_ID; -} +cfdp::TlvTypes EntityIdTlv::getType() const { return cfdp::TlvTypes::ENTITY_ID; } -cfdp::EntityId& EntityIdTlv::getEntityId() { - return entityId; -} +cfdp::EntityId &EntityIdTlv::getEntityId() { return entityId; } diff --git a/src/fsfw/cfdp/tlv/EntityIdTlv.h b/src/fsfw/cfdp/tlv/EntityIdTlv.h index 5860ce05..1443cc17 100644 --- a/src/fsfw/cfdp/tlv/EntityIdTlv.h +++ b/src/fsfw/cfdp/tlv/EntityIdTlv.h @@ -1,39 +1,38 @@ #ifndef FSFW_SRC_FSFW_CFDP_ENTITYIDTLV_H_ #define FSFW_SRC_FSFW_CFDP_ENTITYIDTLV_H_ -#include "fsfw/cfdp/tlv/Tlv.h" -#include "fsfw/cfdp/pdu/PduConfig.h" #include "TlvIF.h" +#include "fsfw/cfdp/pdu/PduConfig.h" +#include "fsfw/cfdp/tlv/Tlv.h" -class EntityIdTlv: public TlvIF { -public: - EntityIdTlv(cfdp::EntityId& entityId); - virtual~ EntityIdTlv(); +class EntityIdTlv : public TlvIF { + public: + EntityIdTlv(cfdp::EntityId& entityId); + virtual ~EntityIdTlv(); - ReturnValue_t serialize(uint8_t **buffer, size_t *size, - size_t maxSize, Endianness streamEndianness) const override; + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; - size_t getSerializedSize() const override; + size_t getSerializedSize() const override; - /** - * Deserialize an entity ID from a raw TLV object - * @param tlv - * @param endianness - * @return - */ - ReturnValue_t deSerialize(cfdp::Tlv& tlv, Endianness endianness); + /** + * Deserialize an entity ID from a raw TLV object + * @param tlv + * @param endianness + * @return + */ + ReturnValue_t deSerialize(cfdp::Tlv& tlv, Endianness endianness); - ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) override; + ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + Endianness streamEndianness) override; - uint8_t getLengthField() const override; - cfdp::TlvTypes getType() const override; + uint8_t getLengthField() const override; + cfdp::TlvTypes getType() const override; - cfdp::EntityId& getEntityId(); -private: - cfdp::EntityId& entityId; + cfdp::EntityId& getEntityId(); + + private: + cfdp::EntityId& entityId; }; - - #endif /* FSFW_SRC_FSFW_CFDP_ENTITYIDTLV_H_ */ diff --git a/src/fsfw/cfdp/tlv/FaultHandlerOverrideTlv.cpp b/src/fsfw/cfdp/tlv/FaultHandlerOverrideTlv.cpp index f5ef9311..f5f777ea 100644 --- a/src/fsfw/cfdp/tlv/FaultHandlerOverrideTlv.cpp +++ b/src/fsfw/cfdp/tlv/FaultHandlerOverrideTlv.cpp @@ -1,64 +1,54 @@ #include "FaultHandlerOverrideTlv.h" FaultHandlerOverrideTlv::FaultHandlerOverrideTlv(cfdp::ConditionCode conditionCode, - cfdp::FaultHandlerCode handlerCode): - conditionCode(conditionCode), handlerCode(handlerCode) { -} + cfdp::FaultHandlerCode handlerCode) + : conditionCode(conditionCode), handlerCode(handlerCode) {} -FaultHandlerOverrideTlv::FaultHandlerOverrideTlv() { -} - -uint8_t FaultHandlerOverrideTlv::getLengthField() const { - return 1; -} +FaultHandlerOverrideTlv::FaultHandlerOverrideTlv() {} +uint8_t FaultHandlerOverrideTlv::getLengthField() const { return 1; } ReturnValue_t FaultHandlerOverrideTlv::serialize(uint8_t **buffer, size_t *size, size_t maxSize, - Endianness streamEndianness) const { - if((maxSize < 3) or ((*size + 3) > maxSize)) { - return SerializeIF::BUFFER_TOO_SHORT; - } - **buffer = getType(); - *size += 1; - *buffer += 1; - **buffer = getLengthField(); - *size += 1; - *buffer += 1; - **buffer = this->conditionCode << 4 | this->handlerCode; - *buffer += 1; - *size += 1; - return HasReturnvaluesIF::RETURN_OK; + Endianness streamEndianness) const { + if ((maxSize < 3) or ((*size + 3) > maxSize)) { + return SerializeIF::BUFFER_TOO_SHORT; + } + **buffer = getType(); + *size += 1; + *buffer += 1; + **buffer = getLengthField(); + *size += 1; + *buffer += 1; + **buffer = this->conditionCode << 4 | this->handlerCode; + *buffer += 1; + *size += 1; + return HasReturnvaluesIF::RETURN_OK; } -size_t FaultHandlerOverrideTlv::getSerializedSize() const { - return getLengthField() + 2; -} +size_t FaultHandlerOverrideTlv::getSerializedSize() const { return getLengthField() + 2; } ReturnValue_t FaultHandlerOverrideTlv::deSerialize(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) { - if(*size < 3) { - return SerializeIF::STREAM_TOO_SHORT; - } - auto detectedType = static_cast(**buffer); - if(detectedType != cfdp::TlvTypes::FAULT_HANDLER) { - return cfdp::INVALID_TLV_TYPE; - } - *buffer += 1; - *size -= 1; - size_t detectedSize = **buffer; - if(detectedSize != getLengthField()) { - return HasReturnvaluesIF::RETURN_FAILED; - } - *buffer += 1; - *size += 1; - this->conditionCode = static_cast((**buffer >> 4) & 0x0f); - this->handlerCode = static_cast(**buffer & 0x0f); - *buffer += 1; - *size += 1; - return HasReturnvaluesIF::RETURN_OK; + Endianness streamEndianness) { + if (*size < 3) { + return SerializeIF::STREAM_TOO_SHORT; + } + auto detectedType = static_cast(**buffer); + if (detectedType != cfdp::TlvTypes::FAULT_HANDLER) { + return cfdp::INVALID_TLV_TYPE; + } + *buffer += 1; + *size -= 1; + size_t detectedSize = **buffer; + if (detectedSize != getLengthField()) { + return HasReturnvaluesIF::RETURN_FAILED; + } + *buffer += 1; + *size += 1; + this->conditionCode = static_cast((**buffer >> 4) & 0x0f); + this->handlerCode = static_cast(**buffer & 0x0f); + *buffer += 1; + *size += 1; + return HasReturnvaluesIF::RETURN_OK; } - -cfdp::TlvTypes FaultHandlerOverrideTlv::getType() const { - return cfdp::TlvTypes::FAULT_HANDLER; -} +cfdp::TlvTypes FaultHandlerOverrideTlv::getType() const { return cfdp::TlvTypes::FAULT_HANDLER; } diff --git a/src/fsfw/cfdp/tlv/FaultHandlerOverrideTlv.h b/src/fsfw/cfdp/tlv/FaultHandlerOverrideTlv.h index 7014ae0e..9f2adbb3 100644 --- a/src/fsfw/cfdp/tlv/FaultHandlerOverrideTlv.h +++ b/src/fsfw/cfdp/tlv/FaultHandlerOverrideTlv.h @@ -6,34 +6,33 @@ namespace cfdp { enum FaultHandlerCode { - RESERVED = 0b0000, - NOTICE_OF_CANCELLATION = 0b0001, - NOTICE_OF_SUSPENSION = 0b0010, - IGNORE_ERROR = 0b0011, - ABANDON_TRANSACTION = 0b0100 + RESERVED = 0b0000, + NOTICE_OF_CANCELLATION = 0b0001, + NOTICE_OF_SUSPENSION = 0b0010, + IGNORE_ERROR = 0b0011, + ABANDON_TRANSACTION = 0b0100 }; } -class FaultHandlerOverrideTlv: public TlvIF { -public: +class FaultHandlerOverrideTlv : public TlvIF { + public: + FaultHandlerOverrideTlv(); + FaultHandlerOverrideTlv(cfdp::ConditionCode conditionCode, cfdp::FaultHandlerCode handlerCode); - FaultHandlerOverrideTlv(); - FaultHandlerOverrideTlv(cfdp::ConditionCode conditionCode, cfdp::FaultHandlerCode handlerCode); + ReturnValue_t serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const override; - ReturnValue_t serialize(uint8_t **buffer, size_t *size, - size_t maxSize, Endianness streamEndianness) const override; + size_t getSerializedSize() const override; - size_t getSerializedSize() const override; + ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) override; + uint8_t getLengthField() const override; + cfdp::TlvTypes getType() const override; - ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) override; - uint8_t getLengthField() const override; - cfdp::TlvTypes getType() const override; - -private: - cfdp::ConditionCode conditionCode = cfdp::ConditionCode::NO_CONDITION_FIELD; - cfdp::FaultHandlerCode handlerCode = cfdp::FaultHandlerCode::RESERVED; + private: + cfdp::ConditionCode conditionCode = cfdp::ConditionCode::NO_CONDITION_FIELD; + cfdp::FaultHandlerCode handlerCode = cfdp::FaultHandlerCode::RESERVED; }; #endif /* FSFW_SRC_FSFW_CFDP_TLV_FAULTHANDLEROVERRIDETLV_H_ */ diff --git a/src/fsfw/cfdp/tlv/FilestoreRequestTlv.cpp b/src/fsfw/cfdp/tlv/FilestoreRequestTlv.cpp index 044c4e9a..9ad7c645 100644 --- a/src/fsfw/cfdp/tlv/FilestoreRequestTlv.cpp +++ b/src/fsfw/cfdp/tlv/FilestoreRequestTlv.cpp @@ -1,83 +1,79 @@ #include "fsfw/cfdp/tlv/FilestoreRequestTlv.h" + #include "fsfw/FSFW.h" FilestoreRequestTlv::FilestoreRequestTlv(cfdp::FilestoreActionCode actionCode, - cfdp::Lv& firstFileName): FilestoreTlvBase(actionCode, firstFileName) { -} + cfdp::Lv &firstFileName) + : FilestoreTlvBase(actionCode, firstFileName) {} -FilestoreRequestTlv::FilestoreRequestTlv(cfdp::Lv &firstFileName): - FilestoreTlvBase(cfdp::FilestoreActionCode::INVALID, firstFileName) { -} +FilestoreRequestTlv::FilestoreRequestTlv(cfdp::Lv &firstFileName) + : FilestoreTlvBase(cfdp::FilestoreActionCode::INVALID, firstFileName) {} void FilestoreRequestTlv::setSecondFileName(cfdp::Lv *secondFileName) { - this->secondFileName = secondFileName; + this->secondFileName = secondFileName; } ReturnValue_t FilestoreRequestTlv::serialize(uint8_t **buffer, size_t *size, size_t maxSize, - Endianness streamEndianness) const { - ReturnValue_t result = commonSerialize(buffer, size, maxSize, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; + Endianness streamEndianness) const { + ReturnValue_t result = commonSerialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = firstFileName.serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (requiresSecondFileName()) { + if (secondFileName == nullptr) { + secondFileNameMissing(); + return cfdp::FILESTORE_REQUIRES_SECOND_FILE; } - result = firstFileName.serialize(buffer, size, maxSize, - streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if(requiresSecondFileName()) { - if(secondFileName == nullptr) { - secondFileNameMissing(); - return cfdp::FILESTORE_REQUIRES_SECOND_FILE; - } - secondFileName->serialize(buffer, size, maxSize, streamEndianness); - } - return HasReturnvaluesIF::RETURN_OK; + secondFileName->serialize(buffer, size, maxSize, streamEndianness); + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t FilestoreRequestTlv::deSerialize(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) { - ReturnValue_t result = commonDeserialize(buffer, size, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return deSerializeFromValue(buffer, size, streamEndianness); + Endianness streamEndianness) { + ReturnValue_t result = commonDeserialize(buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return deSerializeFromValue(buffer, size, streamEndianness); } -ReturnValue_t FilestoreRequestTlv::deSerialize(cfdp::Tlv &tlv, - SerializeIF::Endianness endianness) { - const uint8_t* ptr = tlv.getValue(); - size_t remSz = tlv.getSerializedSize(); +ReturnValue_t FilestoreRequestTlv::deSerialize(cfdp::Tlv &tlv, SerializeIF::Endianness endianness) { + const uint8_t *ptr = tlv.getValue(); + size_t remSz = tlv.getSerializedSize(); - return deSerializeFromValue(&ptr, &remSz, endianness); + return deSerializeFromValue(&ptr, &remSz, endianness); } uint8_t FilestoreRequestTlv::getLengthField() const { - size_t secondFileNameLen = 0; - if(secondFileName != nullptr and requiresSecondFileName()) { - secondFileNameLen = secondFileName->getSerializedSize(); - } - return 1 + firstFileName.getSerializedSize() + secondFileNameLen; + size_t secondFileNameLen = 0; + if (secondFileName != nullptr and requiresSecondFileName()) { + secondFileNameLen = secondFileName->getSerializedSize(); + } + return 1 + firstFileName.getSerializedSize() + secondFileNameLen; } ReturnValue_t FilestoreRequestTlv::deSerializeFromValue(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) { - this->actionCode = static_cast((**buffer >> 4) & 0x0f); - *buffer += 1; - *size -= 1; - ReturnValue_t result = firstFileName.deSerialize(buffer, size, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if(requiresSecondFileName()) { - if(secondFileName == nullptr) { - secondFileNameMissing(); - return HasReturnvaluesIF::RETURN_FAILED; - } - result = secondFileName->deSerialize(buffer, size, streamEndianness); - } + Endianness streamEndianness) { + this->actionCode = static_cast((**buffer >> 4) & 0x0f); + *buffer += 1; + *size -= 1; + ReturnValue_t result = firstFileName.deSerialize(buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { return result; + } + if (requiresSecondFileName()) { + if (secondFileName == nullptr) { + secondFileNameMissing(); + return HasReturnvaluesIF::RETURN_FAILED; + } + result = secondFileName->deSerialize(buffer, size, streamEndianness); + } + return result; } -cfdp::TlvTypes FilestoreRequestTlv::getType() const { - return cfdp::TlvTypes::FILESTORE_REQUEST; -} +cfdp::TlvTypes FilestoreRequestTlv::getType() const { return cfdp::TlvTypes::FILESTORE_REQUEST; } diff --git a/src/fsfw/cfdp/tlv/FilestoreRequestTlv.h b/src/fsfw/cfdp/tlv/FilestoreRequestTlv.h index d4cedbb2..5acb0ef4 100644 --- a/src/fsfw/cfdp/tlv/FilestoreRequestTlv.h +++ b/src/fsfw/cfdp/tlv/FilestoreRequestTlv.h @@ -1,45 +1,42 @@ #ifndef FSFW_SRC_FSFW_CFDP_FILESTOREREQUESTTLV_H_ #define FSFW_SRC_FSFW_CFDP_FILESTOREREQUESTTLV_H_ +#include "../definitions.h" +#include "Lv.h" +#include "TlvIF.h" #include "fsfw/cfdp/tlv/FilestoreTlvBase.h" #include "fsfw/cfdp/tlv/Tlv.h" -#include "TlvIF.h" -#include "Lv.h" -#include "../definitions.h" -class FilestoreRequestTlv: - public cfdp::FilestoreTlvBase { -public: - FilestoreRequestTlv(cfdp::FilestoreActionCode actionCode, cfdp::Lv& firstFileName); +class FilestoreRequestTlv : public cfdp::FilestoreTlvBase { + public: + FilestoreRequestTlv(cfdp::FilestoreActionCode actionCode, cfdp::Lv &firstFileName); - FilestoreRequestTlv(cfdp::Lv& firstFileName); + FilestoreRequestTlv(cfdp::Lv &firstFileName); - void setSecondFileName(cfdp::Lv* secondFileName); + void setSecondFileName(cfdp::Lv *secondFileName); - ReturnValue_t serialize(uint8_t **buffer, size_t *size, - size_t maxSize, Endianness streamEndianness) const override; + ReturnValue_t serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const override; - /** - * Deserialize a FS request from a raw TLV object - * @param tlv - * @param endianness - * @return - */ - ReturnValue_t deSerialize(cfdp::Tlv& tlv, Endianness endianness); + /** + * Deserialize a FS request from a raw TLV object + * @param tlv + * @param endianness + * @return + */ + ReturnValue_t deSerialize(cfdp::Tlv &tlv, Endianness endianness); - ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) override; + ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) override; - uint8_t getLengthField() const override; - cfdp::TlvTypes getType() const override; + uint8_t getLengthField() const override; + cfdp::TlvTypes getType() const override; -private: - cfdp::Lv* secondFileName = nullptr; + private: + cfdp::Lv *secondFileName = nullptr; - ReturnValue_t deSerializeFromValue(const uint8_t **buffer, size_t *size, - Endianness streamEndianness); + ReturnValue_t deSerializeFromValue(const uint8_t **buffer, size_t *size, + Endianness streamEndianness); }; - - #endif /* FSFW_SRC_FSFW_CFDP_FILESTOREREQUESTTLV_H_ */ diff --git a/src/fsfw/cfdp/tlv/FilestoreResponseTlv.cpp b/src/fsfw/cfdp/tlv/FilestoreResponseTlv.cpp index ec57579a..36945725 100644 --- a/src/fsfw/cfdp/tlv/FilestoreResponseTlv.cpp +++ b/src/fsfw/cfdp/tlv/FilestoreResponseTlv.cpp @@ -1,124 +1,115 @@ #include "FilestoreResponseTlv.h" FilestoreResponseTlv::FilestoreResponseTlv(cfdp::FilestoreActionCode actionCode, uint8_t statusCode, - cfdp::Lv& firstFileName, cfdp::Lv* fsMsg): FilestoreTlvBase(actionCode, firstFileName), - statusCode(statusCode), filestoreMsg(fsMsg) { -} + cfdp::Lv &firstFileName, cfdp::Lv *fsMsg) + : FilestoreTlvBase(actionCode, firstFileName), statusCode(statusCode), filestoreMsg(fsMsg) {} -FilestoreResponseTlv::FilestoreResponseTlv(cfdp::Lv &firstFileName, cfdp::Lv* fsMsg): - FilestoreTlvBase(firstFileName), statusCode(0), filestoreMsg(fsMsg) { -} +FilestoreResponseTlv::FilestoreResponseTlv(cfdp::Lv &firstFileName, cfdp::Lv *fsMsg) + : FilestoreTlvBase(firstFileName), statusCode(0), filestoreMsg(fsMsg) {} uint8_t FilestoreResponseTlv::getLengthField() const { - size_t optFieldsLen = 0; - if(secondFileName != nullptr) { - optFieldsLen += secondFileName->getSerializedSize(); - } - if(filestoreMsg != nullptr) { - optFieldsLen += filestoreMsg->getSerializedSize(); - } else { - optFieldsLen += 1; - } - return 1 + firstFileName.getSerializedSize() + optFieldsLen; + size_t optFieldsLen = 0; + if (secondFileName != nullptr) { + optFieldsLen += secondFileName->getSerializedSize(); + } + if (filestoreMsg != nullptr) { + optFieldsLen += filestoreMsg->getSerializedSize(); + } else { + optFieldsLen += 1; + } + return 1 + firstFileName.getSerializedSize() + optFieldsLen; } void FilestoreResponseTlv::setSecondFileName(cfdp::Lv *secondFileName) { - this->secondFileName = secondFileName; + this->secondFileName = secondFileName; } void FilestoreResponseTlv::setFilestoreMessage(cfdp::Lv *filestoreMsg) { - this->filestoreMsg = filestoreMsg; + this->filestoreMsg = filestoreMsg; } ReturnValue_t FilestoreResponseTlv::serialize(uint8_t **buffer, size_t *size, size_t maxSize, - Endianness streamEndianness) const { - ReturnValue_t result = commonSerialize(buffer, size, maxSize, streamEndianness, - true, this->statusCode); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = firstFileName.serialize(buffer, size, maxSize, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if(requiresSecondFileName()) { - if(secondFileName == nullptr) { - secondFileNameMissing(); - return cfdp::FILESTORE_REQUIRES_SECOND_FILE; - } - } - if(filestoreMsg != nullptr) { - result = filestoreMsg->serialize(buffer, size, maxSize, streamEndianness); - } - else { - if(*size == maxSize) { - return SerializeIF::BUFFER_TOO_SHORT; - } - **buffer = 0; - *buffer += 1; - *size +=1; - } + Endianness streamEndianness) const { + ReturnValue_t result = + commonSerialize(buffer, size, maxSize, streamEndianness, true, this->statusCode); + if (result != HasReturnvaluesIF::RETURN_OK) { return result; + } + result = firstFileName.serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (requiresSecondFileName()) { + if (secondFileName == nullptr) { + secondFileNameMissing(); + return cfdp::FILESTORE_REQUIRES_SECOND_FILE; + } + } + if (filestoreMsg != nullptr) { + result = filestoreMsg->serialize(buffer, size, maxSize, streamEndianness); + } else { + if (*size == maxSize) { + return SerializeIF::BUFFER_TOO_SHORT; + } + **buffer = 0; + *buffer += 1; + *size += 1; + } + return result; } ReturnValue_t FilestoreResponseTlv::deSerialize(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) { - ReturnValue_t result = commonDeserialize(buffer, size, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return deSerializeFromValue(buffer, size, streamEndianness); + Endianness streamEndianness) { + ReturnValue_t result = commonDeserialize(buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return deSerializeFromValue(buffer, size, streamEndianness); } ReturnValue_t FilestoreResponseTlv::deSerializeFromValue(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) { - - // The common function above checks whether at least one byte is remaining - this->actionCode = static_cast((**buffer >> 4) & 0x0f); - this->statusCode = **buffer & 0x0f; - *buffer += 1; + Endianness streamEndianness) { + // The common function above checks whether at least one byte is remaining + this->actionCode = static_cast((**buffer >> 4) & 0x0f); + this->statusCode = **buffer & 0x0f; + *buffer += 1; + *size -= 1; + ReturnValue_t result = firstFileName.deSerialize(buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (requiresSecondFileName()) { + if (secondFileName == nullptr) { + return cfdp::FILESTORE_REQUIRES_SECOND_FILE; + } + result = secondFileName->deSerialize(buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + } + // If the filestore message is not empty, the deserialization is only considered successfully + // if the filestore message can be parsed. Also, if data follows after the FS response, + // the FS msg needs to be set as well. + if (*size == 0 or (*size > 1 and filestoreMsg == nullptr)) { + // Filestore message missing or can't parse it + return cfdp::FILESTORE_RESPONSE_CANT_PARSE_FS_MESSAGE; + } + if (filestoreMsg == nullptr) { *size -= 1; - ReturnValue_t result = firstFileName.deSerialize(buffer, size, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if(requiresSecondFileName()) { - if(secondFileName == nullptr) { - return cfdp::FILESTORE_REQUIRES_SECOND_FILE; - } - result = secondFileName->deSerialize(buffer, size, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - } - // If the filestore message is not empty, the deserialization is only considered successfully - // if the filestore message can be parsed. Also, if data follows after the FS response, - // the FS msg needs to be set as well. - if(*size == 0 or (*size > 1 and filestoreMsg == nullptr)) { - // Filestore message missing or can't parse it - return cfdp::FILESTORE_RESPONSE_CANT_PARSE_FS_MESSAGE; - } - if(filestoreMsg == nullptr) { - *size -= 1; - *buffer += 1; - // Ignore empty filestore message - return HasReturnvaluesIF::RETURN_OK; - } - return filestoreMsg->deSerialize(buffer, size, streamEndianness); + *buffer += 1; + // Ignore empty filestore message + return HasReturnvaluesIF::RETURN_OK; + } + return filestoreMsg->deSerialize(buffer, size, streamEndianness); } ReturnValue_t FilestoreResponseTlv::deSerialize(const cfdp::Tlv &tlv, Endianness endianness) { - const uint8_t* ptr = tlv.getValue(); - size_t remSz = tlv.getSerializedSize(); + const uint8_t *ptr = tlv.getValue(); + size_t remSz = tlv.getSerializedSize(); - return deSerializeFromValue(&ptr, &remSz, endianness); + return deSerializeFromValue(&ptr, &remSz, endianness); } -uint8_t FilestoreResponseTlv::getStatusCode() const { - return statusCode; -} +uint8_t FilestoreResponseTlv::getStatusCode() const { return statusCode; } - -cfdp::TlvTypes FilestoreResponseTlv::getType() const { - return cfdp::TlvTypes::FILESTORE_RESPONSE; -} +cfdp::TlvTypes FilestoreResponseTlv::getType() const { return cfdp::TlvTypes::FILESTORE_RESPONSE; } diff --git a/src/fsfw/cfdp/tlv/FilestoreResponseTlv.h b/src/fsfw/cfdp/tlv/FilestoreResponseTlv.h index 1159fdca..7b68ba57 100644 --- a/src/fsfw/cfdp/tlv/FilestoreResponseTlv.h +++ b/src/fsfw/cfdp/tlv/FilestoreResponseTlv.h @@ -1,50 +1,46 @@ #ifndef FSFW_SRC_FSFW_CFDP_FILESTORERESPONSETLV_H_ #define FSFW_SRC_FSFW_CFDP_FILESTORERESPONSETLV_H_ +#include "Lv.h" +#include "TlvIF.h" #include "fsfw/cfdp/tlv/FilestoreTlvBase.h" #include "fsfw/cfdp/tlv/Tlv.h" -#include "TlvIF.h" -#include "Lv.h" -class FilestoreResponseTlv: - public cfdp::FilestoreTlvBase { -public: +class FilestoreResponseTlv : public cfdp::FilestoreTlvBase { + public: + FilestoreResponseTlv(cfdp::Lv& firstFileName, cfdp::Lv* fsMsg); - FilestoreResponseTlv(cfdp::Lv& firstFileName, cfdp::Lv* fsMsg); + FilestoreResponseTlv(cfdp::FilestoreActionCode actionCode, uint8_t statusCode, + cfdp::Lv& firstFileName, cfdp::Lv* fsMsg); - FilestoreResponseTlv(cfdp::FilestoreActionCode actionCode, uint8_t statusCode, - cfdp::Lv& firstFileName, cfdp::Lv* fsMsg); + uint8_t getStatusCode() const; + void setSecondFileName(cfdp::Lv* secondFileName); + void setFilestoreMessage(cfdp::Lv* filestoreMsg); - uint8_t getStatusCode() const; - void setSecondFileName(cfdp::Lv* secondFileName); - void setFilestoreMessage(cfdp::Lv* filestoreMsg); + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; - ReturnValue_t serialize(uint8_t **buffer, size_t *size, - size_t maxSize, Endianness streamEndianness) const override; + /** + * Deserialize a filestore response from a raw TLV object + * @param tlv + * @param endianness + * @return + */ + ReturnValue_t deSerialize(const cfdp::Tlv& tlv, Endianness endianness); - /** - * Deserialize a filestore response from a raw TLV object - * @param tlv - * @param endianness - * @return - */ - ReturnValue_t deSerialize(const cfdp::Tlv& tlv, Endianness endianness); + ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + Endianness streamEndianness) override; - ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) override; + uint8_t getLengthField() const override; + cfdp::TlvTypes getType() const override; - uint8_t getLengthField() const override; - cfdp::TlvTypes getType() const override; + private: + uint8_t statusCode; + cfdp::Lv* secondFileName = nullptr; + cfdp::Lv* filestoreMsg = nullptr; -private: - uint8_t statusCode; - cfdp::Lv* secondFileName = nullptr; - cfdp::Lv* filestoreMsg = nullptr; - - ReturnValue_t deSerializeFromValue(const uint8_t **buffer, size_t *size, - Endianness streamEndianness); + ReturnValue_t deSerializeFromValue(const uint8_t** buffer, size_t* size, + Endianness streamEndianness); }; - - #endif /* FSFW_SRC_FSFW_CFDP_FILESTORERESPONSETLV_H_ */ diff --git a/src/fsfw/cfdp/tlv/FilestoreTlvBase.h b/src/fsfw/cfdp/tlv/FilestoreTlvBase.h index f81b8807..bb9f10bb 100644 --- a/src/fsfw/cfdp/tlv/FilestoreTlvBase.h +++ b/src/fsfw/cfdp/tlv/FilestoreTlvBase.h @@ -6,27 +6,28 @@ #include #include #include + #include #include namespace cfdp { enum FilestoreActionCode { - CREATE_FILE = 0b0000, - DELETE_FILE = 0b0001, - // Second file name present - RENAME_FILE = 0b0010, - // Second file name present - APPEND_FILE = 0b0011, - // Second file name present - REPLACE_FILE = 0b0100, - CREATE_DIRECTORY = 0b0101, - REMOVE_DIRECTORY = 0b0110, - // Delete file if present - DENY_FILE = 0b0111, - // Remove directory if present - DNEY_DIRECTORY = 0b1000, - INVALID = 0b1111 + CREATE_FILE = 0b0000, + DELETE_FILE = 0b0001, + // Second file name present + RENAME_FILE = 0b0010, + // Second file name present + APPEND_FILE = 0b0011, + // Second file name present + REPLACE_FILE = 0b0100, + CREATE_DIRECTORY = 0b0101, + REMOVE_DIRECTORY = 0b0110, + // Delete file if present + DENY_FILE = 0b0111, + // Remove directory if present + DNEY_DIRECTORY = 0b1000, + INVALID = 0b1111 }; // FSR = Filestore Response @@ -59,118 +60,110 @@ static constexpr uint8_t FSR_DENY_FILE_NOT_ALLOWED = 0b0010; static constexpr uint8_t FSR_DENY_DIR_NOT_ALLOWED = 0b0010; -class FilestoreTlvBase: public TlvIF { -public: +class FilestoreTlvBase : public TlvIF { + public: + FilestoreTlvBase(cfdp::Lv& firstFileName) : firstFileName(firstFileName){}; + FilestoreTlvBase(FilestoreActionCode actionCode, cfdp::Lv& firstFileName) + : actionCode(actionCode), firstFileName(firstFileName){}; - FilestoreTlvBase(cfdp::Lv& firstFileName): firstFileName(firstFileName) {}; - FilestoreTlvBase(FilestoreActionCode actionCode, cfdp::Lv& firstFileName): - actionCode(actionCode), firstFileName(firstFileName) {}; - - ReturnValue_t commonSerialize(uint8_t **buffer, size_t *size, - size_t maxSize, Endianness streamEndianness, - bool isResponse = false, uint8_t responseStatusCode = 0) const { - if(buffer == nullptr or size == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - if(maxSize < 3) { - return SerializeIF::BUFFER_TOO_SHORT; - } - **buffer = getType(); - *buffer += 1; - *size += 1; - **buffer = getLengthField(); - *buffer += 1; - *size += 1; - **buffer = this->actionCode << 4; - if(isResponse) { - **buffer |= responseStatusCode; - } - *buffer += 1; - *size += 1; - return HasReturnvaluesIF::RETURN_OK; + ReturnValue_t commonSerialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness, bool isResponse = false, + uint8_t responseStatusCode = 0) const { + if (buffer == nullptr or size == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; } - - ReturnValue_t commonDeserialize(const uint8_t **buffer, size_t *size, - SerializeIF::Endianness streamEndianness) { - if(buffer == nullptr or size == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - if(*size < 3) { - return SerializeIF::STREAM_TOO_SHORT; - } - cfdp::TlvTypes type = static_cast(**buffer); - if(type != getType()) { - return cfdp::INVALID_TLV_TYPE; - } - *size -= 1; - *buffer += 1; - - size_t remainingLength = **buffer; - *size -= 1; - *buffer += 1; - if(remainingLength == 0) { - return SerializeIF::STREAM_TOO_SHORT; - } - return HasReturnvaluesIF::RETURN_OK; + if (maxSize < 3) { + return SerializeIF::BUFFER_TOO_SHORT; } - - bool requiresSecondFileName() const { - using namespace cfdp; - if(actionCode == FilestoreActionCode::RENAME_FILE or - actionCode == FilestoreActionCode::APPEND_FILE or - actionCode == FilestoreActionCode::REPLACE_FILE) { - return true; - } - return false; + **buffer = getType(); + *buffer += 1; + *size += 1; + **buffer = getLengthField(); + *buffer += 1; + *size += 1; + **buffer = this->actionCode << 4; + if (isResponse) { + **buffer |= responseStatusCode; } + *buffer += 1; + *size += 1; + return HasReturnvaluesIF::RETURN_OK; + } - void secondFileNameMissing() const { + ReturnValue_t commonDeserialize(const uint8_t** buffer, size_t* size, + SerializeIF::Endianness streamEndianness) { + if (buffer == nullptr or size == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if (*size < 3) { + return SerializeIF::STREAM_TOO_SHORT; + } + cfdp::TlvTypes type = static_cast(**buffer); + if (type != getType()) { + return cfdp::INVALID_TLV_TYPE; + } + *size -= 1; + *buffer += 1; + + size_t remainingLength = **buffer; + *size -= 1; + *buffer += 1; + if (remainingLength == 0) { + return SerializeIF::STREAM_TOO_SHORT; + } + return HasReturnvaluesIF::RETURN_OK; + } + + bool requiresSecondFileName() const { + using namespace cfdp; + if (actionCode == FilestoreActionCode::RENAME_FILE or + actionCode == FilestoreActionCode::APPEND_FILE or + actionCode == FilestoreActionCode::REPLACE_FILE) { + return true; + } + return false; + } + + void secondFileNameMissing() const { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "FilestoreRequestTlv::deSerialize: Second file name required" - " but TLV pointer not set" << std::endl; + sif::warning << "FilestoreRequestTlv::deSerialize: Second file name required" + " but TLV pointer not set" + << std::endl; #else - sif::printWarning("FilestoreRequestTlv::deSerialize: Second file name required" - " but TLV pointer not set\n"); + sif::printWarning( + "FilestoreRequestTlv::deSerialize: Second file name required" + " but TLV pointer not set\n"); #endif #endif - } + } - FilestoreActionCode getActionCode() const { - return actionCode; - } + FilestoreActionCode getActionCode() const { return actionCode; } - void setActionCode(FilestoreActionCode actionCode) { - this->actionCode = actionCode; - } + void setActionCode(FilestoreActionCode actionCode) { this->actionCode = actionCode; } - cfdp::Lv& getFirstFileName() { - return firstFileName; - } + cfdp::Lv& getFirstFileName() { return firstFileName; } - ReturnValue_t convertToTlv(cfdp::Tlv& tlv, uint8_t *buffer, size_t maxSize, - Endianness streamEndianness) { - size_t serSize = 0; - uint8_t* valueStart = buffer + 2; - ReturnValue_t result = this->serialize(&buffer, &serSize, maxSize, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - tlv.setValue(valueStart, serSize - 2); - tlv.setType(getType()); - return result; + ReturnValue_t convertToTlv(cfdp::Tlv& tlv, uint8_t* buffer, size_t maxSize, + Endianness streamEndianness) { + size_t serSize = 0; + uint8_t* valueStart = buffer + 2; + ReturnValue_t result = this->serialize(&buffer, &serSize, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; } + tlv.setValue(valueStart, serSize - 2); + tlv.setType(getType()); + return result; + } - size_t getSerializedSize() const override { - return getLengthField() + 2; - } -protected: - FilestoreActionCode actionCode = FilestoreActionCode::INVALID; - cfdp::Lv& firstFileName; + size_t getSerializedSize() const override { return getLengthField() + 2; } + + protected: + FilestoreActionCode actionCode = FilestoreActionCode::INVALID; + cfdp::Lv& firstFileName; }; -} - - +} // namespace cfdp #endif /* FSFW_SRC_FSFW_CFDP_FILESTOREREQUESTBASE_H_ */ diff --git a/src/fsfw/cfdp/tlv/FlowLabelTlv.cpp b/src/fsfw/cfdp/tlv/FlowLabelTlv.cpp index c5835414..938af9f4 100644 --- a/src/fsfw/cfdp/tlv/FlowLabelTlv.cpp +++ b/src/fsfw/cfdp/tlv/FlowLabelTlv.cpp @@ -1,5 +1,4 @@ #include "FlowLabelTlv.h" -FlowLabelTlv::FlowLabelTlv(uint8_t* value, size_t size): - Tlv(cfdp::TlvTypes::FLOW_LABEL, value, size) { -} +FlowLabelTlv::FlowLabelTlv(uint8_t* value, size_t size) + : Tlv(cfdp::TlvTypes::FLOW_LABEL, value, size) {} diff --git a/src/fsfw/cfdp/tlv/FlowLabelTlv.h b/src/fsfw/cfdp/tlv/FlowLabelTlv.h index 3375c361..0fac8d51 100644 --- a/src/fsfw/cfdp/tlv/FlowLabelTlv.h +++ b/src/fsfw/cfdp/tlv/FlowLabelTlv.h @@ -3,11 +3,11 @@ #include "Tlv.h" -class FlowLabelTlv: public cfdp::Tlv { -public: - FlowLabelTlv(uint8_t* value, size_t size); -private: +class FlowLabelTlv : public cfdp::Tlv { + public: + FlowLabelTlv(uint8_t* value, size_t size); + private: }; #endif /* FSFW_SRC_FSFW_CFDP_TLV_FLOWLABELTLV_H_ */ diff --git a/src/fsfw/cfdp/tlv/Lv.cpp b/src/fsfw/cfdp/tlv/Lv.cpp index fa3b99e7..1bb16301 100644 --- a/src/fsfw/cfdp/tlv/Lv.cpp +++ b/src/fsfw/cfdp/tlv/Lv.cpp @@ -1,88 +1,85 @@ #include "Lv.h" -cfdp::Lv::Lv(const uint8_t *value, size_t size): value(value, size, true) { - if(size > 0) { - zeroLen = false; - } +cfdp::Lv::Lv(const uint8_t* value, size_t size) : value(value, size, true) { + if (size > 0) { + zeroLen = false; + } } -cfdp::Lv::Lv(): value(static_cast(nullptr), 0, true) { +cfdp::Lv::Lv() : value(static_cast(nullptr), 0, true) {} + +cfdp::Lv::Lv(const Lv& other) + : value(other.value.getConstBuffer(), other.value.getSerializedSize() - 1, true) { + if (other.value.getSerializedSize() - 1 > 0) { + zeroLen = false; + } } -cfdp::Lv::Lv(const Lv& other): - value(other.value.getConstBuffer(), other.value.getSerializedSize() - 1, true) { - if(other.value.getSerializedSize() - 1 > 0) { - zeroLen = false; - } +cfdp::Lv& cfdp::Lv::operator=(const Lv& other) { + size_t otherSize = 0; + uint8_t* value = const_cast(other.getValue(&otherSize)); + if (value == nullptr or otherSize == 0) { + this->zeroLen = true; + } + this->value.setBuffer(value, otherSize); + return *this; } -cfdp::Lv& cfdp::Lv::operator =(const Lv& other) { - size_t otherSize = 0; - uint8_t* value = const_cast(other.getValue(&otherSize)); - if (value == nullptr or otherSize == 0) { - this->zeroLen = true; - } - this->value.setBuffer(value, otherSize); - return *this; -} - - -ReturnValue_t cfdp::Lv::serialize(uint8_t **buffer, size_t *size, size_t maxSize, - Endianness streamEndianness) const { - if(maxSize < 1) { - return BUFFER_TOO_SHORT; - } - if(buffer == nullptr or size == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - if(zeroLen) { - **buffer = 0; - *size += 1; - *buffer += 1; - return HasReturnvaluesIF::RETURN_OK; - } - return value.serialize(buffer, size, maxSize, streamEndianness); +ReturnValue_t cfdp::Lv::serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const { + if (maxSize < 1) { + return BUFFER_TOO_SHORT; + } + if (buffer == nullptr or size == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if (zeroLen) { + **buffer = 0; + *size += 1; + *buffer += 1; + return HasReturnvaluesIF::RETURN_OK; + } + return value.serialize(buffer, size, maxSize, streamEndianness); } size_t cfdp::Lv::getSerializedSize() const { - if(zeroLen) { - return 1; - } - else if(value.getConstBuffer() == nullptr) { - return 0; - } - return value.getSerializedSize(); + if (zeroLen) { + return 1; + } else if (value.getConstBuffer() == nullptr) { + return 0; + } + return value.getSerializedSize(); } -ReturnValue_t cfdp::Lv::deSerialize(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) { - if(buffer == nullptr or size == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - if(*size < 1) { - return SerializeIF::STREAM_TOO_SHORT; - } - size_t lengthField = **buffer; - if(lengthField == 0) { - zeroLen = true; - *buffer += 1; - *size -= 1; - return HasReturnvaluesIF::RETURN_OK; - } else if(*size < lengthField + 1) { - return SerializeIF::STREAM_TOO_SHORT; - } - zeroLen = false; - // Zero-copy implementation - value.setBuffer(const_cast(*buffer + 1), lengthField); - *buffer += 1 + lengthField; - *size -= 1 + lengthField; +ReturnValue_t cfdp::Lv::deSerialize(const uint8_t** buffer, size_t* size, + Endianness streamEndianness) { + if (buffer == nullptr or size == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if (*size < 1) { + return SerializeIF::STREAM_TOO_SHORT; + } + size_t lengthField = **buffer; + if (lengthField == 0) { + zeroLen = true; + *buffer += 1; + *size -= 1; return HasReturnvaluesIF::RETURN_OK; + } else if (*size < lengthField + 1) { + return SerializeIF::STREAM_TOO_SHORT; + } + zeroLen = false; + // Zero-copy implementation + value.setBuffer(const_cast(*buffer + 1), lengthField); + *buffer += 1 + lengthField; + *size -= 1 + lengthField; + return HasReturnvaluesIF::RETURN_OK; } const uint8_t* cfdp::Lv::getValue(size_t* size) const { - if(size != nullptr) { - // Length without length field - *size = value.getSerializedSize() - 1; - } - return value.getConstBuffer(); + if (size != nullptr) { + // Length without length field + *size = value.getSerializedSize() - 1; + } + return value.getConstBuffer(); } diff --git a/src/fsfw/cfdp/tlv/Lv.h b/src/fsfw/cfdp/tlv/Lv.h index 46d47819..29764433 100644 --- a/src/fsfw/cfdp/tlv/Lv.h +++ b/src/fsfw/cfdp/tlv/Lv.h @@ -10,44 +10,44 @@ namespace cfdp { * @details * Thin abstraction layer around a serial buffer adapter */ -class Lv: public SerializeIF { -public: - Lv(const uint8_t* value, size_t size); - Lv(); +class Lv : public SerializeIF { + public: + Lv(const uint8_t* value, size_t size); + Lv(); - // Delete copy ctor and assingment ctor for now because this class contains a reference to - // data - Lv (const Lv&); - Lv& operator= (const Lv&); + // Delete copy ctor and assingment ctor for now because this class contains a reference to + // data + Lv(const Lv&); + Lv& operator=(const Lv&); - ReturnValue_t serialize(uint8_t **buffer, size_t *size, - size_t maxSize, Endianness streamEndianness) const override; + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; - size_t getSerializedSize() const override; + size_t getSerializedSize() const override; - /** - * @brief Deserialize a LV field from a raw buffer - * @param buffer Raw buffer including the size field - * @param size - * @param streamEndianness - * @return - */ - ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) override; + /** + * @brief Deserialize a LV field from a raw buffer + * @param buffer Raw buffer including the size field + * @param size + * @param streamEndianness + * @return + */ + ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + Endianness streamEndianness) override; - /** - * Get value field and its size. - * @param size Optionally retrieve size. Size will be the size of the actual value field - * without the length field of the LV - * @return - */ - const uint8_t* getValue(size_t* size) const; -private: + /** + * Get value field and its size. + * @param size Optionally retrieve size. Size will be the size of the actual value field + * without the length field of the LV + * @return + */ + const uint8_t* getValue(size_t* size) const; - bool zeroLen = true; - SerialBufferAdapter value; + private: + bool zeroLen = true; + SerialBufferAdapter value; }; -} +} // namespace cfdp #endif /* FSFW_SRC_FSFW_CFDP_LV_H_ */ diff --git a/src/fsfw/cfdp/tlv/MessageToUserTlv.cpp b/src/fsfw/cfdp/tlv/MessageToUserTlv.cpp index f776f5ef..9034552b 100644 --- a/src/fsfw/cfdp/tlv/MessageToUserTlv.cpp +++ b/src/fsfw/cfdp/tlv/MessageToUserTlv.cpp @@ -1,8 +1,6 @@ #include "MessageToUserTlv.h" -MessageToUserTlv::MessageToUserTlv(uint8_t *value, size_t size): - Tlv(cfdp::TlvTypes::MSG_TO_USER, value, size) { -} +MessageToUserTlv::MessageToUserTlv(uint8_t *value, size_t size) + : Tlv(cfdp::TlvTypes::MSG_TO_USER, value, size) {} -MessageToUserTlv::MessageToUserTlv(): Tlv() { -} +MessageToUserTlv::MessageToUserTlv() : Tlv() {} diff --git a/src/fsfw/cfdp/tlv/MessageToUserTlv.h b/src/fsfw/cfdp/tlv/MessageToUserTlv.h index 7bbe3a40..1d00bf31 100644 --- a/src/fsfw/cfdp/tlv/MessageToUserTlv.h +++ b/src/fsfw/cfdp/tlv/MessageToUserTlv.h @@ -3,11 +3,12 @@ #include "Tlv.h" -class MessageToUserTlv: public cfdp::Tlv { -public: - MessageToUserTlv(); - MessageToUserTlv(uint8_t* value, size_t size); -private: +class MessageToUserTlv : public cfdp::Tlv { + public: + MessageToUserTlv(); + MessageToUserTlv(uint8_t* value, size_t size); + + private: }; #endif /* FSFW_SRC_FSFW_CFDP_TLV_MESSAGETOUSERTLV_H_ */ diff --git a/src/fsfw/cfdp/tlv/Tlv.cpp b/src/fsfw/cfdp/tlv/Tlv.cpp index 71aa512d..f37ff8d5 100644 --- a/src/fsfw/cfdp/tlv/Tlv.cpp +++ b/src/fsfw/cfdp/tlv/Tlv.cpp @@ -1,114 +1,104 @@ #include "Tlv.h" -cfdp::Tlv::Tlv(TlvTypes type, const uint8_t *value, size_t size): type(type), - value(value, size, true) { - if(size > 0) { - zeroLen = false; - } +cfdp::Tlv::Tlv(TlvTypes type, const uint8_t *value, size_t size) + : type(type), value(value, size, true) { + if (size > 0) { + zeroLen = false; + } } -cfdp::Tlv::Tlv(): value(static_cast(nullptr), 0, true) { -} +cfdp::Tlv::Tlv() : value(static_cast(nullptr), 0, true) {} ReturnValue_t cfdp::Tlv::serialize(uint8_t **buffer, size_t *size, size_t maxSize, - Endianness streamEndianness) const { - if(buffer == nullptr or size == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - if(*size + 2 > maxSize) { - return BUFFER_TOO_SHORT; - } - if(type == TlvTypes::INVALID_TLV) { - return INVALID_TLV_TYPE; - } - **buffer = type; + Endianness streamEndianness) const { + if (buffer == nullptr or size == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if (*size + 2 > maxSize) { + return BUFFER_TOO_SHORT; + } + if (type == TlvTypes::INVALID_TLV) { + return INVALID_TLV_TYPE; + } + **buffer = type; + *size += 1; + *buffer += 1; + + if (zeroLen) { + **buffer = 0; *size += 1; *buffer += 1; - - if(zeroLen) { - **buffer = 0; - *size += 1; - *buffer += 1; - return HasReturnvaluesIF::RETURN_OK; - } - if(value.getConstBuffer() == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - return value.serialize(buffer, size, maxSize, streamEndianness); + return HasReturnvaluesIF::RETURN_OK; + } + if (value.getConstBuffer() == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + return value.serialize(buffer, size, maxSize, streamEndianness); } size_t cfdp::Tlv::getSerializedSize() const { - if(zeroLen) { - return 2; - } - else if (value.getConstBuffer() == nullptr) { - return 0; - } - return value.getSerializedSize() + 1; + if (zeroLen) { + return 2; + } else if (value.getConstBuffer() == nullptr) { + return 0; + } + return value.getSerializedSize() + 1; } ReturnValue_t cfdp::Tlv::deSerialize(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) { - if(buffer == nullptr or size == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - if(*size < 2) { - return STREAM_TOO_SHORT; - } + Endianness streamEndianness) { + if (buffer == nullptr or size == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if (*size < 2) { + return STREAM_TOO_SHORT; + } - uint8_t rawType = **buffer; - if(not checkType(rawType)) { - return INVALID_TLV_TYPE; - } + uint8_t rawType = **buffer; + if (not checkType(rawType)) { + return INVALID_TLV_TYPE; + } - type = static_cast(rawType); + type = static_cast(rawType); + *buffer += 1; + *size -= 1; + + size_t lengthField = **buffer; + if (lengthField == 0) { + zeroLen = true; *buffer += 1; *size -= 1; - - size_t lengthField = **buffer; - if(lengthField == 0) { - zeroLen = true; - *buffer += 1; - *size -= 1; - return HasReturnvaluesIF::RETURN_OK; - } - if(lengthField + 1 > *size) { - return SerializeIF::STREAM_TOO_SHORT; - } - zeroLen = false; - // Zero-copy implementation - value.setBuffer(const_cast(*buffer + 1), lengthField); - *buffer += 1 + lengthField; - *size -= 1 + lengthField; return HasReturnvaluesIF::RETURN_OK; + } + if (lengthField + 1 > *size) { + return SerializeIF::STREAM_TOO_SHORT; + } + zeroLen = false; + // Zero-copy implementation + value.setBuffer(const_cast(*buffer + 1), lengthField); + *buffer += 1 + lengthField; + *size -= 1 + lengthField; + return HasReturnvaluesIF::RETURN_OK; } -const uint8_t* cfdp::Tlv::getValue() const { - return value.getConstBuffer(); -} +const uint8_t *cfdp::Tlv::getValue() const { return value.getConstBuffer(); } -cfdp::TlvTypes cfdp::Tlv::getType() const { - return type; -} +cfdp::TlvTypes cfdp::Tlv::getType() const { return type; } bool cfdp::Tlv::checkType(uint8_t rawType) { - if (rawType != 0x03 and rawType <= 6) { - return true; - } - return false; + if (rawType != 0x03 and rawType <= 6) { + return true; + } + return false; } void cfdp::Tlv::setValue(uint8_t *value, size_t len) { - if(len > 0) { - zeroLen = false; - } - this->value.setBuffer(value, len); + if (len > 0) { + zeroLen = false; + } + this->value.setBuffer(value, len); } -uint8_t cfdp::Tlv::getLengthField() const { - return this->value.getSerializedSize() - 1; -} +uint8_t cfdp::Tlv::getLengthField() const { return this->value.getSerializedSize() - 1; } -void cfdp::Tlv::setType(TlvTypes type) { - this->type = type; -} +void cfdp::Tlv::setType(TlvTypes type) { this->type = type; } diff --git a/src/fsfw/cfdp/tlv/Tlv.h b/src/fsfw/cfdp/tlv/Tlv.h index 65c6ca09..a67c6dd1 100644 --- a/src/fsfw/cfdp/tlv/Tlv.h +++ b/src/fsfw/cfdp/tlv/Tlv.h @@ -11,54 +11,54 @@ namespace cfdp { * @details * Thin abstraction layer around a serial buffer adapter */ -class Tlv: public TlvIF { -public: - Tlv(TlvTypes type, const uint8_t *value, size_t size); - Tlv(); +class Tlv : public TlvIF { + public: + Tlv(TlvTypes type, const uint8_t *value, size_t size); + Tlv(); - /** - * Serialize a TLV into a given buffer - * @param buffer - * @param size - * @param maxSize - * @param streamEndianness - * @return - * - RETURN_OK on success - * - INVALID_TLV_TYPE - * - SerializeIF returncode on wrong serialization parameters - */ - virtual ReturnValue_t serialize(uint8_t **buffer, size_t *size, - size_t maxSize, Endianness streamEndianness) const override; + /** + * Serialize a TLV into a given buffer + * @param buffer + * @param size + * @param maxSize + * @param streamEndianness + * @return + * - RETURN_OK on success + * - INVALID_TLV_TYPE + * - SerializeIF returncode on wrong serialization parameters + */ + virtual ReturnValue_t serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const override; - virtual size_t getSerializedSize() const override; + virtual size_t getSerializedSize() const override; - /** - * @brief Deserialize a LV field from a raw buffer. Zero-copy implementation - * @param buffer Raw buffer including the size field - * @param size - * @param streamEndianness - * - RETURN_OK on success - * - INVALID_TLV_TYPE - * - SerializeIF returncode on wrong deserialization parameters - */ - virtual ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) override; + /** + * @brief Deserialize a LV field from a raw buffer. Zero-copy implementation + * @param buffer Raw buffer including the size field + * @param size + * @param streamEndianness + * - RETURN_OK on success + * - INVALID_TLV_TYPE + * - SerializeIF returncode on wrong deserialization parameters + */ + virtual ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) override; + void setValue(uint8_t *value, size_t len); - void setValue(uint8_t *value, size_t len); + const uint8_t *getValue() const; + void setType(TlvTypes type); + TlvTypes getType() const override; + uint8_t getLengthField() const override; - const uint8_t* getValue() const; - void setType(TlvTypes type); - TlvTypes getType() const override; - uint8_t getLengthField() const override; -private: - bool checkType(uint8_t rawType); + private: + bool checkType(uint8_t rawType); - bool zeroLen = true; - TlvTypes type = TlvTypes::INVALID_TLV; - SerialBufferAdapter value; + bool zeroLen = true; + TlvTypes type = TlvTypes::INVALID_TLV; + SerialBufferAdapter value; }; -} +} // namespace cfdp #endif /* FSFW_SRC_FSFW_CFDP_TLV_H_ */ diff --git a/src/fsfw/cfdp/tlv/TlvIF.h b/src/fsfw/cfdp/tlv/TlvIF.h index 885e7814..9a02b241 100644 --- a/src/fsfw/cfdp/tlv/TlvIF.h +++ b/src/fsfw/cfdp/tlv/TlvIF.h @@ -3,14 +3,12 @@ #include "../definitions.h" -class TlvIF: public SerializeIF { -public: - virtual~ TlvIF() {}; +class TlvIF : public SerializeIF { + public: + virtual ~TlvIF(){}; - virtual uint8_t getLengthField() const = 0; - virtual cfdp::TlvTypes getType() const = 0; + virtual uint8_t getLengthField() const = 0; + virtual cfdp::TlvTypes getType() const = 0; }; - - #endif /* FSFW_SRC_FSFW_CFDP_TLVIF_H_ */ diff --git a/src/fsfw/container/ArrayList.h b/src/fsfw/container/ArrayList.h index 25e281a2..11f40039 100644 --- a/src/fsfw/container/ArrayList.h +++ b/src/fsfw/container/ArrayList.h @@ -13,241 +13,210 @@ * * @ingroup container */ -template +template class ArrayList { - template friend class SerialArrayListAdapter; -public: - static const uint8_t INTERFACE_ID = CLASS_ID::ARRAY_LIST; - static const ReturnValue_t FULL = MAKE_RETURN_CODE(0x01); + template + friend class SerialArrayListAdapter; - /** - * This is the allocating constructor. - * It allocates an array of the specified size. - * @param maxSize - */ - ArrayList(count_t maxSize) : - size(0), maxSize_(maxSize), allocated(true) { - entries = new T[maxSize]; + public: + static const uint8_t INTERFACE_ID = CLASS_ID::ARRAY_LIST; + static const ReturnValue_t FULL = MAKE_RETURN_CODE(0x01); + + /** + * This is the allocating constructor. + * It allocates an array of the specified size. + * @param maxSize + */ + ArrayList(count_t maxSize) : size(0), maxSize_(maxSize), allocated(true) { + entries = new T[maxSize]; + } + + /** + * This is the non-allocating constructor + * + * It expects a pointer to an array of a certain size and initializes + * itself to it. + * + * @param storage the array to use as backend + * @param maxSize size of storage + * @param size size of data already present in storage + */ + ArrayList(T* storage, count_t maxSize, count_t size = 0) + : size(size), entries(storage), maxSize_(maxSize), allocated(false) {} + + /** + * Copying is forbiden by declaring copy ctor and copy assignment deleted + * It is too ambigous in this case. + * (Allocate a new backend? Use the same? What to do in an modifying call?) + */ + ArrayList(const ArrayList& other) = delete; + const ArrayList& operator=(const ArrayList& other) = delete; + + /** + * Number of Elements stored in this List + */ + count_t size; + + /** + * Destructor, if the allocating constructor was used, it deletes the array. + */ + virtual ~ArrayList() { + if (allocated) { + delete[] entries; } + } + + /** + * An Iterator to go trough an ArrayList + * + * It stores a pointer to an element and increments the + * pointer when incremented itself. + */ + class Iterator { + public: + /** + * Empty ctor, points to NULL + */ + Iterator() : value(0) {} /** - * This is the non-allocating constructor + * Initializes the Iterator to point to an element * - * It expects a pointer to an array of a certain size and initializes - * itself to it. - * - * @param storage the array to use as backend - * @param maxSize size of storage - * @param size size of data already present in storage + * @param initialize */ - ArrayList(T *storage, count_t maxSize, count_t size = 0) : - size(size), entries(storage), maxSize_(maxSize), allocated(false) { - } + Iterator(T* initialize) { value = initialize; } /** - * Copying is forbiden by declaring copy ctor and copy assignment deleted - * It is too ambigous in this case. - * (Allocate a new backend? Use the same? What to do in an modifying call?) + * The current element the iterator points to */ - ArrayList(const ArrayList& other) = delete; - const ArrayList& operator=(const ArrayList& other) = delete; + T* value; - /** - * Number of Elements stored in this List - */ - count_t size; - - - /** - * Destructor, if the allocating constructor was used, it deletes the array. - */ - virtual ~ArrayList() { - if (allocated) { - delete[] entries; - } + Iterator& operator++() { + value++; + return *this; } - /** - * An Iterator to go trough an ArrayList - * - * It stores a pointer to an element and increments the - * pointer when incremented itself. - */ - class Iterator { - public: - /** - * Empty ctor, points to NULL - */ - Iterator(): value(0) {} - - /** - * Initializes the Iterator to point to an element - * - * @param initialize - */ - Iterator(T *initialize) { - value = initialize; - } - - /** - * The current element the iterator points to - */ - T *value; - - Iterator& operator++() { - value++; - return *this; - } - - Iterator operator++(int) { - Iterator tmp(*this); - operator++(); - return tmp; - } - - Iterator& operator--() { - value--; - return *this; - } - - Iterator operator--(int) { - Iterator tmp(*this); - operator--(); - return tmp; - } - - T& operator*() { - return *value; - } - - const T& operator*() const { - return *value; - } - - T *operator->() { - return value; - } - - const T *operator->() const { - return value; - } - }; - - friend bool operator==(const ArrayList::Iterator& lhs, - const ArrayList::Iterator& rhs) { - return (lhs.value == rhs.value); + Iterator operator++(int) { + Iterator tmp(*this); + operator++(); + return tmp; } - friend bool operator!=(const ArrayList::Iterator& lhs, - const ArrayList::Iterator& rhs) { - return not (lhs.value == rhs.value); + Iterator& operator--() { + value--; + return *this; } - /** - * Iterator pointing to the first stored elmement - * - * @return Iterator to the first element - */ - Iterator begin() const { - return Iterator(&entries[0]); + Iterator operator--(int) { + Iterator tmp(*this); + operator--(); + return tmp; } - /** - * returns an Iterator pointing to the element after the last stored entry - * - * @return Iterator to the element after the last entry - */ - Iterator end() const { - return Iterator(&entries[size]); + T& operator*() { return *value; } + + const T& operator*() const { return *value; } + + T* operator->() { return value; } + + const T* operator->() const { return value; } + }; + + friend bool operator==(const ArrayList::Iterator& lhs, const ArrayList::Iterator& rhs) { + return (lhs.value == rhs.value); + } + + friend bool operator!=(const ArrayList::Iterator& lhs, const ArrayList::Iterator& rhs) { + return not(lhs.value == rhs.value); + } + + /** + * Iterator pointing to the first stored elmement + * + * @return Iterator to the first element + */ + Iterator begin() const { return Iterator(&entries[0]); } + + /** + * returns an Iterator pointing to the element after the last stored entry + * + * @return Iterator to the element after the last entry + */ + Iterator end() const { return Iterator(&entries[size]); } + + T& operator[](count_t i) const { return entries[i]; } + + /** + * The first element + * + * @return pointer to the first stored element + */ + T* front() { return entries; } + + /** + * The last element + * + * does not return a valid pointer if called on an empty list. + * + * @return pointer to the last stored element + */ + T* back() { + return &entries[size - 1]; + // Alternative solution + // return const_cast(static_cast(*this).back()); + } + + const T* back() const { return &entries[size - 1]; } + + /** + * The maximum number of elements this List can contain + * + * @return maximum number of elements + */ + size_t maxSize() const { return this->maxSize_; } + + /** + * Insert a new element into the list. + * + * The new element is inserted after the last stored element. + * + * @param entry + * @return + * -@c FULL if the List is full + * -@c RETURN_OK else + */ + ReturnValue_t insert(T entry) { + if (size >= maxSize_) { + return FULL; } + entries[size] = entry; + ++size; + return HasReturnvaluesIF::RETURN_OK; + } - T & operator[](count_t i) const { - return entries[i]; - } + /** + * clear the List + * + * This does not actually clear all entries, it only sets the size to 0. + */ + void clear() { size = 0; } - /** - * The first element - * - * @return pointer to the first stored element - */ - T *front() { - return entries; - } + count_t remaining() { return (maxSize_ - size); } - /** - * The last element - * - * does not return a valid pointer if called on an empty list. - * - * @return pointer to the last stored element - */ - T *back() { - return &entries[size - 1]; - //Alternative solution - //return const_cast(static_cast(*this).back()); - } + protected: + /** + * pointer to the array in which the entries are stored + */ + T* entries; + /** + * remembering the maximum size + */ + size_t maxSize_; - const T* back() const{ - return &entries[size-1]; - } - - /** - * The maximum number of elements this List can contain - * - * @return maximum number of elements - */ - size_t maxSize() const { - return this->maxSize_; - } - - /** - * Insert a new element into the list. - * - * The new element is inserted after the last stored element. - * - * @param entry - * @return - * -@c FULL if the List is full - * -@c RETURN_OK else - */ - ReturnValue_t insert(T entry) { - if (size >= maxSize_) { - return FULL; - } - entries[size] = entry; - ++size; - return HasReturnvaluesIF::RETURN_OK; - } - - /** - * clear the List - * - * This does not actually clear all entries, it only sets the size to 0. - */ - void clear() { - size = 0; - } - - count_t remaining() { - return (maxSize_ - size); - } - -protected: - /** - * pointer to the array in which the entries are stored - */ - T *entries; - /** - * remembering the maximum size - */ - size_t maxSize_; - - /** - * true if the array was allocated and needs to be deleted in the destructor. - */ - bool allocated; + /** + * true if the array was allocated and needs to be deleted in the destructor. + */ + bool allocated; }; - - #endif /* FSFW_CONTAINER_ARRAYLIST_H_ */ diff --git a/src/fsfw/container/BinaryTree.h b/src/fsfw/container/BinaryTree.h index 6200cbb1..d36d9ff4 100644 --- a/src/fsfw/container/BinaryTree.h +++ b/src/fsfw/container/BinaryTree.h @@ -3,151 +3,125 @@ #include #include + #include -template +template class BinaryNode { -public: - BinaryNode(Tp* setValue) : - value(setValue), left(NULL), right(NULL), parent(NULL) { - } - Tp *value; - BinaryNode* left; - BinaryNode* right; - BinaryNode* parent; + public: + BinaryNode(Tp* setValue) : value(setValue), left(NULL), right(NULL), parent(NULL) {} + Tp* value; + BinaryNode* left; + BinaryNode* right; + BinaryNode* parent; }; -template +template class ExplicitNodeIterator { -public: - typedef ExplicitNodeIterator _Self; - typedef BinaryNode _Node; - typedef Tp value_type; - typedef Tp* pointer; - typedef Tp& reference; - ExplicitNodeIterator() : - element(NULL) { + public: + typedef ExplicitNodeIterator _Self; + typedef BinaryNode _Node; + typedef Tp value_type; + typedef Tp* pointer; + typedef Tp& reference; + ExplicitNodeIterator() : element(NULL) {} + ExplicitNodeIterator(_Node* node) : element(node) {} + BinaryNode* element; + _Self up() { return _Self(element->parent); } + _Self left() { + if (element != NULL) { + return _Self(element->left); + } else { + return _Self(NULL); } - ExplicitNodeIterator(_Node* node) : - element(node) { + } + _Self right() { + if (element != NULL) { + return _Self(element->right); + } else { + return _Self(NULL); } - BinaryNode* element; - _Self up() { - return _Self(element->parent); - } - _Self left() { - if (element != NULL) { - return _Self(element->left); - } else { - return _Self(NULL); - } - - } - _Self right() { - if (element != NULL) { - return _Self(element->right); - } else { - return _Self(NULL); - } - - } - bool operator==(const _Self& __x) const { - return element == __x.element; - } - bool operator!=(const _Self& __x) const { - return element != __x.element; - } - pointer - operator->() const { - if (element != NULL) { - return element->value; - } else { - return NULL; - } - } - pointer operator*() const { - return this->operator->(); + } + bool operator==(const _Self& __x) const { return element == __x.element; } + bool operator!=(const _Self& __x) const { return element != __x.element; } + pointer operator->() const { + if (element != NULL) { + return element->value; + } else { + return NULL; } + } + pointer operator*() const { return this->operator->(); } }; /** * Pretty rudimentary version of a simple binary tree (not a binary search tree!). */ -template +template class BinaryTree { -public: - typedef ExplicitNodeIterator iterator; - typedef BinaryNode Node; - typedef std::pair children; - BinaryTree() : - rootNode(NULL) { + public: + typedef ExplicitNodeIterator iterator; + typedef BinaryNode Node; + typedef std::pair children; + BinaryTree() : rootNode(NULL) {} + BinaryTree(Node* rootNode) : rootNode(rootNode) {} + iterator begin() const { return iterator(rootNode); } + static iterator end() { return iterator(NULL); } + iterator insert(bool insertLeft, iterator parentNode, Node* newNode) { + newNode->parent = parentNode.element; + if (parentNode.element != NULL) { + if (insertLeft) { + parentNode.element->left = newNode; + } else { + parentNode.element->right = newNode; + } + } else { + // Insert first element. + rootNode = newNode; } - BinaryTree(Node* rootNode) : - rootNode(rootNode) { + return iterator(newNode); + } + // No recursion to children. Needs to be done externally. + children erase(iterator node) { + if (node.element == rootNode) { + // We're root node + rootNode = NULL; + } else { + // Delete parent's reference + if (node.up().left() == node) { + node.up().element->left = NULL; + } else { + node.up().element->right = NULL; + } } - iterator begin() const { - return iterator(rootNode); + return children(node.element->left, node.element->right); + } + static uint32_t countLeft(iterator start) { + if (start == end()) { + return 0; } - static iterator end() { - return iterator(NULL); + // We also count the start node itself. + uint32_t count = 1; + while (start.left() != end()) { + count++; + start = start.left(); } - iterator insert(bool insertLeft, iterator parentNode, Node* newNode ) { - newNode->parent = parentNode.element; - if (parentNode.element != NULL) { - if (insertLeft) { - parentNode.element->left = newNode; - } else { - parentNode.element->right = newNode; - } - } else { - //Insert first element. - rootNode = newNode; - } - return iterator(newNode); + return count; + } + static uint32_t countRight(iterator start) { + if (start == end()) { + return 0; } - //No recursion to children. Needs to be done externally. - children erase(iterator node) { - if (node.element == rootNode) { - //We're root node - rootNode = NULL; - } else { - //Delete parent's reference - if (node.up().left() == node) { - node.up().element->left = NULL; - } else { - node.up().element->right = NULL; - } - } - return children(node.element->left, node.element->right); - } - static uint32_t countLeft(iterator start) { - if (start == end()) { - return 0; - } - //We also count the start node itself. - uint32_t count = 1; - while (start.left() != end()) { - count++; - start = start.left(); - } - return count; - } - static uint32_t countRight(iterator start) { - if (start == end()) { - return 0; - } - //We also count the start node itself. - uint32_t count = 1; - while (start.right() != end()) { - count++; - start = start.right(); - } - return count; + // We also count the start node itself. + uint32_t count = 1; + while (start.right() != end()) { + count++; + start = start.right(); } + return count; + } -protected: - Node* rootNode; + protected: + Node* rootNode; }; - - #endif /* FRAMEWORK_CONTAINER_BINARYTREE_H_ */ diff --git a/src/fsfw/container/DynamicFIFO.h b/src/fsfw/container/DynamicFIFO.h index e1bc3ef2..96f55938 100644 --- a/src/fsfw/container/DynamicFIFO.h +++ b/src/fsfw/container/DynamicFIFO.h @@ -1,9 +1,10 @@ #ifndef FSFW_CONTAINER_DYNAMICFIFO_H_ #define FSFW_CONTAINER_DYNAMICFIFO_H_ -#include "FIFOBase.h" #include +#include "FIFOBase.h" + /** * @brief Simple First-In-First-Out data structure. The maximum size * can be set in the constructor. @@ -14,42 +15,41 @@ * @tparam T Entry Type * @tparam capacity Maximum capacity */ -template -class DynamicFIFO: public FIFOBase { -public: - DynamicFIFO(size_t maxCapacity): FIFOBase(nullptr, maxCapacity), - fifoVector(maxCapacity) { - // trying to pass the pointer of the uninitialized vector - // to the FIFOBase constructor directly lead to a super evil bug. - // So we do it like this now. - this->setContainer(fifoVector.data()); - }; +template +class DynamicFIFO : public FIFOBase { + public: + DynamicFIFO(size_t maxCapacity) : FIFOBase(nullptr, maxCapacity), fifoVector(maxCapacity) { + // trying to pass the pointer of the uninitialized vector + // to the FIFOBase constructor directly lead to a super evil bug. + // So we do it like this now. + this->setContainer(fifoVector.data()); + }; - /** - * @brief Custom copy constructor which prevents setting the - * underlying pointer wrong. This function allocates memory! - * @details This is a very heavy operation so try to avoid this! - * - */ - DynamicFIFO(const DynamicFIFO& other): FIFOBase(other), - fifoVector(other.maxCapacity) { - this->fifoVector = other.fifoVector; - this->setContainer(fifoVector.data()); - } + /** + * @brief Custom copy constructor which prevents setting the + * underlying pointer wrong. This function allocates memory! + * @details This is a very heavy operation so try to avoid this! + * + */ + DynamicFIFO(const DynamicFIFO& other) : FIFOBase(other), fifoVector(other.maxCapacity) { + this->fifoVector = other.fifoVector; + this->setContainer(fifoVector.data()); + } - /** - * @brief Custom assignment operator - * @details This is a very heavy operation so try to avoid this! - * @param other DyamicFIFO to copy from - */ - DynamicFIFO& operator=(const DynamicFIFO& other){ - FIFOBase::operator=(other); - this->fifoVector = other.fifoVector; - this->setContainer(fifoVector.data()); - return *this; - } -private: - std::vector fifoVector; + /** + * @brief Custom assignment operator + * @details This is a very heavy operation so try to avoid this! + * @param other DyamicFIFO to copy from + */ + DynamicFIFO& operator=(const DynamicFIFO& other) { + FIFOBase::operator=(other); + this->fifoVector = other.fifoVector; + this->setContainer(fifoVector.data()); + return *this; + } + + private: + std::vector fifoVector; }; #endif /* FSFW_CONTAINER_DYNAMICFIFO_H_ */ diff --git a/src/fsfw/container/FIFO.h b/src/fsfw/container/FIFO.h index 79ead313..6439fecc 100644 --- a/src/fsfw/container/FIFO.h +++ b/src/fsfw/container/FIFO.h @@ -1,9 +1,10 @@ #ifndef FSFW_CONTAINER_FIFO_H_ #define FSFW_CONTAINER_FIFO_H_ -#include "FIFOBase.h" #include +#include "FIFOBase.h" + /** * @brief Simple First-In-First-Out data structure with size fixed at * compile time @@ -13,35 +14,33 @@ * @tparam T Entry Type * @tparam capacity Maximum capacity */ -template -class FIFO: public FIFOBase { -public: - FIFO(): FIFOBase(nullptr, capacity) { - this->setContainer(fifoArray.data()); - }; +template +class FIFO : public FIFOBase { + public: + FIFO() : FIFOBase(nullptr, capacity) { this->setContainer(fifoArray.data()); }; - /** - * @brief Custom copy constructor to set pointer correctly. - * @param other - */ - FIFO(const FIFO& other): FIFOBase(other) { - this->fifoArray = other.fifoArray; - this->setContainer(fifoArray.data()); - } + /** + * @brief Custom copy constructor to set pointer correctly. + * @param other + */ + FIFO(const FIFO& other) : FIFOBase(other) { + this->fifoArray = other.fifoArray; + this->setContainer(fifoArray.data()); + } - /** - * @brief Custom assignment operator - * @param other - */ - FIFO& operator=(const FIFO& other){ - FIFOBase::operator=(other); - this->fifoArray = other.fifoArray; - this->setContainer(fifoArray.data()); - return *this; - } + /** + * @brief Custom assignment operator + * @param other + */ + FIFO& operator=(const FIFO& other) { + FIFOBase::operator=(other); + this->fifoArray = other.fifoArray; + this->setContainer(fifoArray.data()); + return *this; + } -private: - std::array fifoArray; + private: + std::array fifoArray; }; #endif /* FSFW_CONTAINER_FIFO_H_ */ diff --git a/src/fsfw/container/FIFOBase.h b/src/fsfw/container/FIFOBase.h index eaa80346..25c75515 100644 --- a/src/fsfw/container/FIFOBase.h +++ b/src/fsfw/container/FIFOBase.h @@ -1,77 +1,78 @@ #ifndef FSFW_CONTAINER_FIFOBASE_H_ #define FSFW_CONTAINER_FIFOBASE_H_ -#include "../returnvalues/HasReturnvaluesIF.h" #include #include +#include "../returnvalues/HasReturnvaluesIF.h" + template class FIFOBase { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::FIFO_CLASS; - static const ReturnValue_t FULL = MAKE_RETURN_CODE(1); - static const ReturnValue_t EMPTY = MAKE_RETURN_CODE(2); + public: + static const uint8_t INTERFACE_ID = CLASS_ID::FIFO_CLASS; + static const ReturnValue_t FULL = MAKE_RETURN_CODE(1); + static const ReturnValue_t EMPTY = MAKE_RETURN_CODE(2); - /** Default ctor, takes pointer to first entry of underlying container - * and maximum capacity */ - FIFOBase(T* values, const size_t maxCapacity); + /** Default ctor, takes pointer to first entry of underlying container + * and maximum capacity */ + FIFOBase(T* values, const size_t maxCapacity); - /** - * Insert value into FIFO - * @param value - * @return RETURN_OK on success, FULL if full - */ - ReturnValue_t insert(T value); - /** - * Retrieve item from FIFO. This removes the item from the FIFO. - * @param value Must point to a valid T - * @return RETURN_OK on success, EMPTY if empty and FAILED if nullptr check failed - */ - ReturnValue_t retrieve(T *value); - /** - * Retrieve item from FIFO without removing it from FIFO. - * @param value Must point to a valid T - * @return RETURN_OK on success, EMPTY if empty and FAILED if nullptr check failed - */ - ReturnValue_t peek(T * value); - /** - * Remove item from FIFO. - * @return RETURN_OK on success, EMPTY if empty - */ - ReturnValue_t pop(); + /** + * Insert value into FIFO + * @param value + * @return RETURN_OK on success, FULL if full + */ + ReturnValue_t insert(T value); + /** + * Retrieve item from FIFO. This removes the item from the FIFO. + * @param value Must point to a valid T + * @return RETURN_OK on success, EMPTY if empty and FAILED if nullptr check failed + */ + ReturnValue_t retrieve(T* value); + /** + * Retrieve item from FIFO without removing it from FIFO. + * @param value Must point to a valid T + * @return RETURN_OK on success, EMPTY if empty and FAILED if nullptr check failed + */ + ReturnValue_t peek(T* value); + /** + * Remove item from FIFO. + * @return RETURN_OK on success, EMPTY if empty + */ + ReturnValue_t pop(); - /*** - * Check if FIFO is empty - * @return True if empty, False if not - */ - bool empty(); - /*** - * Check if FIFO is Full - * @return True if full, False if not - */ - bool full(); - /*** - * Current used size (elements) used - * @return size_t in elements - */ - size_t size(); - /*** - * Get maximal capacity of fifo - * @return size_t with max capacity of this fifo - */ - size_t getMaxCapacity() const; + /*** + * Check if FIFO is empty + * @return True if empty, False if not + */ + bool empty(); + /*** + * Check if FIFO is Full + * @return True if full, False if not + */ + bool full(); + /*** + * Current used size (elements) used + * @return size_t in elements + */ + size_t size(); + /*** + * Get maximal capacity of fifo + * @return size_t with max capacity of this fifo + */ + size_t getMaxCapacity() const; -protected: - void setContainer(T* data); - size_t maxCapacity = 0; + protected: + void setContainer(T* data); + size_t maxCapacity = 0; - T* values; + T* values; - size_t readIndex = 0; - size_t writeIndex = 0; - size_t currentSize = 0; + size_t readIndex = 0; + size_t writeIndex = 0; + size_t currentSize = 0; - size_t next(size_t current); + size_t next(size_t current); }; #include "FIFOBase.tpp" diff --git a/src/fsfw/container/FixedArrayList.h b/src/fsfw/container/FixedArrayList.h index 7af636b6..c09a421e 100644 --- a/src/fsfw/container/FixedArrayList.h +++ b/src/fsfw/container/FixedArrayList.h @@ -1,40 +1,38 @@ #ifndef FIXEDARRAYLIST_H_ #define FIXEDARRAYLIST_H_ -#include "ArrayList.h" #include + +#include "ArrayList.h" /** * \ingroup container */ -template -class FixedArrayList: public ArrayList { +template +class FixedArrayList : public ArrayList { #if !defined(_MSC_VER) - static_assert(MAX_SIZE <= (std::pow(2,sizeof(count_t)*8)-1), "count_t is not large enough to hold MAX_SIZE"); + static_assert(MAX_SIZE <= (std::pow(2, sizeof(count_t) * 8) - 1), + "count_t is not large enough to hold MAX_SIZE"); #endif -private: - T data[MAX_SIZE]; -public: - FixedArrayList() : - ArrayList(data, MAX_SIZE) { - } + private: + T data[MAX_SIZE]; - FixedArrayList(const FixedArrayList& other) : - ArrayList(data, MAX_SIZE) { - memcpy(this->data, other.data, sizeof(this->data)); - this->entries = data; - this->size = other.size; - } + public: + FixedArrayList() : ArrayList(data, MAX_SIZE) {} - FixedArrayList& operator=(FixedArrayList other) { - memcpy(this->data, other.data, sizeof(this->data)); - this->entries = data; - this->size = other.size; - return *this; - } + FixedArrayList(const FixedArrayList& other) : ArrayList(data, MAX_SIZE) { + memcpy(this->data, other.data, sizeof(this->data)); + this->entries = data; + this->size = other.size; + } - virtual ~FixedArrayList() { - } + FixedArrayList& operator=(FixedArrayList other) { + memcpy(this->data, other.data, sizeof(this->data)); + this->entries = data; + this->size = other.size; + return *this; + } + virtual ~FixedArrayList() {} }; #endif /* FIXEDARRAYLIST_H_ */ diff --git a/src/fsfw/container/FixedMap.h b/src/fsfw/container/FixedMap.h index bd8e0f83..48822cd5 100644 --- a/src/fsfw/container/FixedMap.h +++ b/src/fsfw/container/FixedMap.h @@ -1,10 +1,11 @@ #ifndef FSFW_CONTAINER_FIXEDMAP_H_ #define FSFW_CONTAINER_FIXEDMAP_H_ -#include "ArrayList.h" -#include "../returnvalues/HasReturnvaluesIF.h" -#include #include +#include + +#include "../returnvalues/HasReturnvaluesIF.h" +#include "ArrayList.h" /** * @brief Map implementation for maps with a pre-defined size. @@ -16,215 +17,191 @@ * @warning A User is not allowed to change the key, otherwise the map is corrupted. * @ingroup container */ -template -class FixedMap: public SerializeIF { - static_assert (std::is_trivially_copyable::value or - std::is_base_of::value, - "Types used in FixedMap must either be trivial copy-able or a " - "derived class from SerializeIF to be serialize-able"); -public: - static const uint8_t INTERFACE_ID = CLASS_ID::FIXED_MAP; - static const ReturnValue_t KEY_ALREADY_EXISTS = MAKE_RETURN_CODE(0x01); - static const ReturnValue_t MAP_FULL = MAKE_RETURN_CODE(0x02); - static const ReturnValue_t KEY_DOES_NOT_EXIST = MAKE_RETURN_CODE(0x03); +template +class FixedMap : public SerializeIF { + static_assert(std::is_trivially_copyable::value or std::is_base_of::value, + "Types used in FixedMap must either be trivial copy-able or a " + "derived class from SerializeIF to be serialize-able"); -private: - static const key_t EMPTY_SLOT = -1; - ArrayList, uint32_t> theMap; - uint32_t _size; + public: + static const uint8_t INTERFACE_ID = CLASS_ID::FIXED_MAP; + static const ReturnValue_t KEY_ALREADY_EXISTS = MAKE_RETURN_CODE(0x01); + static const ReturnValue_t MAP_FULL = MAKE_RETURN_CODE(0x02); + static const ReturnValue_t KEY_DOES_NOT_EXIST = MAKE_RETURN_CODE(0x03); - uint32_t findIndex(key_t key) const { - if (_size == 0) { - return 1; - } - uint32_t i = 0; - for (i = 0; i < _size; ++i) { - if (theMap[i].first == key) { - return i; - } - } + private: + static const key_t EMPTY_SLOT = -1; + ArrayList, uint32_t> theMap; + uint32_t _size; + + uint32_t findIndex(key_t key) const { + if (_size == 0) { + return 1; + } + uint32_t i = 0; + for (i = 0; i < _size; ++i) { + if (theMap[i].first == key) { return i; + } } -public: - FixedMap(uint32_t maxSize) : - theMap(maxSize), _size(0) { + return i; + } + + public: + FixedMap(uint32_t maxSize) : theMap(maxSize), _size(0) {} + + class Iterator : public ArrayList, uint32_t>::Iterator { + public: + Iterator() : ArrayList, uint32_t>::Iterator() {} + + Iterator(std::pair* pair) + : ArrayList, uint32_t>::Iterator(pair) {} + }; + + friend bool operator==(const typename FixedMap::Iterator& lhs, + const typename FixedMap::Iterator& rhs) { + return (lhs.value == rhs.value); + } + + friend bool operator!=(const typename FixedMap::Iterator& lhs, + const typename FixedMap::Iterator& rhs) { + return not(lhs.value == rhs.value); + } + + Iterator begin() const { return Iterator(&theMap[0]); } + + Iterator end() const { return Iterator(&theMap[_size]); } + + uint32_t size() const { return _size; } + + ReturnValue_t insert(key_t key, T value, Iterator* storedValue = nullptr) { + if (exists(key) == HasReturnvaluesIF::RETURN_OK) { + return KEY_ALREADY_EXISTS; + } + if (_size == theMap.maxSize()) { + return MAP_FULL; + } + theMap[_size].first = key; + theMap[_size].second = value; + if (storedValue != nullptr) { + *storedValue = Iterator(&theMap[_size]); + } + ++_size; + return HasReturnvaluesIF::RETURN_OK; + } + + ReturnValue_t insert(std::pair pair) { return insert(pair.first, pair.second); } + + ReturnValue_t exists(key_t key) const { + ReturnValue_t result = KEY_DOES_NOT_EXIST; + if (findIndex(key) < _size) { + result = HasReturnvaluesIF::RETURN_OK; + } + return result; + } + + ReturnValue_t erase(Iterator* iter) { + uint32_t i; + if ((i = findIndex((*iter).value->first)) >= _size) { + return KEY_DOES_NOT_EXIST; + } + theMap[i] = theMap[_size - 1]; + --_size; + --((*iter).value); + return HasReturnvaluesIF::RETURN_OK; + } + + ReturnValue_t erase(key_t key) { + uint32_t i; + if ((i = findIndex(key)) >= _size) { + return KEY_DOES_NOT_EXIST; + } + theMap[i] = theMap[_size - 1]; + --_size; + return HasReturnvaluesIF::RETURN_OK; + } + + T* findValue(key_t key) const { return &theMap[findIndex(key)].second; } + + Iterator find(key_t key) const { + ReturnValue_t result = exists(key); + if (result != HasReturnvaluesIF::RETURN_OK) { + return end(); + } + return Iterator(&theMap[findIndex(key)]); + } + + ReturnValue_t find(key_t key, T** value) const { + ReturnValue_t result = exists(key); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + *value = &theMap[findIndex(key)].second; + return HasReturnvaluesIF::RETURN_OK; + } + + bool empty() { + if (_size == 0) { + return true; + } else { + return false; + } + } + + bool full() { + if (_size >= theMap.maxSize()) { + return true; + } else { + return false; + } + } + + void clear() { _size = 0; } + + uint32_t maxSize() const { return theMap.maxSize(); } + + virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const { + ReturnValue_t result = + SerializeAdapter::serialize(&this->_size, buffer, size, maxSize, streamEndianness); + uint32_t i = 0; + while ((result == HasReturnvaluesIF::RETURN_OK) && (i < this->_size)) { + result = + SerializeAdapter::serialize(&theMap[i].first, buffer, size, maxSize, streamEndianness); + result = + SerializeAdapter::serialize(&theMap[i].second, buffer, size, maxSize, streamEndianness); + ++i; + } + return result; + } + + virtual size_t getSerializedSize() const { + uint32_t printSize = sizeof(_size); + uint32_t i = 0; + + for (i = 0; i < _size; ++i) { + printSize += SerializeAdapter::getSerializedSize(&theMap[i].first); + printSize += SerializeAdapter::getSerializedSize(&theMap[i].second); } - class Iterator: public ArrayList, uint32_t>::Iterator { - public: - Iterator() : - ArrayList, uint32_t>::Iterator() { - } + return printSize; + } - Iterator(std::pair *pair) : - ArrayList, uint32_t>::Iterator(pair) { - } - }; - - friend bool operator==(const typename FixedMap::Iterator& lhs, - const typename FixedMap::Iterator& rhs) { - return (lhs.value == rhs.value); + virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + Endianness streamEndianness) { + ReturnValue_t result = + SerializeAdapter::deSerialize(&this->_size, buffer, size, streamEndianness); + if (this->_size > theMap.maxSize()) { + return SerializeIF::TOO_MANY_ELEMENTS; } - - friend bool operator!=(const typename FixedMap::Iterator& lhs, - const typename FixedMap::Iterator& rhs) { - return not (lhs.value == rhs.value); + uint32_t i = 0; + while ((result == HasReturnvaluesIF::RETURN_OK) && (i < this->_size)) { + result = SerializeAdapter::deSerialize(&theMap[i].first, buffer, size, streamEndianness); + result = SerializeAdapter::deSerialize(&theMap[i].second, buffer, size, streamEndianness); + ++i; } - - Iterator begin() const { - return Iterator(&theMap[0]); - } - - Iterator end() const { - return Iterator(&theMap[_size]); - } - - uint32_t size() const { - return _size; - } - - ReturnValue_t insert(key_t key, T value, Iterator *storedValue = nullptr) { - if (exists(key) == HasReturnvaluesIF::RETURN_OK) { - return KEY_ALREADY_EXISTS; - } - if (_size == theMap.maxSize()) { - return MAP_FULL; - } - theMap[_size].first = key; - theMap[_size].second = value; - if (storedValue != nullptr) { - *storedValue = Iterator(&theMap[_size]); - } - ++_size; - return HasReturnvaluesIF::RETURN_OK; - } - - ReturnValue_t insert(std::pair pair) { - return insert(pair.first, pair.second); - } - - ReturnValue_t exists(key_t key) const { - ReturnValue_t result = KEY_DOES_NOT_EXIST; - if (findIndex(key) < _size) { - result = HasReturnvaluesIF::RETURN_OK; - } - return result; - } - - ReturnValue_t erase(Iterator *iter) { - uint32_t i; - if ((i = findIndex((*iter).value->first)) >= _size) { - return KEY_DOES_NOT_EXIST; - } - theMap[i] = theMap[_size - 1]; - --_size; - --((*iter).value); - return HasReturnvaluesIF::RETURN_OK; - } - - ReturnValue_t erase(key_t key) { - uint32_t i; - if ((i = findIndex(key)) >= _size) { - return KEY_DOES_NOT_EXIST; - } - theMap[i] = theMap[_size - 1]; - --_size; - return HasReturnvaluesIF::RETURN_OK; - } - - T *findValue(key_t key) const { - return &theMap[findIndex(key)].second; - } - - Iterator find(key_t key) const { - ReturnValue_t result = exists(key); - if (result != HasReturnvaluesIF::RETURN_OK) { - return end(); - } - return Iterator(&theMap[findIndex(key)]); - } - - ReturnValue_t find(key_t key, T **value) const { - ReturnValue_t result = exists(key); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - *value = &theMap[findIndex(key)].second; - return HasReturnvaluesIF::RETURN_OK; - } - - bool empty() { - if(_size == 0) { - return true; - } - else { - return false; - } - } - - bool full() { - if(_size >= theMap.maxSize()) { - return true; - } - else { - return false; - } - } - - void clear() { - _size = 0; - } - - uint32_t maxSize() const { - return theMap.maxSize(); - } - - virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const { - ReturnValue_t result = SerializeAdapter::serialize(&this->_size, - buffer, size, maxSize, streamEndianness); - uint32_t i = 0; - while ((result == HasReturnvaluesIF::RETURN_OK) && (i < this->_size)) { - result = SerializeAdapter::serialize(&theMap[i].first, buffer, - size, maxSize, streamEndianness); - result = SerializeAdapter::serialize(&theMap[i].second, buffer, size, - maxSize, streamEndianness); - ++i; - } - return result; - } - - virtual size_t getSerializedSize() const { - uint32_t printSize = sizeof(_size); - uint32_t i = 0; - - for (i = 0; i < _size; ++i) { - printSize += SerializeAdapter::getSerializedSize( - &theMap[i].first); - printSize += SerializeAdapter::getSerializedSize(&theMap[i].second); - } - - return printSize; - } - - virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) { - ReturnValue_t result = SerializeAdapter::deSerialize(&this->_size, - buffer, size, streamEndianness); - if (this->_size > theMap.maxSize()) { - return SerializeIF::TOO_MANY_ELEMENTS; - } - uint32_t i = 0; - while ((result == HasReturnvaluesIF::RETURN_OK) && (i < this->_size)) { - result = SerializeAdapter::deSerialize(&theMap[i].first, buffer, - size, streamEndianness); - result = SerializeAdapter::deSerialize(&theMap[i].second, buffer, size, - streamEndianness); - ++i; - } - return result; - } - + return result; + } }; #endif /* FSFW_CONTAINER_FIXEDMAP_H_ */ diff --git a/src/fsfw/container/FixedOrderedMultimap.h b/src/fsfw/container/FixedOrderedMultimap.h index cb8abdca..3ef8f8f1 100644 --- a/src/fsfw/container/FixedOrderedMultimap.h +++ b/src/fsfw/container/FixedOrderedMultimap.h @@ -1,10 +1,11 @@ #ifndef FSFW_CONTAINER_FIXEDORDEREDMULTIMAP_H_ #define FSFW_CONTAINER_FIXEDORDEREDMULTIMAP_H_ -#include "ArrayList.h" #include #include +#include "ArrayList.h" + /** * @brief An associative container which allows multiple entries of the same key. * @details @@ -31,175 +32,160 @@ * * \ingroup container */ -template> +template > class FixedOrderedMultimap { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::FIXED_MULTIMAP; - static const ReturnValue_t MAP_FULL = MAKE_RETURN_CODE(0x01); - static const ReturnValue_t KEY_DOES_NOT_EXIST = MAKE_RETURN_CODE(0x02); + public: + static const uint8_t INTERFACE_ID = CLASS_ID::FIXED_MULTIMAP; + static const ReturnValue_t MAP_FULL = MAKE_RETURN_CODE(0x01); + static const ReturnValue_t KEY_DOES_NOT_EXIST = MAKE_RETURN_CODE(0x02); - /*** - * Constructor which needs a size_t for the maximum allowed size - * - * Can not be resized during runtime - * - * Allocates memory at construction - * @param maxSize size_t of Maximum allowed size - */ - FixedOrderedMultimap(size_t maxSize):theMap(maxSize), _size(0){ + /*** + * Constructor which needs a size_t for the maximum allowed size + * + * Can not be resized during runtime + * + * Allocates memory at construction + * @param maxSize size_t of Maximum allowed size + */ + FixedOrderedMultimap(size_t maxSize) : theMap(maxSize), _size(0) {} + + /*** + * Virtual destructor frees Memory by deleting its member + */ + virtual ~FixedOrderedMultimap() {} + + /*** + * Special iterator for FixedOrderedMultimap + */ + class Iterator : public ArrayList, size_t>::Iterator { + public: + Iterator() : ArrayList, size_t>::Iterator() {} + + Iterator(std::pair* pair) : ArrayList, size_t>::Iterator(pair) {} + }; + + /*** + * Returns an iterator pointing to the first element + * @return Iterator pointing to first element + */ + Iterator begin() const { return Iterator(&theMap[0]); } + + /** + * Returns an iterator pointing to one element past the end + * @return Iterator pointing to one element past the end + */ + Iterator end() const { return Iterator(&theMap[_size]); } + + /*** + * Returns the current size of the map (not maximum size!) + * @return Current size + */ + size_t size() const { return _size; } + + /** + * Clears the map, does not deallocate any memory + */ + void clear() { _size = 0; } + + /** + * Returns the maximum size of the map + * @return Maximum size of the map + */ + size_t maxSize() const { return theMap.maxSize(); } + + /*** + * Used to insert a key and value separately. + * + * @param[in] key Key of the new element + * @param[in] value Value of the new element + * @param[in/out] (optional) storedValue On success this points to the new value, otherwise a + * nullptr + * @return RETURN_OK if insert was successful, MAP_FULL if no space is available + */ + ReturnValue_t insert(key_t key, T value, Iterator* storedValue = nullptr); + + /*** + * Used to insert new pair instead of single values + * + * @param pair Pair to be inserted + * @return RETURN_OK if insert was successful, MAP_FULL if no space is available + */ + ReturnValue_t insert(std::pair pair); + + /*** + * Can be used to check if a certain key is in the map + * @param key Key to be checked + * @return RETURN_OK if the key exists KEY_DOES_NOT_EXIST otherwise + */ + ReturnValue_t exists(key_t key) const; + + /*** + * Used to delete the element in the iterator + * + * The iterator will point to the element before or begin(), + * but never to one element in front of the map. + * + * @warning The iterator needs to be valid and dereferenceable + * @param[in/out] iter Pointer to iterator to the element that needs to be ereased + * @return RETURN_OK if erased, KEY_DOES_NOT_EXIST if the there is no element like this + */ + ReturnValue_t erase(Iterator* iter); + + /*** + * Used to erase by key + * @param key Key to be erased + * @return RETURN_OK if erased, KEY_DOES_NOT_EXIST if the there is no element like this + */ + ReturnValue_t erase(key_t key); + + /*** + * Find returns the first appearance of the key + * + * If the key does not exist, it points to end() + * + * @param key Key to search for + * @return Iterator pointing to the first entry of key + */ + Iterator find(key_t key) const { + ReturnValue_t result = exists(key); + if (result != HasReturnvaluesIF::RETURN_OK) { + return end(); } + return Iterator(&theMap[findFirstIndex(key)]); + }; - /*** - * Virtual destructor frees Memory by deleting its member - */ - virtual ~FixedOrderedMultimap() { - } + /*** + * Finds first entry of the given key and returns a + * pointer to the value + * + * @param key Key to search for + * @param value Found value + * @return RETURN_OK if it points to the value, + * KEY_DOES_NOT_EXIST if the key is not in the map + */ + ReturnValue_t find(key_t key, T** value) const; - /*** - * Special iterator for FixedOrderedMultimap - */ - class Iterator: public ArrayList, size_t>::Iterator { - public: - Iterator() : - ArrayList, size_t>::Iterator() { - } + friend bool operator==(const typename FixedOrderedMultimap::Iterator& lhs, + const typename FixedOrderedMultimap::Iterator& rhs) { + return (lhs.value == rhs.value); + } - Iterator(std::pair *pair) : - ArrayList, size_t>::Iterator(pair) { - } - }; + friend bool operator!=(const typename FixedOrderedMultimap::Iterator& lhs, + const typename FixedOrderedMultimap::Iterator& rhs) { + return not(lhs.value == rhs.value); + } - /*** - * Returns an iterator pointing to the first element - * @return Iterator pointing to first element - */ - Iterator begin() const { - return Iterator(&theMap[0]); - } + private: + typedef KEY_COMPARE compare; + compare myComp; + ArrayList, size_t> theMap; + size_t _size; - /** - * Returns an iterator pointing to one element past the end - * @return Iterator pointing to one element past the end - */ - Iterator end() const { - return Iterator(&theMap[_size]); - } + size_t findFirstIndex(key_t key, size_t startAt = 0) const; - /*** - * Returns the current size of the map (not maximum size!) - * @return Current size - */ - size_t size() const{ - return _size; - } + size_t findNicePlace(key_t key) const; - /** - * Clears the map, does not deallocate any memory - */ - void clear(){ - _size = 0; - } - - /** - * Returns the maximum size of the map - * @return Maximum size of the map - */ - size_t maxSize() const{ - return theMap.maxSize(); - } - - /*** - * Used to insert a key and value separately. - * - * @param[in] key Key of the new element - * @param[in] value Value of the new element - * @param[in/out] (optional) storedValue On success this points to the new value, otherwise a nullptr - * @return RETURN_OK if insert was successful, MAP_FULL if no space is available - */ - ReturnValue_t insert(key_t key, T value, Iterator *storedValue = nullptr); - - /*** - * Used to insert new pair instead of single values - * - * @param pair Pair to be inserted - * @return RETURN_OK if insert was successful, MAP_FULL if no space is available - */ - ReturnValue_t insert(std::pair pair); - - /*** - * Can be used to check if a certain key is in the map - * @param key Key to be checked - * @return RETURN_OK if the key exists KEY_DOES_NOT_EXIST otherwise - */ - ReturnValue_t exists(key_t key) const; - - /*** - * Used to delete the element in the iterator - * - * The iterator will point to the element before or begin(), - * but never to one element in front of the map. - * - * @warning The iterator needs to be valid and dereferenceable - * @param[in/out] iter Pointer to iterator to the element that needs to be ereased - * @return RETURN_OK if erased, KEY_DOES_NOT_EXIST if the there is no element like this - */ - ReturnValue_t erase(Iterator *iter); - - /*** - * Used to erase by key - * @param key Key to be erased - * @return RETURN_OK if erased, KEY_DOES_NOT_EXIST if the there is no element like this - */ - ReturnValue_t erase(key_t key); - - /*** - * Find returns the first appearance of the key - * - * If the key does not exist, it points to end() - * - * @param key Key to search for - * @return Iterator pointing to the first entry of key - */ - Iterator find(key_t key) const{ - ReturnValue_t result = exists(key); - if (result != HasReturnvaluesIF::RETURN_OK) { - return end(); - } - return Iterator(&theMap[findFirstIndex(key)]); - }; - - /*** - * Finds first entry of the given key and returns a - * pointer to the value - * - * @param key Key to search for - * @param value Found value - * @return RETURN_OK if it points to the value, - * KEY_DOES_NOT_EXIST if the key is not in the map - */ - ReturnValue_t find(key_t key, T **value) const; - - friend bool operator==(const typename FixedOrderedMultimap::Iterator& lhs, - const typename FixedOrderedMultimap::Iterator& rhs) { - return (lhs.value == rhs.value); - } - - friend bool operator!=(const typename FixedOrderedMultimap::Iterator& lhs, - const typename FixedOrderedMultimap::Iterator& rhs) { - return not (lhs.value == rhs.value); - } - -private: - typedef KEY_COMPARE compare; - compare myComp; - ArrayList, size_t> theMap; - size_t _size; - - size_t findFirstIndex(key_t key, size_t startAt = 0) const; - - size_t findNicePlace(key_t key) const; - - void removeFromPosition(size_t position); + void removeFromPosition(size_t position); }; #include "FixedOrderedMultimap.tpp" diff --git a/src/fsfw/container/HybridIterator.h b/src/fsfw/container/HybridIterator.h index 6e33e461..e8b24a3d 100644 --- a/src/fsfw/container/HybridIterator.h +++ b/src/fsfw/container/HybridIterator.h @@ -4,87 +4,73 @@ #include "ArrayList.h" #include "SinglyLinkedList.h" -template -class HybridIterator: public LinkedElement::Iterator, - public ArrayList::Iterator { -public: - HybridIterator() {} +template +class HybridIterator : public LinkedElement::Iterator, public ArrayList::Iterator { + public: + HybridIterator() {} - HybridIterator(typename LinkedElement::Iterator *iter) : - LinkedElement::Iterator(*iter), value(iter->value), - linked(true) { + HybridIterator(typename LinkedElement::Iterator *iter) + : LinkedElement::Iterator(*iter), value(iter->value), linked(true) {} + HybridIterator(LinkedElement *start) + : LinkedElement::Iterator(start), value(start->value), linked(true) {} + + HybridIterator(typename ArrayList::Iterator start, + typename ArrayList::Iterator end) + : ArrayList::Iterator(start), value(start.value), linked(false), end(end.value) { + if (value == this->end) { + value = NULL; } + } - HybridIterator(LinkedElement *start) : - LinkedElement::Iterator(start), value(start->value), - linked(true) { - + HybridIterator(T *firstElement, T *lastElement) + : ArrayList::Iterator(firstElement), + value(firstElement), + linked(false), + end(++lastElement) { + if (value == end) { + value = NULL; } + } - HybridIterator(typename ArrayList::Iterator start, - typename ArrayList::Iterator end) : - ArrayList::Iterator(start), value(start.value), - linked(false), end(end.value) { - if (value == this->end) { - value = NULL; - } + HybridIterator &operator++() { + if (linked) { + LinkedElement::Iterator::operator++(); + if (LinkedElement::Iterator::value != nullptr) { + value = LinkedElement::Iterator::value->value; + } else { + value = nullptr; + } + } else { + ArrayList::Iterator::operator++(); + value = ArrayList::Iterator::value; + + if (value == end) { + value = nullptr; + } } + return *this; + } - HybridIterator(T *firstElement, T *lastElement) : - ArrayList::Iterator(firstElement), value(firstElement), - linked(false), end(++lastElement) { - if (value == end) { - value = NULL; - } - } + HybridIterator operator++(int) { + HybridIterator tmp(*this); + operator++(); + return tmp; + } - HybridIterator& operator++() { - if (linked) { - LinkedElement::Iterator::operator++(); - if (LinkedElement::Iterator::value != nullptr) { - value = LinkedElement::Iterator::value->value; - } else { - value = nullptr; - } - } else { - ArrayList::Iterator::operator++(); - value = ArrayList::Iterator::value; + bool operator==(const HybridIterator &other) const { return value == other.value; } - if (value == end) { - value = nullptr; - } - } - return *this; - } + bool operator!=(const HybridIterator &other) const { return !(*this == other); } - HybridIterator operator++(int) { - HybridIterator tmp(*this); - operator++(); - return tmp; - } + T operator*() { return *value; } - bool operator==(const HybridIterator& other) const { - return value == other.value; - } + T *operator->() { return value; } - bool operator!=(const HybridIterator& other) const { - return !(*this == other); - } + T *value = nullptr; - T operator*() { - return *value; - } - - T *operator->() { - return value; - } - - T* value = nullptr; - -private: - bool linked = false; - T *end = nullptr; + private: + bool linked = false; + T *end = nullptr; }; #endif /* FRAMEWORK_CONTAINER_HYBRIDITERATOR_H_ */ diff --git a/src/fsfw/container/IndexedRingMemoryArray.h b/src/fsfw/container/IndexedRingMemoryArray.h index df8980f7..b76e7d56 100644 --- a/src/fsfw/container/IndexedRingMemoryArray.h +++ b/src/fsfw/container/IndexedRingMemoryArray.h @@ -1,700 +1,663 @@ #ifndef FRAMEWORK_CONTAINER_INDEXEDRINGMEMORY_H_ #define FRAMEWORK_CONTAINER_INDEXEDRINGMEMORY_H_ -#include "ArrayList.h" -#include "../globalfunctions/CRC.h" -#include "../serviceinterface/ServiceInterfaceStream.h" -#include "../returnvalues/HasReturnvaluesIF.h" -#include "../serialize/SerialArrayListAdapter.h" #include -template -class Index: public SerializeIF{ - /** - * Index is the Type used for the list of indices. The template parameter is the type which describes the index, it needs to be a child of SerializeIF to be able to make it persistent - */ - static_assert(std::is_base_of::value,"Wrong Type for Index, Type must implement SerializeIF"); -public: - Index():blockStartAddress(0),size(0),storedPackets(0){} +#include "../globalfunctions/CRC.h" +#include "../returnvalues/HasReturnvaluesIF.h" +#include "../serialize/SerialArrayListAdapter.h" +#include "../serviceinterface/ServiceInterfaceStream.h" +#include "ArrayList.h" - Index(uint32_t startAddress):blockStartAddress(startAddress),size(0),storedPackets(0){ +template +class Index : public SerializeIF { + /** + * Index is the Type used for the list of indices. The template parameter is the type which + * describes the index, it needs to be a child of SerializeIF to be able to make it persistent + */ + static_assert(std::is_base_of::value, + "Wrong Type for Index, Type must implement SerializeIF"); + public: + Index() : blockStartAddress(0), size(0), storedPackets(0) {} + + Index(uint32_t startAddress) : blockStartAddress(startAddress), size(0), storedPackets(0) {} + + void setBlockStartAddress(uint32_t newAddress) { this->blockStartAddress = newAddress; } + + uint32_t getBlockStartAddress() const { return blockStartAddress; } + + const T* getIndexType() const { return &indexType; } + + T* modifyIndexType() { return &indexType; } + /** + * Updates the index Type. Uses = operator + * @param indexType Type to copy from + */ + void setIndexType(T* indexType) { this->indexType = *indexType; } + + uint32_t getSize() const { return size; } + + void setSize(uint32_t size) { this->size = size; } + + void addSize(uint32_t size) { this->size += size; } + + void setStoredPackets(uint32_t newStoredPackets) { this->storedPackets = newStoredPackets; } + + void addStoredPackets(uint32_t packets) { this->storedPackets += packets; } + + uint32_t getStoredPackets() const { return this->storedPackets; } + + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const { + ReturnValue_t result = + SerializeAdapter::serialize(&blockStartAddress, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; } - - void setBlockStartAddress(uint32_t newAddress){ - this->blockStartAddress = newAddress; + result = indexType.serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; } - - uint32_t getBlockStartAddress() const { - return blockStartAddress; + result = SerializeAdapter::serialize(&this->size, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; } + result = + SerializeAdapter::serialize(&this->storedPackets, buffer, size, maxSize, streamEndianness); + return result; + } - const T* getIndexType() const { - return &indexType; + ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, Endianness streamEndianness) { + ReturnValue_t result = + SerializeAdapter::deSerialize(&blockStartAddress, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; } - - T* modifyIndexType(){ - return &indexType; + result = indexType.deSerialize(buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; } - /** - * Updates the index Type. Uses = operator - * @param indexType Type to copy from - */ - void setIndexType(T* indexType) { - this->indexType = *indexType; + result = SerializeAdapter::deSerialize(&this->size, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; } - - uint32_t getSize() const { - return size; + result = SerializeAdapter::deSerialize(&this->storedPackets, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; } + return result; + } - void setSize(uint32_t size) { - this->size = size; - } + size_t getSerializedSize() const { + uint32_t size = SerializeAdapter::getSerializedSize(&blockStartAddress); + size += indexType.getSerializedSize(); + size += SerializeAdapter::getSerializedSize(&this->size); + size += SerializeAdapter::getSerializedSize(&this->storedPackets); + return size; + } - void addSize(uint32_t size){ - this->size += size; - } + bool operator==(const Index& other) { + return ((blockStartAddress == other.getBlockStartAddress()) && (size == other.getSize())) && + (indexType == *(other.getIndexType())); + } - void setStoredPackets(uint32_t newStoredPackets){ - this->storedPackets = newStoredPackets; - } - - void addStoredPackets(uint32_t packets){ - this->storedPackets += packets; - } - - uint32_t getStoredPackets() const{ - return this->storedPackets; - } - - ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const { - ReturnValue_t result = SerializeAdapter::serialize(&blockStartAddress,buffer,size,maxSize,streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK){ - return result; - } - result = indexType.serialize(buffer,size,maxSize,streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK){ - return result; - } - result = SerializeAdapter::serialize(&this->size,buffer,size,maxSize,streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK){ - return result; - } - result = SerializeAdapter::serialize(&this->storedPackets,buffer,size,maxSize,streamEndianness); - return result; - } - - ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness){ - ReturnValue_t result = SerializeAdapter::deSerialize(&blockStartAddress,buffer,size,streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK){ - return result; - } - result = indexType.deSerialize(buffer,size,streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK){ - return result; - } - result = SerializeAdapter::deSerialize(&this->size,buffer,size,streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK){ - return result; - } - result = SerializeAdapter::deSerialize(&this->storedPackets,buffer,size,streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK){ - return result; - } - return result; - } - - size_t getSerializedSize() const { - uint32_t size = SerializeAdapter::getSerializedSize(&blockStartAddress); - size += indexType.getSerializedSize(); - size += SerializeAdapter::getSerializedSize(&this->size); - size += SerializeAdapter::getSerializedSize(&this->storedPackets); - return size; - } - - - bool operator==(const Index& other){ - return ((blockStartAddress == other.getBlockStartAddress()) && (size==other.getSize())) && (indexType == *(other.getIndexType())); - } - -private: - uint32_t blockStartAddress; - uint32_t size; - uint32_t storedPackets; - T indexType; + private: + uint32_t blockStartAddress; + uint32_t size; + uint32_t storedPackets; + T indexType; }; +template +class IndexedRingMemoryArray : public SerializeIF, public ArrayList, uint32_t> { + /** + * Indexed Ring Memory Array is a class for a ring memory with indices. It assumes that the newest + * data comes in last It uses the currentWriteBlock as pointer to the current writing position The + * currentReadBlock must be set manually + */ + public: + IndexedRingMemoryArray(uint32_t startAddress, uint32_t size, uint32_t bytesPerBlock, + SerializeIF* additionalInfo, bool overwriteOld) + : ArrayList, uint32_t>(NULL, (uint32_t)10, (uint32_t)0), + totalSize(size), + indexAddress(startAddress), + currentReadSize(0), + currentReadBlockSizeCached(0), + lastBlockToReadSize(0), + additionalInfo(additionalInfo), + overwriteOld(overwriteOld) { + // Calculate the maximum number of indices needed for this blocksize + uint32_t maxNrOfIndices = floor(static_cast(size) / static_cast(bytesPerBlock)); + // Calculate the Size needeed for the index itself + uint32_t serializedSize = 0; + if (additionalInfo != NULL) { + serializedSize += additionalInfo->getSerializedSize(); + } + // Size of current iterator type + Index tempIndex; + serializedSize += tempIndex.getSerializedSize(); -template -class IndexedRingMemoryArray: public SerializeIF, public ArrayList, uint32_t>{ - /** - * Indexed Ring Memory Array is a class for a ring memory with indices. It assumes that the newest data comes in last - * It uses the currentWriteBlock as pointer to the current writing position - * The currentReadBlock must be set manually - */ -public: - IndexedRingMemoryArray(uint32_t startAddress, uint32_t size, uint32_t bytesPerBlock, SerializeIF* additionalInfo, - bool overwriteOld) :ArrayList,uint32_t>(NULL,(uint32_t)10,(uint32_t)0),totalSize(size),indexAddress(startAddress),currentReadSize(0),currentReadBlockSizeCached(0),lastBlockToReadSize(0), additionalInfo(additionalInfo),overwriteOld(overwriteOld){ + // Add Size of Array + serializedSize += sizeof(uint32_t); // size of array + serializedSize += (tempIndex.getSerializedSize() * maxNrOfIndices); // size of elements + serializedSize += sizeof(uint16_t); // size of crc - //Calculate the maximum number of indices needed for this blocksize - uint32_t maxNrOfIndices = floor(static_cast(size)/static_cast(bytesPerBlock)); + // Calculate new size after index + if (serializedSize > totalSize) { + error << "IndexedRingMemory: Store is too small for index" << std::endl; + } + uint32_t useableSize = totalSize - serializedSize; + // Update the totalSize for calculations + totalSize = useableSize; - //Calculate the Size needeed for the index itself - uint32_t serializedSize = 0; - if(additionalInfo!=NULL){ - serializedSize += additionalInfo->getSerializedSize(); - } - //Size of current iterator type - Index tempIndex; - serializedSize += tempIndex.getSerializedSize(); + // True StartAddress + uint32_t trueStartAddress = indexAddress + serializedSize; - //Add Size of Array - serializedSize += sizeof(uint32_t); //size of array - serializedSize += (tempIndex.getSerializedSize() * maxNrOfIndices); //size of elements - serializedSize += sizeof(uint16_t); //size of crc + // Calculate True number of Blocks and reset size of true Number of Blocks + uint32_t trueNumberOfBlocks = + floor(static_cast(totalSize) / static_cast(bytesPerBlock)); - //Calculate new size after index - if(serializedSize > totalSize){ - error << "IndexedRingMemory: Store is too small for index" << std::endl; - } - uint32_t useableSize = totalSize - serializedSize; - //Update the totalSize for calculations - totalSize = useableSize; + // allocate memory now + this->entries = new Index[trueNumberOfBlocks]; + this->size = trueNumberOfBlocks; + this->maxSize_ = trueNumberOfBlocks; + this->allocated = true; - //True StartAddress - uint32_t trueStartAddress = indexAddress + serializedSize; - - //Calculate True number of Blocks and reset size of true Number of Blocks - uint32_t trueNumberOfBlocks = floor(static_cast(totalSize) / static_cast(bytesPerBlock)); - - //allocate memory now - this->entries = new Index[trueNumberOfBlocks]; - this->size = trueNumberOfBlocks; - this->maxSize_ = trueNumberOfBlocks; - this->allocated = true; - - //Check trueNumberOfBlocks - if(trueNumberOfBlocks<1){ - error << "IndexedRingMemory: Invalid Number of Blocks: " << trueNumberOfBlocks; - } - - - - //Fill address into index - uint32_t address = trueStartAddress; - for (typename IndexedRingMemoryArray::Iterator it = this->begin();it!=this->end();++it) { - it->setBlockStartAddress(address); - it->setSize(0); - it->setStoredPackets(0); - address += bytesPerBlock; - } - - - //Initialize iterators - currentWriteBlock = this->begin(); - currentReadBlock = this->begin(); - lastBlockToRead = this->begin(); - - //Check last blockSize - uint32_t lastBlockSize = (trueStartAddress + useableSize) - (this->back()->getBlockStartAddress()); - if((lastBlockSizesize > 1)){ - //remove the last Block so the second last block has more size - this->size -= 1; - debug << "IndexedRingMemory: Last Block is smaller than bytesPerBlock, removed last block" << std::endl; - } + // Check trueNumberOfBlocks + if (trueNumberOfBlocks < 1) { + error << "IndexedRingMemory: Invalid Number of Blocks: " << trueNumberOfBlocks; } - /** - * Resets the whole index, the iterators and executes the given reset function on every index type - * @param typeResetFnc static reset function which accepts a pointer to the index Type - */ - void reset(void (*typeResetFnc)(T*)){ - currentReadBlock = this->begin(); - currentWriteBlock = this->begin(); - lastBlockToRead = this->begin(); - currentReadSize = 0; - currentReadBlockSizeCached = 0; - lastBlockToReadSize = 0; - for(typename IndexedRingMemoryArray::Iterator it = this->begin();it!=this->end();++it){ - it->setSize(0); - it->setStoredPackets(0); - (*typeResetFnc)(it->modifyIndexType()); - } + // Fill address into index + uint32_t address = trueStartAddress; + for (typename IndexedRingMemoryArray::Iterator it = this->begin(); it != this->end(); ++it) { + it->setBlockStartAddress(address); + it->setSize(0); + it->setStoredPackets(0); + address += bytesPerBlock; } - void resetBlock(typename IndexedRingMemoryArray::Iterator it,void (*typeResetFnc)(T*)){ - it->setSize(0); - it->setStoredPackets(0); - (*typeResetFnc)(it->modifyIndexType()); + // Initialize iterators + currentWriteBlock = this->begin(); + currentReadBlock = this->begin(); + lastBlockToRead = this->begin(); + + // Check last blockSize + uint32_t lastBlockSize = + (trueStartAddress + useableSize) - (this->back()->getBlockStartAddress()); + if ((lastBlockSize < bytesPerBlock) && (this->size > 1)) { + // remove the last Block so the second last block has more size + this->size -= 1; + debug << "IndexedRingMemory: Last Block is smaller than bytesPerBlock, removed last block" + << std::endl; + } + } + + /** + * Resets the whole index, the iterators and executes the given reset function on every index type + * @param typeResetFnc static reset function which accepts a pointer to the index Type + */ + void reset(void (*typeResetFnc)(T*)) { + currentReadBlock = this->begin(); + currentWriteBlock = this->begin(); + lastBlockToRead = this->begin(); + currentReadSize = 0; + currentReadBlockSizeCached = 0; + lastBlockToReadSize = 0; + for (typename IndexedRingMemoryArray::Iterator it = this->begin(); it != this->end(); ++it) { + it->setSize(0); + it->setStoredPackets(0); + (*typeResetFnc)(it->modifyIndexType()); + } + } + + void resetBlock(typename IndexedRingMemoryArray::Iterator it, void (*typeResetFnc)(T*)) { + it->setSize(0); + it->setStoredPackets(0); + (*typeResetFnc)(it->modifyIndexType()); + } + + /* + * Reading + */ + + void setCurrentReadBlock(typename IndexedRingMemoryArray::Iterator it) { + currentReadBlock = it; + currentReadBlockSizeCached = it->getSize(); + } + + void resetRead() { + currentReadBlock = this->begin(); + currentReadSize = 0; + currentReadBlockSizeCached = this->begin()->getSize(); + lastBlockToRead = currentWriteBlock; + lastBlockToReadSize = currentWriteBlock->getSize(); + } + /** + * Sets the last block to read to this iterator. + * Can be used to dump until block x + * @param it The iterator for the last read block + */ + void setLastBlockToRead(typename IndexedRingMemoryArray::Iterator it) { + lastBlockToRead = it; + lastBlockToReadSize = it->getSize(); + } + + /** + * Set the read pointer to the first written Block, which is the first non empty block in front of + * the write block Can be the currentWriteBlock as well + */ + void readOldest() { + resetRead(); + currentReadBlock = getNextNonEmptyBlock(); + currentReadBlockSizeCached = currentReadBlock->getSize(); + } + + /** + * Sets the current read iterator to the next Block and resets the current read size + * The current size of the block will be cached to avoid race condition between write and read + * If the end of the ring is reached the read pointer will be set to the begin + */ + void readNext() { + currentReadSize = 0; + if ((this->size != 0) && (currentReadBlock.value == this->back())) { + currentReadBlock = this->begin(); + } else { + currentReadBlock++; } - /* - * Reading - */ + currentReadBlockSizeCached = currentReadBlock->getSize(); + } - void setCurrentReadBlock(typename IndexedRingMemoryArray::Iterator it){ - currentReadBlock = it; - currentReadBlockSizeCached = it->getSize(); - } - - void resetRead(){ - currentReadBlock = this->begin(); - currentReadSize = 0; - currentReadBlockSizeCached = this->begin()->getSize(); - lastBlockToRead = currentWriteBlock; - lastBlockToReadSize = currentWriteBlock->getSize(); - } - /** - * Sets the last block to read to this iterator. - * Can be used to dump until block x - * @param it The iterator for the last read block - */ - void setLastBlockToRead(typename IndexedRingMemoryArray::Iterator it){ - lastBlockToRead = it; - lastBlockToReadSize = it->getSize(); - } - - /** - * Set the read pointer to the first written Block, which is the first non empty block in front of the write block - * Can be the currentWriteBlock as well - */ - void readOldest(){ - resetRead(); - currentReadBlock = getNextNonEmptyBlock(); - currentReadBlockSizeCached = currentReadBlock->getSize(); - - } - - /** - * Sets the current read iterator to the next Block and resets the current read size - * The current size of the block will be cached to avoid race condition between write and read - * If the end of the ring is reached the read pointer will be set to the begin - */ - void readNext(){ - currentReadSize = 0; - if((this->size != 0) && (currentReadBlock.value ==this->back())){ - currentReadBlock = this->begin(); - }else{ - currentReadBlock++; - } - - currentReadBlockSizeCached = currentReadBlock->getSize(); - } - - /** - * Returns the address which is currently read from - * @return Address to read from - */ - uint32_t getCurrentReadAddress() const { - return getAddressOfCurrentReadBlock() + currentReadSize; - } - /** - * Adds readSize to the current size and checks if the read has no more data left and advances the read block - * @param readSize The size that was read - * @return Returns true if the read can go on - */ - bool addReadSize(uint32_t readSize) { - if(currentReadBlock == lastBlockToRead){ - //The current read block is the last to read - if((currentReadSize+readSize) return true - currentReadSize += readSize; - return true; - }else{ - //Reached end of read -> return false - currentReadSize = lastBlockToReadSize; - return false; - } - }else{ - //We are not in the last Block - if((currentReadSize + readSize)::Iterator it(currentReadBlock); - //Search if any block between this and the last block is not empty - for(;it!=lastBlockToRead;++it){ - if(it == this->end()){ - //This is the end, next block is the begin - it = this->begin(); - if(it == lastBlockToRead){ - //Break if the begin is the lastBlockToRead - break; - } - } - if(it->getSize()!=0){ - //This is a non empty block. Go on reading with this block - currentReadBlock = it; - currentReadBlockSizeCached = it->getSize(); - return true; - } - } - //reached lastBlockToRead and every block was empty, check if the last block is also empty - if(lastBlockToReadSize!=0){ - //go on with last Block - currentReadBlock = lastBlockToRead; - currentReadBlockSizeCached = lastBlockToReadSize; - return true; - } - //There is no non empty block left - return false; - } - //Size is larger than 0 - return true; - } - } - } - uint32_t getRemainigSizeOfCurrentReadBlock() const{ - if(currentReadBlock == lastBlockToRead){ - return (lastBlockToReadSize - currentReadSize); - }else{ - return (currentReadBlockSizeCached - currentReadSize); - } - } - - uint32_t getAddressOfCurrentReadBlock() const { - return currentReadBlock->getBlockStartAddress(); - } - - /** - * Gets the next non empty Block after the current write block, - * @return Returns the iterator to the block. If there is non, the current write block is returned - */ - typename IndexedRingMemoryArray::Iterator getNextNonEmptyBlock() const { - for(typename IndexedRingMemoryArray::Iterator it = getNextWrite();it!=currentWriteBlock;++it){ - if(it == this->end()){ - it = this->begin(); - if(it == currentWriteBlock){ - break; - } - } - if(it->getSize()!=0){ - return it; - } - } - return currentWriteBlock; - } - - /** - * Returns a copy of the oldest Index type - * @return Type of Index - */ - T* getOldest(){ - return (getNextNonEmptyBlock()->modifyIndexType()); - } - - - /* - * Writing - */ - uint32_t getAddressOfCurrentWriteBlock() const{ - return currentWriteBlock->getBlockStartAddress(); - } - - uint32_t getSizeOfCurrentWriteBlock() const{ - return currentWriteBlock->getSize(); - } - - uint32_t getCurrentWriteAddress() const{ - return getAddressOfCurrentWriteBlock() + getSizeOfCurrentWriteBlock(); - } - - void clearCurrentWriteBlock(){ - currentWriteBlock->setSize(0); - currentWriteBlock->setStoredPackets(0); - } - - void addCurrentWriteBlock(uint32_t size, uint32_t storedPackets){ - currentWriteBlock->addSize(size); - currentWriteBlock->addStoredPackets(storedPackets); - } - - T* modifyCurrentWriteBlockIndexType(){ - return currentWriteBlock->modifyIndexType(); - } - void updatePreviousWriteSize(uint32_t size, uint32_t storedPackets){ - typename IndexedRingMemoryArray::Iterator it = getPreviousBlock(currentWriteBlock); - it->addSize(size); - it->addStoredPackets(storedPackets); - } - - - /** - * Checks if the block has enough space for sizeToWrite - * @param sizeToWrite The data to be written in the Block - * @return Returns true if size to write is smaller the remaining size of the block - */ - bool hasCurrentWriteBlockEnoughSpace(uint32_t sizeToWrite){ - typename IndexedRingMemoryArray::Iterator next = getNextWrite(); - uint32_t addressOfNextBlock = next->getBlockStartAddress(); - uint32_t availableSize = ((addressOfNextBlock+totalSize) - (getAddressOfCurrentWriteBlock()+getSizeOfCurrentWriteBlock()))%totalSize; - return (sizeToWrite < availableSize); - } - - /** - * Checks if the store is full if overwrite old is false - * @return Returns true if it is writeable and false if not - */ - bool isNextBlockWritable(){ - //First check if this is the end of the list - typename IndexedRingMemoryArray::Iterator next; - next = getNextWrite(); - if((next->getSize()!=0) && (!overwriteOld)){ - return false; - } + /** + * Returns the address which is currently read from + * @return Address to read from + */ + uint32_t getCurrentReadAddress() const { + return getAddressOfCurrentReadBlock() + currentReadSize; + } + /** + * Adds readSize to the current size and checks if the read has no more data left and advances the + * read block + * @param readSize The size that was read + * @return Returns true if the read can go on + */ + bool addReadSize(uint32_t readSize) { + if (currentReadBlock == lastBlockToRead) { + // The current read block is the last to read + if ((currentReadSize + readSize) < lastBlockToReadSize) { + // the block has more data -> return true + currentReadSize += readSize; return true; - } - - /** - * Updates current write Block Index Type - * @param infoOfNewBlock - */ - void updateCurrentBlock(T* infoOfNewBlock){ - currentWriteBlock->setIndexType(infoOfNewBlock); - } - - - /** - * Succeed to next block, returns FAILED if overwrite is false and the store is full - * @return - */ - ReturnValue_t writeNext(){ - //Check Next Block - if(!isNextBlockWritable()){ - //The Index is full and does not overwrite old - return HasReturnvaluesIF::RETURN_FAILED; - } - //Next block can be written, update Metadata - currentWriteBlock = getNextWrite(); - currentWriteBlock->setSize(0); - currentWriteBlock->setStoredPackets(0); - return HasReturnvaluesIF::RETURN_OK; - } - - /** - * Serializes the Index and calculates the CRC. - * Parameters according to HasSerializeIF - * @param buffer - * @param size - * @param maxSize - * @param streamEndianness - * @return - */ - ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const{ - uint8_t* crcBuffer = *buffer; - uint32_t oldSize = *size; - if(additionalInfo!=NULL){ - additionalInfo->serialize(buffer,size,maxSize,streamEndianness); - } - ReturnValue_t result = currentWriteBlock->serialize(buffer,size,maxSize,streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK){ - return result; - } - result = SerializeAdapter::serialize(&this->size,buffer,size,maxSize,streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK){ - return result; - } - - uint32_t i = 0; - while ((result == HasReturnvaluesIF::RETURN_OK) && (i < this->size)) { - result = SerializeAdapter::serialize(&this->entries[i], buffer, size, - maxSize, streamEndianness); - ++i; - } - if(result != HasReturnvaluesIF::RETURN_OK){ - return result; - } - uint16_t crc = Calculate_CRC(crcBuffer,(*size-oldSize)); - result = SerializeAdapter::serialize(&crc,buffer,size,maxSize,streamEndianness); - return result; - } - - - /** - * Get the serialized Size of the index - * @return The serialized size of the index - */ - size_t getSerializedSize() const { - - uint32_t size = 0; - if(additionalInfo!=NULL){ - size += additionalInfo->getSerializedSize(); - } - size += currentWriteBlock->getSerializedSize(); - size += SerializeAdapter::getSerializedSize(&this->size); - size += (this->entries[0].getSerializedSize()) * this->size; - uint16_t crc = 0; - size += SerializeAdapter::getSerializedSize(&crc); - return size; - } - /** - * DeSerialize the Indexed Ring from a buffer, deSerializes the current write iterator - * CRC Has to be checked before! - * @param buffer - * @param size - * @param streamEndianness - * @return - */ - - ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness){ - - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - if(additionalInfo!=NULL){ - result = additionalInfo->deSerialize(buffer,size,streamEndianness); - } - if(result != HasReturnvaluesIF::RETURN_OK){ - return result; - } - - Index tempIndex; - result = tempIndex.deSerialize(buffer,size,streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK){ - return result; - } - uint32_t tempSize = 0; - result = SerializeAdapter::deSerialize(&tempSize,buffer,size,streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK){ - return result; - } - if(this->size != tempSize){ - return HasReturnvaluesIF::RETURN_FAILED; - } - uint32_t i = 0; - while ((result == HasReturnvaluesIF::RETURN_OK) && (i < this->size)) { - result = SerializeAdapter::deSerialize( - &this->entries[i], buffer, size, - streamEndianness); - ++i; - } - if(result != HasReturnvaluesIF::RETURN_OK){ - return result; - } - typename IndexedRingMemoryArray::Iterator cmp(&tempIndex); - for(typename IndexedRingMemoryArray::Iterator it= this->begin();it!=this->end();++it){ - if(*(cmp.value) == *(it.value)){ - currentWriteBlock = it; - return HasReturnvaluesIF::RETURN_OK; + } else { + // Reached end of read -> return false + currentReadSize = lastBlockToReadSize; + return false; + } + } else { + // We are not in the last Block + if ((currentReadSize + readSize) < currentReadBlockSizeCached) { + // The current Block has more data + currentReadSize += readSize; + return true; + } else { + // The current block is written completely + readNext(); + if (currentReadBlockSizeCached == 0) { + // Next block is empty + typename IndexedRingMemoryArray::Iterator it(currentReadBlock); + // Search if any block between this and the last block is not empty + for (; it != lastBlockToRead; ++it) { + if (it == this->end()) { + // This is the end, next block is the begin + it = this->begin(); + if (it == lastBlockToRead) { + // Break if the begin is the lastBlockToRead + break; + } } + if (it->getSize() != 0) { + // This is a non empty block. Go on reading with this block + currentReadBlock = it; + currentReadBlockSizeCached = it->getSize(); + return true; + } + } + // reached lastBlockToRead and every block was empty, check if the last block is also + // empty + if (lastBlockToReadSize != 0) { + // go on with last Block + currentReadBlock = lastBlockToRead; + currentReadBlockSizeCached = lastBlockToReadSize; + return true; + } + // There is no non empty block left + return false; } - //Reached if current write block iterator is not found - return HasReturnvaluesIF::RETURN_FAILED; + // Size is larger than 0 + return true; + } } - - uint32_t getIndexAddress() const { - return indexAddress; + } + uint32_t getRemainigSizeOfCurrentReadBlock() const { + if (currentReadBlock == lastBlockToRead) { + return (lastBlockToReadSize - currentReadSize); + } else { + return (currentReadBlockSizeCached - currentReadSize); } + } + uint32_t getAddressOfCurrentReadBlock() const { return currentReadBlock->getBlockStartAddress(); } - /* - * Statistics - */ - uint32_t getStoredPackets() const { - uint32_t size = 0; - for(typename IndexedRingMemoryArray::Iterator it= this->begin();it!=this->end();++it){ - size += it->getStoredPackets(); + /** + * Gets the next non empty Block after the current write block, + * @return Returns the iterator to the block. If there is non, the current write block is returned + */ + typename IndexedRingMemoryArray::Iterator getNextNonEmptyBlock() const { + for (typename IndexedRingMemoryArray::Iterator it = getNextWrite(); it != currentWriteBlock; + ++it) { + if (it == this->end()) { + it = this->begin(); + if (it == currentWriteBlock) { + break; } - return size; + } + if (it->getSize() != 0) { + return it; + } + } + return currentWriteBlock; + } + + /** + * Returns a copy of the oldest Index type + * @return Type of Index + */ + T* getOldest() { return (getNextNonEmptyBlock()->modifyIndexType()); } + + /* + * Writing + */ + uint32_t getAddressOfCurrentWriteBlock() const { + return currentWriteBlock->getBlockStartAddress(); + } + + uint32_t getSizeOfCurrentWriteBlock() const { return currentWriteBlock->getSize(); } + + uint32_t getCurrentWriteAddress() const { + return getAddressOfCurrentWriteBlock() + getSizeOfCurrentWriteBlock(); + } + + void clearCurrentWriteBlock() { + currentWriteBlock->setSize(0); + currentWriteBlock->setStoredPackets(0); + } + + void addCurrentWriteBlock(uint32_t size, uint32_t storedPackets) { + currentWriteBlock->addSize(size); + currentWriteBlock->addStoredPackets(storedPackets); + } + + T* modifyCurrentWriteBlockIndexType() { return currentWriteBlock->modifyIndexType(); } + void updatePreviousWriteSize(uint32_t size, uint32_t storedPackets) { + typename IndexedRingMemoryArray::Iterator it = getPreviousBlock(currentWriteBlock); + it->addSize(size); + it->addStoredPackets(storedPackets); + } + + /** + * Checks if the block has enough space for sizeToWrite + * @param sizeToWrite The data to be written in the Block + * @return Returns true if size to write is smaller the remaining size of the block + */ + bool hasCurrentWriteBlockEnoughSpace(uint32_t sizeToWrite) { + typename IndexedRingMemoryArray::Iterator next = getNextWrite(); + uint32_t addressOfNextBlock = next->getBlockStartAddress(); + uint32_t availableSize = ((addressOfNextBlock + totalSize) - + (getAddressOfCurrentWriteBlock() + getSizeOfCurrentWriteBlock())) % + totalSize; + return (sizeToWrite < availableSize); + } + + /** + * Checks if the store is full if overwrite old is false + * @return Returns true if it is writeable and false if not + */ + bool isNextBlockWritable() { + // First check if this is the end of the list + typename IndexedRingMemoryArray::Iterator next; + next = getNextWrite(); + if ((next->getSize() != 0) && (!overwriteOld)) { + return false; + } + return true; + } + + /** + * Updates current write Block Index Type + * @param infoOfNewBlock + */ + void updateCurrentBlock(T* infoOfNewBlock) { currentWriteBlock->setIndexType(infoOfNewBlock); } + + /** + * Succeed to next block, returns FAILED if overwrite is false and the store is full + * @return + */ + ReturnValue_t writeNext() { + // Check Next Block + if (!isNextBlockWritable()) { + // The Index is full and does not overwrite old + return HasReturnvaluesIF::RETURN_FAILED; + } + // Next block can be written, update Metadata + currentWriteBlock = getNextWrite(); + currentWriteBlock->setSize(0); + currentWriteBlock->setStoredPackets(0); + return HasReturnvaluesIF::RETURN_OK; + } + + /** + * Serializes the Index and calculates the CRC. + * Parameters according to HasSerializeIF + * @param buffer + * @param size + * @param maxSize + * @param streamEndianness + * @return + */ + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const { + uint8_t* crcBuffer = *buffer; + uint32_t oldSize = *size; + if (additionalInfo != NULL) { + additionalInfo->serialize(buffer, size, maxSize, streamEndianness); + } + ReturnValue_t result = currentWriteBlock->serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::serialize(&this->size, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; } - uint32_t getTotalSize() const { - return totalSize; + uint32_t i = 0; + while ((result == HasReturnvaluesIF::RETURN_OK) && (i < this->size)) { + result = + SerializeAdapter::serialize(&this->entries[i], buffer, size, maxSize, streamEndianness); + ++i; + } + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + uint16_t crc = Calculate_CRC(crcBuffer, (*size - oldSize)); + result = SerializeAdapter::serialize(&crc, buffer, size, maxSize, streamEndianness); + return result; + } + + /** + * Get the serialized Size of the index + * @return The serialized size of the index + */ + size_t getSerializedSize() const { + uint32_t size = 0; + if (additionalInfo != NULL) { + size += additionalInfo->getSerializedSize(); + } + size += currentWriteBlock->getSerializedSize(); + size += SerializeAdapter::getSerializedSize(&this->size); + size += (this->entries[0].getSerializedSize()) * this->size; + uint16_t crc = 0; + size += SerializeAdapter::getSerializedSize(&crc); + return size; + } + /** + * DeSerialize the Indexed Ring from a buffer, deSerializes the current write iterator + * CRC Has to be checked before! + * @param buffer + * @param size + * @param streamEndianness + * @return + */ + + ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, Endianness streamEndianness) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + if (additionalInfo != NULL) { + result = additionalInfo->deSerialize(buffer, size, streamEndianness); + } + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; } - uint32_t getCurrentSize() const{ - uint32_t size = 0; - for(typename IndexedRingMemoryArray::Iterator it= this->begin();it!=this->end();++it){ - size += it->getSize(); - } - return size; + Index tempIndex; + result = tempIndex.deSerialize(buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + uint32_t tempSize = 0; + result = SerializeAdapter::deSerialize(&tempSize, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (this->size != tempSize) { + return HasReturnvaluesIF::RETURN_FAILED; + } + uint32_t i = 0; + while ((result == HasReturnvaluesIF::RETURN_OK) && (i < this->size)) { + result = SerializeAdapter::deSerialize(&this->entries[i], buffer, size, streamEndianness); + ++i; + } + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + typename IndexedRingMemoryArray::Iterator cmp(&tempIndex); + for (typename IndexedRingMemoryArray::Iterator it = this->begin(); it != this->end(); ++it) { + if (*(cmp.value) == *(it.value)) { + currentWriteBlock = it; + return HasReturnvaluesIF::RETURN_OK; + } + } + // Reached if current write block iterator is not found + return HasReturnvaluesIF::RETURN_FAILED; + } + + uint32_t getIndexAddress() const { return indexAddress; } + + /* + * Statistics + */ + uint32_t getStoredPackets() const { + uint32_t size = 0; + for (typename IndexedRingMemoryArray::Iterator it = this->begin(); it != this->end(); ++it) { + size += it->getStoredPackets(); + } + return size; + } + + uint32_t getTotalSize() const { return totalSize; } + + uint32_t getCurrentSize() const { + uint32_t size = 0; + for (typename IndexedRingMemoryArray::Iterator it = this->begin(); it != this->end(); ++it) { + size += it->getSize(); + } + return size; + } + + bool isEmpty() const { return getCurrentSize() == 0; } + + double getPercentageFilled() const { + uint32_t filledSize = 0; + for (typename IndexedRingMemoryArray::Iterator it = this->begin(); it != this->end(); ++it) { + filledSize += it->getSize(); } - bool isEmpty() const{ - return getCurrentSize()==0; + return (double)filledSize / (double)this->totalSize; + } + + typename IndexedRingMemoryArray::Iterator getCurrentWriteBlock() const { + return currentWriteBlock; + } + /** + * Get the next block of the currentWriteBlock. + * Returns the first one if currentWriteBlock is the last one + * @return Iterator pointing to the next block after currentWriteBlock + */ + typename IndexedRingMemoryArray::Iterator getNextWrite() const { + typename IndexedRingMemoryArray::Iterator next(currentWriteBlock); + if ((this->size != 0) && (currentWriteBlock.value == this->back())) { + next = this->begin(); + } else { + ++next; } - - double getPercentageFilled() const{ - uint32_t filledSize = 0; - for(typename IndexedRingMemoryArray::Iterator it= this->begin();it!=this->end();++it){ - filledSize += it->getSize(); - } - - return (double)filledSize/(double)this->totalSize; + return next; + } + /** + * Get the block in front of the Iterator + * Returns the last block if it is the first block + * @param it iterator which you want the previous block from + * @return pointing to the block before it + */ + typename IndexedRingMemoryArray::Iterator getPreviousBlock( + typename IndexedRingMemoryArray::Iterator it) { + if (this->begin() == it) { + typename IndexedRingMemoryArray::Iterator next((this->back())); + return next; } + typename IndexedRingMemoryArray::Iterator next(it); + --next; + return next; + } - typename IndexedRingMemoryArray::Iterator getCurrentWriteBlock() const{ - return currentWriteBlock; - } - /** - * Get the next block of the currentWriteBlock. - * Returns the first one if currentWriteBlock is the last one - * @return Iterator pointing to the next block after currentWriteBlock - */ - typename IndexedRingMemoryArray::Iterator getNextWrite() const{ - typename IndexedRingMemoryArray::Iterator next(currentWriteBlock); - if((this->size != 0) && (currentWriteBlock.value == this->back())){ - next = this->begin(); - }else{ - ++next; - } - return next; - } - /** - * Get the block in front of the Iterator - * Returns the last block if it is the first block - * @param it iterator which you want the previous block from - * @return pointing to the block before it - */ - typename IndexedRingMemoryArray::Iterator getPreviousBlock(typename IndexedRingMemoryArray::Iterator it) { - if(this->begin() == it){ - typename IndexedRingMemoryArray::Iterator next((this->back())); - return next; - } - typename IndexedRingMemoryArray::Iterator next(it); - --next; - return next; - } -private: - //The total size used by the blocks (without index) - uint32_t totalSize; + private: + // The total size used by the blocks (without index) + uint32_t totalSize; - //The address of the index - const uint32_t indexAddress; + // The address of the index + const uint32_t indexAddress; - //The iterators for writing and reading - typename IndexedRingMemoryArray::Iterator currentWriteBlock; - typename IndexedRingMemoryArray::Iterator currentReadBlock; + // The iterators for writing and reading + typename IndexedRingMemoryArray::Iterator currentWriteBlock; + typename IndexedRingMemoryArray::Iterator currentReadBlock; - //How much of the current read block is read already - uint32_t currentReadSize; + // How much of the current read block is read already + uint32_t currentReadSize; - //Cached Size of current read block - uint32_t currentReadBlockSizeCached; + // Cached Size of current read block + uint32_t currentReadBlockSizeCached; - //Last block of current write (should be write block) - typename IndexedRingMemoryArray::Iterator lastBlockToRead; - //current size of last Block to read - uint32_t lastBlockToReadSize; + // Last block of current write (should be write block) + typename IndexedRingMemoryArray::Iterator lastBlockToRead; + // current size of last Block to read + uint32_t lastBlockToReadSize; - //Additional Info to be serialized with the index - SerializeIF* additionalInfo; - - //Does it overwrite old blocks? - const bool overwriteOld; + // Additional Info to be serialized with the index + SerializeIF* additionalInfo; + // Does it overwrite old blocks? + const bool overwriteOld; }; - - - #endif /* FRAMEWORK_CONTAINER_INDEXEDRINGMEMORY_H_ */ diff --git a/src/fsfw/container/PlacementFactory.h b/src/fsfw/container/PlacementFactory.h index 94b4aeef..936be59d 100644 --- a/src/fsfw/container/PlacementFactory.h +++ b/src/fsfw/container/PlacementFactory.h @@ -1,12 +1,14 @@ #ifndef FRAMEWORK_CONTAINER_PLACEMENTFACTORY_H_ #define FRAMEWORK_CONTAINER_PLACEMENTFACTORY_H_ -#include "../storagemanager/StorageManagerIF.h" #include + +#include "../storagemanager/StorageManagerIF.h" /** * The Placement Factory is used to create objects at runtime in a specific pool. * In general, this should be avoided and it should only be used if you know what you are doing. - * You are not allowed to use this container with a type that allocates memory internally like ArrayList. + * You are not allowed to use this container with a type that allocates memory internally like + * ArrayList. * * Also, you have to check the returned pointer in generate against nullptr! * @@ -21,51 +23,50 @@ * @ingroup container */ class PlacementFactory { -public: - PlacementFactory(StorageManagerIF* backend) : - dataBackend(backend) { - } + public: + PlacementFactory(StorageManagerIF* backend) : dataBackend(backend) {} - /*** - * Generates an object of type T in the backend storage. - * - * @warning Do not use with any Type that allocates memory internally! - * - * @tparam T Type of Object - * @param args Constructor Arguments to be passed - * @return A pointer to the new object or a nullptr in case of failure - */ - template - T* generate(Args&&... args) { - store_address_t tempId; - uint8_t* pData = nullptr; - ReturnValue_t result = dataBackend->getFreeElement(&tempId, sizeof(T), - &pData); - if (result != HasReturnvaluesIF::RETURN_OK) { - return nullptr; - } - T* temp = new (pData) T(std::forward(args)...); - return temp; + /*** + * Generates an object of type T in the backend storage. + * + * @warning Do not use with any Type that allocates memory internally! + * + * @tparam T Type of Object + * @param args Constructor Arguments to be passed + * @return A pointer to the new object or a nullptr in case of failure + */ + template + T* generate(Args&&... args) { + store_address_t tempId; + uint8_t* pData = nullptr; + ReturnValue_t result = dataBackend->getFreeElement(&tempId, sizeof(T), &pData); + if (result != HasReturnvaluesIF::RETURN_OK) { + return nullptr; } - /*** - * Function to destroy the object allocated with generate and free space in backend. - * This must be called by the user. - * - * @param thisElement Element to be destroyed - * @return RETURN_OK if the element was destroyed, different errors on failure - */ - template - ReturnValue_t destroy(T* thisElement) { - if (thisElement == nullptr){ - return HasReturnvaluesIF::RETURN_FAILED; - } - //Need to call destructor first, in case something was allocated by the object (shouldn't do that, however). - thisElement->~T(); - uint8_t* pointer = (uint8_t*) (thisElement); - return dataBackend->deleteData(pointer, sizeof(T)); + T* temp = new (pData) T(std::forward(args)...); + return temp; + } + /*** + * Function to destroy the object allocated with generate and free space in backend. + * This must be called by the user. + * + * @param thisElement Element to be destroyed + * @return RETURN_OK if the element was destroyed, different errors on failure + */ + template + ReturnValue_t destroy(T* thisElement) { + if (thisElement == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; } -private: - StorageManagerIF* dataBackend; + // Need to call destructor first, in case something was allocated by the object (shouldn't do + // that, however). + thisElement->~T(); + uint8_t* pointer = (uint8_t*)(thisElement); + return dataBackend->deleteData(pointer, sizeof(T)); + } + + private: + StorageManagerIF* dataBackend; }; #endif /* FRAMEWORK_CONTAINER_PLACEMENTFACTORY_H_ */ diff --git a/src/fsfw/container/RingBufferBase.h b/src/fsfw/container/RingBufferBase.h index 9277c50b..98207698 100644 --- a/src/fsfw/container/RingBufferBase.h +++ b/src/fsfw/container/RingBufferBase.h @@ -1,113 +1,89 @@ #ifndef FSFW_CONTAINER_RINGBUFFERBASE_H_ #define FSFW_CONTAINER_RINGBUFFERBASE_H_ -#include "../returnvalues/HasReturnvaluesIF.h" #include -template +#include "../returnvalues/HasReturnvaluesIF.h" + +template class RingBufferBase { -public: - RingBufferBase(size_t startAddress, const size_t size, bool overwriteOld) : - start(startAddress), write(startAddress), size(size), - overwriteOld(overwriteOld) { - for (uint8_t count = 0; count < N_READ_PTRS; count++) { - read[count] = startAddress; - } + public: + RingBufferBase(size_t startAddress, const size_t size, bool overwriteOld) + : start(startAddress), write(startAddress), size(size), overwriteOld(overwriteOld) { + for (uint8_t count = 0; count < N_READ_PTRS; count++) { + read[count] = startAddress; } + } - virtual ~RingBufferBase() {} + virtual ~RingBufferBase() {} - bool isFull(uint8_t n = 0) { - return (availableWriteSpace(n) == 0); - } - bool isEmpty(uint8_t n = 0) { - return (getAvailableReadData(n) == 0); - } + bool isFull(uint8_t n = 0) { return (availableWriteSpace(n) == 0); } + bool isEmpty(uint8_t n = 0) { return (getAvailableReadData(n) == 0); } - size_t getAvailableReadData(uint8_t n = 0) const { - return ((write + size) - read[n]) % size; - } - size_t availableWriteSpace(uint8_t n = 0) const { - //One less to avoid ambiguous full/empty problem. - return (((read[n] + size) - write - 1) % size); - } + size_t getAvailableReadData(uint8_t n = 0) const { return ((write + size) - read[n]) % size; } + size_t availableWriteSpace(uint8_t n = 0) const { + // One less to avoid ambiguous full/empty problem. + return (((read[n] + size) - write - 1) % size); + } - bool overwritesOld() const { - return overwriteOld; - } + bool overwritesOld() const { return overwriteOld; } - size_t getMaxSize() const { - return size - 1; - } + size_t getMaxSize() const { return size - 1; } - void clear() { - write = start; - for (uint8_t count = 0; count < N_READ_PTRS; count++) { - read[count] = start; - } + void clear() { + write = start; + for (uint8_t count = 0; count < N_READ_PTRS; count++) { + read[count] = start; } + } - size_t writeTillWrap() { - return (start + size) - write; - } + size_t writeTillWrap() { return (start + size) - write; } - size_t readTillWrap(uint8_t n = 0) { - return (start + size) - read[n]; - } + size_t readTillWrap(uint8_t n = 0) { return (start + size) - read[n]; } - size_t getStart() const { - return start; - } + size_t getStart() const { return start; } -protected: - const size_t start; - size_t write; - size_t read[N_READ_PTRS]; - const size_t size; - const bool overwriteOld; + protected: + const size_t start; + size_t write; + size_t read[N_READ_PTRS]; + const size_t size; + const bool overwriteOld; - void incrementWrite(uint32_t amount) { - write = ((write + amount - start) % size) + start; - } - void incrementRead(uint32_t amount, uint8_t n = 0) { - read[n] = ((read[n] + amount - start) % size) + start; - } + void incrementWrite(uint32_t amount) { write = ((write + amount - start) % size) + start; } + void incrementRead(uint32_t amount, uint8_t n = 0) { + read[n] = ((read[n] + amount - start) % size) + start; + } - ReturnValue_t readData(uint32_t amount, uint8_t n = 0) { - if (getAvailableReadData(n) >= amount) { - incrementRead(amount, n); - return HasReturnvaluesIF::RETURN_OK; - } else { - return HasReturnvaluesIF::RETURN_FAILED; - } + ReturnValue_t readData(uint32_t amount, uint8_t n = 0) { + if (getAvailableReadData(n) >= amount) { + incrementRead(amount, n); + return HasReturnvaluesIF::RETURN_OK; + } else { + return HasReturnvaluesIF::RETURN_FAILED; } + } - ReturnValue_t writeData(uint32_t amount) { - if (availableWriteSpace() >= amount or overwriteOld) { - incrementWrite(amount); - return HasReturnvaluesIF::RETURN_OK; - } else { - return HasReturnvaluesIF::RETURN_FAILED; - } + ReturnValue_t writeData(uint32_t amount) { + if (availableWriteSpace() >= amount or overwriteOld) { + incrementWrite(amount); + return HasReturnvaluesIF::RETURN_OK; + } else { + return HasReturnvaluesIF::RETURN_FAILED; } + } - size_t getRead(uint8_t n = 0) const { - return read[n]; - } + size_t getRead(uint8_t n = 0) const { return read[n]; } - void setRead(uint32_t read, uint8_t n = 0) { - if (read >= start && read < (start+size)) { - this->read[n] = read; - } + void setRead(uint32_t read, uint8_t n = 0) { + if (read >= start && read < (start + size)) { + this->read[n] = read; } + } - uint32_t getWrite() const { - return write; - } + uint32_t getWrite() const { return write; } - void setWrite(uint32_t write) { - this->write = write; - } + void setWrite(uint32_t write) { this->write = write; } }; #endif /* FSFW_CONTAINER_RINGBUFFERBASE_H_ */ diff --git a/src/fsfw/container/SharedRingBuffer.cpp b/src/fsfw/container/SharedRingBuffer.cpp index f7c97802..111019e0 100644 --- a/src/fsfw/container/SharedRingBuffer.cpp +++ b/src/fsfw/container/SharedRingBuffer.cpp @@ -1,60 +1,47 @@ #include "fsfw/container/SharedRingBuffer.h" + #include "fsfw/ipc/MutexFactory.h" #include "fsfw/ipc/MutexGuard.h" -SharedRingBuffer::SharedRingBuffer(object_id_t objectId, const size_t size, - bool overwriteOld, size_t maxExcessBytes): - SystemObject(objectId), SimpleRingBuffer(size, overwriteOld, - maxExcessBytes) { - mutex = MutexFactory::instance()->createMutex(); +SharedRingBuffer::SharedRingBuffer(object_id_t objectId, const size_t size, bool overwriteOld, + size_t maxExcessBytes) + : SystemObject(objectId), SimpleRingBuffer(size, overwriteOld, maxExcessBytes) { + mutex = MutexFactory::instance()->createMutex(); } - -SharedRingBuffer::SharedRingBuffer(object_id_t objectId, uint8_t *buffer, - const size_t size, bool overwriteOld, size_t maxExcessBytes): - SystemObject(objectId), SimpleRingBuffer(buffer, size, overwriteOld, - maxExcessBytes) { - mutex = MutexFactory::instance()->createMutex(); +SharedRingBuffer::SharedRingBuffer(object_id_t objectId, uint8_t* buffer, const size_t size, + bool overwriteOld, size_t maxExcessBytes) + : SystemObject(objectId), SimpleRingBuffer(buffer, size, overwriteOld, maxExcessBytes) { + mutex = MutexFactory::instance()->createMutex(); } -SharedRingBuffer::~SharedRingBuffer() { - MutexFactory::instance()->deleteMutex(mutex); +SharedRingBuffer::~SharedRingBuffer() { MutexFactory::instance()->deleteMutex(mutex); } + +void SharedRingBuffer::setToUseReceiveSizeFIFO(size_t fifoDepth) { this->fifoDepth = fifoDepth; } + +ReturnValue_t SharedRingBuffer::lockRingBufferMutex(MutexIF::TimeoutType timeoutType, + dur_millis_t timeout) { + return mutex->lockMutex(timeoutType, timeout); } -void SharedRingBuffer::setToUseReceiveSizeFIFO(size_t fifoDepth) { - this->fifoDepth = fifoDepth; -} +ReturnValue_t SharedRingBuffer::unlockRingBufferMutex() { return mutex->unlockMutex(); } -ReturnValue_t SharedRingBuffer::lockRingBufferMutex( - MutexIF::TimeoutType timeoutType, dur_millis_t timeout) { - return mutex->lockMutex(timeoutType, timeout); -} - -ReturnValue_t SharedRingBuffer::unlockRingBufferMutex() { - return mutex->unlockMutex(); -} - - - -MutexIF* SharedRingBuffer::getMutexHandle() const { - return mutex; -} +MutexIF* SharedRingBuffer::getMutexHandle() const { return mutex; } ReturnValue_t SharedRingBuffer::initialize() { - if(fifoDepth > 0) { - receiveSizesFIFO = new DynamicFIFO(fifoDepth); - } - return SystemObject::initialize(); + if (fifoDepth > 0) { + receiveSizesFIFO = new DynamicFIFO(fifoDepth); + } + return SystemObject::initialize(); } DynamicFIFO* SharedRingBuffer::getReceiveSizesFIFO() { - if(receiveSizesFIFO == nullptr) { - // Configuration error. + if (receiveSizesFIFO == nullptr) { + // Configuration error. #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "SharedRingBuffer::getReceiveSizesFIFO: Ring buffer" - << " was not configured to have sizes FIFO, returning nullptr!" - << std::endl; + sif::warning << "SharedRingBuffer::getReceiveSizesFIFO: Ring buffer" + << " was not configured to have sizes FIFO, returning nullptr!" << std::endl; #endif - } - return receiveSizesFIFO; + } + return receiveSizesFIFO; } diff --git a/src/fsfw/container/SharedRingBuffer.h b/src/fsfw/container/SharedRingBuffer.h index 26aa45c1..6ae36432 100644 --- a/src/fsfw/container/SharedRingBuffer.h +++ b/src/fsfw/container/SharedRingBuffer.h @@ -1,9 +1,8 @@ #ifndef FSFW_CONTAINER_SHAREDRINGBUFFER_H_ #define FSFW_CONTAINER_SHAREDRINGBUFFER_H_ -#include "SimpleRingBuffer.h" #include "DynamicFIFO.h" - +#include "SimpleRingBuffer.h" #include "fsfw/ipc/MutexIF.h" #include "fsfw/objectmanager/SystemObject.h" #include "fsfw/timemanager/Clock.h" @@ -15,82 +14,77 @@ * buffer. It is still up to the developer to actually perform the lock * and unlock operations. */ -class SharedRingBuffer: public SystemObject, - public SimpleRingBuffer { -public: - /** - * This constructor allocates a new internal buffer with the supplied size. - * @param size - * @param overwriteOld - * If the ring buffer is overflowing at a write operartion, the oldest data - * will be overwritten. - */ - SharedRingBuffer(object_id_t objectId, const size_t size, - bool overwriteOld, size_t maxExcessBytes); - /** - * This constructor takes an external buffer with the specified size. - * @param buffer - * @param size - * @param overwriteOld - * If the ring buffer is overflowing at a write operartion, the oldest data - * will be overwritten. - */ - SharedRingBuffer(object_id_t objectId, uint8_t* buffer, const size_t size, - bool overwriteOld, size_t maxExcessBytes); +class SharedRingBuffer : public SystemObject, public SimpleRingBuffer { + public: + /** + * This constructor allocates a new internal buffer with the supplied size. + * @param size + * @param overwriteOld + * If the ring buffer is overflowing at a write operartion, the oldest data + * will be overwritten. + */ + SharedRingBuffer(object_id_t objectId, const size_t size, bool overwriteOld, + size_t maxExcessBytes); + /** + * This constructor takes an external buffer with the specified size. + * @param buffer + * @param size + * @param overwriteOld + * If the ring buffer is overflowing at a write operartion, the oldest data + * will be overwritten. + */ + SharedRingBuffer(object_id_t objectId, uint8_t* buffer, const size_t size, bool overwriteOld, + size_t maxExcessBytes); - virtual~ SharedRingBuffer(); + virtual ~SharedRingBuffer(); - /** - * @brief This function can be used to add an optional FIFO to the class - * @details - * This FIFO will be allocated in the initialize function (and will - * have a fixed maximum size after that). It can be used to store - * values like packet sizes, for example for a shared ring buffer - * used by producer/consumer tasks. - */ - void setToUseReceiveSizeFIFO(size_t fifoDepth); + /** + * @brief This function can be used to add an optional FIFO to the class + * @details + * This FIFO will be allocated in the initialize function (and will + * have a fixed maximum size after that). It can be used to store + * values like packet sizes, for example for a shared ring buffer + * used by producer/consumer tasks. + */ + void setToUseReceiveSizeFIFO(size_t fifoDepth); + /** + * Unless a read-only constant value is read, all operations on the + * shared ring buffer should be protected by calling this function. + * @param timeoutType + * @param timeout + * @return + */ + virtual ReturnValue_t lockRingBufferMutex(MutexIF::TimeoutType timeoutType, dur_millis_t timeout); + /** + * Any locked mutex also has to be unlocked, otherwise, access to the + * shared ring buffer will be blocked. + * @return + */ + virtual ReturnValue_t unlockRingBufferMutex(); + /** + * The mutex handle can be accessed directly, for example to perform + * the lock with the #MutexGuard for a RAII compliant lock operation. + * @return + */ + MutexIF* getMutexHandle() const; - /** - * Unless a read-only constant value is read, all operations on the - * shared ring buffer should be protected by calling this function. - * @param timeoutType - * @param timeout - * @return - */ - virtual ReturnValue_t lockRingBufferMutex(MutexIF::TimeoutType timeoutType, - dur_millis_t timeout); - /** - * Any locked mutex also has to be unlocked, otherwise, access to the - * shared ring buffer will be blocked. - * @return - */ - virtual ReturnValue_t unlockRingBufferMutex(); + ReturnValue_t initialize() override; - /** - * The mutex handle can be accessed directly, for example to perform - * the lock with the #MutexGuard for a RAII compliant lock operation. - * @return - */ - MutexIF* getMutexHandle() const; + /** + * If the shared ring buffer was configured to have a sizes FIFO, a handle + * to that FIFO can be retrieved with this function. + * Do not forget to protect access with a lock if required! + * @return + */ + DynamicFIFO* getReceiveSizesFIFO(); - ReturnValue_t initialize() override; + private: + MutexIF* mutex = nullptr; - /** - * If the shared ring buffer was configured to have a sizes FIFO, a handle - * to that FIFO can be retrieved with this function. - * Do not forget to protect access with a lock if required! - * @return - */ - DynamicFIFO* getReceiveSizesFIFO(); -private: - MutexIF* mutex = nullptr; - - size_t fifoDepth = 0; - DynamicFIFO* receiveSizesFIFO = nullptr; + size_t fifoDepth = 0; + DynamicFIFO* receiveSizesFIFO = nullptr; }; - - #endif /* FSFW_CONTAINER_SHAREDRINGBUFFER_H_ */ diff --git a/src/fsfw/container/SimpleRingBuffer.cpp b/src/fsfw/container/SimpleRingBuffer.cpp index 8de9cf08..bcf3cf20 100644 --- a/src/fsfw/container/SimpleRingBuffer.cpp +++ b/src/fsfw/container/SimpleRingBuffer.cpp @@ -2,131 +2,118 @@ #include -SimpleRingBuffer::SimpleRingBuffer(const size_t size, bool overwriteOld, - size_t maxExcessBytes) : - RingBufferBase<>(0, size, overwriteOld), - maxExcessBytes(maxExcessBytes) { - if(maxExcessBytes > size) { - this->maxExcessBytes = size; - } - else { - this->maxExcessBytes = maxExcessBytes; - } - buffer = new uint8_t[size + maxExcessBytes]; +SimpleRingBuffer::SimpleRingBuffer(const size_t size, bool overwriteOld, size_t maxExcessBytes) + : RingBufferBase<>(0, size, overwriteOld), maxExcessBytes(maxExcessBytes) { + if (maxExcessBytes > size) { + this->maxExcessBytes = size; + } else { + this->maxExcessBytes = maxExcessBytes; + } + buffer = new uint8_t[size + maxExcessBytes]; } -SimpleRingBuffer::SimpleRingBuffer(uint8_t *buffer, const size_t size, - bool overwriteOld, size_t maxExcessBytes): - RingBufferBase<>(0, size, overwriteOld), buffer(buffer) { - if(maxExcessBytes > size) { - this->maxExcessBytes = size; - } - else { - this->maxExcessBytes = maxExcessBytes; - } +SimpleRingBuffer::SimpleRingBuffer(uint8_t* buffer, const size_t size, bool overwriteOld, + size_t maxExcessBytes) + : RingBufferBase<>(0, size, overwriteOld), buffer(buffer) { + if (maxExcessBytes > size) { + this->maxExcessBytes = size; + } else { + this->maxExcessBytes = maxExcessBytes; + } } -SimpleRingBuffer::~SimpleRingBuffer() { - delete[] buffer; -} +SimpleRingBuffer::~SimpleRingBuffer() { delete[] buffer; } -ReturnValue_t SimpleRingBuffer::getFreeElement(uint8_t **writePointer, - size_t amount) { - if (availableWriteSpace() >= amount or overwriteOld) { - size_t amountTillWrap = writeTillWrap(); - if (amountTillWrap < amount) { - if((amount - amountTillWrap + excessBytes) > maxExcessBytes) { - return HasReturnvaluesIF::RETURN_FAILED; - } - excessBytes = amount - amountTillWrap; - } - *writePointer = &buffer[write]; - return HasReturnvaluesIF::RETURN_OK; - } - else { +ReturnValue_t SimpleRingBuffer::getFreeElement(uint8_t** writePointer, size_t amount) { + if (availableWriteSpace() >= amount or overwriteOld) { + size_t amountTillWrap = writeTillWrap(); + if (amountTillWrap < amount) { + if ((amount - amountTillWrap + excessBytes) > maxExcessBytes) { return HasReturnvaluesIF::RETURN_FAILED; + } + excessBytes = amount - amountTillWrap; } + *writePointer = &buffer[write]; + return HasReturnvaluesIF::RETURN_OK; + } else { + return HasReturnvaluesIF::RETURN_FAILED; + } } void SimpleRingBuffer::confirmBytesWritten(size_t amount) { - if(getExcessBytes() > 0) { - moveExcessBytesToStart(); + if (getExcessBytes() > 0) { + moveExcessBytesToStart(); + } + incrementWrite(amount); +} + +ReturnValue_t SimpleRingBuffer::writeData(const uint8_t* data, size_t amount) { + if (availableWriteSpace() >= amount or overwriteOld) { + size_t amountTillWrap = writeTillWrap(); + if (amountTillWrap >= amount) { + // remaining size in buffer is sufficient to fit full amount. + memcpy(&buffer[write], data, amount); + } else { + memcpy(&buffer[write], data, amountTillWrap); + memcpy(buffer, data + amountTillWrap, amount - amountTillWrap); } incrementWrite(amount); - -} - -ReturnValue_t SimpleRingBuffer::writeData(const uint8_t* data, - size_t amount) { - if (availableWriteSpace() >= amount or overwriteOld) { - size_t amountTillWrap = writeTillWrap(); - if (amountTillWrap >= amount) { - // remaining size in buffer is sufficient to fit full amount. - memcpy(&buffer[write], data, amount); - } - else { - memcpy(&buffer[write], data, amountTillWrap); - memcpy(buffer, data + amountTillWrap, amount - amountTillWrap); - } - incrementWrite(amount); - return HasReturnvaluesIF::RETURN_OK; - } else { - return HasReturnvaluesIF::RETURN_FAILED; - } -} - -ReturnValue_t SimpleRingBuffer::readData(uint8_t* data, size_t amount, - bool incrementReadPtr, bool readRemaining, size_t* trueAmount) { - size_t availableData = getAvailableReadData(READ_PTR); - size_t amountTillWrap = readTillWrap(READ_PTR); - if (availableData < amount) { - if (readRemaining) { - // more data available than amount specified. - amount = availableData; - } else { - return HasReturnvaluesIF::RETURN_FAILED; - } - } - if (trueAmount != nullptr) { - *trueAmount = amount; - } - if (amountTillWrap >= amount) { - memcpy(data, &buffer[read[READ_PTR]], amount); - } else { - memcpy(data, &buffer[read[READ_PTR]], amountTillWrap); - memcpy(data + amountTillWrap, buffer, amount - amountTillWrap); - } - - if(incrementReadPtr) { - deleteData(amount, readRemaining); - } return HasReturnvaluesIF::RETURN_OK; + } else { + return HasReturnvaluesIF::RETURN_FAILED; + } } -size_t SimpleRingBuffer::getExcessBytes() const { - return excessBytes; +ReturnValue_t SimpleRingBuffer::readData(uint8_t* data, size_t amount, bool incrementReadPtr, + bool readRemaining, size_t* trueAmount) { + size_t availableData = getAvailableReadData(READ_PTR); + size_t amountTillWrap = readTillWrap(READ_PTR); + if (availableData < amount) { + if (readRemaining) { + // more data available than amount specified. + amount = availableData; + } else { + return HasReturnvaluesIF::RETURN_FAILED; + } + } + if (trueAmount != nullptr) { + *trueAmount = amount; + } + if (amountTillWrap >= amount) { + memcpy(data, &buffer[read[READ_PTR]], amount); + } else { + memcpy(data, &buffer[read[READ_PTR]], amountTillWrap); + memcpy(data + amountTillWrap, buffer, amount - amountTillWrap); + } + + if (incrementReadPtr) { + deleteData(amount, readRemaining); + } + return HasReturnvaluesIF::RETURN_OK; } +size_t SimpleRingBuffer::getExcessBytes() const { return excessBytes; } + void SimpleRingBuffer::moveExcessBytesToStart() { - if(excessBytes > 0) { - std::memcpy(buffer, &buffer[size], excessBytes); - excessBytes = 0; - } + if (excessBytes > 0) { + std::memcpy(buffer, &buffer[size], excessBytes); + excessBytes = 0; + } } -ReturnValue_t SimpleRingBuffer::deleteData(size_t amount, - bool deleteRemaining, size_t* trueAmount) { - size_t availableData = getAvailableReadData(READ_PTR); - if (availableData < amount) { - if (deleteRemaining) { - amount = availableData; - } else { - return HasReturnvaluesIF::RETURN_FAILED; - } +ReturnValue_t SimpleRingBuffer::deleteData(size_t amount, bool deleteRemaining, + size_t* trueAmount) { + size_t availableData = getAvailableReadData(READ_PTR); + if (availableData < amount) { + if (deleteRemaining) { + amount = availableData; + } else { + return HasReturnvaluesIF::RETURN_FAILED; } - if (trueAmount != nullptr) { - *trueAmount = amount; - } - incrementRead(amount, READ_PTR); - return HasReturnvaluesIF::RETURN_OK; + } + if (trueAmount != nullptr) { + *trueAmount = amount; + } + incrementRead(amount, READ_PTR); + return HasReturnvaluesIF::RETURN_OK; } diff --git a/src/fsfw/container/SimpleRingBuffer.h b/src/fsfw/container/SimpleRingBuffer.h index dc0aeba8..b9762451 100644 --- a/src/fsfw/container/SimpleRingBuffer.h +++ b/src/fsfw/container/SimpleRingBuffer.h @@ -1,9 +1,10 @@ #ifndef FSFW_CONTAINER_SIMPLERINGBUFFER_H_ #define FSFW_CONTAINER_SIMPLERINGBUFFER_H_ -#include "RingBufferBase.h" #include +#include "RingBufferBase.h" + /** * @brief Circular buffer implementation, useful for buffering into data streams. * @details @@ -11,118 +12,115 @@ * This class allocated dynamically, so * @ingroup containers */ -class SimpleRingBuffer: public RingBufferBase<> { -public: - /** - * This constructor allocates a new internal buffer with the supplied size. - * - * @param size - * @param overwriteOld If the ring buffer is overflowing at a write - * operation, the oldest data will be overwritten. - * @param maxExcessBytes These additional bytes will be allocated in addition - * to the specified size to accommodate continuous write operations - * with getFreeElement. - * - */ - SimpleRingBuffer(const size_t size, bool overwriteOld, - size_t maxExcessBytes = 0); - /** - * This constructor takes an external buffer with the specified size. - * @param buffer - * @param size - * @param overwriteOld - * If the ring buffer is overflowing at a write operation, the oldest data - * will be overwritten. - * @param maxExcessBytes - * If the buffer can accommodate additional bytes for contiguous write - * operations with getFreeElement, this is the maximum allowed additional - * size - */ - SimpleRingBuffer(uint8_t* buffer, const size_t size, bool overwriteOld, - size_t maxExcessBytes = 0); +class SimpleRingBuffer : public RingBufferBase<> { + public: + /** + * This constructor allocates a new internal buffer with the supplied size. + * + * @param size + * @param overwriteOld If the ring buffer is overflowing at a write + * operation, the oldest data will be overwritten. + * @param maxExcessBytes These additional bytes will be allocated in addition + * to the specified size to accommodate continuous write operations + * with getFreeElement. + * + */ + SimpleRingBuffer(const size_t size, bool overwriteOld, size_t maxExcessBytes = 0); + /** + * This constructor takes an external buffer with the specified size. + * @param buffer + * @param size + * @param overwriteOld + * If the ring buffer is overflowing at a write operation, the oldest data + * will be overwritten. + * @param maxExcessBytes + * If the buffer can accommodate additional bytes for contiguous write + * operations with getFreeElement, this is the maximum allowed additional + * size + */ + SimpleRingBuffer(uint8_t* buffer, const size_t size, bool overwriteOld, + size_t maxExcessBytes = 0); - virtual ~SimpleRingBuffer(); + virtual ~SimpleRingBuffer(); - /** - * Write to circular buffer and increment write pointer by amount. - * @param data - * @param amount - * @return -@c RETURN_OK if write operation was successful - * -@c RETURN_FAILED if - */ - ReturnValue_t writeData(const uint8_t* data, size_t amount); + /** + * Write to circular buffer and increment write pointer by amount. + * @param data + * @param amount + * @return -@c RETURN_OK if write operation was successful + * -@c RETURN_FAILED if + */ + ReturnValue_t writeData(const uint8_t* data, size_t amount); - /** - * Returns a pointer to a free element. If the remaining buffer is - * not large enough, the data will be written past the actual size - * and the amount of excess bytes will be cached. This function - * does not increment the write pointer! - * @param writePointer Pointer to a pointer which can be used to write - * contiguous blocks into the ring buffer - * @param amount - * @return - */ - ReturnValue_t getFreeElement(uint8_t** writePointer, size_t amount); + /** + * Returns a pointer to a free element. If the remaining buffer is + * not large enough, the data will be written past the actual size + * and the amount of excess bytes will be cached. This function + * does not increment the write pointer! + * @param writePointer Pointer to a pointer which can be used to write + * contiguous blocks into the ring buffer + * @param amount + * @return + */ + ReturnValue_t getFreeElement(uint8_t** writePointer, size_t amount); - /** - * This increments the write pointer and also copies the excess bytes - * to the beginning. It should be called if the write operation - * conducted after calling getFreeElement() was performed. - * @return - */ - void confirmBytesWritten(size_t amount); + /** + * This increments the write pointer and also copies the excess bytes + * to the beginning. It should be called if the write operation + * conducted after calling getFreeElement() was performed. + * @return + */ + void confirmBytesWritten(size_t amount); - virtual size_t getExcessBytes() const; - /** - * Helper functions which moves any excess bytes to the start - * of the ring buffer. - * @return - */ - virtual void moveExcessBytesToStart(); + virtual size_t getExcessBytes() const; + /** + * Helper functions which moves any excess bytes to the start + * of the ring buffer. + * @return + */ + virtual void moveExcessBytesToStart(); - /** - * Read from circular buffer at read pointer. - * @param data - * @param amount - * @param incrementReadPtr - * If this is set to true, the read pointer will be incremented. - * If readRemaining is set to true, the read pointer will be incremented - * accordingly. - * @param readRemaining - * If this is set to true, the data will be read even if the amount - * specified exceeds the read data available. - * @param trueAmount [out] - * If readRemaining was set to true, the true amount read will be assigned - * to the passed value. - * @return - * - @c RETURN_OK if data was read successfully - * - @c RETURN_FAILED if not enough data was available and readRemaining - * was set to false. - */ - ReturnValue_t readData(uint8_t* data, size_t amount, - bool incrementReadPtr = false, bool readRemaining = false, - size_t* trueAmount = nullptr); + /** + * Read from circular buffer at read pointer. + * @param data + * @param amount + * @param incrementReadPtr + * If this is set to true, the read pointer will be incremented. + * If readRemaining is set to true, the read pointer will be incremented + * accordingly. + * @param readRemaining + * If this is set to true, the data will be read even if the amount + * specified exceeds the read data available. + * @param trueAmount [out] + * If readRemaining was set to true, the true amount read will be assigned + * to the passed value. + * @return + * - @c RETURN_OK if data was read successfully + * - @c RETURN_FAILED if not enough data was available and readRemaining + * was set to false. + */ + ReturnValue_t readData(uint8_t* data, size_t amount, bool incrementReadPtr = false, + bool readRemaining = false, size_t* trueAmount = nullptr); - /** - * Delete data by incrementing read pointer. - * @param amount - * @param deleteRemaining - * If the amount specified is larger than the remaining size to read and this - * is set to true, the remaining amount will be deleted as well - * @param trueAmount [out] - * If deleteRemaining was set to true, the amount deleted will be assigned - * to the passed value. - * @return - */ - ReturnValue_t deleteData(size_t amount, bool deleteRemaining = false, - size_t* trueAmount = nullptr); + /** + * Delete data by incrementing read pointer. + * @param amount + * @param deleteRemaining + * If the amount specified is larger than the remaining size to read and this + * is set to true, the remaining amount will be deleted as well + * @param trueAmount [out] + * If deleteRemaining was set to true, the amount deleted will be assigned + * to the passed value. + * @return + */ + ReturnValue_t deleteData(size_t amount, bool deleteRemaining = false, + size_t* trueAmount = nullptr); -private: - static const uint8_t READ_PTR = 0; - uint8_t* buffer = nullptr; - size_t maxExcessBytes; - size_t excessBytes = 0; + private: + static const uint8_t READ_PTR = 0; + uint8_t* buffer = nullptr; + size_t maxExcessBytes; + size_t excessBytes = 0; }; #endif /* FSFW_CONTAINER_SIMPLERINGBUFFER_H_ */ - diff --git a/src/fsfw/container/SinglyLinkedList.h b/src/fsfw/container/SinglyLinkedList.h index 02d590c5..9ea1386b 100644 --- a/src/fsfw/container/SinglyLinkedList.h +++ b/src/fsfw/container/SinglyLinkedList.h @@ -9,146 +9,116 @@ * each entry has a pointer to the next entry (singly) * @ingroup container */ -template +template class LinkedElement { -public: - T *value; - class Iterator { - public: - LinkedElement *value = nullptr; - Iterator() {} + public: + T* value; + class Iterator { + public: + LinkedElement* value = nullptr; + Iterator() {} - Iterator(LinkedElement *element) : - value(element) { - } + Iterator(LinkedElement* element) : value(element) {} - Iterator& operator++() { - value = value->getNext(); - return *this; - } - - Iterator operator++(int) { - Iterator tmp(*this); - operator++(); - return tmp; - } - - bool operator==(Iterator other) { - return value == other.value; - } - - bool operator!=(Iterator other) { - return !(*this == other); - } - T *operator->() { - return value->value; - } - }; - - LinkedElement(T* setElement, LinkedElement* setNext = nullptr): - value(setElement), next(setNext) {} - - virtual ~LinkedElement(){} - - virtual LinkedElement* getNext() const { - return next; + Iterator& operator++() { + value = value->getNext(); + return *this; } - virtual void setNext(LinkedElement* next) { - this->next = next; + Iterator operator++(int) { + Iterator tmp(*this); + operator++(); + return tmp; } - virtual void setEnd() { - this->next = nullptr; - } + bool operator==(Iterator other) { return value == other.value; } - LinkedElement* begin() { - return this; - } - LinkedElement* end() { - return nullptr; - } -private: - LinkedElement *next; + bool operator!=(Iterator other) { return !(*this == other); } + T* operator->() { return value->value; } + }; + + LinkedElement(T* setElement, LinkedElement* setNext = nullptr) + : value(setElement), next(setNext) {} + + virtual ~LinkedElement() {} + + virtual LinkedElement* getNext() const { return next; } + + virtual void setNext(LinkedElement* next) { this->next = next; } + + virtual void setEnd() { this->next = nullptr; } + + LinkedElement* begin() { return this; } + LinkedElement* end() { return nullptr; } + + private: + LinkedElement* next; }; -template +template class SinglyLinkedList { -public: - using ElementIterator = typename LinkedElement::Iterator; + public: + using ElementIterator = typename LinkedElement::Iterator; - SinglyLinkedList() {} + SinglyLinkedList() {} - SinglyLinkedList(ElementIterator start) : - start(start.value) {} + SinglyLinkedList(ElementIterator start) : start(start.value) {} - SinglyLinkedList(LinkedElement* startElement) : - start(startElement) {} + SinglyLinkedList(LinkedElement* startElement) : start(startElement) {} - ElementIterator begin() const { - return ElementIterator::Iterator(start); + ElementIterator begin() const { return ElementIterator::Iterator(start); } + + /** Returns iterator to nulltr */ + ElementIterator end() const { return ElementIterator::Iterator(); } + + /** + * Returns last element in singly linked list. + * @return + */ + ElementIterator back() const { + LinkedElement* element = start; + while (element->getNext() != nullptr) { + element = element->getNext(); } + return ElementIterator::Iterator(element); + } - /** Returns iterator to nulltr */ - ElementIterator end() const { - return ElementIterator::Iterator(); + size_t getSize() const { + size_t size = 0; + LinkedElement* element = start; + while (element != nullptr) { + size++; + element = element->getNext(); } + return size; + } + void setStart(LinkedElement* firstElement) { start = firstElement; } - /** - * Returns last element in singly linked list. - * @return - */ - ElementIterator back() const { - LinkedElement *element = start; - while (element->getNext() != nullptr) { - element = element->getNext(); - } - return ElementIterator::Iterator(element); - } + void setNext(LinkedElement* currentElement, LinkedElement* nextElement) { + currentElement->setNext(nextElement); + } - size_t getSize() const { - size_t size = 0; - LinkedElement *element = start; - while (element != nullptr) { - size++; - element = element->getNext(); - } - return size; - } - void setStart(LinkedElement* firstElement) { - start = firstElement; - } + void setLast(LinkedElement* lastElement) { lastElement->setEnd(); } - void setNext(LinkedElement* currentElement, - LinkedElement* nextElement) { - currentElement->setNext(nextElement); + void insertElement(LinkedElement* element, size_t position) { + LinkedElement* currentElement = start; + for (size_t count = 0; count < position; count++) { + if (currentElement == nullptr) { + return; + } + currentElement = currentElement->getNext(); } - - void setLast(LinkedElement* lastElement) { - lastElement->setEnd(); + LinkedElement* elementAfterCurrent = currentElement->next; + currentElement->setNext(element); + if (elementAfterCurrent != nullptr) { + element->setNext(elementAfterCurrent); } + } - void insertElement(LinkedElement* element, size_t position) { - LinkedElement *currentElement = start; - for(size_t count = 0; count < position; count++) { - if(currentElement == nullptr) { - return; - } - currentElement = currentElement->getNext(); - } - LinkedElement* elementAfterCurrent = currentElement->next; - currentElement->setNext(element); - if(elementAfterCurrent != nullptr) { - element->setNext(elementAfterCurrent); - } - } + void insertBack(LinkedElement* lastElement) { back().value->setNext(lastElement); } - void insertBack(LinkedElement* lastElement) { - back().value->setNext(lastElement); - } - -protected: - LinkedElement *start = nullptr; + protected: + LinkedElement* start = nullptr; }; #endif /* SINGLYLINKEDLIST_H_ */ diff --git a/src/fsfw/container/group.h b/src/fsfw/container/group.h index 5a39d34e..2c1ba56a 100644 --- a/src/fsfw/container/group.h +++ b/src/fsfw/container/group.h @@ -11,5 +11,4 @@ * as an Adapter to swap the endianness. */ - #endif /* GROUP_H_ */ diff --git a/src/fsfw/controller/ControllerBase.cpp b/src/fsfw/controller/ControllerBase.cpp index 86838068..953dacb4 100644 --- a/src/fsfw/controller/ControllerBase.cpp +++ b/src/fsfw/controller/ControllerBase.cpp @@ -1,138 +1,120 @@ #include "fsfw/controller/ControllerBase.h" -#include "fsfw/subsystem/SubsystemBase.h" -#include "fsfw/ipc/QueueFactory.h" #include "fsfw/action/HasActionsIF.h" +#include "fsfw/ipc/QueueFactory.h" #include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/subsystem/SubsystemBase.h" ControllerBase::ControllerBase(object_id_t setObjectId, object_id_t parentId, - size_t commandQueueDepth) : - SystemObject(setObjectId), parentId(parentId), mode(MODE_OFF), - submode(SUBMODE_NONE), modeHelper(this), - healthHelper(this, setObjectId) { - commandQueue = QueueFactory::instance()->createMessageQueue( - commandQueueDepth); + size_t commandQueueDepth) + : SystemObject(setObjectId), + parentId(parentId), + mode(MODE_OFF), + submode(SUBMODE_NONE), + modeHelper(this), + healthHelper(this, setObjectId) { + commandQueue = QueueFactory::instance()->createMessageQueue(commandQueueDepth); } -ControllerBase::~ControllerBase() { - QueueFactory::instance()->deleteMessageQueue(commandQueue); -} +ControllerBase::~ControllerBase() { QueueFactory::instance()->deleteMessageQueue(commandQueue); } ReturnValue_t ControllerBase::initialize() { - ReturnValue_t result = SystemObject::initialize(); - if (result != RETURN_OK) { - return result; + ReturnValue_t result = SystemObject::initialize(); + if (result != RETURN_OK) { + return result; + } + + MessageQueueId_t parentQueue = 0; + if (parentId != objects::NO_OBJECT) { + SubsystemBase* parent = ObjectManager::instance()->get(parentId); + if (parent == nullptr) { + return RETURN_FAILED; } + parentQueue = parent->getCommandQueue(); - MessageQueueId_t parentQueue = 0; - if (parentId != objects::NO_OBJECT) { - SubsystemBase *parent = ObjectManager::instance()->get(parentId); - if (parent == nullptr) { - return RETURN_FAILED; - } - parentQueue = parent->getCommandQueue(); + parent->registerChild(getObjectId()); + } - parent->registerChild(getObjectId()); - } + result = healthHelper.initialize(parentQueue); + if (result != RETURN_OK) { + return result; + } - result = healthHelper.initialize(parentQueue); - if (result != RETURN_OK) { - return result; - } + result = modeHelper.initialize(parentQueue); + if (result != RETURN_OK) { + return result; + } - result = modeHelper.initialize(parentQueue); - if (result != RETURN_OK) { - return result; - } - - return RETURN_OK; + return RETURN_OK; } -MessageQueueId_t ControllerBase::getCommandQueue() const { - return commandQueue->getId(); -} +MessageQueueId_t ControllerBase::getCommandQueue() const { return commandQueue->getId(); } void ControllerBase::handleQueue() { - CommandMessage command; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - for (result = commandQueue->receiveMessage(&command); - result == RETURN_OK; - result = commandQueue->receiveMessage(&command)) { - - result = modeHelper.handleModeCommand(&command); - if (result == RETURN_OK) { - continue; - } - - result = healthHelper.handleHealthCommand(&command); - if (result == RETURN_OK) { - continue; - } - result = handleCommandMessage(&command); - if (result == RETURN_OK) { - continue; - } - command.setToUnknownCommand(); - commandQueue->reply(&command); + CommandMessage command; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + for (result = commandQueue->receiveMessage(&command); result == RETURN_OK; + result = commandQueue->receiveMessage(&command)) { + result = modeHelper.handleModeCommand(&command); + if (result == RETURN_OK) { + continue; } + result = healthHelper.handleHealthCommand(&command); + if (result == RETURN_OK) { + continue; + } + result = handleCommandMessage(&command); + if (result == RETURN_OK) { + continue; + } + command.setToUnknownCommand(); + commandQueue->reply(&command); + } } void ControllerBase::startTransition(Mode_t mode, Submode_t submode) { - changeHK(this->mode, this->submode, false); - triggerEvent(CHANGING_MODE, mode, submode); - this->mode = mode; - this->submode = submode; - modeHelper.modeChanged(mode, submode); - modeChanged(mode, submode); - announceMode(false); - changeHK(this->mode, this->submode, true); + changeHK(this->mode, this->submode, false); + triggerEvent(CHANGING_MODE, mode, submode); + this->mode = mode; + this->submode = submode; + modeHelper.modeChanged(mode, submode); + modeChanged(mode, submode); + announceMode(false); + changeHK(this->mode, this->submode, true); } void ControllerBase::getMode(Mode_t* mode, Submode_t* submode) { - *mode = this->mode; - *submode = this->submode; + *mode = this->mode; + *submode = this->submode; } -void ControllerBase::setToExternalControl() { - healthHelper.setHealth(EXTERNAL_CONTROL); -} +void ControllerBase::setToExternalControl() { healthHelper.setHealth(EXTERNAL_CONTROL); } -void ControllerBase::announceMode(bool recursive) { - triggerEvent(MODE_INFO, mode, submode); -} +void ControllerBase::announceMode(bool recursive) { triggerEvent(MODE_INFO, mode, submode); } ReturnValue_t ControllerBase::performOperation(uint8_t opCode) { - handleQueue(); - performControlOperation(); - return RETURN_OK; + handleQueue(); + performControlOperation(); + return RETURN_OK; } -void ControllerBase::modeChanged(Mode_t mode, Submode_t submode) { - return; -} +void ControllerBase::modeChanged(Mode_t mode, Submode_t submode) { return; } ReturnValue_t ControllerBase::setHealth(HealthState health) { - switch (health) { + switch (health) { case HEALTHY: case EXTERNAL_CONTROL: - healthHelper.setHealth(health); - return RETURN_OK; + healthHelper.setHealth(health); + return RETURN_OK; default: - return INVALID_HEALTH_STATE; - } + return INVALID_HEALTH_STATE; + } } -HasHealthIF::HealthState ControllerBase::getHealth() { - return healthHelper.getHealth(); -} -void ControllerBase::setTaskIF(PeriodicTaskIF* task_){ - executingTask = task_; -} +HasHealthIF::HealthState ControllerBase::getHealth() { return healthHelper.getHealth(); } +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 HasReturnvaluesIF::RETURN_OK; -} +ReturnValue_t ControllerBase::initializeAfterTaskCreation() { return HasReturnvaluesIF::RETURN_OK; } diff --git a/src/fsfw/controller/ControllerBase.h b/src/fsfw/controller/ControllerBase.h index 1efe0cc1..db75982c 100644 --- a/src/fsfw/controller/ControllerBase.h +++ b/src/fsfw/controller/ControllerBase.h @@ -1,6 +1,7 @@ #ifndef FSFW_CONTROLLER_CONTROLLERBASE_H_ #define FSFW_CONTROLLER_CONTROLLERBASE_H_ +#include "fsfw/datapool/HkSwitchHelper.h" #include "fsfw/health/HasHealthIF.h" #include "fsfw/health/HealthHelper.h" #include "fsfw/modes/HasModesIF.h" @@ -8,7 +9,6 @@ #include "fsfw/objectmanager/SystemObject.h" #include "fsfw/tasks/ExecutableObjectIF.h" #include "fsfw/tasks/PeriodicTaskIF.h" -#include "fsfw/datapool/HkSwitchHelper.h" /** * @brief Generic base class for controller classes @@ -16,79 +16,77 @@ * Implements common interfaces for controllers, which generally have * a mode and a health state. This avoids boilerplate code. */ -class ControllerBase: public HasModesIF, - public HasHealthIF, - public ExecutableObjectIF, - public SystemObject, - public HasReturnvaluesIF { -public: - static const Mode_t MODE_NORMAL = 2; +class ControllerBase : public HasModesIF, + public HasHealthIF, + public ExecutableObjectIF, + public SystemObject, + public HasReturnvaluesIF { + public: + static const Mode_t MODE_NORMAL = 2; - ControllerBase(object_id_t setObjectId, object_id_t parentId, - size_t commandQueueDepth = 3); - virtual ~ControllerBase(); + ControllerBase(object_id_t setObjectId, object_id_t parentId, size_t commandQueueDepth = 3); + virtual ~ControllerBase(); - /** SystemObject override */ - virtual ReturnValue_t initialize() override; + /** SystemObject override */ + virtual ReturnValue_t initialize() override; - virtual MessageQueueId_t getCommandQueue() const override; + virtual MessageQueueId_t getCommandQueue() const override; - /** HasHealthIF overrides */ - virtual ReturnValue_t setHealth(HealthState health) override; - virtual HasHealthIF::HealthState getHealth() override; + /** HasHealthIF overrides */ + virtual ReturnValue_t setHealth(HealthState health) override; + virtual HasHealthIF::HealthState getHealth() override; - /** ExecutableObjectIF overrides */ - virtual ReturnValue_t performOperation(uint8_t opCode) override; - virtual void setTaskIF(PeriodicTaskIF* task) override; - virtual ReturnValue_t initializeAfterTaskCreation() override; + /** ExecutableObjectIF overrides */ + virtual ReturnValue_t performOperation(uint8_t opCode) override; + virtual void setTaskIF(PeriodicTaskIF *task) override; + virtual ReturnValue_t initializeAfterTaskCreation() override; -protected: + protected: + /** + * Implemented by child class. Handle command messages which are not + * mode or health messages. + * @param message + * @return + */ + virtual ReturnValue_t handleCommandMessage(CommandMessage *message) = 0; - /** - * Implemented by child class. Handle command messages which are not - * mode or health messages. - * @param message - * @return - */ - virtual ReturnValue_t handleCommandMessage(CommandMessage *message) = 0; + /** + * Periodic helper, implemented by child class. + */ + virtual void performControlOperation() = 0; - /** - * Periodic helper, implemented by child class. - */ - virtual void performControlOperation() = 0; + virtual ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, + uint32_t *msToReachTheMode) = 0; - virtual ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, - uint32_t *msToReachTheMode) = 0; + const object_id_t parentId; - const object_id_t parentId; + Mode_t mode; - Mode_t mode; + Submode_t submode; - Submode_t submode; + MessageQueueIF *commandQueue = nullptr; - MessageQueueIF* commandQueue = nullptr; + ModeHelper modeHelper; - ModeHelper modeHelper; + HealthHelper healthHelper; - HealthHelper healthHelper; + /** + * Pointer to the task which executes this component, + * is invalid before setTaskIF was called. + */ + PeriodicTaskIF *executingTask = nullptr; - /** - * Pointer to the task which executes this component, - * is invalid before setTaskIF was called. - */ - PeriodicTaskIF* executingTask = nullptr; + /** Handle mode and health messages */ + virtual void handleQueue(); - /** Handle mode and health messages */ - virtual void handleQueue(); - - /** Mode helpers */ - virtual void modeChanged(Mode_t mode, Submode_t submode); - virtual void startTransition(Mode_t mode, Submode_t submode); - virtual void getMode(Mode_t *mode, Submode_t *submode); - virtual void setToExternalControl(); - virtual void announceMode(bool recursive); - /** HK helpers */ - virtual void changeHK(Mode_t mode, Submode_t submode, bool enable); + /** Mode helpers */ + virtual void modeChanged(Mode_t mode, Submode_t submode); + virtual void startTransition(Mode_t mode, Submode_t submode); + virtual void getMode(Mode_t *mode, Submode_t *submode); + virtual void setToExternalControl(); + virtual void announceMode(bool recursive); + /** HK helpers */ + virtual void changeHK(Mode_t mode, Submode_t submode, bool enable); }; #endif /* FSFW_CONTROLLER_CONTROLLERBASE_H_ */ diff --git a/src/fsfw/controller/ExtendedControllerBase.cpp b/src/fsfw/controller/ExtendedControllerBase.cpp index f59c50a9..0dfd9dc7 100644 --- a/src/fsfw/controller/ExtendedControllerBase.cpp +++ b/src/fsfw/controller/ExtendedControllerBase.cpp @@ -1,103 +1,94 @@ #include "fsfw/controller/ExtendedControllerBase.h" -ExtendedControllerBase::ExtendedControllerBase(object_id_t objectId, - object_id_t parentId, size_t commandQueueDepth): - ControllerBase(objectId, parentId, commandQueueDepth), - poolManager(this, commandQueue), - actionHelper(this, commandQueue) { -} +ExtendedControllerBase::ExtendedControllerBase(object_id_t objectId, object_id_t parentId, + size_t commandQueueDepth) + : ControllerBase(objectId, parentId, commandQueueDepth), + poolManager(this, commandQueue), + actionHelper(this, commandQueue) {} -ExtendedControllerBase::~ExtendedControllerBase() { -} +ExtendedControllerBase::~ExtendedControllerBase() {} ReturnValue_t ExtendedControllerBase::executeAction(ActionId_t actionId, - MessageQueueId_t commandedBy, const uint8_t *data, size_t size) { - /* Needs to be overriden and implemented by child class. */ - return HasReturnvaluesIF::RETURN_OK; + MessageQueueId_t commandedBy, + const uint8_t *data, size_t size) { + /* Needs to be overriden and implemented by child class. */ + return HasReturnvaluesIF::RETURN_OK; } -object_id_t ExtendedControllerBase::getObjectId() const { - return SystemObject::getObjectId(); -} +object_id_t ExtendedControllerBase::getObjectId() const { return SystemObject::getObjectId(); } uint32_t ExtendedControllerBase::getPeriodicOperationFrequency() const { - return this->executingTask->getPeriodMs(); + return this->executingTask->getPeriodMs(); } -ReturnValue_t ExtendedControllerBase::handleCommandMessage( - CommandMessage *message) { - ReturnValue_t result = actionHelper.handleActionMessage(message); - if(result == HasReturnvaluesIF::RETURN_OK) { - return result; - } - return poolManager.handleHousekeepingMessage(message); +ReturnValue_t ExtendedControllerBase::handleCommandMessage(CommandMessage *message) { + ReturnValue_t result = actionHelper.handleActionMessage(message); + if (result == HasReturnvaluesIF::RETURN_OK) { + return result; + } + return poolManager.handleHousekeepingMessage(message); } void ExtendedControllerBase::handleQueue() { - CommandMessage command; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - for (result = commandQueue->receiveMessage(&command); - result == RETURN_OK; - result = commandQueue->receiveMessage(&command)) { - result = actionHelper.handleActionMessage(&command); - if (result == RETURN_OK) { - continue; - } - - result = modeHelper.handleModeCommand(&command); - if (result == RETURN_OK) { - continue; - } - - result = healthHelper.handleHealthCommand(&command); - if (result == RETURN_OK) { - continue; - } - - result = poolManager.handleHousekeepingMessage(&command); - if (result == RETURN_OK) { - continue; - } - - result = handleCommandMessage(&command); - if (result == RETURN_OK) { - continue; - } - command.setToUnknownCommand(); - commandQueue->reply(&command); + CommandMessage command; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + for (result = commandQueue->receiveMessage(&command); result == RETURN_OK; + result = commandQueue->receiveMessage(&command)) { + result = actionHelper.handleActionMessage(&command); + if (result == RETURN_OK) { + continue; } + + result = modeHelper.handleModeCommand(&command); + if (result == RETURN_OK) { + continue; + } + + result = healthHelper.handleHealthCommand(&command); + if (result == RETURN_OK) { + continue; + } + + result = poolManager.handleHousekeepingMessage(&command); + if (result == RETURN_OK) { + continue; + } + + result = handleCommandMessage(&command); + if (result == RETURN_OK) { + continue; + } + command.setToUnknownCommand(); + commandQueue->reply(&command); + } } ReturnValue_t ExtendedControllerBase::initialize() { - ReturnValue_t result = ControllerBase::initialize(); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = actionHelper.initialize(commandQueue); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + ReturnValue_t result = ControllerBase::initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = actionHelper.initialize(commandQueue); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - return poolManager.initialize(commandQueue); + return poolManager.initialize(commandQueue); } ReturnValue_t ExtendedControllerBase::initializeAfterTaskCreation() { - return poolManager.initializeAfterTaskCreation(); + return poolManager.initializeAfterTaskCreation(); } ReturnValue_t ExtendedControllerBase::performOperation(uint8_t opCode) { - handleQueue(); - performControlOperation(); - /* We do this after performing control operation because variables will be set changed - in this function. */ - poolManager.performHkOperation(); - return RETURN_OK; + handleQueue(); + performControlOperation(); + /* We do this after performing control operation because variables will be set changed + in this function. */ + poolManager.performHkOperation(); + return RETURN_OK; } -MessageQueueId_t ExtendedControllerBase::getCommandQueue() const { - return commandQueue->getId(); -} +MessageQueueId_t ExtendedControllerBase::getCommandQueue() const { return commandQueue->getId(); } -LocalDataPoolManager* ExtendedControllerBase::getHkManagerHandle() { - return &poolManager; -} +LocalDataPoolManager *ExtendedControllerBase::getHkManagerHandle() { return &poolManager; } diff --git a/src/fsfw/controller/ExtendedControllerBase.h b/src/fsfw/controller/ExtendedControllerBase.h index abd48637..0c64f5b9 100644 --- a/src/fsfw/controller/ExtendedControllerBase.h +++ b/src/fsfw/controller/ExtendedControllerBase.h @@ -2,7 +2,6 @@ #define FSFW_CONTROLLER_EXTENDEDCONTROLLERBASE_H_ #include "ControllerBase.h" - #include "fsfw/action.h" #include "fsfw/datapoollocal/HasLocalDataPoolIF.h" #include "fsfw/datapoollocal/LocalDataPoolManager.h" @@ -14,62 +13,58 @@ * variables. Default implementations required for the interfaces will be empty and have * to be implemented by child class. */ -class ExtendedControllerBase: public ControllerBase, - public HasActionsIF, - public HasLocalDataPoolIF { -public: - ExtendedControllerBase(object_id_t objectId, object_id_t parentId, - size_t commandQueueDepth = 3); - virtual ~ExtendedControllerBase(); +class ExtendedControllerBase : public ControllerBase, + public HasActionsIF, + public HasLocalDataPoolIF { + public: + ExtendedControllerBase(object_id_t objectId, object_id_t parentId, size_t commandQueueDepth = 3); + virtual ~ExtendedControllerBase(); - /* SystemObjectIF overrides */ - virtual ReturnValue_t initialize() override; + /* SystemObjectIF overrides */ + virtual ReturnValue_t initialize() override; - virtual MessageQueueId_t getCommandQueue() const override; + virtual MessageQueueId_t getCommandQueue() const override; - /* ExecutableObjectIF overrides */ - virtual ReturnValue_t performOperation(uint8_t opCode) override; - virtual ReturnValue_t initializeAfterTaskCreation() override; + /* ExecutableObjectIF overrides */ + virtual ReturnValue_t performOperation(uint8_t opCode) override; + virtual ReturnValue_t initializeAfterTaskCreation() override; -protected: - LocalDataPoolManager poolManager; - ActionHelper actionHelper; + protected: + LocalDataPoolManager poolManager; + ActionHelper actionHelper; - /** - * Implemented by child class. Handle all command messages which are - * not health, mode, action or housekeeping messages. - * @param message - * @return - */ - virtual ReturnValue_t handleCommandMessage(CommandMessage *message) = 0; + /** + * Implemented by child class. Handle all command messages which are + * not health, mode, action or housekeeping messages. + * @param message + * @return + */ + virtual ReturnValue_t handleCommandMessage(CommandMessage* message) = 0; - /** - * Periodic helper from ControllerBase, implemented by child class. - */ - virtual void performControlOperation() = 0; + /** + * Periodic helper from ControllerBase, implemented by child class. + */ + virtual void performControlOperation() = 0; - /* Handle the four messages mentioned above */ - void handleQueue() override; + /* Handle the four messages mentioned above */ + void handleQueue() override; - /* HasActionsIF overrides */ - virtual ReturnValue_t executeAction(ActionId_t actionId, - MessageQueueId_t commandedBy, const uint8_t* data, - size_t size) override; + /* HasActionsIF overrides */ + virtual ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, + const uint8_t* data, size_t size) override; - /* HasLocalDatapoolIF overrides */ - virtual LocalDataPoolManager* getHkManagerHandle() override; - virtual object_id_t getObjectId() const override; - virtual uint32_t getPeriodicOperationFrequency() const override; + /* HasLocalDatapoolIF overrides */ + virtual LocalDataPoolManager* getHkManagerHandle() override; + virtual object_id_t getObjectId() const override; + virtual uint32_t getPeriodicOperationFrequency() const override; - virtual ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, - LocalDataPoolManager& poolManager) override = 0; - virtual LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override = 0; + virtual ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) override = 0; + virtual LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override = 0; - // Mode abstract functions - virtual ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, - uint32_t *msToReachTheMode) override = 0; + // Mode abstract functions + virtual ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, + uint32_t* msToReachTheMode) override = 0; }; - - #endif /* FSFW_CONTROLLER_EXTENDEDCONTROLLERBASE_H_ */ diff --git a/src/fsfw/coordinates/CoordinateTransformations.cpp b/src/fsfw/coordinates/CoordinateTransformations.cpp index fe879dd1..322a7f0d 100644 --- a/src/fsfw/coordinates/CoordinateTransformations.cpp +++ b/src/fsfw/coordinates/CoordinateTransformations.cpp @@ -1,230 +1,209 @@ #include "fsfw/coordinates/CoordinateTransformations.h" + +#include +#include + #include "fsfw/globalfunctions/constants.h" #include "fsfw/globalfunctions/math/MatrixOperations.h" #include "fsfw/globalfunctions/math/VectorOperations.h" -#include -#include - - -void CoordinateTransformations::positionEcfToEci(const double* ecfPosition, - double* eciPosition, timeval *timeUTC) { - ecfToEci(ecfPosition, eciPosition, NULL, timeUTC); - +void CoordinateTransformations::positionEcfToEci(const double* ecfPosition, double* eciPosition, + timeval* timeUTC) { + ecfToEci(ecfPosition, eciPosition, NULL, timeUTC); } void CoordinateTransformations::velocityEcfToEci(const double* ecfVelocity, - const double* ecfPosition, double* eciVelocity, timeval *timeUTC) { - ecfToEci(ecfVelocity, eciVelocity, ecfPosition, timeUTC); + const double* ecfPosition, double* eciVelocity, + timeval* timeUTC) { + ecfToEci(ecfVelocity, eciVelocity, ecfPosition, timeUTC); } void CoordinateTransformations::positionEciToEcf(const double* eciCoordinates, - double* ecfCoordinates,timeval *timeUTC){ - eciToEcf(eciCoordinates,ecfCoordinates,NULL,timeUTC); + double* ecfCoordinates, timeval* timeUTC) { + eciToEcf(eciCoordinates, ecfCoordinates, NULL, timeUTC); }; void CoordinateTransformations::velocityEciToEcf(const double* eciVelocity, - const double* eciPosition, double* ecfVelocity,timeval* timeUTC){ - eciToEcf(eciVelocity,ecfVelocity,eciPosition,timeUTC); + const double* eciPosition, double* ecfVelocity, + timeval* timeUTC) { + eciToEcf(eciVelocity, ecfVelocity, eciPosition, timeUTC); } double CoordinateTransformations::getEarthRotationAngle(timeval timeUTC) { + double jD2000UTC; + Clock::convertTimevalToJD2000(timeUTC, &jD2000UTC); - double jD2000UTC; - Clock::convertTimevalToJD2000(timeUTC, &jD2000UTC); + double TTt2000 = getJuleanCenturiesTT(timeUTC); - double TTt2000 = getJuleanCenturiesTT(timeUTC); + double theta = 2 * Math::PI * (0.779057273264 + 1.00273781191135448 * jD2000UTC); - double theta = 2 * Math::PI - * (0.779057273264 + 1.00273781191135448 * jD2000UTC); - - //Correct theta according to IAU 2000 precession-nutation model - theta = theta + 7.03270725817493E-008 + 0.0223603701 * TTt2000 - + 6.77128219501896E-006 * TTt2000 * TTt2000 - + 4.5300990362875E-010 * TTt2000 * TTt2000 * TTt2000 - + 9.12419347848147E-011 * TTt2000 * TTt2000 * TTt2000 * TTt2000; - return theta; + // Correct theta according to IAU 2000 precession-nutation model + theta = theta + 7.03270725817493E-008 + 0.0223603701 * TTt2000 + + 6.77128219501896E-006 * TTt2000 * TTt2000 + + 4.5300990362875E-010 * TTt2000 * TTt2000 * TTt2000 + + 9.12419347848147E-011 * TTt2000 * TTt2000 * TTt2000 * TTt2000; + return theta; } -void CoordinateTransformations::getEarthRotationMatrix(timeval timeUTC, - double matrix[][3]) { - double theta = getEarthRotationAngle(timeUTC); +void CoordinateTransformations::getEarthRotationMatrix(timeval timeUTC, double matrix[][3]) { + double theta = getEarthRotationAngle(timeUTC); - matrix[0][0] = cos(theta); - matrix[0][1] = sin(theta); - matrix[0][2] = 0; - matrix[1][0] = -sin(theta); - matrix[1][1] = cos(theta); - matrix[1][2] = 0; - matrix[2][0] = 0; - matrix[2][1] = 0; - matrix[2][2] = 1; + matrix[0][0] = cos(theta); + matrix[0][1] = sin(theta); + matrix[0][2] = 0; + matrix[1][0] = -sin(theta); + matrix[1][1] = cos(theta); + matrix[1][2] = 0; + matrix[2][0] = 0; + matrix[2][1] = 0; + matrix[2][2] = 1; } -void CoordinateTransformations::ecfToEci(const double* ecfCoordinates, - double* eciCoordinates, - const double* ecfPositionIfCoordinatesAreVelocity, timeval *timeUTCin) { +void CoordinateTransformations::ecfToEci(const double* ecfCoordinates, double* eciCoordinates, + const double* ecfPositionIfCoordinatesAreVelocity, + timeval* timeUTCin) { + timeval timeUTC; + if (timeUTCin != NULL) { + timeUTC = *timeUTCin; + } else { + Clock::getClock_timeval(&timeUTC); + } - timeval timeUTC; - if (timeUTCin != NULL) { - timeUTC = *timeUTCin; - } else { - Clock::getClock_timeval(&timeUTC); - } + double Tfi[3][3]; + double Tif[3][3]; + getTransMatrixECITOECF(timeUTC, Tfi); - double Tfi[3][3]; - double Tif[3][3]; - getTransMatrixECITOECF(timeUTC,Tfi); + MatrixOperations::transpose(Tfi[0], Tif[0], 3); - MatrixOperations::transpose(Tfi[0], Tif[0], 3); + MatrixOperations::multiply(Tif[0], ecfCoordinates, eciCoordinates, 3, 3, 1); - MatrixOperations::multiply(Tif[0], ecfCoordinates, eciCoordinates, - 3, 3, 1); + if (ecfPositionIfCoordinatesAreVelocity != NULL) { + double Tdotfi[3][3]; + double Tdotif[3][3]; + double Trot[3][3] = {{0, Earth::OMEGA, 0}, {0 - Earth::OMEGA, 0, 0}, {0, 0, 0}}; + MatrixOperations::multiply(Trot[0], Tfi[0], Tdotfi[0], 3, 3, 3); + MatrixOperations::transpose(Tdotfi[0], Tdotif[0], 3); + double velocityCorrection[3]; - if (ecfPositionIfCoordinatesAreVelocity != NULL) { + MatrixOperations::multiply(Tdotif[0], ecfPositionIfCoordinatesAreVelocity, + velocityCorrection, 3, 3, 1); - double Tdotfi[3][3]; - double Tdotif[3][3]; - double Trot[3][3] = { { 0, Earth::OMEGA, 0 }, - { 0 - Earth::OMEGA, 0, 0 }, { 0, 0, 0 } }; - - MatrixOperations::multiply(Trot[0], Tfi[0], Tdotfi[0], 3, 3, - 3); - - MatrixOperations::transpose(Tdotfi[0], Tdotif[0], 3); - - double velocityCorrection[3]; - - MatrixOperations::multiply(Tdotif[0], - ecfPositionIfCoordinatesAreVelocity, velocityCorrection, 3, 3, - 1); - - VectorOperations::add(velocityCorrection, eciCoordinates, - eciCoordinates, 3); - } + VectorOperations::add(velocityCorrection, eciCoordinates, eciCoordinates, 3); + } } double CoordinateTransformations::getJuleanCenturiesTT(timeval timeUTC) { - timeval timeTT; - Clock::convertUTCToTT(timeUTC, &timeTT); - double jD2000TT; - Clock::convertTimevalToJD2000(timeTT, &jD2000TT); + timeval timeTT; + Clock::convertUTCToTT(timeUTC, &timeTT); + double jD2000TT; + Clock::convertTimevalToJD2000(timeTT, &jD2000TT); - return jD2000TT / 36525.; + return jD2000TT / 36525.; } -void CoordinateTransformations::eciToEcf(const double* eciCoordinates, - double* ecfCoordinates, - const double* eciPositionIfCoordinatesAreVelocity,timeval *timeUTCin){ - timeval timeUTC; - if (timeUTCin != NULL) { - timeUTC = *timeUTCin; - }else{ - Clock::getClock_timeval(&timeUTC); - } +void CoordinateTransformations::eciToEcf(const double* eciCoordinates, double* ecfCoordinates, + const double* eciPositionIfCoordinatesAreVelocity, + timeval* timeUTCin) { + timeval timeUTC; + if (timeUTCin != NULL) { + timeUTC = *timeUTCin; + } else { + Clock::getClock_timeval(&timeUTC); + } - double Tfi[3][3]; + double Tfi[3][3]; - getTransMatrixECITOECF(timeUTC,Tfi); + getTransMatrixECITOECF(timeUTC, Tfi); - MatrixOperations::multiply(Tfi[0],eciCoordinates,ecfCoordinates,3,3,1); + MatrixOperations::multiply(Tfi[0], eciCoordinates, ecfCoordinates, 3, 3, 1); - if (eciPositionIfCoordinatesAreVelocity != NULL) { + if (eciPositionIfCoordinatesAreVelocity != NULL) { + double Tdotfi[3][3]; + double Trot[3][3] = {{0, Earth::OMEGA, 0}, {0 - Earth::OMEGA, 0, 0}, {0, 0, 0}}; - double Tdotfi[3][3]; - double Trot[3][3] = { { 0, Earth::OMEGA, 0 }, - { 0 - Earth::OMEGA, 0, 0 }, { 0, 0, 0 } }; + MatrixOperations::multiply(Trot[0], Tfi[0], Tdotfi[0], 3, 3, 3); - MatrixOperations::multiply(Trot[0], Tfi[0], Tdotfi[0], 3, 3, - 3); + double velocityCorrection[3]; - double velocityCorrection[3]; + MatrixOperations::multiply(Tdotfi[0], eciPositionIfCoordinatesAreVelocity, + velocityCorrection, 3, 3, 1); - MatrixOperations::multiply(Tdotfi[0], - eciPositionIfCoordinatesAreVelocity, velocityCorrection, 3, 3, - 1); - - VectorOperations::add(ecfCoordinates, velocityCorrection, - ecfCoordinates, 3); - } + VectorOperations::add(ecfCoordinates, velocityCorrection, ecfCoordinates, 3); + } }; -void CoordinateTransformations::getTransMatrixECITOECF(timeval timeUTC,double Tfi[3][3]){ - double TTt2000 = getJuleanCenturiesTT(timeUTC); +void CoordinateTransformations::getTransMatrixECITOECF(timeval timeUTC, double Tfi[3][3]) { + double TTt2000 = getJuleanCenturiesTT(timeUTC); - ////////////////////////////////////////////////////////// - // Calculate Precession Matrix + ////////////////////////////////////////////////////////// + // Calculate Precession Matrix - double zeta = 0.0111808609 * TTt2000 - + 1.46355554053347E-006 * TTt2000 * TTt2000 - + 8.72567663260943E-008 * TTt2000 * TTt2000 * TTt2000; - double theta_p = 0.0097171735 * TTt2000 - - 2.06845757045384E-006 * TTt2000 * TTt2000 - - 2.02812107218552E-007 * TTt2000 * TTt2000 * TTt2000; - double z = zeta + 3.8436028638364E-006 * TTt2000 * TTt2000 - + 0.000000001 * TTt2000 * TTt2000 * TTt2000; + double zeta = 0.0111808609 * TTt2000 + 1.46355554053347E-006 * TTt2000 * TTt2000 + + 8.72567663260943E-008 * TTt2000 * TTt2000 * TTt2000; + double theta_p = 0.0097171735 * TTt2000 - 2.06845757045384E-006 * TTt2000 * TTt2000 - + 2.02812107218552E-007 * TTt2000 * TTt2000 * TTt2000; + double z = + zeta + 3.8436028638364E-006 * TTt2000 * TTt2000 + 0.000000001 * TTt2000 * TTt2000 * TTt2000; - double mPrecession[3][3]; + double mPrecession[3][3]; - mPrecession[0][0] = -sin(z) * sin(zeta) + cos(z) * cos(theta_p) * cos(zeta); - mPrecession[1][0] = cos(z) * sin(zeta) + sin(z) * cos(theta_p) * cos(zeta); - mPrecession[2][0] = sin(theta_p) * cos(zeta); + mPrecession[0][0] = -sin(z) * sin(zeta) + cos(z) * cos(theta_p) * cos(zeta); + mPrecession[1][0] = cos(z) * sin(zeta) + sin(z) * cos(theta_p) * cos(zeta); + mPrecession[2][0] = sin(theta_p) * cos(zeta); - mPrecession[0][1] = -sin(z) * cos(zeta) - cos(z) * cos(theta_p) * sin(zeta); - mPrecession[1][1] = cos(z) * cos(zeta) - sin(z) * cos(theta_p) * sin(zeta); - mPrecession[2][1] = -sin(theta_p) * sin(zeta); + mPrecession[0][1] = -sin(z) * cos(zeta) - cos(z) * cos(theta_p) * sin(zeta); + mPrecession[1][1] = cos(z) * cos(zeta) - sin(z) * cos(theta_p) * sin(zeta); + mPrecession[2][1] = -sin(theta_p) * sin(zeta); - mPrecession[0][2] = -cos(z) * sin(theta_p); - mPrecession[1][2] = -sin(z) * sin(theta_p); - mPrecession[2][2] = cos(theta_p); + mPrecession[0][2] = -cos(z) * sin(theta_p); + mPrecession[1][2] = -sin(z) * sin(theta_p); + mPrecession[2][2] = cos(theta_p); - ////////////////////////////////////////////////////////// - // Calculate Nutation Matrix + ////////////////////////////////////////////////////////// + // Calculate Nutation Matrix - double omega_moon = 2.1824386244 - 33.7570459338 * TTt2000 - + 3.61428599267159E-005 * TTt2000 * TTt2000 - + 3.87850944887629E-008 * TTt2000 * TTt2000 * TTt2000; + double omega_moon = 2.1824386244 - 33.7570459338 * TTt2000 + + 3.61428599267159E-005 * TTt2000 * TTt2000 + + 3.87850944887629E-008 * TTt2000 * TTt2000 * TTt2000; - double deltaPsi = -0.000083388 * sin(omega_moon); - double deltaEpsilon = 4.46174030725106E-005 * cos(omega_moon); + double deltaPsi = -0.000083388 * sin(omega_moon); + double deltaEpsilon = 4.46174030725106E-005 * cos(omega_moon); - double epsilon = 0.4090928042 - 0.0002269655 * TTt2000 - - 2.86040071854626E-009 * TTt2000 * TTt2000 - + 8.78967203851589E-009 * TTt2000 * TTt2000 * TTt2000; + double epsilon = 0.4090928042 - 0.0002269655 * TTt2000 - + 2.86040071854626E-009 * TTt2000 * TTt2000 + + 8.78967203851589E-009 * TTt2000 * TTt2000 * TTt2000; + double mNutation[3][3]; - double mNutation[3][3]; + mNutation[0][0] = cos(deltaPsi); + mNutation[1][0] = cos(epsilon + deltaEpsilon) * sin(deltaPsi); + mNutation[2][0] = sin(epsilon + deltaEpsilon) * sin(deltaPsi); - mNutation[0][0] = cos(deltaPsi); - mNutation[1][0] = cos(epsilon + deltaEpsilon) * sin(deltaPsi); - mNutation[2][0] = sin(epsilon + deltaEpsilon) * sin(deltaPsi); + mNutation[0][1] = -cos(epsilon) * sin(deltaPsi); + mNutation[1][1] = cos(epsilon) * cos(epsilon + deltaEpsilon) * cos(deltaPsi) + + sin(epsilon) * sin(epsilon + deltaEpsilon); + mNutation[2][1] = cos(epsilon) * sin(epsilon + deltaEpsilon) * cos(deltaPsi) - + sin(epsilon) * cos(epsilon + deltaEpsilon); - mNutation[0][1] = -cos(epsilon) * sin(deltaPsi); - mNutation[1][1] = cos(epsilon) * cos(epsilon + deltaEpsilon) * cos(deltaPsi) - + sin(epsilon) * sin(epsilon + deltaEpsilon); - mNutation[2][1] = cos(epsilon) * sin(epsilon + deltaEpsilon) * cos(deltaPsi) - - sin(epsilon) * cos(epsilon + deltaEpsilon); + mNutation[0][2] = -sin(epsilon) * sin(deltaPsi); + mNutation[1][2] = sin(epsilon) * cos(epsilon + deltaEpsilon) * cos(deltaPsi) - + cos(epsilon) * sin(epsilon + deltaEpsilon); + mNutation[2][2] = sin(epsilon) * sin(epsilon + deltaEpsilon) * cos(deltaPsi) + + cos(epsilon) * cos(epsilon + deltaEpsilon); - mNutation[0][2] = -sin(epsilon) * sin(deltaPsi); - mNutation[1][2] = sin(epsilon) * cos(epsilon + deltaEpsilon) * cos(deltaPsi) - - cos(epsilon) * sin(epsilon + deltaEpsilon); - mNutation[2][2] = sin(epsilon) * sin(epsilon + deltaEpsilon) * cos(deltaPsi) - + cos(epsilon) * cos(epsilon + deltaEpsilon); + ////////////////////////////////////////////////////////// + // Calculate Earth rotation matrix + // calculate theta - ////////////////////////////////////////////////////////// - // Calculate Earth rotation matrix - //calculate theta + double mTheta[3][3]; + double Ttemp[3][3]; + getEarthRotationMatrix(timeUTC, mTheta); - double mTheta[3][3]; - double Ttemp[3][3]; - getEarthRotationMatrix(timeUTC, mTheta); + // polar motion is neglected + MatrixOperations::multiply(mNutation[0], mPrecession[0], Ttemp[0], 3, 3, 3); - //polar motion is neglected - MatrixOperations::multiply(mNutation[0], mPrecession[0], Ttemp[0], - 3, 3, 3); - - MatrixOperations::multiply(mTheta[0], Ttemp[0], Tfi[0], 3, 3, 3); + MatrixOperations::multiply(mTheta[0], Ttemp[0], Tfi[0], 3, 3, 3); }; diff --git a/src/fsfw/coordinates/CoordinateTransformations.h b/src/fsfw/coordinates/CoordinateTransformations.h index ddc715d1..d3760388 100644 --- a/src/fsfw/coordinates/CoordinateTransformations.h +++ b/src/fsfw/coordinates/CoordinateTransformations.h @@ -1,35 +1,37 @@ #ifndef COORDINATETRANSFORMATIONS_H_ #define COORDINATETRANSFORMATIONS_H_ -#include "coordinatesConf.h" -#include "fsfw/timemanager/Clock.h" #include +#include "coordinatesConf.h" +#include "fsfw/timemanager/Clock.h" + class CoordinateTransformations { -public: - static void positionEcfToEci(const double* ecfCoordinates, double* eciCoordinates, timeval *timeUTC = NULL); + public: + static void positionEcfToEci(const double* ecfCoordinates, double* eciCoordinates, + timeval* timeUTC = NULL); - static void velocityEcfToEci(const double* ecfVelocity, - const double* ecfPosition, - double* eciVelocity, timeval *timeUTC = NULL); + static void velocityEcfToEci(const double* ecfVelocity, const double* ecfPosition, + double* eciVelocity, timeval* timeUTC = NULL); - static void positionEciToEcf(const double* eciCoordinates, double* ecfCoordinates,timeval *timeUTC = NULL); - static void velocityEciToEcf(const double* eciVelocity,const double* eciPosition, double* ecfVelocity,timeval* timeUTC = NULL); + static void positionEciToEcf(const double* eciCoordinates, double* ecfCoordinates, + timeval* timeUTC = NULL); + static void velocityEciToEcf(const double* eciVelocity, const double* eciPosition, + double* ecfVelocity, timeval* timeUTC = NULL); - static double getEarthRotationAngle(timeval timeUTC); + static double getEarthRotationAngle(timeval timeUTC); - static void getEarthRotationMatrix(timeval timeUTC, double matrix[][3]); -private: - CoordinateTransformations(); - static void ecfToEci(const double* ecfCoordinates, double* eciCoordinates, - const double* ecfPositionIfCoordinatesAreVelocity, timeval *timeUTCin); - static void eciToEcf(const double* eciCoordinates, - double* ecfCoordinates, - const double* eciPositionIfCoordinatesAreVelocity,timeval *timeUTCin); + static void getEarthRotationMatrix(timeval timeUTC, double matrix[][3]); - static double getJuleanCenturiesTT(timeval timeUTC); - static void getTransMatrixECITOECF(timeval time,double Tfi[3][3]); + private: + CoordinateTransformations(); + static void ecfToEci(const double* ecfCoordinates, double* eciCoordinates, + const double* ecfPositionIfCoordinatesAreVelocity, timeval* timeUTCin); + static void eciToEcf(const double* eciCoordinates, double* ecfCoordinates, + const double* eciPositionIfCoordinatesAreVelocity, timeval* timeUTCin); + static double getJuleanCenturiesTT(timeval timeUTC); + static void getTransMatrixECITOECF(timeval time, double Tfi[3][3]); }; #endif /* COORDINATETRANSFORMATIONS_H_ */ diff --git a/src/fsfw/coordinates/Jgm3Model.h b/src/fsfw/coordinates/Jgm3Model.h index 0eeaf08f..e0be20a3 100644 --- a/src/fsfw/coordinates/Jgm3Model.h +++ b/src/fsfw/coordinates/Jgm3Model.h @@ -1,181 +1,185 @@ #ifndef FRAMEWORK_COORDINATES_JGM3MODEL_H_ #define FRAMEWORK_COORDINATES_JGM3MODEL_H_ -#include "coordinatesConf.h" -#include "CoordinateTransformations.h" - -#include "fsfw/globalfunctions/math/VectorOperations.h" -#include "fsfw/globalfunctions/timevalOperations.h" -#include "fsfw/globalfunctions/constants.h" #include + #include -template +#include "CoordinateTransformations.h" +#include "coordinatesConf.h" +#include "fsfw/globalfunctions/constants.h" +#include "fsfw/globalfunctions/math/VectorOperations.h" +#include "fsfw/globalfunctions/timevalOperations.h" + +template class Jgm3Model { -public: - static const uint32_t factorialLookupTable[DEGREE+3]; //This table is used instead of factorial calculation, must be increased if order or degree is higher + public: + static const uint32_t + factorialLookupTable[DEGREE + 3]; // This table is used instead of factorial calculation, + // must be increased if order or degree is higher - Jgm3Model() { - y0[0] = 0; - y0[1] = 0; - y0[2] = 0; - y0[3] = 0; - y0[4] = 0; - y0[5] = 0; + Jgm3Model() { + y0[0] = 0; + y0[1] = 0; + y0[2] = 0; + y0[3] = 0; + y0[4] = 0; + y0[5] = 0; - lastExecutionTime.tv_sec = 0; - lastExecutionTime.tv_usec = 0; - } - virtual ~Jgm3Model(){}; + lastExecutionTime.tv_sec = 0; + lastExecutionTime.tv_usec = 0; + } + virtual ~Jgm3Model(){}; - //double acsNavOrbit(double posECF[3],double velECF[3],timeval gpsTime); + // double acsNavOrbit(double posECF[3],double velECF[3],timeval gpsTime); - double y0[6]; //position and velocity at beginning of RK step in EC - timeval lastExecutionTime; //Time of last execution + double y0[6]; // position and velocity at beginning of RK step in EC + timeval lastExecutionTime; // Time of last execution + void accelDegOrd(const double pos[3], const double S[ORDER + 1][DEGREE + 1], + const double C[ORDER + 1][DEGREE + 1], double* accel) { + // Get radius of this position + double r = VectorOperations::norm(pos, 3); - void accelDegOrd(const double pos[3],const double S[ORDER+1][DEGREE+1],const double C[ORDER+1][DEGREE+1],double* accel){ - //Get radius of this position - double r = VectorOperations::norm(pos,3); + // Initialize the V and W matrix + double V[DEGREE + 2][ORDER + 2] = {{0}}; + double W[DEGREE + 2][ORDER + 2] = {{0}}; + for (uint8_t m = 0; m < (ORDER + 2); m++) { + for (uint8_t n = m; n < (DEGREE + 2); n++) { + if ((n == 0) && (m == 0)) { + // Montenbruck "Satellite Orbits Eq.3.31" + V[0][0] = Earth::MEAN_RADIUS / r; + W[0][0] = 0; + } else { + if (n == m) { + // Montenbruck "Satellite Orbits Eq.3.29" + V[m][m] = (2 * m - 1) * (pos[0] * Earth::MEAN_RADIUS / pow(r, 2) * V[m - 1][m - 1] - + pos[1] * Earth::MEAN_RADIUS / pow(r, 2) * W[m - 1][m - 1]); + W[m][m] = (2 * m - 1) * (pos[0] * Earth::MEAN_RADIUS / pow(r, 2) * W[m - 1][m - 1] + + pos[1] * Earth::MEAN_RADIUS / pow(r, 2) * V[m - 1][m - 1]); + } else { + // Montenbruck "Satellite Orbits Eq.3.30" + V[n][m] = ((2 * n - 1) / (double)(n - m)) * pos[2] * Earth::MEAN_RADIUS / pow(r, 2) * + V[n - 1][m]; + W[n][m] = ((2 * n - 1) / (double)(n - m)) * pos[2] * Earth::MEAN_RADIUS / pow(r, 2) * + W[n - 1][m]; + if (n != (m + 1)) { + V[n][m] = V[n][m] - (((n + m - 1) / (double)(n - m)) * + (pow(Earth::MEAN_RADIUS, 2) / pow(r, 2)) * V[n - 2][m]); + W[n][m] = W[n][m] - (((n + m - 1) / (double)(n - m)) * + (pow(Earth::MEAN_RADIUS, 2) / pow(r, 2)) * W[n - 2][m]); + } // End of if(n!=(m+1)) + } // End of if(n==m){ + } // End of if(n==0 and m==0) + } // End of for(uint8_t n=0;n<(DEGREE+1);n++) + } // End of for(uint8_t m=0;m<(ORDER+1);m++) + // overwrite accel if not properly initialized + accel[0] = 0; + accel[1] = 0; + accel[2] = 0; - //Initialize the V and W matrix - double V[DEGREE+2][ORDER+2] = {{0}}; - double W[DEGREE+2][ORDER+2] = {{0}}; + for (uint8_t m = 0; m < (ORDER + 1); m++) { + for (uint8_t n = m; n < (DEGREE + 1); n++) { + // Use table lookup to get factorial + double partAccel[3] = {0}; + double factor = Earth::STANDARD_GRAVITATIONAL_PARAMETER / pow(Earth::MEAN_RADIUS, 2); + if (m == 0) { + // Montenbruck "Satellite Orbits Eq.3.33" + partAccel[0] = factor * (-C[n][0] * V[n + 1][1]); + partAccel[1] = factor * (-C[n][0] * W[n + 1][1]); + } else { + double factMN = static_cast(factorialLookupTable[n - m + 2]) / + static_cast(factorialLookupTable[n - m]); + partAccel[0] = factor * 0.5 * + ((-C[n][m] * V[n + 1][m + 1] - S[n][m] * W[n + 1][m + 1]) + + factMN * (C[n][m] * V[n + 1][m - 1] + S[n][m] * W[n + 1][m - 1])); + partAccel[1] = factor * 0.5 * + ((-C[n][m] * W[n + 1][m + 1] + S[n][m] * V[n + 1][m + 1]) + + factMN * (-C[n][m] * W[n + 1][m - 1] + S[n][m] * V[n + 1][m - 1])); + } - for(uint8_t m=0;m<(ORDER+2);m++){ - for(uint8_t n=m;n<(DEGREE+2);n++){ - if((n==0) && (m==0)){ - //Montenbruck "Satellite Orbits Eq.3.31" - V[0][0] = Earth::MEAN_RADIUS / r; - W[0][0] = 0; - }else{ - if(n==m){ - //Montenbruck "Satellite Orbits Eq.3.29" - V[m][m] = (2*m-1)* (pos[0]*Earth::MEAN_RADIUS/pow(r,2)*V[m-1][m-1] - pos[1]*Earth::MEAN_RADIUS/pow(r,2)*W[m-1][m-1]); - W[m][m] = (2*m-1)* (pos[0]*Earth::MEAN_RADIUS/pow(r,2)*W[m-1][m-1] + pos[1]*Earth::MEAN_RADIUS/pow(r,2)*V[m-1][m-1]); - }else{ - //Montenbruck "Satellite Orbits Eq.3.30" - V[n][m] = ((2*n-1)/(double)(n-m))*pos[2]*Earth::MEAN_RADIUS / pow(r,2)*V[n-1][m]; - W[n][m] = ((2*n-1)/(double)(n-m))*pos[2]*Earth::MEAN_RADIUS / pow(r,2)*W[n-1][m]; - if(n!=(m+1)){ - V[n][m] = V[n][m] - (((n+m-1)/(double)(n-m)) * (pow(Earth::MEAN_RADIUS,2) / pow(r,2)) * V[n-2][m]); - W[n][m] = W[n][m] - (((n+m-1)/(double)(n-m)) * (pow(Earth::MEAN_RADIUS,2) / pow(r,2)) * W[n-2][m]); - }//End of if(n!=(m+1)) - }//End of if(n==m){ - }//End of if(n==0 and m==0) - }//End of for(uint8_t n=0;n<(DEGREE+1);n++) - }//End of for(uint8_t m=0;m<(ORDER+1);m++) + partAccel[2] = factor * ((n - m + 1) * (-C[n][m] * V[n + 1][m] - S[n][m] * W[n + 1][m])); + accel[0] += partAccel[0]; + accel[1] += partAccel[1]; + accel[2] += partAccel[2]; + } // End of for(uint8_t n=0;n(factorialLookupTable[n-m+2]) / static_cast(factorialLookupTable[n-m]); - partAccel[0] = factor * 0.5 * ((-C[n][m]*V[n+1][m+1]-S[n][m]*W[n+1][m+1])+factMN*(C[n][m]*V[n+1][m-1]+S[n][m]*W[n+1][m-1])); - partAccel[1] = factor * 0.5 * ((-C[n][m]*W[n+1][m+1]+S[n][m]*V[n+1][m+1])+factMN*(-C[n][m]*W[n+1][m-1]+S[n][m]*V[n+1][m-1])); - } + void acsNavOrbit(timeval timeUTC, const double S[ORDER + 1][DEGREE + 1], + const double C[ORDER + 1][DEGREE + 1], double outputPos[3], + double outputVel[3]) { + // RK4 Integration for this timestamp + double deltaT = timevalOperations::toDouble(timeUTC - lastExecutionTime); - partAccel[2] = factor * ((n-m+1)*(-C[n][m]*V[n+1][m]-S[n][m]*W[n+1][m])); + double y0dot[6] = {0, 0, 0, 0, 0, 0}; + double yA[6] = {0, 0, 0, 0, 0, 0}; + double yAdot[6] = {0, 0, 0, 0, 0, 0}; + double yB[6] = {0, 0, 0, 0, 0, 0}; + double yBdot[6] = {0, 0, 0, 0, 0, 0}; + double yC[6] = {0, 0, 0, 0, 0, 0}; + double yCdot[6] = {0, 0, 0, 0, 0, 0}; + // Step One + rungeKuttaStep(y0, y0dot, lastExecutionTime, S, C); - accel[0] += partAccel[0]; - accel[1] += partAccel[1]; - accel[2] += partAccel[2]; - }//End of for(uint8_t n=0;n::mulScalar(y0dot, deltaT / 2, yA, 6); + VectorOperations::add(y0, yA, yA, 6); + rungeKuttaStep(yA, yAdot, lastExecutionTime, S, C); - void initializeNavOrbit(const double position[3],const double velocity[3], timeval timeUTC){ - CoordinateTransformations::positionEcfToEci(position,&y0[0],&timeUTC); - CoordinateTransformations::velocityEcfToEci(velocity,position,&y0[3],&timeUTC); - lastExecutionTime = timeUTC; - } + // Step Three + VectorOperations::mulScalar(yAdot, deltaT / 2, yB, 6); + VectorOperations::add(y0, yB, yB, 6); + rungeKuttaStep(yB, yBdot, lastExecutionTime, S, C); + // Step Four + VectorOperations::mulScalar(yBdot, deltaT, yC, 6); + VectorOperations::add(y0, yC, yC, 6); + rungeKuttaStep(yC, yCdot, lastExecutionTime, S, C); - void acsNavOrbit(timeval timeUTC, const double S[ORDER+1][DEGREE+1],const double C[ORDER+1][DEGREE+1], double outputPos[3],double outputVel[3]){ + // Calc new State + VectorOperations::mulScalar(yAdot, 2, yAdot, 6); + VectorOperations::mulScalar(yBdot, 2, yBdot, 6); + VectorOperations::add(y0dot, yAdot, y0dot, 6); + VectorOperations::add(y0dot, yBdot, y0dot, 6); + VectorOperations::add(y0dot, yCdot, y0dot, 6); + VectorOperations::mulScalar(y0dot, 1. / 6. * deltaT, y0dot, 6); + VectorOperations::add(y0, y0dot, y0, 6); - //RK4 Integration for this timestamp - double deltaT = timevalOperations::toDouble(timeUTC-lastExecutionTime); + CoordinateTransformations::positionEciToEcf(&y0[0], outputPos, &timeUTC); + CoordinateTransformations::velocityEciToEcf(&y0[3], &y0[0], outputVel, &timeUTC); - double y0dot[6] = {0,0,0,0,0,0}; - double yA[6] = {0,0,0,0,0,0}; - double yAdot[6] = {0,0,0,0,0,0}; - double yB[6] = {0,0,0,0,0,0}; - double yBdot[6] = {0,0,0,0,0,0}; - double yC[6] = {0,0,0,0,0,0}; - double yCdot[6] = {0,0,0,0,0,0}; + lastExecutionTime = timeUTC; + } - //Step One - rungeKuttaStep(y0,y0dot,lastExecutionTime,S,C); + void rungeKuttaStep(const double* yIn, double* yOut, timeval time, + const double S[ORDER + 1][DEGREE + 1], + const double C[ORDER + 1][DEGREE + 1]) { + double rECF[3] = {0, 0, 0}; + double rDotECF[3] = {0, 0, 0}; + double accelECF[3] = {0, 0, 0}; + double accelECI[3] = {0, 0, 0}; - //Step Two - VectorOperations::mulScalar(y0dot,deltaT/2,yA,6); - VectorOperations::add(y0,yA,yA,6); - rungeKuttaStep(yA,yAdot,lastExecutionTime,S,C); - - //Step Three - VectorOperations::mulScalar(yAdot,deltaT/2,yB,6); - VectorOperations::add(y0,yB,yB,6); - rungeKuttaStep(yB,yBdot,lastExecutionTime,S,C); - - //Step Four - VectorOperations::mulScalar(yBdot,deltaT,yC,6); - VectorOperations::add(y0,yC,yC,6); - rungeKuttaStep(yC,yCdot,lastExecutionTime,S,C); - - //Calc new State - VectorOperations::mulScalar(yAdot,2,yAdot,6); - VectorOperations::mulScalar(yBdot,2,yBdot,6); - VectorOperations::add(y0dot,yAdot,y0dot,6); - VectorOperations::add(y0dot,yBdot,y0dot,6); - VectorOperations::add(y0dot,yCdot,y0dot,6); - VectorOperations::mulScalar(y0dot,1./6.*deltaT,y0dot,6); - VectorOperations::add(y0,y0dot,y0,6); - - CoordinateTransformations::positionEciToEcf(&y0[0],outputPos,&timeUTC); - CoordinateTransformations::velocityEciToEcf(&y0[3],&y0[0],outputVel,&timeUTC); - - lastExecutionTime = timeUTC; - - - } - - - void rungeKuttaStep(const double* yIn,double* yOut,timeval time, const double S[ORDER+1][DEGREE+1],const double C[ORDER+1][DEGREE+1]){ - double rECF[3] = {0,0,0}; - double rDotECF[3] = {0,0,0}; - double accelECF[3] = {0,0,0}; - double accelECI[3] = {0,0,0}; - - - CoordinateTransformations::positionEciToEcf(&yIn[0],rECF,&time); - CoordinateTransformations::velocityEciToEcf(&yIn[3],&yIn[0],rDotECF,&time); - accelDegOrd(rECF,S,C,accelECF); - //This is not correct, as the acceleration would have derived terms but we don't know the velocity and position at that time - //Tests showed that a wrong velocity does make the equation worse than neglecting it - CoordinateTransformations::positionEcfToEci(accelECF,accelECI,&time); - memcpy(&yOut[0],&yIn[3],sizeof(yOut[0])*3); - memcpy(&yOut[3],accelECI,sizeof(yOut[0])*3); - } + CoordinateTransformations::positionEciToEcf(&yIn[0], rECF, &time); + CoordinateTransformations::velocityEciToEcf(&yIn[3], &yIn[0], rDotECF, &time); + accelDegOrd(rECF, S, C, accelECF); + // This is not correct, as the acceleration would have derived terms but we don't know the + // velocity and position at that time Tests showed that a wrong velocity does make the equation + // worse than neglecting it + CoordinateTransformations::positionEcfToEci(accelECF, accelECI, &time); + memcpy(&yOut[0], &yIn[3], sizeof(yOut[0]) * 3); + memcpy(&yOut[3], accelECI, sizeof(yOut[0]) * 3); + } }; - - - - - #endif /* FRAMEWORK_COORDINATES_JGM3MODEL_H_ */ diff --git a/src/fsfw/coordinates/Sgp4Propagator.cpp b/src/fsfw/coordinates/Sgp4Propagator.cpp index a0e66ebd..4a43842c 100644 --- a/src/fsfw/coordinates/Sgp4Propagator.cpp +++ b/src/fsfw/coordinates/Sgp4Propagator.cpp @@ -1,231 +1,200 @@ -#include "fsfw/coordinates/CoordinateTransformations.h" #include "fsfw/coordinates/Sgp4Propagator.h" +#include + +#include "fsfw/coordinates/CoordinateTransformations.h" #include "fsfw/globalfunctions/constants.h" #include "fsfw/globalfunctions/math/MatrixOperations.h" #include "fsfw/globalfunctions/math/VectorOperations.h" #include "fsfw/globalfunctions/timevalOperations.h" -#include +Sgp4Propagator::Sgp4Propagator() : initialized(false), epoch({0, 0}), whichconst(wgs84) {} -Sgp4Propagator::Sgp4Propagator() : - initialized(false), epoch({0, 0}), whichconst(wgs84) { +Sgp4Propagator::~Sgp4Propagator() {} +void jday(int year, int mon, int day, int hr, int minute, double sec, double& jd) { + jd = 367.0 * year - floor((7 * (year + floor((mon + 9) / 12.0))) * 0.25) + + floor(275 * mon / 9.0) + day + 1721013.5 + + ((sec / 60.0 + minute) / 60.0 + hr) / 24.0; // ut in days + // - 0.5*sgn(100.0*year + mon - 190002.5) + 0.5; } -Sgp4Propagator::~Sgp4Propagator() { +void days2mdhms(int year, double days, int& mon, int& day, int& hr, int& minute, double& sec) { + int i, inttemp, dayofyr; + double temp; + int lmonth[] = {31, 28, 31, 30, 31, 30, 31, 31, 30, 31, 30, 31}; + dayofyr = (int)floor(days); + /* ----------------- find month and day of month ---------------- */ + if ((year % 4) == 0) lmonth[1] = 29; + + i = 1; + inttemp = 0; + while ((dayofyr > inttemp + lmonth[i - 1]) && (i < 12)) { + inttemp = inttemp + lmonth[i - 1]; + i++; + } + mon = i; + day = dayofyr - inttemp; + + /* ----------------- find hours minutes and seconds ------------- */ + temp = (days - dayofyr) * 24.0; + hr = (int)floor(temp); + temp = (temp - hr) * 60.0; + minute = (int)floor(temp); + sec = (temp - minute) * 60.0; } -void jday(int year, int mon, int day, int hr, int minute, double sec, - double& jd) { - jd = 367.0 * year - floor((7 * (year + floor((mon + 9) / 12.0))) * 0.25) - + floor(275 * mon / 9.0) + day + 1721013.5 - + ((sec / 60.0 + minute) / 60.0 + hr) / 24.0; // ut in days - // - 0.5*sgn(100.0*year + mon - 190002.5) + 0.5; +ReturnValue_t Sgp4Propagator::initialize(const uint8_t* line1, const uint8_t* line2) { + char longstr1[130]; + char longstr2[130]; + + // need some space for decimal points + memcpy(longstr1, line1, 69); + memcpy(longstr2, line2, 69); + + const double deg2rad = Math::PI / 180.0; // 0.0174532925199433 + const double xpdotp = 1440.0 / (2.0 * Math::PI); // 229.1831180523293 + + double sec, mu, radiusearthkm, tumin, xke, j2, j3, j4, j3oj2; + int cardnumb, numb, j; + long revnum = 0, elnum = 0; + char classification, intldesg[11]; + int year = 0; + int mon, day, hr, minute, nexp, ibexp; + + getgravconst(whichconst, tumin, mu, radiusearthkm, xke, j2, j3, j4, j3oj2); + + satrec.error = 0; + + // set the implied decimal points since doing a formated read + // fixes for bad input data values (missing, ...) + for (j = 10; j <= 15; j++) + if (longstr1[j] == ' ') longstr1[j] = '_'; + + if (longstr1[44] != ' ') longstr1[43] = longstr1[44]; + longstr1[44] = '.'; + if (longstr1[7] == ' ') longstr1[7] = 'U'; + if (longstr1[9] == ' ') longstr1[9] = '.'; + for (j = 45; j <= 49; j++) + if (longstr1[j] == ' ') longstr1[j] = '0'; + if (longstr1[51] == ' ') longstr1[51] = '0'; + if (longstr1[53] != ' ') longstr1[52] = longstr1[53]; + longstr1[53] = '.'; + longstr2[25] = '.'; + for (j = 26; j <= 32; j++) + if (longstr2[j] == ' ') longstr2[j] = '0'; + if (longstr1[62] == ' ') longstr1[62] = '0'; + if (longstr1[68] == ' ') longstr1[68] = '0'; + + sscanf(longstr1, "%2d %5ld %1c %10s %2d %12lf %11lf %7lf %2d %7lf %2d %2d %6ld ", &cardnumb, + &satrec.satnum, &classification, intldesg, &satrec.epochyr, &satrec.epochdays, + &satrec.ndot, &satrec.nddot, &nexp, &satrec.bstar, &ibexp, &numb, &elnum); + + if (longstr2[52] == ' ') { + sscanf(longstr2, "%2d %5ld %9lf %9lf %8lf %9lf %9lf %10lf %6ld \n", &cardnumb, &satrec.satnum, + &satrec.inclo, &satrec.nodeo, &satrec.ecco, &satrec.argpo, &satrec.mo, &satrec.no, + &revnum); + } else { + sscanf(longstr2, "%2d %5ld %9lf %9lf %8lf %9lf %9lf %11lf %6ld \n", &cardnumb, &satrec.satnum, + &satrec.inclo, &satrec.nodeo, &satrec.ecco, &satrec.argpo, &satrec.mo, &satrec.no, + &revnum); + } + + // ---- find no, ndot, nddot ---- + satrec.no = satrec.no / xpdotp; //* rad/min + satrec.nddot = satrec.nddot * pow(10.0, nexp); + satrec.bstar = satrec.bstar * pow(10.0, ibexp); + + // ---- convert to sgp4 units ---- + satrec.a = pow(satrec.no * tumin, (-2.0 / 3.0)); + satrec.ndot = satrec.ndot / (xpdotp * 1440.0); //* ? * minperday + satrec.nddot = satrec.nddot / (xpdotp * 1440.0 * 1440); + + // ---- find standard orbital elements ---- + satrec.inclo = satrec.inclo * deg2rad; + satrec.nodeo = satrec.nodeo * deg2rad; + satrec.argpo = satrec.argpo * deg2rad; + satrec.mo = satrec.mo * deg2rad; + + satrec.alta = satrec.a * (1.0 + satrec.ecco) - 1.0; + satrec.altp = satrec.a * (1.0 - satrec.ecco) - 1.0; + + // ---------------------------------------------------------------- + // find sgp4epoch time of element set + // remember that sgp4 uses units of days from 0 jan 1950 (sgp4epoch) + // and minutes from the epoch (time) + // ---------------------------------------------------------------- + + // ---------------- temp fix for years from 1957-2056 ------------------- + // --------- correct fix will occur when year is 4-digit in tle --------- + if (satrec.epochyr < 57) { + year = satrec.epochyr + 2000; + } else { + year = satrec.epochyr + 1900; + } + + days2mdhms(year, satrec.epochdays, mon, day, hr, minute, sec); + jday(year, mon, day, hr, minute, sec, satrec.jdsatepoch); + + double unixSeconds = (satrec.jdsatepoch - 2451544.5) * 24 * 3600 + 946684800; + + epoch.tv_sec = unixSeconds; + double subseconds = unixSeconds - epoch.tv_sec; + epoch.tv_usec = subseconds * 1000000; + + // ---------------- initialize the orbit at sgp4epoch ------------------- + uint8_t result = + sgp4init(whichconst, satrec.satnum, satrec.jdsatepoch - 2433281.5, satrec.bstar, satrec.ecco, + satrec.argpo, satrec.inclo, satrec.mo, satrec.no, satrec.nodeo, satrec); + + if (result != 00) { + return MAKE_RETURN_CODE(result); + } else { + initialized = true; + return HasReturnvaluesIF::RETURN_OK; + } } -void days2mdhms(int year, double days, int& mon, int& day, int& hr, int& minute, - double& sec) { - int i, inttemp, dayofyr; - double temp; - int lmonth[] = { 31, 28, 31, 30, 31, 30, 31, 31, 30, 31, 30, 31 }; +ReturnValue_t Sgp4Propagator::propagate(double* position, double* velocity, timeval time, + uint8_t gpsUtcOffset) { + if (!initialized) { + return TLE_NOT_INITIALIZED; + } - dayofyr = (int) floor(days); - /* ----------------- find month and day of month ---------------- */ - if ((year % 4) == 0) - lmonth[1] = 29; + // Time since epoch in minutes + timeval timeSinceEpoch = time - epoch; + double minutesSinceEpoch = timeSinceEpoch.tv_sec / 60. + timeSinceEpoch.tv_usec / 60000000.; - i = 1; - inttemp = 0; - while ((dayofyr > inttemp + lmonth[i - 1]) && (i < 12)) { - inttemp = inttemp + lmonth[i - 1]; - i++; - } - mon = i; - day = dayofyr - inttemp; + double yearsSinceEpoch = minutesSinceEpoch / 60 / 24 / 365; - /* ----------------- find hours minutes and seconds ------------- */ - temp = (days - dayofyr) * 24.0; - hr = (int) floor(temp); - temp = (temp - hr) * 60.0; - minute = (int) floor(temp); - sec = (temp - minute) * 60.0; -} - -ReturnValue_t Sgp4Propagator::initialize(const uint8_t* line1, - const uint8_t* line2) { - - char longstr1[130]; - char longstr2[130]; - - //need some space for decimal points - memcpy(longstr1, line1, 69); - memcpy(longstr2, line2, 69); - - const double deg2rad = Math::PI / 180.0; // 0.0174532925199433 - const double xpdotp = 1440.0 / (2.0 * Math::PI); // 229.1831180523293 - - double sec, mu, radiusearthkm, tumin, xke, j2, j3, j4, j3oj2; - int cardnumb, numb, j; - long revnum = 0, elnum = 0; - char classification, intldesg[11]; - int year = 0; - int mon, day, hr, minute, nexp, ibexp; - - getgravconst(whichconst, tumin, mu, radiusearthkm, xke, j2, j3, j4, j3oj2); - - satrec.error = 0; - - // set the implied decimal points since doing a formated read - // fixes for bad input data values (missing, ...) - for (j = 10; j <= 15; j++) - if (longstr1[j] == ' ') - longstr1[j] = '_'; - - if (longstr1[44] != ' ') - longstr1[43] = longstr1[44]; - longstr1[44] = '.'; - if (longstr1[7] == ' ') - longstr1[7] = 'U'; - if (longstr1[9] == ' ') - longstr1[9] = '.'; - for (j = 45; j <= 49; j++) - if (longstr1[j] == ' ') - longstr1[j] = '0'; - if (longstr1[51] == ' ') - longstr1[51] = '0'; - if (longstr1[53] != ' ') - longstr1[52] = longstr1[53]; - longstr1[53] = '.'; - longstr2[25] = '.'; - for (j = 26; j <= 32; j++) - if (longstr2[j] == ' ') - longstr2[j] = '0'; - if (longstr1[62] == ' ') - longstr1[62] = '0'; - if (longstr1[68] == ' ') - longstr1[68] = '0'; - - sscanf(longstr1, - "%2d %5ld %1c %10s %2d %12lf %11lf %7lf %2d %7lf %2d %2d %6ld ", - &cardnumb, &satrec.satnum, &classification, intldesg, - &satrec.epochyr, &satrec.epochdays, &satrec.ndot, &satrec.nddot, - &nexp, &satrec.bstar, &ibexp, &numb, &elnum); - - if (longstr2[52] == ' ') { - sscanf(longstr2, "%2d %5ld %9lf %9lf %8lf %9lf %9lf %10lf %6ld \n", - &cardnumb, &satrec.satnum, &satrec.inclo, &satrec.nodeo, - &satrec.ecco, &satrec.argpo, &satrec.mo, &satrec.no, &revnum); - } else { - sscanf(longstr2, "%2d %5ld %9lf %9lf %8lf %9lf %9lf %11lf %6ld \n", - &cardnumb, &satrec.satnum, &satrec.inclo, &satrec.nodeo, - &satrec.ecco, &satrec.argpo, &satrec.mo, &satrec.no, &revnum); - } - - // ---- find no, ndot, nddot ---- - satrec.no = satrec.no / xpdotp; //* rad/min - satrec.nddot = satrec.nddot * pow(10.0, nexp); - satrec.bstar = satrec.bstar * pow(10.0, ibexp); - - // ---- convert to sgp4 units ---- - satrec.a = pow(satrec.no * tumin, (-2.0 / 3.0)); - satrec.ndot = satrec.ndot / (xpdotp * 1440.0); //* ? * minperday - satrec.nddot = satrec.nddot / (xpdotp * 1440.0 * 1440); - - // ---- find standard orbital elements ---- - satrec.inclo = satrec.inclo * deg2rad; - satrec.nodeo = satrec.nodeo * deg2rad; - satrec.argpo = satrec.argpo * deg2rad; - satrec.mo = satrec.mo * deg2rad; - - satrec.alta = satrec.a * (1.0 + satrec.ecco) - 1.0; - satrec.altp = satrec.a * (1.0 - satrec.ecco) - 1.0; - - // ---------------------------------------------------------------- - // find sgp4epoch time of element set - // remember that sgp4 uses units of days from 0 jan 1950 (sgp4epoch) - // and minutes from the epoch (time) - // ---------------------------------------------------------------- - - // ---------------- temp fix for years from 1957-2056 ------------------- - // --------- correct fix will occur when year is 4-digit in tle --------- - if (satrec.epochyr < 57) { - year = satrec.epochyr + 2000; - } else { - year = satrec.epochyr + 1900; - } - - days2mdhms(year, satrec.epochdays, mon, day, hr, minute, sec); - jday(year, mon, day, hr, minute, sec, satrec.jdsatepoch); - - double unixSeconds = (satrec.jdsatepoch - 2451544.5) * 24 * 3600 - + 946684800; - - epoch.tv_sec = unixSeconds; - double subseconds = unixSeconds - epoch.tv_sec; - epoch.tv_usec = subseconds * 1000000; - - // ---------------- initialize the orbit at sgp4epoch ------------------- - uint8_t result = sgp4init(whichconst, satrec.satnum, - satrec.jdsatepoch - 2433281.5, satrec.bstar, satrec.ecco, - satrec.argpo, satrec.inclo, satrec.mo, satrec.no, satrec.nodeo, - satrec); - - if (result != 00) { - return MAKE_RETURN_CODE(result); - } else { - initialized = true; - return HasReturnvaluesIF::RETURN_OK; - } - -} - -ReturnValue_t Sgp4Propagator::propagate(double* position, double* velocity, - timeval time, uint8_t gpsUtcOffset) { - - if (!initialized) { - return TLE_NOT_INITIALIZED; - } - - //Time since epoch in minutes - timeval timeSinceEpoch = time - epoch; - double minutesSinceEpoch = timeSinceEpoch.tv_sec / 60. - + timeSinceEpoch.tv_usec / 60000000.; - - double yearsSinceEpoch = minutesSinceEpoch / 60 / 24 / 365; - - if ((yearsSinceEpoch > 1) || (yearsSinceEpoch < -1)) { - return TLE_TOO_OLD; - } - - double positionTEME[3]; - double velocityTEME[3]; - - uint8_t result = sgp4(whichconst, satrec, minutesSinceEpoch, positionTEME, - velocityTEME); - - VectorOperations::mulScalar(positionTEME, 1000, positionTEME, 3); - VectorOperations::mulScalar(velocityTEME, 1000, velocityTEME, 3); - - //Transform to ECF - double earthRotationMatrix[3][3]; - CoordinateTransformations::getEarthRotationMatrix(time, - earthRotationMatrix); - - MatrixOperations::multiply(earthRotationMatrix[0], positionTEME, - position, 3, 3, 1); - MatrixOperations::multiply(earthRotationMatrix[0], velocityTEME, - velocity, 3, 3, 1); - - double omegaEarth[3] = { 0, 0, Earth::OMEGA }; - double velocityCorrection[3]; - VectorOperations::cross(omegaEarth, position, velocityCorrection); - VectorOperations::subtract(velocity, velocityCorrection, velocity); - - if (result != 0) { - return MAKE_RETURN_CODE(result || 0xB0); - } else { - return HasReturnvaluesIF::RETURN_OK; - } + if ((yearsSinceEpoch > 1) || (yearsSinceEpoch < -1)) { + return TLE_TOO_OLD; + } + + double positionTEME[3]; + double velocityTEME[3]; + + uint8_t result = sgp4(whichconst, satrec, minutesSinceEpoch, positionTEME, velocityTEME); + + VectorOperations::mulScalar(positionTEME, 1000, positionTEME, 3); + VectorOperations::mulScalar(velocityTEME, 1000, velocityTEME, 3); + + // Transform to ECF + double earthRotationMatrix[3][3]; + CoordinateTransformations::getEarthRotationMatrix(time, earthRotationMatrix); + + MatrixOperations::multiply(earthRotationMatrix[0], positionTEME, position, 3, 3, 1); + MatrixOperations::multiply(earthRotationMatrix[0], velocityTEME, velocity, 3, 3, 1); + + double omegaEarth[3] = {0, 0, Earth::OMEGA}; + double velocityCorrection[3]; + VectorOperations::cross(omegaEarth, position, velocityCorrection); + VectorOperations::subtract(velocity, velocityCorrection, velocity); + + if (result != 0) { + return MAKE_RETURN_CODE(result || 0xB0); + } else { + return HasReturnvaluesIF::RETURN_OK; + } } diff --git a/src/fsfw/coordinates/Sgp4Propagator.h b/src/fsfw/coordinates/Sgp4Propagator.h index 7c7a0a8c..0edaf459 100644 --- a/src/fsfw/coordinates/Sgp4Propagator.h +++ b/src/fsfw/coordinates/Sgp4Propagator.h @@ -7,43 +7,40 @@ #ifndef PLATFORM_WIN #include #endif -#include "fsfw_contrib/sgp4/sgp4unit.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "fsfw_contrib/sgp4/sgp4unit.h" class Sgp4Propagator { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::SGP4PROPAGATOR_CLASS; - static const ReturnValue_t INVALID_ECCENTRICITY = MAKE_RETURN_CODE(0xA1); - static const ReturnValue_t INVALID_MEAN_MOTION = MAKE_RETURN_CODE(0xA2); - static const ReturnValue_t INVALID_PERTURBATION_ELEMENTS = MAKE_RETURN_CODE(0xA3); - static const ReturnValue_t INVALID_SEMI_LATUS_RECTUM = MAKE_RETURN_CODE(0xA4); - static const ReturnValue_t INVALID_EPOCH_ELEMENTS = MAKE_RETURN_CODE(0xA5); - static const ReturnValue_t SATELLITE_HAS_DECAYED = MAKE_RETURN_CODE(0xA6); - static const ReturnValue_t TLE_TOO_OLD = MAKE_RETURN_CODE(0xB1); - static const ReturnValue_t TLE_NOT_INITIALIZED = MAKE_RETURN_CODE(0xB2); + public: + static const uint8_t INTERFACE_ID = CLASS_ID::SGP4PROPAGATOR_CLASS; + static const ReturnValue_t INVALID_ECCENTRICITY = MAKE_RETURN_CODE(0xA1); + static const ReturnValue_t INVALID_MEAN_MOTION = MAKE_RETURN_CODE(0xA2); + static const ReturnValue_t INVALID_PERTURBATION_ELEMENTS = MAKE_RETURN_CODE(0xA3); + static const ReturnValue_t INVALID_SEMI_LATUS_RECTUM = MAKE_RETURN_CODE(0xA4); + static const ReturnValue_t INVALID_EPOCH_ELEMENTS = MAKE_RETURN_CODE(0xA5); + static const ReturnValue_t SATELLITE_HAS_DECAYED = MAKE_RETURN_CODE(0xA6); + static const ReturnValue_t TLE_TOO_OLD = MAKE_RETURN_CODE(0xB1); + static const ReturnValue_t TLE_NOT_INITIALIZED = MAKE_RETURN_CODE(0xB2); + Sgp4Propagator(); + virtual ~Sgp4Propagator(); + ReturnValue_t initialize(const uint8_t *line1, const uint8_t *line2); - Sgp4Propagator(); - virtual ~Sgp4Propagator(); - - ReturnValue_t initialize(const uint8_t *line1, const uint8_t *line2); - - /** - * - * @param[out] position in ECF - * @param[out] velocity in ECF - * @param time to which to propagate - * @return - */ - ReturnValue_t propagate(double *position, double *velocity, timeval time, uint8_t gpsUtcOffset); - -private: - bool initialized; - timeval epoch; - elsetrec satrec; - gravconsttype whichconst; + /** + * + * @param[out] position in ECF + * @param[out] velocity in ECF + * @param time to which to propagate + * @return + */ + ReturnValue_t propagate(double *position, double *velocity, timeval time, uint8_t gpsUtcOffset); + private: + bool initialized; + timeval epoch; + elsetrec satrec; + gravconsttype whichconst; }; #endif /* SGP4PROPAGATOR_H_ */ diff --git a/src/fsfw/datalinklayer/BCFrame.h b/src/fsfw/datalinklayer/BCFrame.h index 9cedd41b..e9a8e813 100644 --- a/src/fsfw/datalinklayer/BCFrame.h +++ b/src/fsfw/datalinklayer/BCFrame.h @@ -8,56 +8,54 @@ #ifndef BCFRAME_H_ #define BCFRAME_H_ -#include "dllConf.h" #include "CCSDSReturnValuesIF.h" +#include "dllConf.h" /** * Small helper class to identify a BcFrame. * @ingroup ccsds_handling */ -class BcFrame: public CCSDSReturnValuesIF { -private: - static const uint8_t UNLOCK_COMMAND = 0b00000000;//! Identifier for a certain BC Command. - static const uint8_t SET_V_R_1 = 0b10000010;//! Identifier for a certain BC Command. - static const uint8_t SET_V_R_2 = 0b00000000;//! Identifier for a certain BC Command. +class BcFrame : public CCSDSReturnValuesIF { + private: + static const uint8_t UNLOCK_COMMAND = 0b00000000; //! Identifier for a certain BC Command. + static const uint8_t SET_V_R_1 = 0b10000010; //! Identifier for a certain BC Command. + static const uint8_t SET_V_R_2 = 0b00000000; //! Identifier for a certain BC Command. -public: - uint8_t byte1; //!< First content byte - uint8_t byte2; //!< Second content byte - uint8_t vR; //!< vR byte - /** - * Simple default constructor. - */ - BcFrame() : - byte1(0), byte2(0), vR(0) { - } - /** - * Main and only useful method of the class. - * With the buffer and size information passed, the class passes the content - * and checks if it is one of the two valid BC Command Frames. - * @param inBuffer Content of the frame to check, - * @param inSize Size of the data to check. - * @return - #BC_ILLEGAL_COMMAND if it is no command. - * - #BC_IS_UNLOCK_COMMAND if it is an unlock command. - * - #BC_IS_SET_VR_COMMAND if it is such. - */ - ReturnValue_t initialize(const uint8_t* inBuffer, uint16_t inSize) { - ReturnValue_t returnValue = BC_ILLEGAL_COMMAND; - if (inSize == 1) { - byte1 = inBuffer[0]; - if (byte1 == UNLOCK_COMMAND) { - returnValue = BC_IS_UNLOCK_COMMAND; - } - } else if (inSize == 3) { - byte1 = inBuffer[0]; - byte2 = inBuffer[1]; - vR = inBuffer[2]; - if (byte1 == SET_V_R_1 && byte2 == SET_V_R_2) { - returnValue = BC_IS_SET_VR_COMMAND; - } - } - return returnValue; - } + public: + uint8_t byte1; //!< First content byte + uint8_t byte2; //!< Second content byte + uint8_t vR; //!< vR byte + /** + * Simple default constructor. + */ + BcFrame() : byte1(0), byte2(0), vR(0) {} + /** + * Main and only useful method of the class. + * With the buffer and size information passed, the class passes the content + * and checks if it is one of the two valid BC Command Frames. + * @param inBuffer Content of the frame to check, + * @param inSize Size of the data to check. + * @return - #BC_ILLEGAL_COMMAND if it is no command. + * - #BC_IS_UNLOCK_COMMAND if it is an unlock command. + * - #BC_IS_SET_VR_COMMAND if it is such. + */ + ReturnValue_t initialize(const uint8_t* inBuffer, uint16_t inSize) { + ReturnValue_t returnValue = BC_ILLEGAL_COMMAND; + if (inSize == 1) { + byte1 = inBuffer[0]; + if (byte1 == UNLOCK_COMMAND) { + returnValue = BC_IS_UNLOCK_COMMAND; + } + } else if (inSize == 3) { + byte1 = inBuffer[0]; + byte2 = inBuffer[1]; + vR = inBuffer[2]; + if (byte1 == SET_V_R_1 && byte2 == SET_V_R_2) { + returnValue = BC_IS_SET_VR_COMMAND; + } + } + return returnValue; + } }; #endif /* BCFRAME_H_ */ diff --git a/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h b/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h index a31f9ced..22ff12e4 100644 --- a/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +++ b/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h @@ -14,44 +14,67 @@ * This is a helper class to collect special return values that come up during CCSDS Handling. * @ingroup ccsds_handling */ -class CCSDSReturnValuesIF: public HasReturnvaluesIF { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::CCSDS_HANDLER_IF; //!< Basic ID of the interface. +class CCSDSReturnValuesIF : public HasReturnvaluesIF { + public: + static const uint8_t INTERFACE_ID = CLASS_ID::CCSDS_HANDLER_IF; //!< Basic ID of the interface. - static const ReturnValue_t BC_IS_SET_VR_COMMAND = MAKE_RETURN_CODE( 0x01 ); //!< A value to describe a BC frame. - static const ReturnValue_t BC_IS_UNLOCK_COMMAND = MAKE_RETURN_CODE( 0x02 ); //!< A value to describe a BC frame. - static const ReturnValue_t BC_ILLEGAL_COMMAND = MAKE_RETURN_CODE( 0xB0 );//!< A value to describe an illegal BC frame. - static const ReturnValue_t BOARD_READING_NOT_FINISHED = MAKE_RETURN_CODE( 0xB1 ); //! The CCSDS Board is not yet finished reading, it requires another cycle. + static const ReturnValue_t BC_IS_SET_VR_COMMAND = + MAKE_RETURN_CODE(0x01); //!< A value to describe a BC frame. + static const ReturnValue_t BC_IS_UNLOCK_COMMAND = + MAKE_RETURN_CODE(0x02); //!< A value to describe a BC frame. + static const ReturnValue_t BC_ILLEGAL_COMMAND = + MAKE_RETURN_CODE(0xB0); //!< A value to describe an illegal BC frame. + static const ReturnValue_t BOARD_READING_NOT_FINISHED = MAKE_RETURN_CODE( + 0xB1); //! The CCSDS Board is not yet finished reading, it requires another cycle. - static const ReturnValue_t NS_POSITIVE_W = MAKE_RETURN_CODE( 0xF0 );//!< NS is in the positive window - static const ReturnValue_t NS_NEGATIVE_W = MAKE_RETURN_CODE( 0xF1 );//!< NS is in the negative window - static const ReturnValue_t NS_LOCKOUT = MAKE_RETURN_CODE( 0xF2 ); //!< NS is in lockout state - static const ReturnValue_t FARM_IN_LOCKOUT = MAKE_RETURN_CODE( 0xF3 );//!< FARM-1 is currently in lockout state - static const ReturnValue_t FARM_IN_WAIT = MAKE_RETURN_CODE( 0xF4 ); //!< FARM-1 is currently in wait state + static const ReturnValue_t NS_POSITIVE_W = + MAKE_RETURN_CODE(0xF0); //!< NS is in the positive window + static const ReturnValue_t NS_NEGATIVE_W = + MAKE_RETURN_CODE(0xF1); //!< NS is in the negative window + static const ReturnValue_t NS_LOCKOUT = MAKE_RETURN_CODE(0xF2); //!< NS is in lockout state + static const ReturnValue_t FARM_IN_LOCKOUT = + MAKE_RETURN_CODE(0xF3); //!< FARM-1 is currently in lockout state + static const ReturnValue_t FARM_IN_WAIT = + MAKE_RETURN_CODE(0xF4); //!< FARM-1 is currently in wait state - static const ReturnValue_t WRONG_SYMBOL = MAKE_RETURN_CODE( 0xE0 ); //!< An error code in the FrameFinder. - static const ReturnValue_t DOUBLE_START = MAKE_RETURN_CODE( 0xE1 ); //!< An error code in the FrameFinder. - static const ReturnValue_t START_SYMBOL_MISSED = MAKE_RETURN_CODE( 0xE2 );//!< An error code in the FrameFinder. - static const ReturnValue_t END_WITHOUT_START = MAKE_RETURN_CODE( 0xE3 );//!< An error code in the FrameFinder. - static const ReturnValue_t TOO_LARGE = MAKE_RETURN_CODE( 0xE4 );//!< An error code for a frame. - static const ReturnValue_t TOO_SHORT = MAKE_RETURN_CODE( 0xE5 );//!< An error code for a frame. - static const ReturnValue_t WRONG_TF_VERSION = MAKE_RETURN_CODE( 0xE6 ); //!< An error code for a frame. - static const ReturnValue_t WRONG_SPACECRAFT_ID = MAKE_RETURN_CODE( 0xE7 );//!< An error code for a frame. - static const ReturnValue_t NO_VALID_FRAME_TYPE = MAKE_RETURN_CODE( 0xE8 );//!< An error code for a frame. - static const ReturnValue_t CRC_FAILED = MAKE_RETURN_CODE( 0xE9 );//!< An error code for a frame. - static const ReturnValue_t VC_NOT_FOUND = MAKE_RETURN_CODE( 0xEA ); //!< An error code for a frame. - static const ReturnValue_t FORWARDING_FAILED = MAKE_RETURN_CODE( 0xEB );//!< An error code for a frame. - static const ReturnValue_t CONTENT_TOO_LARGE = MAKE_RETURN_CODE( 0xEC );//!< An error code for a frame. - static const ReturnValue_t RESIDUAL_DATA = MAKE_RETURN_CODE( 0xED );//!< An error code for a frame. - static const ReturnValue_t DATA_CORRUPTED = MAKE_RETURN_CODE( 0xEE );//!< An error code for a frame. - static const ReturnValue_t ILLEGAL_SEGMENTATION_FLAG = MAKE_RETURN_CODE( 0xEF );//!< An error code for a frame. - static const ReturnValue_t ILLEGAL_FLAG_COMBINATION = MAKE_RETURN_CODE( 0xD0 ); //!< An error code for a frame. - static const ReturnValue_t SHORTER_THAN_HEADER = MAKE_RETURN_CODE( 0xD1 ); //!< An error code for a frame. - static const ReturnValue_t TOO_SHORT_BLOCKED_PACKET = MAKE_RETURN_CODE( 0xD2 ); //!< An error code for a frame. - static const ReturnValue_t TOO_SHORT_MAP_EXTRACTION = MAKE_RETURN_CODE( 0xD3 ); //!< An error code for a frame. + static const ReturnValue_t WRONG_SYMBOL = + MAKE_RETURN_CODE(0xE0); //!< An error code in the FrameFinder. + static const ReturnValue_t DOUBLE_START = + MAKE_RETURN_CODE(0xE1); //!< An error code in the FrameFinder. + static const ReturnValue_t START_SYMBOL_MISSED = + MAKE_RETURN_CODE(0xE2); //!< An error code in the FrameFinder. + static const ReturnValue_t END_WITHOUT_START = + MAKE_RETURN_CODE(0xE3); //!< An error code in the FrameFinder. + static const ReturnValue_t TOO_LARGE = MAKE_RETURN_CODE(0xE4); //!< An error code for a frame. + static const ReturnValue_t TOO_SHORT = MAKE_RETURN_CODE(0xE5); //!< An error code for a frame. + static const ReturnValue_t WRONG_TF_VERSION = + MAKE_RETURN_CODE(0xE6); //!< An error code for a frame. + static const ReturnValue_t WRONG_SPACECRAFT_ID = + MAKE_RETURN_CODE(0xE7); //!< An error code for a frame. + static const ReturnValue_t NO_VALID_FRAME_TYPE = + MAKE_RETURN_CODE(0xE8); //!< An error code for a frame. + static const ReturnValue_t CRC_FAILED = MAKE_RETURN_CODE(0xE9); //!< An error code for a frame. + static const ReturnValue_t VC_NOT_FOUND = MAKE_RETURN_CODE(0xEA); //!< An error code for a frame. + static const ReturnValue_t FORWARDING_FAILED = + MAKE_RETURN_CODE(0xEB); //!< An error code for a frame. + static const ReturnValue_t CONTENT_TOO_LARGE = + MAKE_RETURN_CODE(0xEC); //!< An error code for a frame. + static const ReturnValue_t RESIDUAL_DATA = + MAKE_RETURN_CODE(0xED); //!< An error code for a frame. + static const ReturnValue_t DATA_CORRUPTED = + MAKE_RETURN_CODE(0xEE); //!< An error code for a frame. + static const ReturnValue_t ILLEGAL_SEGMENTATION_FLAG = + MAKE_RETURN_CODE(0xEF); //!< An error code for a frame. + static const ReturnValue_t ILLEGAL_FLAG_COMBINATION = + MAKE_RETURN_CODE(0xD0); //!< An error code for a frame. + static const ReturnValue_t SHORTER_THAN_HEADER = + MAKE_RETURN_CODE(0xD1); //!< An error code for a frame. + static const ReturnValue_t TOO_SHORT_BLOCKED_PACKET = + MAKE_RETURN_CODE(0xD2); //!< An error code for a frame. + static const ReturnValue_t TOO_SHORT_MAP_EXTRACTION = + MAKE_RETURN_CODE(0xD3); //!< An error code for a frame. - virtual ~CCSDSReturnValuesIF() { - } //!< Empty virtual destructor + virtual ~CCSDSReturnValuesIF() {} //!< Empty virtual destructor }; #endif /* CCSDSRETURNVALUESIF_H_ */ diff --git a/src/fsfw/datalinklayer/Clcw.cpp b/src/fsfw/datalinklayer/Clcw.cpp index 9f2fe7d3..6e40df12 100644 --- a/src/fsfw/datalinklayer/Clcw.cpp +++ b/src/fsfw/datalinklayer/Clcw.cpp @@ -1,56 +1,52 @@ #include "fsfw/datalinklayer/Clcw.h" + #include "fsfw/serviceinterface/ServiceInterface.h" Clcw::Clcw() { - content.raw = 0; - content.status = STATUS_FIELD_DEFAULT; + content.raw = 0; + content.status = STATUS_FIELD_DEFAULT; } -Clcw::~Clcw() { -} +Clcw::~Clcw() {} void Clcw::setVirtualChannel(uint8_t setChannel) { - content.virtualChannelIdSpare = ((setChannel & 0x3F) << 2); + content.virtualChannelIdSpare = ((setChannel & 0x3F) << 2); } void Clcw::setLockoutFlag(bool lockout) { - content.flags = (content.flags & LOCKOUT_FLAG_MASK) | (lockout << LOCKOUT_FLAG_POSITION); + content.flags = (content.flags & LOCKOUT_FLAG_MASK) | (lockout << LOCKOUT_FLAG_POSITION); } void Clcw::setWaitFlag(bool waitFlag) { - content.flags = (content.flags & WAIT_FLAG_MASK) | (waitFlag << WAIT_FLAG_POSITION); + content.flags = (content.flags & WAIT_FLAG_MASK) | (waitFlag << WAIT_FLAG_POSITION); } void Clcw::setRetransmitFlag(bool retransmitFlag) { - content.flags = (content.flags & RETRANSMIT_FLAG_MASK) | (retransmitFlag << RETRANSMIT_FLAG_POSITION); + content.flags = + (content.flags & RETRANSMIT_FLAG_MASK) | (retransmitFlag << RETRANSMIT_FLAG_POSITION); } void Clcw::setFarmBCount(uint8_t count) { - content.flags = (content.flags & FARM_B_COUNT_MASK) | ((count & 0x03) << 1); + content.flags = (content.flags & FARM_B_COUNT_MASK) | ((count & 0x03) << 1); } -void Clcw::setReceiverFrameSequenceNumber(uint8_t vR) { - content.vRValue = vR; -} +void Clcw::setReceiverFrameSequenceNumber(uint8_t vR) { content.vRValue = vR; } -uint32_t Clcw::getAsWhole() { - return content.raw; -} +uint32_t Clcw::getAsWhole() { return content.raw; } void Clcw::setRFAvailable(bool rfAvailable) { - content.flags = (content.flags & NO_RF_AVIALABLE_MASK) | (!rfAvailable << NO_RF_AVIALABLE_POSITION); + content.flags = + (content.flags & NO_RF_AVIALABLE_MASK) | (!rfAvailable << NO_RF_AVIALABLE_POSITION); } void Clcw::setBitLock(bool bitLock) { - content.flags = (content.flags & NO_BIT_LOCK_MASK) | (!bitLock << NO_BIT_LOCK_POSITION); + content.flags = (content.flags & NO_BIT_LOCK_MASK) | (!bitLock << NO_BIT_LOCK_POSITION); } void Clcw::print() { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "Clcw::print: Clcw is: " << std::hex << getAsWhole() << std::dec << std::endl; + sif::debug << "Clcw::print: Clcw is: " << std::hex << getAsWhole() << std::dec << std::endl; #endif } -void Clcw::setWhole(uint32_t rawClcw) { - content.raw = rawClcw; -} +void Clcw::setWhole(uint32_t rawClcw) { content.raw = rawClcw; } diff --git a/src/fsfw/datalinklayer/Clcw.h b/src/fsfw/datalinklayer/Clcw.h index aa1ee35b..68a0c53c 100644 --- a/src/fsfw/datalinklayer/Clcw.h +++ b/src/fsfw/datalinklayer/Clcw.h @@ -1,8 +1,8 @@ #ifndef CLCW_H_ #define CLCW_H_ -#include "dllConf.h" #include "ClcwIF.h" +#include "dllConf.h" /** * Small helper method to handle the Clcw values. @@ -10,52 +10,62 @@ * @ingroup ccsds_handling */ class Clcw : public ClcwIF { -private: - static const uint8_t STATUS_FIELD_DEFAULT = 0b00000001; //!< Default for the status field. - static const uint8_t NO_RF_AVIALABLE_POSITION = 7; //!< Position of a flag in the register (starting with 0). - static const uint8_t NO_BIT_LOCK_POSITION = 6; //!< Position of a flag in the register (starting with 0). - static const uint8_t LOCKOUT_FLAG_POSITION = 5; //!< Position of a flag in the register (starting with 0). - static const uint8_t WAIT_FLAG_POSITION = 4; //!< Position of a flag in the register (starting with 0). - static const uint8_t RETRANSMIT_FLAG_POSITION = 3; //!< Position of a flag in the register (starting with 0). - static const uint8_t NO_RF_AVIALABLE_MASK = 0xFF xor (1 << NO_RF_AVIALABLE_POSITION); //!< Mask for a flag in the register. - static const uint8_t NO_BIT_LOCK_MASK = 0xFF xor (1 << NO_BIT_LOCK_POSITION); //!< Mask for a flag in the register. - static const uint8_t LOCKOUT_FLAG_MASK = 0xFF xor (1 << LOCKOUT_FLAG_POSITION); //!< Mask for a flag in the register. - static const uint8_t WAIT_FLAG_MASK = 0xFF xor (1 << WAIT_FLAG_POSITION); //!< Mask for a flag in the register. - static const uint8_t RETRANSMIT_FLAG_MASK = 0xFF xor (1 << RETRANSMIT_FLAG_POSITION); //!< Mask for a flag in the register. - static const uint8_t FARM_B_COUNT_MASK = 0b11111001; //!< Mask for a counter in the register. - /** - * This is the data structure of the CLCW register. - */ - union clcwContent { - uint32_t raw; - struct { - uint8_t status; - uint8_t virtualChannelIdSpare; - uint8_t flags; - uint8_t vRValue; - }; - }; - clcwContent content; //!< Represents the content of the register. -public: - /** - * The constructor sets everything to default values. - */ - Clcw(); - /** - * Nothing happens in the destructor. - */ - ~Clcw(); - void setVirtualChannel( uint8_t setChannel ); - void setLockoutFlag( bool lockout ); - void setWaitFlag( bool waitFlag ); - void setRetransmitFlag( bool retransmitFlag ); - void setFarmBCount( uint8_t count ); - void setReceiverFrameSequenceNumber( uint8_t vR ); - void setRFAvailable( bool rfAvailable ); - void setBitLock( bool bitLock ); - uint32_t getAsWhole(); - void setWhole( uint32_t rawClcw ); - void print(); + private: + static const uint8_t STATUS_FIELD_DEFAULT = 0b00000001; //!< Default for the status field. + static const uint8_t NO_RF_AVIALABLE_POSITION = + 7; //!< Position of a flag in the register (starting with 0). + static const uint8_t NO_BIT_LOCK_POSITION = + 6; //!< Position of a flag in the register (starting with 0). + static const uint8_t LOCKOUT_FLAG_POSITION = + 5; //!< Position of a flag in the register (starting with 0). + static const uint8_t WAIT_FLAG_POSITION = + 4; //!< Position of a flag in the register (starting with 0). + static const uint8_t RETRANSMIT_FLAG_POSITION = + 3; //!< Position of a flag in the register (starting with 0). + static const uint8_t NO_RF_AVIALABLE_MASK = + 0xFF xor (1 << NO_RF_AVIALABLE_POSITION); //!< Mask for a flag in the register. + static const uint8_t NO_BIT_LOCK_MASK = + 0xFF xor (1 << NO_BIT_LOCK_POSITION); //!< Mask for a flag in the register. + static const uint8_t LOCKOUT_FLAG_MASK = + 0xFF xor (1 << LOCKOUT_FLAG_POSITION); //!< Mask for a flag in the register. + static const uint8_t WAIT_FLAG_MASK = + 0xFF xor (1 << WAIT_FLAG_POSITION); //!< Mask for a flag in the register. + static const uint8_t RETRANSMIT_FLAG_MASK = + 0xFF xor (1 << RETRANSMIT_FLAG_POSITION); //!< Mask for a flag in the register. + static const uint8_t FARM_B_COUNT_MASK = 0b11111001; //!< Mask for a counter in the register. + /** + * This is the data structure of the CLCW register. + */ + union clcwContent { + uint32_t raw; + struct { + uint8_t status; + uint8_t virtualChannelIdSpare; + uint8_t flags; + uint8_t vRValue; + }; + }; + clcwContent content; //!< Represents the content of the register. + public: + /** + * The constructor sets everything to default values. + */ + Clcw(); + /** + * Nothing happens in the destructor. + */ + ~Clcw(); + void setVirtualChannel(uint8_t setChannel); + void setLockoutFlag(bool lockout); + void setWaitFlag(bool waitFlag); + void setRetransmitFlag(bool retransmitFlag); + void setFarmBCount(uint8_t count); + void setReceiverFrameSequenceNumber(uint8_t vR); + void setRFAvailable(bool rfAvailable); + void setBitLock(bool bitLock); + uint32_t getAsWhole(); + void setWhole(uint32_t rawClcw); + void print(); }; #endif /* CLCW_H_ */ diff --git a/src/fsfw/datalinklayer/ClcwIF.h b/src/fsfw/datalinklayer/ClcwIF.h index fc517856..73fd7c70 100644 --- a/src/fsfw/datalinklayer/ClcwIF.h +++ b/src/fsfw/datalinklayer/ClcwIF.h @@ -15,56 +15,55 @@ * @ingroup ccsds_handling */ class ClcwIF { -public: - /** - * Empty virtual destructor. - */ - virtual ~ClcwIF() { } - /** - * Simple setter. - * @param setChannel The virtual channel id to set. - */ - virtual void setVirtualChannel( uint8_t setChannel ) = 0; - /** - * Simple setter. - * @param lockout status of the flag. - */ - virtual void setLockoutFlag( bool lockout ) = 0; - /** - * Simple setter. - * @param waitFlag status of the flag. - */ - virtual void setWaitFlag( bool waitFlag ) = 0; - /** - * Simple setter. - * @param retransmitFlag status of the flag. - */ - virtual void setRetransmitFlag( bool retransmitFlag ) = 0; - /** - * Sets the farm B count. - * @param count A full 8bit counter value can be passed. Only the last three bits are used. - */ - virtual void setFarmBCount( uint8_t count ) = 0; - /** - * Simple setter. - * @param vR Value of vR. - */ - virtual void setReceiverFrameSequenceNumber( uint8_t vR ) = 0; - /** - * Returns the register as a full 32bit value. - * @return The value. - */ - virtual uint32_t getAsWhole() = 0; - /** - * Sets the whole content to this value. - * @param rawClcw The value to set the content. - */ - virtual void setWhole( uint32_t rawClcw ) = 0; - /** - * Debug method to print the CLCW. - */ - virtual void print() = 0; + public: + /** + * Empty virtual destructor. + */ + virtual ~ClcwIF() {} + /** + * Simple setter. + * @param setChannel The virtual channel id to set. + */ + virtual void setVirtualChannel(uint8_t setChannel) = 0; + /** + * Simple setter. + * @param lockout status of the flag. + */ + virtual void setLockoutFlag(bool lockout) = 0; + /** + * Simple setter. + * @param waitFlag status of the flag. + */ + virtual void setWaitFlag(bool waitFlag) = 0; + /** + * Simple setter. + * @param retransmitFlag status of the flag. + */ + virtual void setRetransmitFlag(bool retransmitFlag) = 0; + /** + * Sets the farm B count. + * @param count A full 8bit counter value can be passed. Only the last three bits are used. + */ + virtual void setFarmBCount(uint8_t count) = 0; + /** + * Simple setter. + * @param vR Value of vR. + */ + virtual void setReceiverFrameSequenceNumber(uint8_t vR) = 0; + /** + * Returns the register as a full 32bit value. + * @return The value. + */ + virtual uint32_t getAsWhole() = 0; + /** + * Sets the whole content to this value. + * @param rawClcw The value to set the content. + */ + virtual void setWhole(uint32_t rawClcw) = 0; + /** + * Debug method to print the CLCW. + */ + virtual void print() = 0; }; - #endif /* CLCWIF_H_ */ diff --git a/src/fsfw/datalinklayer/DataLinkLayer.cpp b/src/fsfw/datalinklayer/DataLinkLayer.cpp index 94199bc4..ca607478 100644 --- a/src/fsfw/datalinklayer/DataLinkLayer.cpp +++ b/src/fsfw/datalinklayer/DataLinkLayer.cpp @@ -1,143 +1,145 @@ #include "fsfw/datalinklayer/DataLinkLayer.h" + #include "fsfw/globalfunctions/CRC.h" #include "fsfw/serviceinterface/ServiceInterface.h" DataLinkLayer::DataLinkLayer(uint8_t* set_frame_buffer, ClcwIF* setClcw, - uint8_t set_start_sequence_length, uint16_t set_scid) : - spacecraftId(set_scid), frameBuffer(set_frame_buffer), clcw(setClcw), receivedDataLength(0), currentFrame( - NULL), startSequenceLength(set_start_sequence_length) { - //Nothing to do except from setting the values above. + uint8_t set_start_sequence_length, uint16_t set_scid) + : spacecraftId(set_scid), + frameBuffer(set_frame_buffer), + clcw(setClcw), + receivedDataLength(0), + currentFrame(NULL), + startSequenceLength(set_start_sequence_length) { + // Nothing to do except from setting the values above. } -DataLinkLayer::~DataLinkLayer() { - -} +DataLinkLayer::~DataLinkLayer() {} ReturnValue_t DataLinkLayer::frameDelimitingAndFillRemoval() { - if ((receivedDataLength - startSequenceLength) < FRAME_PRIMARY_HEADER_LENGTH) { - return SHORTER_THAN_HEADER; - } - //Removing start sequence. - //SHOULDDO: Not implemented here. - while ( *frameBuffer == START_SEQUENCE_PATTERN ) { - frameBuffer++; - } - TcTransferFrame frame_candidate(frameBuffer); - this->currentFrame = frame_candidate; //should work with shallow copy. + if ((receivedDataLength - startSequenceLength) < FRAME_PRIMARY_HEADER_LENGTH) { + return SHORTER_THAN_HEADER; + } + // Removing start sequence. + // SHOULDDO: Not implemented here. + while (*frameBuffer == START_SEQUENCE_PATTERN) { + frameBuffer++; + } + TcTransferFrame frame_candidate(frameBuffer); + this->currentFrame = frame_candidate; // should work with shallow copy. - return RETURN_OK; + return RETURN_OK; } ReturnValue_t DataLinkLayer::frameValidationCheck() { - //Check TF_version number - if (this->currentFrame.getVersionNumber() != FRAME_VERSION_NUMBER_DEFAULT) { - return WRONG_TF_VERSION; - } - //Check SpaceCraft ID - if (this->currentFrame.getSpacecraftId() != this->spacecraftId) { - return WRONG_SPACECRAFT_ID; - } - //Check other header limitations: - if (!this->currentFrame.bypassFlagSet() && this->currentFrame.controlCommandFlagSet()) { - return NO_VALID_FRAME_TYPE; - } - //- Spares are zero - if (!this->currentFrame.spareIsZero()) { - return NO_VALID_FRAME_TYPE; - } - //Compare detected frame length with the one in the header - uint16_t length = currentFrame.getFullSize(); - if (length > receivedDataLength) { - //Frame is too long or just right -// error << "frameValidationCheck: Too short."; -// currentFrame.print(); - return TOO_SHORT; - } - if (USE_CRC) { - return this->frameCheckCRC(); - } - return RETURN_OK; + // Check TF_version number + if (this->currentFrame.getVersionNumber() != FRAME_VERSION_NUMBER_DEFAULT) { + return WRONG_TF_VERSION; + } + // Check SpaceCraft ID + if (this->currentFrame.getSpacecraftId() != this->spacecraftId) { + return WRONG_SPACECRAFT_ID; + } + // Check other header limitations: + if (!this->currentFrame.bypassFlagSet() && this->currentFrame.controlCommandFlagSet()) { + return NO_VALID_FRAME_TYPE; + } + //- Spares are zero + if (!this->currentFrame.spareIsZero()) { + return NO_VALID_FRAME_TYPE; + } + // Compare detected frame length with the one in the header + uint16_t length = currentFrame.getFullSize(); + if (length > receivedDataLength) { + // Frame is too long or just right + // error << "frameValidationCheck: Too short."; + // currentFrame.print(); + return TOO_SHORT; + } + if (USE_CRC) { + return this->frameCheckCRC(); + } + return RETURN_OK; } ReturnValue_t DataLinkLayer::frameCheckCRC() { - uint16_t checkValue = CRC::crc16ccitt(this->currentFrame.getFullFrame(), - this->currentFrame.getFullSize()); - if (checkValue == 0) { - return RETURN_OK; - } else { - return CRC_FAILED; - } - + uint16_t checkValue = + CRC::crc16ccitt(this->currentFrame.getFullFrame(), this->currentFrame.getFullSize()); + if (checkValue == 0) { + return RETURN_OK; + } else { + return CRC_FAILED; + } } ReturnValue_t DataLinkLayer::allFramesReception() { - ReturnValue_t status = this->frameDelimitingAndFillRemoval(); - if (status != RETURN_OK) { - return status; - } - return this->frameValidationCheck(); + ReturnValue_t status = this->frameDelimitingAndFillRemoval(); + if (status != RETURN_OK) { + return status; + } + return this->frameValidationCheck(); } ReturnValue_t DataLinkLayer::masterChannelDemultiplexing() { - //Nothing to do at present. Ideally, there would be a map of MCID's identifying which MC to use. - return virtualChannelDemultiplexing(); + // Nothing to do at present. Ideally, there would be a map of MCID's identifying which MC to use. + return virtualChannelDemultiplexing(); } ReturnValue_t DataLinkLayer::virtualChannelDemultiplexing() { - uint8_t vcId = currentFrame.getVirtualChannelId(); - virtualChannelIterator iter = virtualChannels.find(vcId); - if (iter == virtualChannels.end()) { - //Do not report because passive board will get this error all the time. - return RETURN_OK; - } else { - return (iter->second)->frameAcceptanceAndReportingMechanism(¤tFrame, clcw); - } + uint8_t vcId = currentFrame.getVirtualChannelId(); + virtualChannelIterator iter = virtualChannels.find(vcId); + if (iter == virtualChannels.end()) { + // Do not report because passive board will get this error all the time. + return RETURN_OK; + } else { + return (iter->second)->frameAcceptanceAndReportingMechanism(¤tFrame, clcw); + } } ReturnValue_t DataLinkLayer::processFrame(uint16_t length) { - receivedDataLength = length; - ReturnValue_t status = allFramesReception(); - if (status != RETURN_OK) { + receivedDataLength = length; + ReturnValue_t status = allFramesReception(); + if (status != RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "DataLinkLayer::processFrame: frame reception failed. " - "Error code: " << std::hex << status << std::dec << std::endl; + sif::error << "DataLinkLayer::processFrame: frame reception failed. " + "Error code: " + << std::hex << status << std::dec << std::endl; #endif -// currentFrame.print(); - return status; - } else { - return masterChannelDemultiplexing(); - } + // currentFrame.print(); + return status; + } else { + return masterChannelDemultiplexing(); + } } ReturnValue_t DataLinkLayer::addVirtualChannel(uint8_t virtualChannelId, - VirtualChannelReceptionIF* object) { - std::pair returnValue = virtualChannels.insert( - std::pair(virtualChannelId, object)); - if (returnValue.second == true) { - return RETURN_OK; - } else { - return RETURN_FAILED; - } + VirtualChannelReceptionIF* object) { + std::pair returnValue = virtualChannels.insert( + std::pair(virtualChannelId, object)); + if (returnValue.second == true) { + return RETURN_OK; + } else { + return RETURN_FAILED; + } } ReturnValue_t DataLinkLayer::initialize() { - ReturnValue_t returnValue = RETURN_FAILED; - //Set Virtual Channel ID to first virtual channel instance in this DataLinkLayer instance to avoid faulty information (e.g. 0) in the VCID. - if ( virtualChannels.begin() != virtualChannels.end() ) { - clcw->setVirtualChannel( virtualChannels.begin()->second->getChannelId() ); - } else { + ReturnValue_t returnValue = RETURN_FAILED; + // Set Virtual Channel ID to first virtual channel instance in this DataLinkLayer instance to + // avoid faulty information (e.g. 0) in the VCID. + if (virtualChannels.begin() != virtualChannels.end()) { + clcw->setVirtualChannel(virtualChannels.begin()->second->getChannelId()); + } else { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "DataLinkLayer::initialize: No VC assigned to this DLL instance! " << std::endl; + sif::error << "DataLinkLayer::initialize: No VC assigned to this DLL instance! " << std::endl; #endif - return RETURN_FAILED; - } - - for (virtualChannelIterator iterator = virtualChannels.begin(); - iterator != virtualChannels.end(); iterator++) { - returnValue = iterator->second->initialize(); - if (returnValue != RETURN_OK) - break; - } - return returnValue; + return RETURN_FAILED; + } + for (virtualChannelIterator iterator = virtualChannels.begin(); iterator != virtualChannels.end(); + iterator++) { + returnValue = iterator->second->initialize(); + if (returnValue != RETURN_OK) break; + } + return returnValue; } diff --git a/src/fsfw/datalinklayer/DataLinkLayer.h b/src/fsfw/datalinklayer/DataLinkLayer.h index 9c2a2952..edfba8a6 100644 --- a/src/fsfw/datalinklayer/DataLinkLayer.h +++ b/src/fsfw/datalinklayer/DataLinkLayer.h @@ -1,16 +1,15 @@ #ifndef DATALINKLAYER_H_ #define DATALINKLAYER_H_ -#include "dllConf.h" +#include + #include "CCSDSReturnValuesIF.h" #include "ClcwIF.h" #include "TcTransferFrame.h" #include "VirtualChannelReceptionIF.h" +#include "dllConf.h" #include "fsfw/events/Event.h" -#include - - class VirtualChannelReception; /** * A complete representation of the CCSDS Data Link Layer. @@ -19,102 +18,113 @@ class VirtualChannelReception; * steps are performed. */ class DataLinkLayer : public CCSDSReturnValuesIF { -public: - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::SYSTEM_1; - //! [EXPORT] : [COMMENT] A RF available signal was detected. P1: raw RFA state, P2: 0 - static const Event RF_AVAILABLE = MAKE_EVENT(0, severity::INFO); - //! [EXPORT] : [COMMENT] A previously found RF available signal was lost. - //! P1: raw RFA state, P2: 0 - static const Event RF_LOST = MAKE_EVENT(1, severity::INFO); - //! [EXPORT] : [COMMENT] A Bit Lock signal. Was detected. P1: raw BLO state, P2: 0 - static const Event BIT_LOCK = MAKE_EVENT(2, severity::INFO); - //! [EXPORT] : [COMMENT] A previously found Bit Lock signal was lost. P1: raw BLO state, P2: 0 - static const Event BIT_LOCK_LOST = MAKE_EVENT(3, severity::INFO); -// static const Event RF_CHAIN_LOST = MAKE_EVENT(4, severity::INFO); //!< The CCSDS Board detected that either bit lock or RF available or both are lost. No parameters. - //! [EXPORT] : [COMMENT] The CCSDS Board could not interpret a TC - static const Event FRAME_PROCESSING_FAILED = MAKE_EVENT(5, severity::LOW); - /** - * The Constructor sets the passed parameters and nothing else. - * @param set_frame_buffer The buffer in which incoming frame candidates are stored. - * @param setClcw The CLCW class to work on when returning CLCW information. - * @param set_start_sequence_length Length of the Start sequence in front of every TC Transfer Frame. - * @param set_scid The SCID to operate on. - */ - DataLinkLayer( uint8_t* set_frame_buffer, ClcwIF* setClcw, uint8_t set_start_sequence_length, uint16_t set_scid ); - /** - * Empty virtual destructor. - */ - ~DataLinkLayer(); - /** - * This method tries to process a frame that is placed in #frameBuffer. - * The procedures described in the Standard are performed. - * @param length Length of the incoming frame candidate. - * @return @c RETURN_OK on successful handling, otherwise the return codes of the higher methods. - */ - ReturnValue_t processFrame( uint16_t length ); - /** - * Configuration method to add a new TC Virtual Channel. - * Shall only be called during initialization. As soon as the method was called, the layer can - * handle Frames directed to this VC. - * @param virtualChannelId Id of the VC. Shall be smaller than 64. - * @param object Reference to the object that handles the Frame. - * @return @c RETURN_OK on success, @c RETURN_FAILED otherwise. - */ - ReturnValue_t addVirtualChannel( uint8_t virtualChannelId, VirtualChannelReceptionIF* object ); - /** - * The initialization method calls the @c initialize routine of all virtual channels. - * @return The return code of the first failed VC initialization or @c RETURN_OK. - */ - ReturnValue_t initialize(); -private: - typedef std::map::iterator virtualChannelIterator; //!< Typedef to simplify handling the #virtualChannels map. - static const uint8_t FRAME_VERSION_NUMBER_DEFAULT = 0x00; //!< Constant for the default value of Frame Version Numbers. - static const uint8_t FRAME_PRIMARY_HEADER_LENGTH = 5; //!< Length of the frame's primary header. - static const uint8_t START_SEQUENCE_PATTERN = 0x00; //!< The start sequence pattern which might be with the frame. - static const bool USE_CRC = true; //!< A global, so called "Managed Parameter" that identifies if incoming frames have CRC's or not. - uint16_t spacecraftId; //!< The Space Craft Identifier (SCID) configured. - uint8_t* frameBuffer; //!< A pointer to point to the current incoming frame. - ClcwIF* clcw; //!< Pointer to store the CLCW to work on. - uint16_t receivedDataLength; //!< Stores the length of the currently processed frame. - TcTransferFrame currentFrame; //!< Stores a more convenient access to the current frame. - uint8_t startSequenceLength; //!< Configured length of the start sequence. Maybe this must be done more variable. - std::map virtualChannels; //!< Map of all virtual channels assigned. - /** - * Method that performs all possible frame validity checks (as specified). - * @return Various error codes or @c RETURN_OK on success. - */ - ReturnValue_t frameValidationCheck(); - /** - * First method to call. - * Removes start sequence bytes and checks if the complete frame was received. - * SHOULDDO: Maybe handling the start sequence must be done more variable. - * @return @c RETURN_OK or @c TOO_SHORT. - */ - ReturnValue_t frameDelimitingAndFillRemoval(); - /** - * Small helper method to check the CRC of the Frame. - * @return @c RETURN_OK or @c CRC_FAILED. - */ - ReturnValue_t frameCheckCRC(); - /** - * Method that groups the reception process of all Frames. - * Calls #frameDelimitingAndFillRemoval and #frameValidationCheck. - * @return The return codes of the sub calls. - */ - ReturnValue_t allFramesReception(); - /** - * Dummy method for master channel demultiplexing. - * As there's only one Master Channel here, the method calls #virtualChannelDemultiplexing. - * @return The return codes of #virtualChannelDemultiplexing. - */ - ReturnValue_t masterChannelDemultiplexing(); - /** - * Method to demultiplex the Frames to Virtual Channels (VC's). - * Looks up the requested VC in #virtualChannels and forwards the Frame to its - * #frameAcceptanceAndReportingMechanism method, if found. - * @return The higher method codes or @c VC_NOT_FOUND. - */ - ReturnValue_t virtualChannelDemultiplexing(); + public: + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::SYSTEM_1; + //! [EXPORT] : [COMMENT] A RF available signal was detected. P1: raw RFA state, P2: 0 + static const Event RF_AVAILABLE = MAKE_EVENT(0, severity::INFO); + //! [EXPORT] : [COMMENT] A previously found RF available signal was lost. + //! P1: raw RFA state, P2: 0 + static const Event RF_LOST = MAKE_EVENT(1, severity::INFO); + //! [EXPORT] : [COMMENT] A Bit Lock signal. Was detected. P1: raw BLO state, P2: 0 + static const Event BIT_LOCK = MAKE_EVENT(2, severity::INFO); + //! [EXPORT] : [COMMENT] A previously found Bit Lock signal was lost. P1: raw BLO state, P2: 0 + static const Event BIT_LOCK_LOST = MAKE_EVENT(3, severity::INFO); + // static const Event RF_CHAIN_LOST = MAKE_EVENT(4, severity::INFO); //!< The CCSDS Board + //detected that either bit lock or RF available or both are lost. No parameters. + //! [EXPORT] : [COMMENT] The CCSDS Board could not interpret a TC + static const Event FRAME_PROCESSING_FAILED = MAKE_EVENT(5, severity::LOW); + /** + * The Constructor sets the passed parameters and nothing else. + * @param set_frame_buffer The buffer in which incoming frame candidates are stored. + * @param setClcw The CLCW class to work on when returning CLCW information. + * @param set_start_sequence_length Length of the Start sequence in front of every TC Transfer + * Frame. + * @param set_scid The SCID to operate on. + */ + DataLinkLayer(uint8_t* set_frame_buffer, ClcwIF* setClcw, uint8_t set_start_sequence_length, + uint16_t set_scid); + /** + * Empty virtual destructor. + */ + ~DataLinkLayer(); + /** + * This method tries to process a frame that is placed in #frameBuffer. + * The procedures described in the Standard are performed. + * @param length Length of the incoming frame candidate. + * @return @c RETURN_OK on successful handling, otherwise the return codes of the higher + * methods. + */ + ReturnValue_t processFrame(uint16_t length); + /** + * Configuration method to add a new TC Virtual Channel. + * Shall only be called during initialization. As soon as the method was called, the layer can + * handle Frames directed to this VC. + * @param virtualChannelId Id of the VC. Shall be smaller than 64. + * @param object Reference to the object that handles the Frame. + * @return @c RETURN_OK on success, @c RETURN_FAILED otherwise. + */ + ReturnValue_t addVirtualChannel(uint8_t virtualChannelId, VirtualChannelReceptionIF* object); + /** + * The initialization method calls the @c initialize routine of all virtual channels. + * @return The return code of the first failed VC initialization or @c RETURN_OK. + */ + ReturnValue_t initialize(); + + private: + typedef std::map::iterator + virtualChannelIterator; //!< Typedef to simplify handling the #virtualChannels map. + static const uint8_t FRAME_VERSION_NUMBER_DEFAULT = + 0x00; //!< Constant for the default value of Frame Version Numbers. + static const uint8_t FRAME_PRIMARY_HEADER_LENGTH = 5; //!< Length of the frame's primary header. + static const uint8_t START_SEQUENCE_PATTERN = + 0x00; //!< The start sequence pattern which might be with the frame. + static const bool USE_CRC = true; //!< A global, so called "Managed Parameter" that identifies if + //!< incoming frames have CRC's or not. + uint16_t spacecraftId; //!< The Space Craft Identifier (SCID) configured. + uint8_t* frameBuffer; //!< A pointer to point to the current incoming frame. + ClcwIF* clcw; //!< Pointer to store the CLCW to work on. + uint16_t receivedDataLength; //!< Stores the length of the currently processed frame. + TcTransferFrame currentFrame; //!< Stores a more convenient access to the current frame. + uint8_t startSequenceLength; //!< Configured length of the start sequence. Maybe this must be + //!< done more variable. + std::map + virtualChannels; //!< Map of all virtual channels assigned. + /** + * Method that performs all possible frame validity checks (as specified). + * @return Various error codes or @c RETURN_OK on success. + */ + ReturnValue_t frameValidationCheck(); + /** + * First method to call. + * Removes start sequence bytes and checks if the complete frame was received. + * SHOULDDO: Maybe handling the start sequence must be done more variable. + * @return @c RETURN_OK or @c TOO_SHORT. + */ + ReturnValue_t frameDelimitingAndFillRemoval(); + /** + * Small helper method to check the CRC of the Frame. + * @return @c RETURN_OK or @c CRC_FAILED. + */ + ReturnValue_t frameCheckCRC(); + /** + * Method that groups the reception process of all Frames. + * Calls #frameDelimitingAndFillRemoval and #frameValidationCheck. + * @return The return codes of the sub calls. + */ + ReturnValue_t allFramesReception(); + /** + * Dummy method for master channel demultiplexing. + * As there's only one Master Channel here, the method calls #virtualChannelDemultiplexing. + * @return The return codes of #virtualChannelDemultiplexing. + */ + ReturnValue_t masterChannelDemultiplexing(); + /** + * Method to demultiplex the Frames to Virtual Channels (VC's). + * Looks up the requested VC in #virtualChannels and forwards the Frame to its + * #frameAcceptanceAndReportingMechanism method, if found. + * @return The higher method codes or @c VC_NOT_FOUND. + */ + ReturnValue_t virtualChannelDemultiplexing(); }; #endif /* DATALINKLAYER_H_ */ diff --git a/src/fsfw/datalinklayer/Farm1StateIF.h b/src/fsfw/datalinklayer/Farm1StateIF.h index 7e1ba2ec..1728c5fe 100644 --- a/src/fsfw/datalinklayer/Farm1StateIF.h +++ b/src/fsfw/datalinklayer/Farm1StateIF.h @@ -8,8 +8,8 @@ #ifndef FARM1STATEIF_H_ #define FARM1STATEIF_H_ -#include "dllConf.h" #include "CCSDSReturnValuesIF.h" +#include "dllConf.h" class VirtualChannelReception; class TcTransferFrame; @@ -21,36 +21,34 @@ class ClcwIF; * of the state pattern. */ class Farm1StateIF : public CCSDSReturnValuesIF { -public: - /** - * A method that shall handle an incoming frame as AD Frame. - * @param frame The frame to handle. - * @param clcw Any changes to the CLCW shall be done with the help of this interface. - * @return If forwarding to a MAP Channel is required, the return value shall be #FRAME_OK. - * Otherwise, an appropriate return value or error code shall be generated. - */ - virtual ReturnValue_t handleADFrame( TcTransferFrame* frame, ClcwIF* clcw ) = 0; - /** - * This method shall handle frames that have been successfully identified as BC Unlock frames. - * @param clcw Any changes to the CLCW shall be done with the help of this interface. - * @return If forwarding to a MAP Channel is required, the return value shall be #FRAME_OK. - * Otherwise, an appropriate return value or error code shall be generated. - */ - virtual ReturnValue_t handleBCUnlockCommand( ClcwIF* clcw ) = 0; - /** - * This method shall handle frames that have been successfully identified as BC Set VR frames. - * @param clcw Any changes to the CLCW shall be done with the help of this interface. - * @param vr The V(r) value found in the frame. - * @return If forwarding to a MAP Channel is required, the return value shall be #FRAME_OK. - * Otherwise, an appropriate return value or error code shall be generated. - */ - virtual ReturnValue_t handleBCSetVrCommand( ClcwIF* clcw, uint8_t vr ) = 0; - /** - * Empty virtual destructor. - */ - virtual ~Farm1StateIF() { - - } + public: + /** + * A method that shall handle an incoming frame as AD Frame. + * @param frame The frame to handle. + * @param clcw Any changes to the CLCW shall be done with the help of this interface. + * @return If forwarding to a MAP Channel is required, the return value shall be #FRAME_OK. + * Otherwise, an appropriate return value or error code shall be generated. + */ + virtual ReturnValue_t handleADFrame(TcTransferFrame* frame, ClcwIF* clcw) = 0; + /** + * This method shall handle frames that have been successfully identified as BC Unlock frames. + * @param clcw Any changes to the CLCW shall be done with the help of this interface. + * @return If forwarding to a MAP Channel is required, the return value shall be #FRAME_OK. + * Otherwise, an appropriate return value or error code shall be generated. + */ + virtual ReturnValue_t handleBCUnlockCommand(ClcwIF* clcw) = 0; + /** + * This method shall handle frames that have been successfully identified as BC Set VR frames. + * @param clcw Any changes to the CLCW shall be done with the help of this interface. + * @param vr The V(r) value found in the frame. + * @return If forwarding to a MAP Channel is required, the return value shall be #FRAME_OK. + * Otherwise, an appropriate return value or error code shall be generated. + */ + virtual ReturnValue_t handleBCSetVrCommand(ClcwIF* clcw, uint8_t vr) = 0; + /** + * Empty virtual destructor. + */ + virtual ~Farm1StateIF() {} }; #endif /* FARM1STATEIF_H_ */ diff --git a/src/fsfw/datalinklayer/Farm1StateLockout.cpp b/src/fsfw/datalinklayer/Farm1StateLockout.cpp index b74d0a5f..2a73102d 100644 --- a/src/fsfw/datalinklayer/Farm1StateLockout.cpp +++ b/src/fsfw/datalinklayer/Farm1StateLockout.cpp @@ -1,27 +1,25 @@ -#include "fsfw/datalinklayer/ClcwIF.h" #include "fsfw/datalinklayer/Farm1StateLockout.h" + +#include "fsfw/datalinklayer/ClcwIF.h" #include "fsfw/datalinklayer/TcTransferFrame.h" #include "fsfw/datalinklayer/VirtualChannelReception.h" -Farm1StateLockout::Farm1StateLockout(VirtualChannelReception* setMyVC) : myVC(setMyVC) { -} +Farm1StateLockout::Farm1StateLockout(VirtualChannelReception* setMyVC) : myVC(setMyVC) {} -ReturnValue_t Farm1StateLockout::handleADFrame(TcTransferFrame* frame, - ClcwIF* clcw) { - return FARM_IN_LOCKOUT; +ReturnValue_t Farm1StateLockout::handleADFrame(TcTransferFrame* frame, ClcwIF* clcw) { + return FARM_IN_LOCKOUT; } ReturnValue_t Farm1StateLockout::handleBCUnlockCommand(ClcwIF* clcw) { - myVC->farmBCounter++; - clcw->setRetransmitFlag(false); - clcw->setLockoutFlag( false ); - clcw->setWaitFlag( false ); - myVC->currentState = &(myVC->openState); - return BC_IS_UNLOCK_COMMAND; + myVC->farmBCounter++; + clcw->setRetransmitFlag(false); + clcw->setLockoutFlag(false); + clcw->setWaitFlag(false); + myVC->currentState = &(myVC->openState); + return BC_IS_UNLOCK_COMMAND; } -ReturnValue_t Farm1StateLockout::handleBCSetVrCommand(ClcwIF* clcw, - uint8_t vr) { - myVC->farmBCounter++; - return BC_IS_SET_VR_COMMAND; +ReturnValue_t Farm1StateLockout::handleBCSetVrCommand(ClcwIF* clcw, uint8_t vr) { + myVC->farmBCounter++; + return BC_IS_SET_VR_COMMAND; } diff --git a/src/fsfw/datalinklayer/Farm1StateLockout.h b/src/fsfw/datalinklayer/Farm1StateLockout.h index a039c89b..60e7893a 100644 --- a/src/fsfw/datalinklayer/Farm1StateLockout.h +++ b/src/fsfw/datalinklayer/Farm1StateLockout.h @@ -1,8 +1,8 @@ #ifndef FARM1STATELOCKOUT_H_ #define FARM1STATELOCKOUT_H_ -#include "dllConf.h" #include "Farm1StateIF.h" +#include "dllConf.h" /** * This class represents the FARM-1 "Lockout" State. @@ -11,43 +11,43 @@ * command is required. */ class Farm1StateLockout : public Farm1StateIF { -private: - /** - * This is a reference to the "owner" class the State works on. - */ - VirtualChannelReception* myVC; -public: - /** - * The default constructor if the State. - * Sets the "owner" of the State. - * @param setMyVC The "owner" class. - */ - Farm1StateLockout( VirtualChannelReception* setMyVC ); - /** - * All AD Frames are rejected with FARM_IN_LOCKOUT - * @param frame The frame to handle. - * @param clcw Any changes to the CLCW shall be done with the help of this interface. - * @return FARM_IN_LOCKOUT - */ - ReturnValue_t handleADFrame( TcTransferFrame* frame, ClcwIF* clcw ); - /** - * These commands are handled as specified. - * State changes to Farm1StateOpen. - * @param clcw Any changes to the CLCW shall be done with the help of this interface. - * @return As the frame needs no forwarding to a MAP Channel, #BC_IS_UNLOCK_COMMAND - * is returned. - */ - ReturnValue_t handleBCUnlockCommand( ClcwIF* clcw ); - /** - * These commands are handled as specified. - * The V(r) value is not set in Lockout State, even though the Command itself is accepted. - * @param clcw Any changes to the CLCW shall be done with the help of this interface. - * @param vr The V(r) value found in the frame. - * @return As the frame needs no forwarding to a MAP Channel, #BC_IS_SET_VR_COMMAND - * is returned. - */ - ReturnValue_t handleBCSetVrCommand( ClcwIF* clcw, uint8_t vr ); + private: + /** + * This is a reference to the "owner" class the State works on. + */ + VirtualChannelReception* myVC; + + public: + /** + * The default constructor if the State. + * Sets the "owner" of the State. + * @param setMyVC The "owner" class. + */ + Farm1StateLockout(VirtualChannelReception* setMyVC); + /** + * All AD Frames are rejected with FARM_IN_LOCKOUT + * @param frame The frame to handle. + * @param clcw Any changes to the CLCW shall be done with the help of this interface. + * @return FARM_IN_LOCKOUT + */ + ReturnValue_t handleADFrame(TcTransferFrame* frame, ClcwIF* clcw); + /** + * These commands are handled as specified. + * State changes to Farm1StateOpen. + * @param clcw Any changes to the CLCW shall be done with the help of this interface. + * @return As the frame needs no forwarding to a MAP Channel, #BC_IS_UNLOCK_COMMAND + * is returned. + */ + ReturnValue_t handleBCUnlockCommand(ClcwIF* clcw); + /** + * These commands are handled as specified. + * The V(r) value is not set in Lockout State, even though the Command itself is accepted. + * @param clcw Any changes to the CLCW shall be done with the help of this interface. + * @param vr The V(r) value found in the frame. + * @return As the frame needs no forwarding to a MAP Channel, #BC_IS_SET_VR_COMMAND + * is returned. + */ + ReturnValue_t handleBCSetVrCommand(ClcwIF* clcw, uint8_t vr); }; - #endif /* FARM1STATELOCKOUT_H_ */ diff --git a/src/fsfw/datalinklayer/Farm1StateOpen.cpp b/src/fsfw/datalinklayer/Farm1StateOpen.cpp index 6f91df47..cf3339a7 100644 --- a/src/fsfw/datalinklayer/Farm1StateOpen.cpp +++ b/src/fsfw/datalinklayer/Farm1StateOpen.cpp @@ -1,39 +1,38 @@ -#include "fsfw/datalinklayer/ClcwIF.h" #include "fsfw/datalinklayer/Farm1StateOpen.h" + +#include "fsfw/datalinklayer/ClcwIF.h" #include "fsfw/datalinklayer/TcTransferFrame.h" #include "fsfw/datalinklayer/VirtualChannelReception.h" -Farm1StateOpen::Farm1StateOpen(VirtualChannelReception* setMyVC) : myVC(setMyVC) { +Farm1StateOpen::Farm1StateOpen(VirtualChannelReception* setMyVC) : myVC(setMyVC) {} + +ReturnValue_t Farm1StateOpen::handleADFrame(TcTransferFrame* frame, ClcwIF* clcw) { + int8_t diff = frame->getSequenceNumber() - myVC->vR; + if (diff == 0) { + myVC->vR++; + clcw->setRetransmitFlag(false); + return RETURN_OK; + } else if (diff < myVC->positiveWindow && diff > 0) { + clcw->setRetransmitFlag(true); + return NS_POSITIVE_W; + } else if (diff < 0 && diff >= -myVC->negativeWindow) { + return NS_NEGATIVE_W; + } else { + clcw->setLockoutFlag(true); + myVC->currentState = &(myVC->lockoutState); + return NS_LOCKOUT; + } } -ReturnValue_t Farm1StateOpen::handleADFrame(TcTransferFrame* frame, - ClcwIF* clcw) { - int8_t diff = frame->getSequenceNumber() - myVC->vR; - if (diff == 0 ) { - myVC->vR++; - clcw->setRetransmitFlag(false); - return RETURN_OK; - } else if (diff < myVC->positiveWindow && diff > 0 ) { - clcw->setRetransmitFlag(true); - return NS_POSITIVE_W; - } else if (diff < 0 && diff >= -myVC->negativeWindow) { - return NS_NEGATIVE_W; - } else { - clcw->setLockoutFlag(true); - myVC->currentState = &(myVC->lockoutState); - return NS_LOCKOUT; - } +ReturnValue_t Farm1StateOpen::handleBCUnlockCommand(ClcwIF* clcw) { + myVC->farmBCounter++; + clcw->setRetransmitFlag(false); + return BC_IS_UNLOCK_COMMAND; } -ReturnValue_t Farm1StateOpen::handleBCUnlockCommand( ClcwIF* clcw ) { - myVC->farmBCounter++; - clcw->setRetransmitFlag(false); - return BC_IS_UNLOCK_COMMAND; -} - -ReturnValue_t Farm1StateOpen::handleBCSetVrCommand( ClcwIF* clcw, uint8_t vr ) { - myVC->farmBCounter++; - clcw->setRetransmitFlag(false); - myVC->vR = vr; - return BC_IS_SET_VR_COMMAND; +ReturnValue_t Farm1StateOpen::handleBCSetVrCommand(ClcwIF* clcw, uint8_t vr) { + myVC->farmBCounter++; + clcw->setRetransmitFlag(false); + myVC->vR = vr; + return BC_IS_SET_VR_COMMAND; } diff --git a/src/fsfw/datalinklayer/Farm1StateOpen.h b/src/fsfw/datalinklayer/Farm1StateOpen.h index c5506e7a..0bca931d 100644 --- a/src/fsfw/datalinklayer/Farm1StateOpen.h +++ b/src/fsfw/datalinklayer/Farm1StateOpen.h @@ -8,8 +8,8 @@ #ifndef FARM1STATEOPEN_H_ #define FARM1STATEOPEN_H_ -#include "dllConf.h" #include "Farm1StateIF.h" +#include "dllConf.h" /** * This class represents the FARM-1 "Open" State. @@ -18,46 +18,46 @@ * State reacts as specified. */ class Farm1StateOpen : public Farm1StateIF { -private: - /** - * This is a reference to the "owner" class the State works on. - */ - VirtualChannelReception* myVC; -public: - /** - * The default constructor if the State. - * Sets the "owner" of the State. - * @param setMyVC The "owner" class. - */ - Farm1StateOpen( VirtualChannelReception* setMyVC ); - /** - * Method to check the validity of AD Frames. - * It checks the Frame Sequence Number and reacts as specified in the standard. The state may - * change to Farm1StateLockout. - * @param frame The frame to handle. - * @param clcw Any changes to the CLCW shall be done with the help of this interface. - * @return If the Sequence Number is ok, it returns #RETURN_OK. Otherwise either #NS_POSITIVE_W, - * #NS_NEGATIVE_W or NS_LOCKOUT is returned. - */ - ReturnValue_t handleADFrame( TcTransferFrame* frame, ClcwIF* clcw ); - /** - * These commands are handled as specified. - * State does not change. - * @param clcw Any changes to the CLCW shall be done with the help of this interface. - * @return As the frame needs no forwarding to a MAP Channel, #BC_IS_UNLOCK_COMMAND - * is returned. - */ - ReturnValue_t handleBCUnlockCommand( ClcwIF* clcw ); - /** - * These commands are handled as specified. - * State does not change. - * @param clcw Any changes to the CLCW shall be done with the help of this interface. - * @param vr The V(r) value found in the frame. - * @return As the frame needs no forwarding to a MAP Channel, #BC_IS_SET_VR_COMMAND - * is returned. - */ - ReturnValue_t handleBCSetVrCommand( ClcwIF* clcw, uint8_t vr ); + private: + /** + * This is a reference to the "owner" class the State works on. + */ + VirtualChannelReception* myVC; + + public: + /** + * The default constructor if the State. + * Sets the "owner" of the State. + * @param setMyVC The "owner" class. + */ + Farm1StateOpen(VirtualChannelReception* setMyVC); + /** + * Method to check the validity of AD Frames. + * It checks the Frame Sequence Number and reacts as specified in the standard. The state may + * change to Farm1StateLockout. + * @param frame The frame to handle. + * @param clcw Any changes to the CLCW shall be done with the help of this interface. + * @return If the Sequence Number is ok, it returns #RETURN_OK. Otherwise either #NS_POSITIVE_W, + * #NS_NEGATIVE_W or NS_LOCKOUT is returned. + */ + ReturnValue_t handleADFrame(TcTransferFrame* frame, ClcwIF* clcw); + /** + * These commands are handled as specified. + * State does not change. + * @param clcw Any changes to the CLCW shall be done with the help of this interface. + * @return As the frame needs no forwarding to a MAP Channel, #BC_IS_UNLOCK_COMMAND + * is returned. + */ + ReturnValue_t handleBCUnlockCommand(ClcwIF* clcw); + /** + * These commands are handled as specified. + * State does not change. + * @param clcw Any changes to the CLCW shall be done with the help of this interface. + * @param vr The V(r) value found in the frame. + * @return As the frame needs no forwarding to a MAP Channel, #BC_IS_SET_VR_COMMAND + * is returned. + */ + ReturnValue_t handleBCSetVrCommand(ClcwIF* clcw, uint8_t vr); }; - #endif /* FARM1STATEOPEN_H_ */ diff --git a/src/fsfw/datalinklayer/Farm1StateWait.cpp b/src/fsfw/datalinklayer/Farm1StateWait.cpp index 8d3f97fc..ae8d2c45 100644 --- a/src/fsfw/datalinklayer/Farm1StateWait.cpp +++ b/src/fsfw/datalinklayer/Farm1StateWait.cpp @@ -1,35 +1,33 @@ -#include "fsfw/datalinklayer/ClcwIF.h" #include "fsfw/datalinklayer/Farm1StateWait.h" + +#include "fsfw/datalinklayer/ClcwIF.h" #include "fsfw/datalinklayer/TcTransferFrame.h" #include "fsfw/datalinklayer/VirtualChannelReception.h" -Farm1StateWait::Farm1StateWait(VirtualChannelReception* setMyVC) : myVC(setMyVC) { -} +Farm1StateWait::Farm1StateWait(VirtualChannelReception* setMyVC) : myVC(setMyVC) {} -ReturnValue_t Farm1StateWait::handleADFrame(TcTransferFrame* frame, - ClcwIF* clcw) { - - int8_t diff = frame->getSequenceNumber() - myVC->vR; - if ( diff < -myVC->negativeWindow || diff >= myVC->positiveWindow ) { - clcw->setLockoutFlag(true); - myVC->currentState = &(myVC->lockoutState); - } - return FARM_IN_WAIT; +ReturnValue_t Farm1StateWait::handleADFrame(TcTransferFrame* frame, ClcwIF* clcw) { + int8_t diff = frame->getSequenceNumber() - myVC->vR; + if (diff < -myVC->negativeWindow || diff >= myVC->positiveWindow) { + clcw->setLockoutFlag(true); + myVC->currentState = &(myVC->lockoutState); + } + return FARM_IN_WAIT; } ReturnValue_t Farm1StateWait::handleBCUnlockCommand(ClcwIF* clcw) { - myVC->farmBCounter++; - clcw->setRetransmitFlag(false); - clcw->setWaitFlag( false ); - myVC->currentState = &(myVC->openState); - return BC_IS_UNLOCK_COMMAND; + myVC->farmBCounter++; + clcw->setRetransmitFlag(false); + clcw->setWaitFlag(false); + myVC->currentState = &(myVC->openState); + return BC_IS_UNLOCK_COMMAND; } ReturnValue_t Farm1StateWait::handleBCSetVrCommand(ClcwIF* clcw, uint8_t vr) { - myVC->farmBCounter++; - clcw->setWaitFlag( false ); - clcw->setRetransmitFlag(false); - myVC->vR = vr; - myVC->currentState = &(myVC->openState); - return BC_IS_SET_VR_COMMAND; + myVC->farmBCounter++; + clcw->setWaitFlag(false); + clcw->setRetransmitFlag(false); + myVC->vR = vr; + myVC->currentState = &(myVC->openState); + return BC_IS_SET_VR_COMMAND; } diff --git a/src/fsfw/datalinklayer/Farm1StateWait.h b/src/fsfw/datalinklayer/Farm1StateWait.h index 76704fdb..6a1f3c61 100644 --- a/src/fsfw/datalinklayer/Farm1StateWait.h +++ b/src/fsfw/datalinklayer/Farm1StateWait.h @@ -8,8 +8,8 @@ #ifndef FARM1STATEWAIT_H_ #define FARM1STATEWAIT_H_ -#include "dllConf.h" #include "Farm1StateIF.h" +#include "dllConf.h" /** * This class represents the FARM-1 "Wait" State. @@ -17,43 +17,43 @@ * for a certain period. Currently, it is not in use. */ class Farm1StateWait : public Farm1StateIF { -private: - /** - * This is a reference to the "owner" class the State works on. - */ - VirtualChannelReception* myVC; -public: - /** - * The default constructor if the State. - * Sets the "owner" of the State. - * @param setMyVC The "owner" class. - */ - Farm1StateWait( VirtualChannelReception* setMyVC ); - /** - * AD Frames are always discarded. - * If the frame number is in the lockout window, the state changes to Farm1StateLockout. - * @param frame The frame to handle. - * @param clcw Any changes to the CLCW shall be done with the help of this interface. - * @return Always returns FARM_IN_WAIT. - */ - ReturnValue_t handleADFrame( TcTransferFrame* frame, ClcwIF* clcw ); - /** - * These commands are handled as specified. - * State changes to Farm1StateOpen. - * @param clcw Any changes to the CLCW shall be done with the help of this interface. - * @return As the frame needs no forwarding to a MAP Channel, #BC_IS_UNLOCK_COMMAND - * is returned. - */ - ReturnValue_t handleBCUnlockCommand( ClcwIF* clcw ); - /** - * These commands are handled as specified. - * @param clcw Any changes to the CLCW shall be done with the help of this interface. - * @param vr The V(r) value found in the frame. - * @return As the frame needs no forwarding to a MAP Channel, #BC_IS_SET_VR_COMMAND - * is returned. - */ - ReturnValue_t handleBCSetVrCommand( ClcwIF* clcw, uint8_t vr ); + private: + /** + * This is a reference to the "owner" class the State works on. + */ + VirtualChannelReception* myVC; + + public: + /** + * The default constructor if the State. + * Sets the "owner" of the State. + * @param setMyVC The "owner" class. + */ + Farm1StateWait(VirtualChannelReception* setMyVC); + /** + * AD Frames are always discarded. + * If the frame number is in the lockout window, the state changes to Farm1StateLockout. + * @param frame The frame to handle. + * @param clcw Any changes to the CLCW shall be done with the help of this interface. + * @return Always returns FARM_IN_WAIT. + */ + ReturnValue_t handleADFrame(TcTransferFrame* frame, ClcwIF* clcw); + /** + * These commands are handled as specified. + * State changes to Farm1StateOpen. + * @param clcw Any changes to the CLCW shall be done with the help of this interface. + * @return As the frame needs no forwarding to a MAP Channel, #BC_IS_UNLOCK_COMMAND + * is returned. + */ + ReturnValue_t handleBCUnlockCommand(ClcwIF* clcw); + /** + * These commands are handled as specified. + * @param clcw Any changes to the CLCW shall be done with the help of this interface. + * @param vr The V(r) value found in the frame. + * @return As the frame needs no forwarding to a MAP Channel, #BC_IS_SET_VR_COMMAND + * is returned. + */ + ReturnValue_t handleBCSetVrCommand(ClcwIF* clcw, uint8_t vr); }; - #endif /* FARM1STATEWAIT_H_ */ diff --git a/src/fsfw/datalinklayer/MapPacketExtraction.cpp b/src/fsfw/datalinklayer/MapPacketExtraction.cpp index 7d06695a..57aa2f08 100644 --- a/src/fsfw/datalinklayer/MapPacketExtraction.cpp +++ b/src/fsfw/datalinklayer/MapPacketExtraction.cpp @@ -1,162 +1,151 @@ #include "fsfw/datalinklayer/MapPacketExtraction.h" +#include + #include "fsfw/ipc/QueueFactory.h" +#include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/storagemanager/StorageManagerIF.h" #include "fsfw/tmtcpacket/SpacePacketBase.h" #include "fsfw/tmtcservices/AcceptsTelecommandsIF.h" #include "fsfw/tmtcservices/TmTcMessage.h" -#include "fsfw/objectmanager/ObjectManager.h" -#include - -MapPacketExtraction::MapPacketExtraction(uint8_t setMapId, - object_id_t setPacketDestination) : - lastSegmentationFlag(NO_SEGMENTATION), mapId(setMapId), - bufferPosition(packetBuffer), packetDestination(setPacketDestination), - tcQueueId(MessageQueueIF::NO_QUEUE) { - std::memset(packetBuffer, 0, sizeof(packetBuffer)); +MapPacketExtraction::MapPacketExtraction(uint8_t setMapId, object_id_t setPacketDestination) + : lastSegmentationFlag(NO_SEGMENTATION), + mapId(setMapId), + bufferPosition(packetBuffer), + packetDestination(setPacketDestination), + tcQueueId(MessageQueueIF::NO_QUEUE) { + std::memset(packetBuffer, 0, sizeof(packetBuffer)); } ReturnValue_t MapPacketExtraction::extractPackets(TcTransferFrame* frame) { - uint8_t segmentationFlag = frame->getSequenceFlags(); - ReturnValue_t status = TOO_SHORT_MAP_EXTRACTION; - switch (segmentationFlag) { - case NO_SEGMENTATION: - status = unpackBlockingPackets(frame); - break; - case FIRST_PORTION: - packetLength = frame->getDataLength(); - if (packetLength <= MAX_PACKET_SIZE) { - memcpy(packetBuffer, frame->getDataField(), packetLength); - bufferPosition = &packetBuffer[packetLength]; - status = RETURN_OK; - } else { + uint8_t segmentationFlag = frame->getSequenceFlags(); + ReturnValue_t status = TOO_SHORT_MAP_EXTRACTION; + switch (segmentationFlag) { + case NO_SEGMENTATION: + status = unpackBlockingPackets(frame); + break; + case FIRST_PORTION: + packetLength = frame->getDataLength(); + if (packetLength <= MAX_PACKET_SIZE) { + memcpy(packetBuffer, frame->getDataField(), packetLength); + bufferPosition = &packetBuffer[packetLength]; + status = RETURN_OK; + } else { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error - << "MapPacketExtraction::extractPackets. Packet too large! Size: " - << packetLength << std::endl; + sif::error << "MapPacketExtraction::extractPackets. Packet too large! Size: " + << packetLength << std::endl; #endif - clearBuffers(); - status = CONTENT_TOO_LARGE; - } - break; - case CONTINUING_PORTION: - case LAST_PORTION: - if (lastSegmentationFlag == FIRST_PORTION - || lastSegmentationFlag == CONTINUING_PORTION) { - packetLength += frame->getDataLength(); - if (packetLength <= MAX_PACKET_SIZE) { - memcpy(bufferPosition, frame->getDataField(), - frame->getDataLength()); - bufferPosition = &packetBuffer[packetLength]; - if (segmentationFlag == LAST_PORTION) { - status = sendCompletePacket(packetBuffer, packetLength); - clearBuffers(); - } - status = RETURN_OK; - } else { + clearBuffers(); + status = CONTENT_TOO_LARGE; + } + break; + case CONTINUING_PORTION: + case LAST_PORTION: + if (lastSegmentationFlag == FIRST_PORTION || lastSegmentationFlag == CONTINUING_PORTION) { + packetLength += frame->getDataLength(); + if (packetLength <= MAX_PACKET_SIZE) { + memcpy(bufferPosition, frame->getDataField(), frame->getDataLength()); + bufferPosition = &packetBuffer[packetLength]; + if (segmentationFlag == LAST_PORTION) { + status = sendCompletePacket(packetBuffer, packetLength); + clearBuffers(); + } + status = RETURN_OK; + } else { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error - << "MapPacketExtraction::extractPackets. Packet too large! Size: " - << packetLength << std::endl; + sif::error << "MapPacketExtraction::extractPackets. Packet too large! Size: " + << packetLength << std::endl; #endif - clearBuffers(); - status = CONTENT_TOO_LARGE; - } - } else { + clearBuffers(); + status = CONTENT_TOO_LARGE; + } + } else { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error - << "MapPacketExtraction::extractPackets. Illegal segment! Last flag: " - << (int) lastSegmentationFlag << std::endl; + sif::error << "MapPacketExtraction::extractPackets. Illegal segment! Last flag: " + << (int)lastSegmentationFlag << std::endl; #endif - clearBuffers(); - status = ILLEGAL_SEGMENTATION_FLAG; - } - break; - default: + clearBuffers(); + status = ILLEGAL_SEGMENTATION_FLAG; + } + break; + default: #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error - << "MapPacketExtraction::extractPackets. Illegal segmentationFlag: " - << (int) segmentationFlag << std::endl; + sif::error << "MapPacketExtraction::extractPackets. Illegal segmentationFlag: " + << (int)segmentationFlag << std::endl; #endif - clearBuffers(); - status = DATA_CORRUPTED; - break; - } - lastSegmentationFlag = segmentationFlag; - return status; + clearBuffers(); + status = DATA_CORRUPTED; + break; + } + lastSegmentationFlag = segmentationFlag; + return status; } -ReturnValue_t MapPacketExtraction::unpackBlockingPackets( - TcTransferFrame* frame) { - ReturnValue_t status = TOO_SHORT_BLOCKED_PACKET; - uint32_t totalLength = frame->getDataLength(); - if (totalLength > MAX_PACKET_SIZE) - return CONTENT_TOO_LARGE; - uint8_t* position = frame->getDataField(); - while ((totalLength > SpacePacketBase::MINIMUM_SIZE)) { - SpacePacketBase packet(position); - uint32_t packetSize = packet.getFullSize(); - if (packetSize <= totalLength) { - status = sendCompletePacket(packet.getWholeData(), - packet.getFullSize()); - totalLength -= packet.getFullSize(); - position += packet.getFullSize(); - status = RETURN_OK; - } else { - status = DATA_CORRUPTED; - totalLength = 0; - } - } - if (totalLength > 0) { - status = RESIDUAL_DATA; - } - return status; +ReturnValue_t MapPacketExtraction::unpackBlockingPackets(TcTransferFrame* frame) { + ReturnValue_t status = TOO_SHORT_BLOCKED_PACKET; + uint32_t totalLength = frame->getDataLength(); + if (totalLength > MAX_PACKET_SIZE) return CONTENT_TOO_LARGE; + uint8_t* position = frame->getDataField(); + while ((totalLength > SpacePacketBase::MINIMUM_SIZE)) { + SpacePacketBase packet(position); + uint32_t packetSize = packet.getFullSize(); + if (packetSize <= totalLength) { + status = sendCompletePacket(packet.getWholeData(), packet.getFullSize()); + totalLength -= packet.getFullSize(); + position += packet.getFullSize(); + status = RETURN_OK; + } else { + status = DATA_CORRUPTED; + totalLength = 0; + } + } + if (totalLength > 0) { + status = RESIDUAL_DATA; + } + return status; } -ReturnValue_t MapPacketExtraction::sendCompletePacket(uint8_t* data, - uint32_t size) { - store_address_t store_id; - ReturnValue_t status = this->packetStore->addData(&store_id, data, size); - if (status == RETURN_OK) { - TmTcMessage message(store_id); - status = MessageQueueSenderIF::sendMessage(tcQueueId,&message); - } - return status; +ReturnValue_t MapPacketExtraction::sendCompletePacket(uint8_t* data, uint32_t size) { + store_address_t store_id; + ReturnValue_t status = this->packetStore->addData(&store_id, data, size); + if (status == RETURN_OK) { + TmTcMessage message(store_id); + status = MessageQueueSenderIF::sendMessage(tcQueueId, &message); + } + return status; } void MapPacketExtraction::clearBuffers() { - memset(packetBuffer, 0, sizeof(packetBuffer)); - bufferPosition = packetBuffer; - packetLength = 0; - lastSegmentationFlag = NO_SEGMENTATION; + memset(packetBuffer, 0, sizeof(packetBuffer)); + bufferPosition = packetBuffer; + packetLength = 0; + lastSegmentationFlag = NO_SEGMENTATION; } ReturnValue_t MapPacketExtraction::initialize() { - packetStore = ObjectManager::instance()->get(objects::TC_STORE); - AcceptsTelecommandsIF* distributor = ObjectManager::instance()-> - get(packetDestination); - if ((packetStore != NULL) && (distributor != NULL)) { - tcQueueId = distributor->getRequestQueue(); - return RETURN_OK; - } else { - return RETURN_FAILED; - } + packetStore = ObjectManager::instance()->get(objects::TC_STORE); + AcceptsTelecommandsIF* distributor = + ObjectManager::instance()->get(packetDestination); + if ((packetStore != NULL) && (distributor != NULL)) { + tcQueueId = distributor->getRequestQueue(); + return RETURN_OK; + } else { + return RETURN_FAILED; + } } void MapPacketExtraction::printPacketBuffer(void) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "DLL: packet_buffer contains: " << std::endl; + sif::debug << "DLL: packet_buffer contains: " << std::endl; #endif - for (uint32_t i = 0; i < this->packetLength; ++i) { + for (uint32_t i = 0; i < this->packetLength; ++i) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "packet_buffer[" << std::dec << i << "]: 0x" << std::hex - << (uint16_t) this->packetBuffer[i] << std::endl; + sif::debug << "packet_buffer[" << std::dec << i << "]: 0x" << std::hex + << (uint16_t)this->packetBuffer[i] << std::endl; #endif - } + } } -uint8_t MapPacketExtraction::getMapId() const { - return mapId; -} +uint8_t MapPacketExtraction::getMapId() const { return mapId; } diff --git a/src/fsfw/datalinklayer/MapPacketExtraction.h b/src/fsfw/datalinklayer/MapPacketExtraction.h index 30552a8e..c2673b2e 100644 --- a/src/fsfw/datalinklayer/MapPacketExtraction.h +++ b/src/fsfw/datalinklayer/MapPacketExtraction.h @@ -1,11 +1,11 @@ #ifndef FSFW_DATALINKLAYER_MAPPACKETEXTRACTION_H_ #define FSFW_DATALINKLAYER_MAPPACKETEXTRACTION_H_ -#include "dllConf.h" #include "MapPacketExtractionIF.h" +#include "dllConf.h" +#include "fsfw/ipc/MessageQueueSenderIF.h" #include "fsfw/objectmanager/ObjectManagerIF.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" -#include "fsfw/ipc/MessageQueueSenderIF.h" class StorageManagerIF; @@ -16,59 +16,61 @@ class StorageManagerIF; * fully received. All found packets are forwarded to a single distribution entity. * @author B. Baetz */ -class MapPacketExtraction: public MapPacketExtractionIF { -private: - static const uint32_t MAX_PACKET_SIZE = 4096; - uint8_t lastSegmentationFlag; //!< The segmentation flag of the last received frame. - uint8_t mapId; //!< MAP ID of this MAP Channel. - uint32_t packetLength = 0; //!< Complete length of the current Space Packet. - uint8_t* bufferPosition; //!< Position to write to in the internal Packet buffer. - uint8_t packetBuffer[MAX_PACKET_SIZE]; //!< The internal Space Packet Buffer. - object_id_t packetDestination; - //!< Pointer to the store where full TC packets are stored. - StorageManagerIF* packetStore = nullptr; - MessageQueueId_t tcQueueId; //!< QueueId to send found packets to the distributor. - /** - * Debug method to print the packet Buffer's content. - */ - void printPacketBuffer(); - /** - * Method that is called if the segmentation flag is @c NO_SEGMENTATION. - * The method extracts one or more packets within the frame and forwards them to the OBSW. - * @param frame The TC Transfer Frame to work on. - * @return @c RETURN_OK if all Packets were extracted. If something is entirely wrong, - * @c DATA_CORRUPTED is returned, if some bytes are left over @c RESIDUAL_DATA. - */ - ReturnValue_t unpackBlockingPackets(TcTransferFrame* frame); - /** - * Helper method to forward a complete packet to the OBSW. - * @param data Pointer to the data, either directly from the frame or from the packetBuffer. - * @param size Complete total size of the packet. - * @return Return Code of the Packet Store or the Message Queue. - */ - ReturnValue_t sendCompletePacket( uint8_t* data, uint32_t size ); - /** - * Helper method to reset the internal buffer. - */ - void clearBuffers(); -public: - /** - * Default constructor. - * Members are set to default values. - * @param setMapId The MAP ID of the instance. - */ - MapPacketExtraction( uint8_t setMapId, object_id_t setPacketDestination ); - ReturnValue_t extractPackets(TcTransferFrame* frame); - /** - * The #packetStore and the default destination of #tcQueue are initialized here. - * @return @c RETURN_OK on success, @c RETURN_FAILED otherwise. - */ - ReturnValue_t initialize(); - /** - * Getter. - * @return The MAP ID of this instance. - */ - uint8_t getMapId() const; +class MapPacketExtraction : public MapPacketExtractionIF { + private: + static const uint32_t MAX_PACKET_SIZE = 4096; + uint8_t lastSegmentationFlag; //!< The segmentation flag of the last received frame. + uint8_t mapId; //!< MAP ID of this MAP Channel. + uint32_t packetLength = 0; //!< Complete length of the current Space Packet. + uint8_t* bufferPosition; //!< Position to write to in the internal Packet buffer. + uint8_t packetBuffer[MAX_PACKET_SIZE]; //!< The internal Space Packet Buffer. + object_id_t packetDestination; + //!< Pointer to the store where full TC packets are stored. + StorageManagerIF* packetStore = nullptr; + MessageQueueId_t tcQueueId; //!< QueueId to send found packets to the distributor. + /** + * Debug method to print the packet Buffer's content. + */ + void printPacketBuffer(); + /** + * Method that is called if the segmentation flag is @c NO_SEGMENTATION. + * The method extracts one or more packets within the frame and forwards them to the OBSW. + * @param frame The TC Transfer Frame to work on. + * @return @c RETURN_OK if all Packets were extracted. If something is entirely wrong, + * @c DATA_CORRUPTED is returned, if some bytes are left over @c RESIDUAL_DATA. + */ + ReturnValue_t unpackBlockingPackets(TcTransferFrame* frame); + /** + * Helper method to forward a complete packet to the OBSW. + * @param data Pointer to the data, either directly from the frame or from the + * packetBuffer. + * @param size Complete total size of the packet. + * @return Return Code of the Packet Store or the Message Queue. + */ + ReturnValue_t sendCompletePacket(uint8_t* data, uint32_t size); + /** + * Helper method to reset the internal buffer. + */ + void clearBuffers(); + + public: + /** + * Default constructor. + * Members are set to default values. + * @param setMapId The MAP ID of the instance. + */ + MapPacketExtraction(uint8_t setMapId, object_id_t setPacketDestination); + ReturnValue_t extractPackets(TcTransferFrame* frame); + /** + * The #packetStore and the default destination of #tcQueue are initialized here. + * @return @c RETURN_OK on success, @c RETURN_FAILED otherwise. + */ + ReturnValue_t initialize(); + /** + * Getter. + * @return The MAP ID of this instance. + */ + uint8_t getMapId() const; }; #endif /* FSFW_DATALINKLAYER_MAPPACKETEXTRACTION_H_ */ diff --git a/src/fsfw/datalinklayer/MapPacketExtractionIF.h b/src/fsfw/datalinklayer/MapPacketExtractionIF.h index 7f8a60af..9495f25e 100644 --- a/src/fsfw/datalinklayer/MapPacketExtractionIF.h +++ b/src/fsfw/datalinklayer/MapPacketExtractionIF.h @@ -8,9 +8,9 @@ #ifndef MAPPACKETEXTRACTIONIF_H_ #define MAPPACKETEXTRACTIONIF_H_ -#include "dllConf.h" #include "CCSDSReturnValuesIF.h" #include "TcTransferFrame.h" +#include "dllConf.h" /** * This is the interface for MAP Packet Extraction classes. @@ -19,30 +19,31 @@ * Protocol. */ class MapPacketExtractionIF : public CCSDSReturnValuesIF { -protected: - static const uint8_t FIRST_PORTION = 0b01; //!< Identification of the first part of a segmented Packet. - static const uint8_t CONTINUING_PORTION = 0b00; //!< Identification of a continuing part of segmented Packets. - static const uint8_t LAST_PORTION = 0b10; //!< The last portion of a segmented Packet. - static const uint8_t NO_SEGMENTATION = 0b11; //!< A Frame without segmentation but maybe with blocking. -public: - /** - * Empty virtual destructor. - */ - virtual ~MapPacketExtractionIF() { - } - /** - * Method to call to handle a single Transfer Frame. - * The method tries to extract Packets from the frame as stated in the Standard. - * @param frame - * @return - */ - virtual ReturnValue_t extractPackets( TcTransferFrame* frame ) = 0; - /** - * Any post-instantiation initialization shall be done in this method. - * @return - */ - virtual ReturnValue_t initialize() = 0; + protected: + static const uint8_t FIRST_PORTION = + 0b01; //!< Identification of the first part of a segmented Packet. + static const uint8_t CONTINUING_PORTION = + 0b00; //!< Identification of a continuing part of segmented Packets. + static const uint8_t LAST_PORTION = 0b10; //!< The last portion of a segmented Packet. + static const uint8_t NO_SEGMENTATION = + 0b11; //!< A Frame without segmentation but maybe with blocking. + public: + /** + * Empty virtual destructor. + */ + virtual ~MapPacketExtractionIF() {} + /** + * Method to call to handle a single Transfer Frame. + * The method tries to extract Packets from the frame as stated in the Standard. + * @param frame + * @return + */ + virtual ReturnValue_t extractPackets(TcTransferFrame* frame) = 0; + /** + * Any post-instantiation initialization shall be done in this method. + * @return + */ + virtual ReturnValue_t initialize() = 0; }; - #endif /* MAPPACKETEXTRACTIONIF_H_ */ diff --git a/src/fsfw/datalinklayer/TcTransferFrame.cpp b/src/fsfw/datalinklayer/TcTransferFrame.cpp index 42ccf7ca..ebf0f38c 100644 --- a/src/fsfw/datalinklayer/TcTransferFrame.cpp +++ b/src/fsfw/datalinklayer/TcTransferFrame.cpp @@ -1,102 +1,80 @@ #include "fsfw/datalinklayer/TcTransferFrame.h" + #include "fsfw/serviceinterface/ServiceInterface.h" -TcTransferFrame::TcTransferFrame() { - frame = nullptr; -} +TcTransferFrame::TcTransferFrame() { frame = nullptr; } -TcTransferFrame::TcTransferFrame(uint8_t* setData) { - this->frame = (tc_transfer_frame*)setData; -} +TcTransferFrame::TcTransferFrame(uint8_t* setData) { this->frame = (tc_transfer_frame*)setData; } uint8_t TcTransferFrame::getVersionNumber() { - return (this->frame->header.flagsAndScid & 0b11000000) >> 6; + return (this->frame->header.flagsAndScid & 0b11000000) >> 6; } bool TcTransferFrame::bypassFlagSet() { - return (this->frame->header.flagsAndScid & 0b00100000) != 0; + return (this->frame->header.flagsAndScid & 0b00100000) != 0; } bool TcTransferFrame::controlCommandFlagSet() { - return (this->frame->header.flagsAndScid & 0b00010000) != 0; + return (this->frame->header.flagsAndScid & 0b00010000) != 0; } bool TcTransferFrame::spareIsZero() { - return ( (this->frame->header.flagsAndScid & 0b00001100) == 0 ); + return ((this->frame->header.flagsAndScid & 0b00001100) == 0); } uint16_t TcTransferFrame::getSpacecraftId() { - return ( (this->frame->header.flagsAndScid & 0b00000011) << 8 ) + this->frame->header.spacecraftId_l; + return ((this->frame->header.flagsAndScid & 0b00000011) << 8) + + this->frame->header.spacecraftId_l; } uint8_t TcTransferFrame::getVirtualChannelId() { - return (this->frame->header.vcidAndLength_h & 0b11111100) >> 2; + return (this->frame->header.vcidAndLength_h & 0b11111100) >> 2; } uint16_t TcTransferFrame::getFrameLength() { - return ( (this->frame->header.vcidAndLength_h & 0b00000011) << 8 ) + this->frame->header.length_l; + return ((this->frame->header.vcidAndLength_h & 0b00000011) << 8) + this->frame->header.length_l; } uint16_t TcTransferFrame::getDataLength() { - return this->getFrameLength() - this->getHeaderSize() -1 - FRAME_CRC_SIZE + 1; // -1 for the segment header. + return this->getFrameLength() - this->getHeaderSize() - 1 - FRAME_CRC_SIZE + + 1; // -1 for the segment header. } -uint8_t TcTransferFrame::getSequenceNumber() { - return this->frame->header.sequenceNumber; -} +uint8_t TcTransferFrame::getSequenceNumber() { return this->frame->header.sequenceNumber; } -uint8_t TcTransferFrame::getSequenceFlags() { - return (this->frame->dataField & 0b11000000)>>6; -} +uint8_t TcTransferFrame::getSequenceFlags() { return (this->frame->dataField & 0b11000000) >> 6; } -uint8_t TcTransferFrame::getMAPId() { - return this->frame->dataField & 0b00111111; -} +uint8_t TcTransferFrame::getMAPId() { return this->frame->dataField & 0b00111111; } -uint8_t* TcTransferFrame::getDataField() { - return &(this->frame->dataField) + 1; -} +uint8_t* TcTransferFrame::getDataField() { return &(this->frame->dataField) + 1; } -uint8_t* TcTransferFrame::getFullFrame() { - return (uint8_t*)this->frame; -} +uint8_t* TcTransferFrame::getFullFrame() { return (uint8_t*)this->frame; } -uint16_t TcTransferFrame::getFullSize() { - return this->getFrameLength() + 1; -} +uint16_t TcTransferFrame::getFullSize() { return this->getFrameLength() + 1; } -uint16_t TcTransferFrame::getHeaderSize() { - return sizeof(frame->header); -} +uint16_t TcTransferFrame::getHeaderSize() { return sizeof(frame->header); } uint16_t TcTransferFrame::getFullDataLength() { - return this->getFrameLength() - this->getHeaderSize() - FRAME_CRC_SIZE + 1; + return this->getFrameLength() - this->getHeaderSize() - FRAME_CRC_SIZE + 1; } -uint8_t* TcTransferFrame::getFullDataField() { - return &frame->dataField; -} +uint8_t* TcTransferFrame::getFullDataField() { return &frame->dataField; } void TcTransferFrame::print() { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "Raw Frame: " << std::hex << std::endl; - for (uint16_t count = 0; count < this->getFullSize(); count++ ) { - sif::debug << (uint16_t)this->getFullFrame()[count] << " "; - } - sif::debug << std::dec << std::endl; + sif::debug << "Raw Frame: " << std::hex << std::endl; + for (uint16_t count = 0; count < this->getFullSize(); count++) { + sif::debug << (uint16_t)this->getFullFrame()[count] << " "; + } + sif::debug << std::dec << std::endl; - sif::debug << "Frame Header:" << std::endl; - sif::debug << "Version Number: " << std::hex - << (uint16_t)this->getVersionNumber() << std::endl; - sif::debug << "Bypass Flag set?| Ctrl Cmd Flag set?: " - << (uint16_t)this->bypassFlagSet() << " | " - << (uint16_t)this->controlCommandFlagSet() << std::endl; - sif::debug << "SCID : " << this->getSpacecraftId() << std::endl; - sif::debug << "VCID : " << (uint16_t)this->getVirtualChannelId() - << std::endl; - sif::debug << "Frame length: " << std::dec << this->getFrameLength() - << std::endl; - sif::debug << "Sequence Number: " << (uint16_t)this->getSequenceNumber() - << std::endl; + sif::debug << "Frame Header:" << std::endl; + sif::debug << "Version Number: " << std::hex << (uint16_t)this->getVersionNumber() << std::endl; + sif::debug << "Bypass Flag set?| Ctrl Cmd Flag set?: " << (uint16_t)this->bypassFlagSet() << " | " + << (uint16_t)this->controlCommandFlagSet() << std::endl; + sif::debug << "SCID : " << this->getSpacecraftId() << std::endl; + sif::debug << "VCID : " << (uint16_t)this->getVirtualChannelId() << std::endl; + sif::debug << "Frame length: " << std::dec << this->getFrameLength() << std::endl; + sif::debug << "Sequence Number: " << (uint16_t)this->getSequenceNumber() << std::endl; #endif } diff --git a/src/fsfw/datalinklayer/TcTransferFrame.h b/src/fsfw/datalinklayer/TcTransferFrame.h index 9d4f6349..0bead0dc 100644 --- a/src/fsfw/datalinklayer/TcTransferFrame.h +++ b/src/fsfw/datalinklayer/TcTransferFrame.h @@ -1,10 +1,10 @@ #ifndef TCTRANSFERFRAME_H_ #define TCTRANSFERFRAME_H_ -#include "dllConf.h" - -#include #include +#include + +#include "dllConf.h" /** * The TcTransferFrame class simplifies handling of such Frames. @@ -14,126 +14,127 @@ * @ingroup ccsds_handling */ class TcTransferFrame { -protected: - /** - * The struct that defines the Frame's Primary Header. - */ - struct TcTransferFramePrimaryHeader { - uint8_t flagsAndScid; //!< Highest byte with Flags and part of SCID. - uint8_t spacecraftId_l; //!< Byte with rest of SCID - uint8_t vcidAndLength_h; //!< Byte with VCID and part of length. - uint8_t length_l; //!< Byte with rest of length. - uint8_t sequenceNumber; //!< Lowest byte with Frame Sequence Number N(S). - }; - /** - * The struct defining the whole Transfer Frame. - */ - struct tc_transfer_frame { - TcTransferFramePrimaryHeader header; //!< The header struct. - uint8_t dataField; //!< The data field of the Transfer Frame. - }; - tc_transfer_frame* frame; //!< Pointer to a buffer where a Frame is placed. -public: - static const uint8_t FRAME_CRC_SIZE = 2; //!< Constant for the CRC size. - /** - * Empty Constructor that sets the data pointer to NULL. - */ - TcTransferFrame(); - /** - * The data pointer passed in this Constructor is casted to the #tc_transfer_frame struct. - * @param setData The data on which the class shall operate. - */ - TcTransferFrame(uint8_t* setData); - /** - * Getter. - * @return The Version number. - */ - uint8_t getVersionNumber(); - /** - * Getter. - * @return If the bypass flag is set or not. - */ - bool bypassFlagSet(); - /** - * Getter. - * @return If the control command flag is set or not. - */ - bool controlCommandFlagSet(); - /** - * Getter. - * @return If the spare bits in the Header are zero or not. - */ - bool spareIsZero(); - /** - * Getter. - * @return The Spacecraft Identifier. - */ - uint16_t getSpacecraftId(); - /** - * Getter. - * @return The Virtual Channel Identifier. - */ - uint8_t getVirtualChannelId(); - /** - * Getter. - * @return The Frame length as stored in the Header. - */ - uint16_t getFrameLength(); - /** - * Getter. - * @return The length of pure data (without CRC), assuming that a Segment Header is present. - */ - uint16_t getDataLength(); - /** - * Getter. - * @return The length of pure data (without CRC), assuming that no Segment Header is present (for BC Frames). - */ - uint16_t getFullDataLength(); - /** - * Getter. - * @return The sequence number from the header. - */ - uint8_t getSequenceNumber(); - /** - * Getter. - * @return The Sequence Flags in the Segment Header byte (right aligned). - */ - uint8_t getSequenceFlags(); - /** - * Getter. - * @return The Multiplexer Access Point Identifier from the Segment Header byte. - */ - uint8_t getMAPId(); - /** - * Getter. - * @return A pointer to the date field AFTER a Segment Header. - */ - uint8_t* getDataField(); - /** - * Getter. - * @return A pointer to the first byte in the Data Field (ignoring potential Segment Headers, for BC Frames). - */ - uint8_t* getFullDataField(); - /** - * Getter. - * @return A pointer to the beginning of the Frame. - */ - uint8_t* getFullFrame(); - /** - * Getter - * @return The total size of the Frame, which is the size stated in the Header + 1. - */ - uint16_t getFullSize(); - /** - * Getter. - * @return Size of the #TcTransferFramePrimaryHeader. - */ - uint16_t getHeaderSize(); - /** - * Debug method to print the whole Frame to screen. - */ - void print(); - + protected: + /** + * The struct that defines the Frame's Primary Header. + */ + struct TcTransferFramePrimaryHeader { + uint8_t flagsAndScid; //!< Highest byte with Flags and part of SCID. + uint8_t spacecraftId_l; //!< Byte with rest of SCID + uint8_t vcidAndLength_h; //!< Byte with VCID and part of length. + uint8_t length_l; //!< Byte with rest of length. + uint8_t sequenceNumber; //!< Lowest byte with Frame Sequence Number N(S). + }; + /** + * The struct defining the whole Transfer Frame. + */ + struct tc_transfer_frame { + TcTransferFramePrimaryHeader header; //!< The header struct. + uint8_t dataField; //!< The data field of the Transfer Frame. + }; + tc_transfer_frame* frame; //!< Pointer to a buffer where a Frame is placed. + public: + static const uint8_t FRAME_CRC_SIZE = 2; //!< Constant for the CRC size. + /** + * Empty Constructor that sets the data pointer to NULL. + */ + TcTransferFrame(); + /** + * The data pointer passed in this Constructor is casted to the #tc_transfer_frame struct. + * @param setData The data on which the class shall operate. + */ + TcTransferFrame(uint8_t* setData); + /** + * Getter. + * @return The Version number. + */ + uint8_t getVersionNumber(); + /** + * Getter. + * @return If the bypass flag is set or not. + */ + bool bypassFlagSet(); + /** + * Getter. + * @return If the control command flag is set or not. + */ + bool controlCommandFlagSet(); + /** + * Getter. + * @return If the spare bits in the Header are zero or not. + */ + bool spareIsZero(); + /** + * Getter. + * @return The Spacecraft Identifier. + */ + uint16_t getSpacecraftId(); + /** + * Getter. + * @return The Virtual Channel Identifier. + */ + uint8_t getVirtualChannelId(); + /** + * Getter. + * @return The Frame length as stored in the Header. + */ + uint16_t getFrameLength(); + /** + * Getter. + * @return The length of pure data (without CRC), assuming that a Segment Header is present. + */ + uint16_t getDataLength(); + /** + * Getter. + * @return The length of pure data (without CRC), assuming that no Segment Header is present (for + * BC Frames). + */ + uint16_t getFullDataLength(); + /** + * Getter. + * @return The sequence number from the header. + */ + uint8_t getSequenceNumber(); + /** + * Getter. + * @return The Sequence Flags in the Segment Header byte (right aligned). + */ + uint8_t getSequenceFlags(); + /** + * Getter. + * @return The Multiplexer Access Point Identifier from the Segment Header byte. + */ + uint8_t getMAPId(); + /** + * Getter. + * @return A pointer to the date field AFTER a Segment Header. + */ + uint8_t* getDataField(); + /** + * Getter. + * @return A pointer to the first byte in the Data Field (ignoring potential Segment Headers, for + * BC Frames). + */ + uint8_t* getFullDataField(); + /** + * Getter. + * @return A pointer to the beginning of the Frame. + */ + uint8_t* getFullFrame(); + /** + * Getter + * @return The total size of the Frame, which is the size stated in the Header + 1. + */ + uint16_t getFullSize(); + /** + * Getter. + * @return Size of the #TcTransferFramePrimaryHeader. + */ + uint16_t getHeaderSize(); + /** + * Debug method to print the whole Frame to screen. + */ + void print(); }; #endif /* TCTRANSFERFRAME_H_ */ diff --git a/src/fsfw/datalinklayer/TcTransferFrameLocal.cpp b/src/fsfw/datalinklayer/TcTransferFrameLocal.cpp index f88f79e2..572f27fd 100644 --- a/src/fsfw/datalinklayer/TcTransferFrameLocal.cpp +++ b/src/fsfw/datalinklayer/TcTransferFrameLocal.cpp @@ -1,45 +1,49 @@ #include "fsfw/datalinklayer/TcTransferFrameLocal.h" -#include "fsfw/globalfunctions/CRC.h" -#include "fsfw/serviceinterface/ServiceInterface.h" #include +#include "fsfw/globalfunctions/CRC.h" +#include "fsfw/serviceinterface/ServiceInterface.h" + TcTransferFrameLocal::TcTransferFrameLocal(bool bypass, bool controlCommand, uint16_t scid, - uint8_t vcId, uint8_t sequenceNumber, uint8_t setSegmentHeader, uint8_t* data, uint16_t dataSize, uint16_t forceCrc) { - this->frame = (tc_transfer_frame*)&localData; - frame->header.flagsAndScid = (bypass << 5) + (controlCommand << 4) + ((scid & 0x0300) >> 8); - frame->header.spacecraftId_l = (scid & 0x00FF); - frame->header.vcidAndLength_h = (vcId & 0b00111111) << 2; - frame->header.length_l = sizeof(TcTransferFramePrimaryHeader) -1; - frame->header.sequenceNumber = sequenceNumber; - frame->dataField = setSegmentHeader; - if (data != NULL) { - if (bypass && controlCommand) { - memcpy(&(frame->dataField), data, dataSize); - uint16_t totalSize = sizeof(TcTransferFramePrimaryHeader) + dataSize + FRAME_CRC_SIZE -1; - frame->header.vcidAndLength_h |= (totalSize & 0x0300) >> 8; - frame->header.length_l = (totalSize & 0x00FF); - uint16_t crc = CRC::crc16ccitt(getFullFrame(), getFullSize() -2); - this->getFullFrame()[getFullSize()-2] = (crc & 0xFF00) >> 8; - this->getFullFrame()[getFullSize()-1] = (crc & 0x00FF); - } else if (dataSize <= 1016) { - memcpy(&(frame->dataField) +1, data, dataSize); - uint16_t dataCrcSize = sizeof(TcTransferFramePrimaryHeader) + 1 + dataSize + FRAME_CRC_SIZE -1; - frame->header.vcidAndLength_h |= (dataCrcSize & 0x0300) >> 8; - frame->header.length_l = (dataCrcSize & 0x00FF); - uint16_t crc = CRC::crc16ccitt(getFullFrame(), getFullSize() -2); - this->getFullFrame()[getFullSize()-2] = (crc & 0xFF00) >> 8; - this->getFullFrame()[getFullSize()-1] = (crc & 0x00FF); - } else { + uint8_t vcId, uint8_t sequenceNumber, + uint8_t setSegmentHeader, uint8_t* data, + uint16_t dataSize, uint16_t forceCrc) { + this->frame = (tc_transfer_frame*)&localData; + frame->header.flagsAndScid = (bypass << 5) + (controlCommand << 4) + ((scid & 0x0300) >> 8); + frame->header.spacecraftId_l = (scid & 0x00FF); + frame->header.vcidAndLength_h = (vcId & 0b00111111) << 2; + frame->header.length_l = sizeof(TcTransferFramePrimaryHeader) - 1; + frame->header.sequenceNumber = sequenceNumber; + frame->dataField = setSegmentHeader; + if (data != NULL) { + if (bypass && controlCommand) { + memcpy(&(frame->dataField), data, dataSize); + uint16_t totalSize = sizeof(TcTransferFramePrimaryHeader) + dataSize + FRAME_CRC_SIZE - 1; + frame->header.vcidAndLength_h |= (totalSize & 0x0300) >> 8; + frame->header.length_l = (totalSize & 0x00FF); + uint16_t crc = CRC::crc16ccitt(getFullFrame(), getFullSize() - 2); + this->getFullFrame()[getFullSize() - 2] = (crc & 0xFF00) >> 8; + this->getFullFrame()[getFullSize() - 1] = (crc & 0x00FF); + } else if (dataSize <= 1016) { + memcpy(&(frame->dataField) + 1, data, dataSize); + uint16_t dataCrcSize = + sizeof(TcTransferFramePrimaryHeader) + 1 + dataSize + FRAME_CRC_SIZE - 1; + frame->header.vcidAndLength_h |= (dataCrcSize & 0x0300) >> 8; + frame->header.length_l = (dataCrcSize & 0x00FF); + uint16_t crc = CRC::crc16ccitt(getFullFrame(), getFullSize() - 2); + this->getFullFrame()[getFullSize() - 2] = (crc & 0xFF00) >> 8; + this->getFullFrame()[getFullSize() - 1] = (crc & 0x00FF); + } else { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "TcTransferFrameLocal: dataSize too large: " << dataSize << std::endl; + sif::warning << "TcTransferFrameLocal: dataSize too large: " << dataSize << std::endl; #endif - } - } else { - //No data in frame - } - if (forceCrc != 0 ) { - localData.data[getFullSize()-2] = (forceCrc & 0xFF00) >> 8; - localData.data[getFullSize()-1] = (forceCrc & 0x00FF); - } + } + } else { + // No data in frame + } + if (forceCrc != 0) { + localData.data[getFullSize() - 2] = (forceCrc & 0xFF00) >> 8; + localData.data[getFullSize() - 1] = (forceCrc & 0x00FF); + } } diff --git a/src/fsfw/datalinklayer/TcTransferFrameLocal.h b/src/fsfw/datalinklayer/TcTransferFrameLocal.h index f2bf3275..a23c2dfe 100644 --- a/src/fsfw/datalinklayer/TcTransferFrameLocal.h +++ b/src/fsfw/datalinklayer/TcTransferFrameLocal.h @@ -8,8 +8,8 @@ #ifndef TCTRANSFERFRAMELOCAL_H_ #define TCTRANSFERFRAMELOCAL_H_ -#include "dllConf.h" #include "TcTransferFrame.h" +#include "dllConf.h" /** * This is a helper class to locally create TC Transfer Frames. @@ -17,34 +17,35 @@ * @ingroup ccsds_handling */ class TcTransferFrameLocal : public TcTransferFrame { -private: - /** - * A stuct to locally store the complete data. - */ - struct frameData { - TcTransferFramePrimaryHeader header; //!< The primary header. - uint8_t data[1019]; //!< The data field. - }; -public: - frameData localData; //!< The local data in the Frame. - /** - * The default Constructor. - * All parameters in the Header are passed. - * If a BC Frame is detected no segment header is created. - * Otherwise (AD and BD), the Segment Header is set. - * @param bypass The bypass flag. - * @param controlCommand The Control Command flag. - * @param scid The SCID. - * @param vcId The VCID. - * @param sequenceNumber The Frame Sequence Number N(s) - * @param setSegmentHeader A value for the Segment Header. - * @param data Data to put into the Frame Data Field. - * @param dataSize Size of the Data. - * @param forceCrc if != 0, the value is used as CRC. - */ - TcTransferFrameLocal(bool bypass, bool controlCommand, uint16_t scid, uint8_t vcId, uint8_t sequenceNumber, - uint8_t setSegmentHeader = 0xC0, uint8_t* data = NULL, uint16_t dataSize = 0, uint16_t forceCrc = 0); + private: + /** + * A stuct to locally store the complete data. + */ + struct frameData { + TcTransferFramePrimaryHeader header; //!< The primary header. + uint8_t data[1019]; //!< The data field. + }; + + public: + frameData localData; //!< The local data in the Frame. + /** + * The default Constructor. + * All parameters in the Header are passed. + * If a BC Frame is detected no segment header is created. + * Otherwise (AD and BD), the Segment Header is set. + * @param bypass The bypass flag. + * @param controlCommand The Control Command flag. + * @param scid The SCID. + * @param vcId The VCID. + * @param sequenceNumber The Frame Sequence Number N(s) + * @param setSegmentHeader A value for the Segment Header. + * @param data Data to put into the Frame Data Field. + * @param dataSize Size of the Data. + * @param forceCrc if != 0, the value is used as CRC. + */ + TcTransferFrameLocal(bool bypass, bool controlCommand, uint16_t scid, uint8_t vcId, + uint8_t sequenceNumber, uint8_t setSegmentHeader = 0xC0, + uint8_t* data = NULL, uint16_t dataSize = 0, uint16_t forceCrc = 0); }; - #endif /* TCTRANSFERFRAMELOCAL_H_ */ diff --git a/src/fsfw/datalinklayer/VirtualChannelReception.cpp b/src/fsfw/datalinklayer/VirtualChannelReception.cpp index e0a88e8e..4ee0c008 100644 --- a/src/fsfw/datalinklayer/VirtualChannelReception.cpp +++ b/src/fsfw/datalinklayer/VirtualChannelReception.cpp @@ -5,119 +5,125 @@ * @author baetz */ -#include "fsfw/datalinklayer/BCFrame.h" #include "fsfw/datalinklayer/VirtualChannelReception.h" + +#include "fsfw/datalinklayer/BCFrame.h" #include "fsfw/serviceinterface/ServiceInterface.h" VirtualChannelReception::VirtualChannelReception(uint8_t setChannelId, - uint8_t setSlidingWindowWidth) : - channelId(setChannelId), slidingWindowWidth(setSlidingWindowWidth), positiveWindow( - setSlidingWindowWidth / 2), negativeWindow(setSlidingWindowWidth / 2), currentState( - &openState), openState(this), waitState(this), lockoutState(this), vR(0), farmBCounter( - 0) { - internalClcw.setVirtualChannel(channelId); + uint8_t setSlidingWindowWidth) + : channelId(setChannelId), + slidingWindowWidth(setSlidingWindowWidth), + positiveWindow(setSlidingWindowWidth / 2), + negativeWindow(setSlidingWindowWidth / 2), + currentState(&openState), + openState(this), + waitState(this), + lockoutState(this), + vR(0), + farmBCounter(0) { + internalClcw.setVirtualChannel(channelId); } ReturnValue_t VirtualChannelReception::mapDemultiplexing(TcTransferFrame* frame) { - uint8_t mapId = frame->getMAPId(); - mapChannelIterator iter = mapChannels.find(mapId); - if (iter == mapChannels.end()) { -// error << "VirtualChannelReception::mapDemultiplexing on VC " << std::hex << (int) channelId -// << ": MapChannel " << (int) mapId << std::dec << " not found." << std::endl; - return VC_NOT_FOUND; - } else { - return (iter->second)->extractPackets(frame); - } + uint8_t mapId = frame->getMAPId(); + mapChannelIterator iter = mapChannels.find(mapId); + if (iter == mapChannels.end()) { + // error << "VirtualChannelReception::mapDemultiplexing on VC " << std::hex << (int) + //channelId + // << ": MapChannel " << (int) mapId << std::dec << " not found." << + //std::endl; + return VC_NOT_FOUND; + } else { + return (iter->second)->extractPackets(frame); + } } ReturnValue_t VirtualChannelReception::doFARM(TcTransferFrame* frame, ClcwIF* clcw) { - uint8_t bypass = frame->bypassFlagSet(); - uint8_t controlCommand = frame->controlCommandFlagSet(); - uint8_t typeValue = (bypass << 1) + controlCommand; - switch (typeValue) { - case AD_FRAME: - return currentState->handleADFrame(frame, clcw); - case BD_FRAME: - return handleBDFrame(frame, clcw); - case BC_FRAME: - return handleBCFrame(frame, clcw); - default: - return ILLEGAL_FLAG_COMBINATION; - } + uint8_t bypass = frame->bypassFlagSet(); + uint8_t controlCommand = frame->controlCommandFlagSet(); + uint8_t typeValue = (bypass << 1) + controlCommand; + switch (typeValue) { + case AD_FRAME: + return currentState->handleADFrame(frame, clcw); + case BD_FRAME: + return handleBDFrame(frame, clcw); + case BC_FRAME: + return handleBCFrame(frame, clcw); + default: + return ILLEGAL_FLAG_COMBINATION; + } } ReturnValue_t VirtualChannelReception::frameAcceptanceAndReportingMechanism(TcTransferFrame* frame, - ClcwIF* clcw) { - ReturnValue_t result = RETURN_OK; - result = doFARM(frame, &internalClcw); - internalClcw.setReceiverFrameSequenceNumber(vR); - internalClcw.setFarmBCount(farmBCounter); - clcw->setWhole(internalClcw.getAsWhole()); - switch (result) { - case RETURN_OK: - return mapDemultiplexing(frame); - case BC_IS_SET_VR_COMMAND: - case BC_IS_UNLOCK_COMMAND: - //Need to catch these codes to avoid error reporting later. - return RETURN_OK; - default: - break; - } - return result; + ClcwIF* clcw) { + ReturnValue_t result = RETURN_OK; + result = doFARM(frame, &internalClcw); + internalClcw.setReceiverFrameSequenceNumber(vR); + internalClcw.setFarmBCount(farmBCounter); + clcw->setWhole(internalClcw.getAsWhole()); + switch (result) { + case RETURN_OK: + return mapDemultiplexing(frame); + case BC_IS_SET_VR_COMMAND: + case BC_IS_UNLOCK_COMMAND: + // Need to catch these codes to avoid error reporting later. + return RETURN_OK; + default: + break; + } + return result; } ReturnValue_t VirtualChannelReception::addMapChannel(uint8_t mapId, MapPacketExtractionIF* object) { - std::pair returnValue = mapChannels.insert( - std::pair(mapId, object)); - if (returnValue.second == true) { - return RETURN_OK; - } else { - return RETURN_FAILED; - } + std::pair returnValue = + mapChannels.insert(std::pair(mapId, object)); + if (returnValue.second == true) { + return RETURN_OK; + } else { + return RETURN_FAILED; + } } ReturnValue_t VirtualChannelReception::handleBDFrame(TcTransferFrame* frame, ClcwIF* clcw) { - farmBCounter++; - return RETURN_OK; + farmBCounter++; + return RETURN_OK; } ReturnValue_t VirtualChannelReception::handleBCFrame(TcTransferFrame* frame, ClcwIF* clcw) { - BcFrame content; - ReturnValue_t returnValue = content.initialize(frame->getFullDataField(), - frame->getFullDataLength()); - if (returnValue == BC_IS_UNLOCK_COMMAND) { - returnValue = currentState->handleBCUnlockCommand(clcw); - } else if (returnValue == BC_IS_SET_VR_COMMAND) { - returnValue = currentState->handleBCSetVrCommand(clcw, content.vR); - } else { - //Do nothing - } - return returnValue; + BcFrame content; + ReturnValue_t returnValue = + content.initialize(frame->getFullDataField(), frame->getFullDataLength()); + if (returnValue == BC_IS_UNLOCK_COMMAND) { + returnValue = currentState->handleBCUnlockCommand(clcw); + } else if (returnValue == BC_IS_SET_VR_COMMAND) { + returnValue = currentState->handleBCSetVrCommand(clcw, content.vR); + } else { + // Do nothing + } + return returnValue; } -uint8_t VirtualChannelReception::getChannelId() const { - return channelId; -} +uint8_t VirtualChannelReception::getChannelId() const { return channelId; } ReturnValue_t VirtualChannelReception::initialize() { - ReturnValue_t returnValue = RETURN_FAILED; - if ((slidingWindowWidth > 254) || (slidingWindowWidth % 2 != 0)) { + ReturnValue_t returnValue = RETURN_FAILED; + if ((slidingWindowWidth > 254) || (slidingWindowWidth % 2 != 0)) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "VirtualChannelReception::initialize: Illegal sliding window width: " - << (int) slidingWindowWidth << std::endl; + sif::error << "VirtualChannelReception::initialize: Illegal sliding window width: " + << (int)slidingWindowWidth << std::endl; #endif - return RETURN_FAILED; - } - for (mapChannelIterator iterator = mapChannels.begin(); iterator != mapChannels.end(); - iterator++) { - returnValue = iterator->second->initialize(); - if (returnValue != RETURN_OK) - break; - } - return returnValue; + return RETURN_FAILED; + } + for (mapChannelIterator iterator = mapChannels.begin(); iterator != mapChannels.end(); + iterator++) { + returnValue = iterator->second->initialize(); + if (returnValue != RETURN_OK) break; + } + return returnValue; } void VirtualChannelReception::setToWaitState() { - internalClcw.setWaitFlag(true); - this->currentState = &waitState; + internalClcw.setWaitFlag(true); + this->currentState = &waitState; } diff --git a/src/fsfw/datalinklayer/VirtualChannelReception.h b/src/fsfw/datalinklayer/VirtualChannelReception.h index 314e18ec..6dc17dd8 100644 --- a/src/fsfw/datalinklayer/VirtualChannelReception.h +++ b/src/fsfw/datalinklayer/VirtualChannelReception.h @@ -8,7 +8,8 @@ #ifndef VIRTUALCHANNELRECEPTION_H_ #define VIRTUALCHANNELRECEPTION_H_ -#include "dllConf.h" +#include + #include "CCSDSReturnValuesIF.h" #include "Clcw.h" #include "Farm1StateIF.h" @@ -17,8 +18,7 @@ #include "Farm1StateWait.h" #include "MapPacketExtractionIF.h" #include "VirtualChannelReceptionIF.h" - -#include +#include "dllConf.h" /** * Implementation of a TC Virtual Channel. * This is a full implementation of a virtual channel as specified in the CCSDS TC Space Data Link @@ -31,86 +31,95 @@ * The FARM-1 state machine uses the State Pattern. */ class VirtualChannelReception : public VirtualChannelReceptionIF, public CCSDSReturnValuesIF { - friend class Farm1StateOpen; - friend class Farm1StateWait; - friend class Farm1StateLockout; -private: - uint8_t channelId; //!< Stores the VCID that was assigned on construction. - uint8_t slidingWindowWidth; //!< A constant to set the FARM-1 sliding window width. - uint8_t positiveWindow; //!< The positive window for the FARM-1 machine. - uint8_t negativeWindow; //!< The negative window for the FARM-1 machine. -protected: - Farm1StateIF* currentState; //!< The current state. To change, one of the other states must be assigned to this pointer. - Farm1StateOpen openState; //!< Instance of the FARM-1 State "Open". - Farm1StateWait waitState; //!< Instance of the FARM-1 State "Wait". - Farm1StateLockout lockoutState; //!< Instance of the FARM-1 State "Lockout". - Clcw internalClcw; //!< A CLCW class to internally set the values before writing them back to the TTC System. - uint8_t vR; //!< The Receiver Frame Sequence Number V(R) as it shall be maintained for every Virtual Channel. - uint8_t farmBCounter; //!< The FARM-B COunter as it shall be maintained for every Virtual Channel. - typedef std::map::iterator mapChannelIterator; //!< Typedef to simplify handling of the mapChannels map. - std::map mapChannels; //!< A map that maintains all map Channels. Channels must be configured on initialization. MAy be omitted in a simplified version. - /** - * This method handles demultiplexing to different map channels. - * It parses the entries of #mapChannels and forwards the Frame to a found MAP Channel. - * @param frame The frame to forward. - * @return #VC_NOT_FOUND or the return value of the map channel extraction. - */ - ReturnValue_t mapDemultiplexing( TcTransferFrame* frame ); - /** - * A sub-method that actually does the FARM-1 handling for different Frame types. - * @param frame The Tc Transfer Frame to handle. - * @param clcw Any changes on the CLCW shall be done with this method. - * @return The return code of higher methods or @c ILLEGAL_FLAG_COMBINATION. - */ - ReturnValue_t doFARM(TcTransferFrame* frame, ClcwIF* clcw); - /** - * Handles incoming BD Frames. - * Handling these Frames is independent of the State, so no subcall to #currentState is - * required. - * @param frame The Tc Transfer Frame to handle. - * @param clcw Any changes on the CLCW shall be done with this method. - * @return Always returns @c RETURN_OK. - */ - ReturnValue_t handleBDFrame( TcTransferFrame* frame, ClcwIF* clcw ); - /** - * Handles incoming BC Frames. - * The type of the BC Frame is detected and checked first, then methods of #currentState are called. - * @param frame The Tc Transfer Frame to handle. - * @param clcw Any changes on the CLCW shall be done with this method. - * @return The failure code of BC Frame interpretation or the return code of higher methods. - */ - ReturnValue_t handleBCFrame( TcTransferFrame* frame, ClcwIF* clcw ); -public: - /** - * Default constructor. - * Only sets the channelId of the channel. Setting the Sliding Window width is possible as well. - * @param setChannelId Virtual Channel Identifier (VCID) of the channel. - */ - VirtualChannelReception( uint8_t setChannelId, uint8_t setSlidingWindowWidth ); - ReturnValue_t frameAcceptanceAndReportingMechanism( TcTransferFrame* frame, ClcwIF* clcw ); - /** - * Helper method to simplify adding a mapChannel during construction. - * @param mapId The mapId of the object to add. - * @param object Pointer to the MapPacketExtraction object itself. - * @return @c RETURN_OK if the channel was successfully inserted, @c RETURN_FAILED otherwise. - */ - ReturnValue_t addMapChannel( uint8_t mapId, MapPacketExtractionIF* object ); - /** - * The initialization routine checks the set #slidingWindowWidth and initializes all MAP - * channels. - * @return @c RETURN_OK on successful initialization, @c RETURN_FAILED otherwise. - */ - ReturnValue_t initialize(); - /** - * Getter for the VCID. - * @return The #channelId. - */ - uint8_t getChannelId() const; - /** - * Small method to set the state to Farm1StateWait. - */ - void setToWaitState(); + friend class Farm1StateOpen; + friend class Farm1StateWait; + friend class Farm1StateLockout; + + private: + uint8_t channelId; //!< Stores the VCID that was assigned on construction. + uint8_t slidingWindowWidth; //!< A constant to set the FARM-1 sliding window width. + uint8_t positiveWindow; //!< The positive window for the FARM-1 machine. + uint8_t negativeWindow; //!< The negative window for the FARM-1 machine. + protected: + Farm1StateIF* currentState; //!< The current state. To change, one of the other states must be + //!< assigned to this pointer. + Farm1StateOpen openState; //!< Instance of the FARM-1 State "Open". + Farm1StateWait waitState; //!< Instance of the FARM-1 State "Wait". + Farm1StateLockout lockoutState; //!< Instance of the FARM-1 State "Lockout". + Clcw internalClcw; //!< A CLCW class to internally set the values before writing them back to the + //!< TTC System. + uint8_t vR; //!< The Receiver Frame Sequence Number V(R) as it shall be maintained for every + //!< Virtual Channel. + uint8_t + farmBCounter; //!< The FARM-B COunter as it shall be maintained for every Virtual Channel. + typedef std::map::iterator + mapChannelIterator; //!< Typedef to simplify handling of the mapChannels map. + std::map + mapChannels; //!< A map that maintains all map Channels. Channels must be configured on + //!< initialization. MAy be omitted in a simplified version. + /** + * This method handles demultiplexing to different map channels. + * It parses the entries of #mapChannels and forwards the Frame to a found MAP Channel. + * @param frame The frame to forward. + * @return #VC_NOT_FOUND or the return value of the map channel extraction. + */ + ReturnValue_t mapDemultiplexing(TcTransferFrame* frame); + /** + * A sub-method that actually does the FARM-1 handling for different Frame types. + * @param frame The Tc Transfer Frame to handle. + * @param clcw Any changes on the CLCW shall be done with this method. + * @return The return code of higher methods or @c ILLEGAL_FLAG_COMBINATION. + */ + ReturnValue_t doFARM(TcTransferFrame* frame, ClcwIF* clcw); + /** + * Handles incoming BD Frames. + * Handling these Frames is independent of the State, so no subcall to #currentState is + * required. + * @param frame The Tc Transfer Frame to handle. + * @param clcw Any changes on the CLCW shall be done with this method. + * @return Always returns @c RETURN_OK. + */ + ReturnValue_t handleBDFrame(TcTransferFrame* frame, ClcwIF* clcw); + /** + * Handles incoming BC Frames. + * The type of the BC Frame is detected and checked first, then methods of #currentState are + * called. + * @param frame The Tc Transfer Frame to handle. + * @param clcw Any changes on the CLCW shall be done with this method. + * @return The failure code of BC Frame interpretation or the return code of higher methods. + */ + ReturnValue_t handleBCFrame(TcTransferFrame* frame, ClcwIF* clcw); + + public: + /** + * Default constructor. + * Only sets the channelId of the channel. Setting the Sliding Window width is possible as well. + * @param setChannelId Virtual Channel Identifier (VCID) of the channel. + */ + VirtualChannelReception(uint8_t setChannelId, uint8_t setSlidingWindowWidth); + ReturnValue_t frameAcceptanceAndReportingMechanism(TcTransferFrame* frame, ClcwIF* clcw); + /** + * Helper method to simplify adding a mapChannel during construction. + * @param mapId The mapId of the object to add. + * @param object Pointer to the MapPacketExtraction object itself. + * @return @c RETURN_OK if the channel was successfully inserted, @c RETURN_FAILED otherwise. + */ + ReturnValue_t addMapChannel(uint8_t mapId, MapPacketExtractionIF* object); + /** + * The initialization routine checks the set #slidingWindowWidth and initializes all MAP + * channels. + * @return @c RETURN_OK on successful initialization, @c RETURN_FAILED otherwise. + */ + ReturnValue_t initialize(); + /** + * Getter for the VCID. + * @return The #channelId. + */ + uint8_t getChannelId() const; + /** + * Small method to set the state to Farm1StateWait. + */ + void setToWaitState(); }; - #endif /* VIRTUALCHANNELRECEPTION_H_ */ diff --git a/src/fsfw/datalinklayer/VirtualChannelReceptionIF.h b/src/fsfw/datalinklayer/VirtualChannelReceptionIF.h index e7a21b3c..3426f21c 100644 --- a/src/fsfw/datalinklayer/VirtualChannelReceptionIF.h +++ b/src/fsfw/datalinklayer/VirtualChannelReceptionIF.h @@ -8,9 +8,9 @@ #ifndef VIRTUALCHANNELRECEPTIONIF_H_ #define VIRTUALCHANNELRECEPTIONIF_H_ -#include "dllConf.h" #include "ClcwIF.h" #include "TcTransferFrame.h" +#include "dllConf.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" /** @@ -18,41 +18,35 @@ * It represents a single TC Virtual Channel that operates on one IO */ class VirtualChannelReceptionIF { -public: - /** - * Enum including all valid types of frames. - * The type is made up by two flags, so 0b1111 is definitely illegal. - */ - enum frameType { - AD_FRAME = 0b00, - BC_FRAME = 0b11, - BD_FRAME = 0b10, - ILLEGAL_FRAME = 0b1111 - }; - /** - * Empty virtual destructor. - */ - virtual ~VirtualChannelReceptionIF() { - } - /** - * This method shall accept frames and do all FARM-1 stuff. - * Handling the Frame includes forwarding to higher-level procedures. - * @param frame The Tc Transfer Frame that was received and checked. - * @param clcw Any changes to the CLCW value are forwarded by using this parameter. - * @return The return Value shall indicate successful processing with @c RETURN_OK. - */ - virtual ReturnValue_t frameAcceptanceAndReportingMechanism( TcTransferFrame* frame, ClcwIF* clcw ) = 0; - /** - * If any other System Objects are required for operation they shall be initialized here. - * @return @c RETURN_OK for successful initialization. - */ - virtual ReturnValue_t initialize() = 0; - /** - * Getter for the VCID. - * @return The #channelId. - */ - virtual uint8_t getChannelId() const = 0; + public: + /** + * Enum including all valid types of frames. + * The type is made up by two flags, so 0b1111 is definitely illegal. + */ + enum frameType { AD_FRAME = 0b00, BC_FRAME = 0b11, BD_FRAME = 0b10, ILLEGAL_FRAME = 0b1111 }; + /** + * Empty virtual destructor. + */ + virtual ~VirtualChannelReceptionIF() {} + /** + * This method shall accept frames and do all FARM-1 stuff. + * Handling the Frame includes forwarding to higher-level procedures. + * @param frame The Tc Transfer Frame that was received and checked. + * @param clcw Any changes to the CLCW value are forwarded by using this parameter. + * @return The return Value shall indicate successful processing with @c RETURN_OK. + */ + virtual ReturnValue_t frameAcceptanceAndReportingMechanism(TcTransferFrame* frame, + ClcwIF* clcw) = 0; + /** + * If any other System Objects are required for operation they shall be initialized here. + * @return @c RETURN_OK for successful initialization. + */ + virtual ReturnValue_t initialize() = 0; + /** + * Getter for the VCID. + * @return The #channelId. + */ + virtual uint8_t getChannelId() const = 0; }; - #endif /* VIRTUALCHANNELRECEPTIONIF_H_ */ diff --git a/src/fsfw/datapool/DataSetIF.h b/src/fsfw/datapool/DataSetIF.h index ea1a7126..492bcf29 100644 --- a/src/fsfw/datapool/DataSetIF.h +++ b/src/fsfw/datapool/DataSetIF.h @@ -16,30 +16,30 @@ class PoolVariableIF; * @ingroup data_pool */ class DataSetIF { -public: - static constexpr uint8_t INTERFACE_ID = CLASS_ID::DATA_SET_CLASS; - static constexpr ReturnValue_t INVALID_PARAMETER_DEFINITION = MAKE_RETURN_CODE(1); - static constexpr ReturnValue_t SET_WAS_ALREADY_READ = MAKE_RETURN_CODE(2); - static constexpr ReturnValue_t COMMITING_WITHOUT_READING = MAKE_RETURN_CODE(3); + public: + static constexpr uint8_t INTERFACE_ID = CLASS_ID::DATA_SET_CLASS; + static constexpr ReturnValue_t INVALID_PARAMETER_DEFINITION = MAKE_RETURN_CODE(1); + static constexpr ReturnValue_t SET_WAS_ALREADY_READ = MAKE_RETURN_CODE(2); + static constexpr ReturnValue_t COMMITING_WITHOUT_READING = MAKE_RETURN_CODE(3); - static constexpr ReturnValue_t DATA_SET_UNINITIALISED = MAKE_RETURN_CODE(4); - static constexpr ReturnValue_t DATA_SET_FULL = MAKE_RETURN_CODE(5); - static constexpr ReturnValue_t POOL_VAR_NULL = MAKE_RETURN_CODE(6); + static constexpr ReturnValue_t DATA_SET_UNINITIALISED = MAKE_RETURN_CODE(4); + static constexpr ReturnValue_t DATA_SET_FULL = MAKE_RETURN_CODE(5); + static constexpr ReturnValue_t POOL_VAR_NULL = MAKE_RETURN_CODE(6); - /** - * @brief This is an empty virtual destructor, - * as it is proposed for C++ interfaces. - */ - virtual ~DataSetIF() {} + /** + * @brief This is an empty virtual destructor, + * as it is proposed for C++ interfaces. + */ + virtual ~DataSetIF() {} - /** - * @brief This operation provides a method to register local data pool - * variables to register in a data set by passing itself - * to this DataSet operation. - */ - virtual ReturnValue_t registerVariable(PoolVariableIF* variable) = 0; + /** + * @brief This operation provides a method to register local data pool + * variables to register in a data set by passing itself + * to this DataSet operation. + */ + virtual ReturnValue_t registerVariable(PoolVariableIF* variable) = 0; - virtual uint16_t getFillCount() const = 0; + virtual uint16_t getFillCount() const = 0; }; #endif /* FSFW_DATAPOOL_DATASETIF_H_ */ diff --git a/src/fsfw/datapool/HkSwitchHelper.cpp b/src/fsfw/datapool/HkSwitchHelper.cpp index bcf237ba..7f6ffd17 100644 --- a/src/fsfw/datapool/HkSwitchHelper.cpp +++ b/src/fsfw/datapool/HkSwitchHelper.cpp @@ -1,75 +1,67 @@ #include "fsfw/datapool/HkSwitchHelper.h" + #include "fsfw/ipc/QueueFactory.h" -HkSwitchHelper::HkSwitchHelper(EventReportingProxyIF* eventProxy) : - commandActionHelper(this), eventProxy(eventProxy) { - actionQueue = QueueFactory::instance()->createMessageQueue(); +HkSwitchHelper::HkSwitchHelper(EventReportingProxyIF* eventProxy) + : commandActionHelper(this), eventProxy(eventProxy) { + actionQueue = QueueFactory::instance()->createMessageQueue(); } -HkSwitchHelper::~HkSwitchHelper() { - QueueFactory::instance()->deleteMessageQueue(actionQueue); -} +HkSwitchHelper::~HkSwitchHelper() { QueueFactory::instance()->deleteMessageQueue(actionQueue); } ReturnValue_t HkSwitchHelper::initialize() { - ReturnValue_t result = commandActionHelper.initialize(); + ReturnValue_t result = commandActionHelper.initialize(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - return result; + return result; } ReturnValue_t HkSwitchHelper::performOperation(uint8_t operationCode) { - CommandMessage command; - while (actionQueue->receiveMessage(&command) == HasReturnvaluesIF::RETURN_OK) { - ReturnValue_t result = commandActionHelper.handleReply(&command); - if (result == HasReturnvaluesIF::RETURN_OK) { - continue; - } - command.setToUnknownCommand(); - actionQueue->reply(&command); - } + CommandMessage command; + while (actionQueue->receiveMessage(&command) == HasReturnvaluesIF::RETURN_OK) { + ReturnValue_t result = commandActionHelper.handleReply(&command); + if (result == HasReturnvaluesIF::RETURN_OK) { + continue; + } + command.setToUnknownCommand(); + actionQueue->reply(&command); + } - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } -void HkSwitchHelper::stepSuccessfulReceived(ActionId_t actionId, uint8_t step) { -} +void HkSwitchHelper::stepSuccessfulReceived(ActionId_t actionId, uint8_t step) {} void HkSwitchHelper::stepFailedReceived(ActionId_t actionId, uint8_t step, - ReturnValue_t returnCode) { - eventProxy->forwardEvent(SWITCHING_TM_FAILED, returnCode, actionId); + ReturnValue_t returnCode) { + eventProxy->forwardEvent(SWITCHING_TM_FAILED, returnCode, actionId); } -void HkSwitchHelper::dataReceived(ActionId_t actionId, const uint8_t* data, - uint32_t size) { -} +void HkSwitchHelper::dataReceived(ActionId_t actionId, const uint8_t* data, uint32_t size) {} -void HkSwitchHelper::completionSuccessfulReceived(ActionId_t actionId) { -} +void HkSwitchHelper::completionSuccessfulReceived(ActionId_t actionId) {} -void HkSwitchHelper::completionFailedReceived(ActionId_t actionId, - ReturnValue_t returnCode) { - eventProxy->forwardEvent(SWITCHING_TM_FAILED, returnCode, actionId); +void HkSwitchHelper::completionFailedReceived(ActionId_t actionId, ReturnValue_t returnCode) { + eventProxy->forwardEvent(SWITCHING_TM_FAILED, returnCode, actionId); } ReturnValue_t HkSwitchHelper::switchHK(SerializeIF* sids, bool enable) { -// ActionId_t action = HKService::DISABLE_HK; -// if (enable) { -// action = HKService::ENABLE_HK; -// } -// -// ReturnValue_t result = commandActionHelper.commandAction( -// objects::PUS_HK_SERVICE, action, sids); -// -// if (result != HasReturnvaluesIF::RETURN_OK) { -// eventProxy->forwardEvent(SWITCHING_TM_FAILED, result); -// } -// return result; - return HasReturnvaluesIF::RETURN_OK; + // ActionId_t action = HKService::DISABLE_HK; + // if (enable) { + // action = HKService::ENABLE_HK; + // } + // + // ReturnValue_t result = commandActionHelper.commandAction( + // objects::PUS_HK_SERVICE, action, sids); + // + // if (result != HasReturnvaluesIF::RETURN_OK) { + // eventProxy->forwardEvent(SWITCHING_TM_FAILED, result); + // } + // return result; + return HasReturnvaluesIF::RETURN_OK; } -MessageQueueIF* HkSwitchHelper::getCommandQueuePtr() { - return actionQueue; -} +MessageQueueIF* HkSwitchHelper::getCommandQueuePtr() { return actionQueue; } diff --git a/src/fsfw/datapool/HkSwitchHelper.h b/src/fsfw/datapool/HkSwitchHelper.h index 611c5d86..a0becd81 100644 --- a/src/fsfw/datapool/HkSwitchHelper.h +++ b/src/fsfw/datapool/HkSwitchHelper.h @@ -1,46 +1,44 @@ #ifndef FRAMEWORK_DATAPOOL_HKSWITCHHELPER_H_ #define FRAMEWORK_DATAPOOL_HKSWITCHHELPER_H_ -#include "fsfw/tasks/ExecutableObjectIF.h" #include "fsfw/action/CommandsActionsIF.h" #include "fsfw/events/EventReportingProxyIF.h" +#include "fsfw/tasks/ExecutableObjectIF.h" -//TODO this class violations separation between mission and framework -//but it is only a transitional solution until the Datapool is -//implemented decentrally +// TODO this class violations separation between mission and framework +// but it is only a transitional solution until the Datapool is +// implemented decentrally -class HkSwitchHelper: public ExecutableObjectIF, public CommandsActionsIF { -public: +class HkSwitchHelper : public ExecutableObjectIF, public CommandsActionsIF { + public: + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::HK; + static const Event SWITCHING_TM_FAILED = + MAKE_EVENT(1, severity::LOW); //!< Commanding the HK Service failed, p1: error code, p2 + //!< action: 0 disable / 1 enable - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::HK; - static const Event SWITCHING_TM_FAILED = MAKE_EVENT(1, severity::LOW); //!< Commanding the HK Service failed, p1: error code, p2 action: 0 disable / 1 enable + HkSwitchHelper(EventReportingProxyIF* eventProxy); + virtual ~HkSwitchHelper(); - HkSwitchHelper(EventReportingProxyIF *eventProxy); - virtual ~HkSwitchHelper(); + ReturnValue_t initialize(); - ReturnValue_t initialize(); + virtual ReturnValue_t performOperation(uint8_t operationCode = 0); - virtual ReturnValue_t performOperation(uint8_t operationCode = 0); + ReturnValue_t switchHK(SerializeIF* sids, bool enable); - ReturnValue_t switchHK(SerializeIF *sids, bool enable); + virtual void setTaskIF(PeriodicTaskIF* task_){}; - virtual void setTaskIF(PeriodicTaskIF* task_){}; + protected: + virtual void stepSuccessfulReceived(ActionId_t actionId, uint8_t step); + virtual void stepFailedReceived(ActionId_t actionId, uint8_t step, ReturnValue_t returnCode); + virtual void dataReceived(ActionId_t actionId, const uint8_t* data, uint32_t size); + virtual void completionSuccessfulReceived(ActionId_t actionId); + virtual void completionFailedReceived(ActionId_t actionId, ReturnValue_t returnCode); + virtual MessageQueueIF* getCommandQueuePtr(); -protected: - virtual void stepSuccessfulReceived(ActionId_t actionId, uint8_t step); - virtual void stepFailedReceived(ActionId_t actionId, uint8_t step, - ReturnValue_t returnCode); - virtual void dataReceived(ActionId_t actionId, const uint8_t* data, - uint32_t size); - virtual void completionSuccessfulReceived(ActionId_t actionId); - virtual void completionFailedReceived(ActionId_t actionId, - ReturnValue_t returnCode); - virtual MessageQueueIF* getCommandQueuePtr(); - -private: - CommandActionHelper commandActionHelper; - MessageQueueIF* actionQueue; - EventReportingProxyIF *eventProxy; + private: + CommandActionHelper commandActionHelper; + MessageQueueIF* actionQueue; + EventReportingProxyIF* eventProxy; }; #endif /* FRAMEWORK_DATAPOOL_HKSWITCHHELPER_H_ */ diff --git a/src/fsfw/datapool/PoolDataSetBase.cpp b/src/fsfw/datapool/PoolDataSetBase.cpp index 7856dc9a..b31f4725 100644 --- a/src/fsfw/datapool/PoolDataSetBase.cpp +++ b/src/fsfw/datapool/PoolDataSetBase.cpp @@ -1,233 +1,217 @@ #include "fsfw/datapool/PoolDataSetBase.h" -#include "fsfw/datapool/ReadCommitIFAttorney.h" - -#include "fsfw/serviceinterface/ServiceInterface.h" #include +#include "fsfw/datapool/ReadCommitIFAttorney.h" +#include "fsfw/serviceinterface/ServiceInterface.h" + PoolDataSetBase::PoolDataSetBase(PoolVariableIF** registeredVariablesArray, - const size_t maxFillCount): - registeredVariables(registeredVariablesArray), - maxFillCount(maxFillCount) {} + const size_t maxFillCount) + : registeredVariables(registeredVariablesArray), maxFillCount(maxFillCount) {} PoolDataSetBase::~PoolDataSetBase() {} - -ReturnValue_t PoolDataSetBase::registerVariable(PoolVariableIF *variable) { - if(registeredVariables == nullptr) { - /* Underlying container invalid */ - return HasReturnvaluesIF::RETURN_FAILED; - } - if (state != States::STATE_SET_UNINITIALISED) { +ReturnValue_t PoolDataSetBase::registerVariable(PoolVariableIF* variable) { + if (registeredVariables == nullptr) { + /* Underlying container invalid */ + return HasReturnvaluesIF::RETURN_FAILED; + } + if (state != States::STATE_SET_UNINITIALISED) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "DataSet::registerVariable: Call made in wrong position." << std::endl; + sif::error << "DataSet::registerVariable: Call made in wrong position." << std::endl; #else - sif::printError("DataSet::registerVariable: Call made in wrong position."); + sif::printError("DataSet::registerVariable: Call made in wrong position."); #endif - return DataSetIF::DATA_SET_UNINITIALISED; - } - if (variable == nullptr) { + return DataSetIF::DATA_SET_UNINITIALISED; + } + if (variable == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "DataSet::registerVariable: Pool variable is nullptr." << std::endl; + sif::error << "DataSet::registerVariable: Pool variable is nullptr." << std::endl; #else - sif::printError("DataSet::registerVariable: Pool variable is nullptr.\n"); + sif::printError("DataSet::registerVariable: Pool variable is nullptr.\n"); #endif - return DataSetIF::POOL_VAR_NULL; - } - if (fillCount >= maxFillCount) { + return DataSetIF::POOL_VAR_NULL; + } + if (fillCount >= maxFillCount) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "DataSet::registerVariable: DataSet is full." << std::endl; + sif::error << "DataSet::registerVariable: DataSet is full." << std::endl; #else - sif::printError("DataSet::registerVariable: DataSet is full.\n"); + sif::printError("DataSet::registerVariable: DataSet is full.\n"); #endif - return DataSetIF::DATA_SET_FULL; - } - registeredVariables[fillCount] = variable; - fillCount++; - return HasReturnvaluesIF::RETURN_OK; + return DataSetIF::DATA_SET_FULL; + } + registeredVariables[fillCount] = variable; + fillCount++; + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t PoolDataSetBase::read(MutexIF::TimeoutType timeoutType, - uint32_t lockTimeout) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - ReturnValue_t error = result; - if (state == States::STATE_SET_UNINITIALISED) { - lockDataPool(timeoutType, lockTimeout); - for (uint16_t count = 0; count < fillCount; count++) { - result = readVariable(count); - if(result != RETURN_OK) { - error = result; - } - } - state = States::STATE_SET_WAS_READ; - unlockDataPool(); +ReturnValue_t PoolDataSetBase::read(MutexIF::TimeoutType timeoutType, uint32_t lockTimeout) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + ReturnValue_t error = result; + if (state == States::STATE_SET_UNINITIALISED) { + lockDataPool(timeoutType, lockTimeout); + for (uint16_t count = 0; count < fillCount; count++) { + result = readVariable(count); + if (result != RETURN_OK) { + error = result; + } } - else { + state = States::STATE_SET_WAS_READ; + unlockDataPool(); + } else { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "PoolDataSetBase::read: Call made in wrong position. Don't forget to " - "commit member datasets!" << std::endl; + sif::warning << "PoolDataSetBase::read: Call made in wrong position. Don't forget to " + "commit member datasets!" + << std::endl; #else - sif::printWarning("PoolDataSetBase::read: Call made in wrong position. Don't forget to " - "commit member datasets!\n"); + sif::printWarning( + "PoolDataSetBase::read: Call made in wrong position. Don't forget to " + "commit member datasets!\n"); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ - result = SET_WAS_ALREADY_READ; - } + result = SET_WAS_ALREADY_READ; + } - if(error != HasReturnvaluesIF::RETURN_OK) { - result = error; - } - return result; + if (error != HasReturnvaluesIF::RETURN_OK) { + result = error; + } + return result; } -uint16_t PoolDataSetBase::getFillCount() const { - return fillCount; -} +uint16_t PoolDataSetBase::getFillCount() const { return fillCount; } ReturnValue_t PoolDataSetBase::readVariable(uint16_t count) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - if(registeredVariables[count] == nullptr) { - /* Configuration error. */ - return HasReturnvaluesIF::RETURN_FAILED; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + if (registeredVariables[count] == nullptr) { + /* Configuration error. */ + return HasReturnvaluesIF::RETURN_FAILED; + } + + /* These checks are often performed by the respective variable implementation too, but I guess + a double check does not hurt. */ + if (registeredVariables[count]->getReadWriteMode() != PoolVariableIF::VAR_WRITE and + registeredVariables[count]->getDataPoolId() != PoolVariableIF::NO_PARAMETER) { + if (protectEveryReadCommitCall) { + result = + registeredVariables[count]->read(timeoutTypeForSingleVars, mutexTimeoutForSingleVars); + } else { + /* The readWithoutLock function is protected, so we use the attorney here */ + result = ReadCommitIFAttorney::readWithoutLock(registeredVariables[count]); } - /* These checks are often performed by the respective variable implementation too, but I guess - a double check does not hurt. */ - if (registeredVariables[count]->getReadWriteMode() != PoolVariableIF::VAR_WRITE and - registeredVariables[count]->getDataPoolId() != PoolVariableIF::NO_PARAMETER) { - if(protectEveryReadCommitCall) { - result = registeredVariables[count]->read(timeoutTypeForSingleVars, - mutexTimeoutForSingleVars); - } - else { - /* The readWithoutLock function is protected, so we use the attorney here */ - result = ReadCommitIFAttorney::readWithoutLock(registeredVariables[count]); - } - - if(result != HasReturnvaluesIF::RETURN_OK) { - result = INVALID_PARAMETER_DEFINITION; - } + if (result != HasReturnvaluesIF::RETURN_OK) { + result = INVALID_PARAMETER_DEFINITION; } - return result; + } + return result; } -ReturnValue_t PoolDataSetBase::commit(MutexIF::TimeoutType timeoutType, - uint32_t lockTimeout) { - if (state == States::STATE_SET_WAS_READ) { - handleAlreadyReadDatasetCommit(timeoutType, lockTimeout); - return HasReturnvaluesIF::RETURN_OK; - } - else { - return handleUnreadDatasetCommit(timeoutType, lockTimeout); - } +ReturnValue_t PoolDataSetBase::commit(MutexIF::TimeoutType timeoutType, uint32_t lockTimeout) { + if (state == States::STATE_SET_WAS_READ) { + handleAlreadyReadDatasetCommit(timeoutType, lockTimeout); + return HasReturnvaluesIF::RETURN_OK; + } else { + return handleUnreadDatasetCommit(timeoutType, lockTimeout); + } } -void PoolDataSetBase::handleAlreadyReadDatasetCommit( - MutexIF::TimeoutType timeoutType, uint32_t lockTimeout) { - lockDataPool(timeoutType, lockTimeout); - for (uint16_t count = 0; count < fillCount; count++) { - if ((registeredVariables[count]->getReadWriteMode() != PoolVariableIF::VAR_READ) and - (registeredVariables[count]->getDataPoolId() != PoolVariableIF::NO_PARAMETER)) { - if(protectEveryReadCommitCall) { - registeredVariables[count]->commit(timeoutTypeForSingleVars, - mutexTimeoutForSingleVars); - } - else { - /* The commitWithoutLock function is protected, so we use the attorney here */ - ReadCommitIFAttorney::commitWithoutLock(registeredVariables[count]); - } - } +void PoolDataSetBase::handleAlreadyReadDatasetCommit(MutexIF::TimeoutType timeoutType, + uint32_t lockTimeout) { + lockDataPool(timeoutType, lockTimeout); + for (uint16_t count = 0; count < fillCount; count++) { + if ((registeredVariables[count]->getReadWriteMode() != PoolVariableIF::VAR_READ) and + (registeredVariables[count]->getDataPoolId() != PoolVariableIF::NO_PARAMETER)) { + if (protectEveryReadCommitCall) { + registeredVariables[count]->commit(timeoutTypeForSingleVars, mutexTimeoutForSingleVars); + } else { + /* The commitWithoutLock function is protected, so we use the attorney here */ + ReadCommitIFAttorney::commitWithoutLock(registeredVariables[count]); + } } - state = States::STATE_SET_UNINITIALISED; - unlockDataPool(); + } + state = States::STATE_SET_UNINITIALISED; + unlockDataPool(); } -ReturnValue_t PoolDataSetBase::handleUnreadDatasetCommit( - MutexIF::TimeoutType timeoutType, uint32_t lockTimeout) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - lockDataPool(timeoutType, lockTimeout); - for (uint16_t count = 0; count < fillCount; count++) { - if ((registeredVariables[count]->getReadWriteMode() == PoolVariableIF::VAR_WRITE) and - (registeredVariables[count]->getDataPoolId() != PoolVariableIF::NO_PARAMETER)) { - if(protectEveryReadCommitCall) { - result = registeredVariables[count]->commit(timeoutTypeForSingleVars, - mutexTimeoutForSingleVars); - } - else { - /* The commitWithoutLock function is protected, so we use the attorney here */ - ReadCommitIFAttorney::commitWithoutLock(registeredVariables[count]); - } +ReturnValue_t PoolDataSetBase::handleUnreadDatasetCommit(MutexIF::TimeoutType timeoutType, + uint32_t lockTimeout) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + lockDataPool(timeoutType, lockTimeout); + for (uint16_t count = 0; count < fillCount; count++) { + if ((registeredVariables[count]->getReadWriteMode() == PoolVariableIF::VAR_WRITE) and + (registeredVariables[count]->getDataPoolId() != PoolVariableIF::NO_PARAMETER)) { + if (protectEveryReadCommitCall) { + result = + registeredVariables[count]->commit(timeoutTypeForSingleVars, mutexTimeoutForSingleVars); + } else { + /* The commitWithoutLock function is protected, so we use the attorney here */ + ReadCommitIFAttorney::commitWithoutLock(registeredVariables[count]); + } - } else if (registeredVariables[count]->getDataPoolId() - != PoolVariableIF::NO_PARAMETER) { - if (result != COMMITING_WITHOUT_READING) { + } else if (registeredVariables[count]->getDataPoolId() != PoolVariableIF::NO_PARAMETER) { + if (result != COMMITING_WITHOUT_READING) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "DataSet::commit(): commit-without-read call made " - "with non write-only variable." << std::endl; + sif::error << "DataSet::commit(): commit-without-read call made " + "with non write-only variable." + << std::endl; #endif - result = COMMITING_WITHOUT_READING; - } - } + result = COMMITING_WITHOUT_READING; + } } - state = States::STATE_SET_UNINITIALISED; - unlockDataPool(); - return result; + } + state = States::STATE_SET_UNINITIALISED; + unlockDataPool(); + return result; } - ReturnValue_t PoolDataSetBase::lockDataPool(MutexIF::TimeoutType timeoutType, - uint32_t lockTimeout) { - return HasReturnvaluesIF::RETURN_OK; + uint32_t lockTimeout) { + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t PoolDataSetBase::unlockDataPool() { - return HasReturnvaluesIF::RETURN_OK; -} +ReturnValue_t PoolDataSetBase::unlockDataPool() { return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t PoolDataSetBase::serialize(uint8_t** buffer, size_t* size, - const size_t maxSize, SerializeIF::Endianness streamEndianness) const { - ReturnValue_t result = HasReturnvaluesIF::RETURN_FAILED; - for (uint16_t count = 0; count < fillCount; count++) { - result = registeredVariables[count]->serialize(buffer, size, maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } +ReturnValue_t PoolDataSetBase::serialize(uint8_t** buffer, size_t* size, const size_t maxSize, + SerializeIF::Endianness streamEndianness) const { + ReturnValue_t result = HasReturnvaluesIF::RETURN_FAILED; + for (uint16_t count = 0; count < fillCount; count++) { + result = registeredVariables[count]->serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; } - return result; + } + return result; } ReturnValue_t PoolDataSetBase::deSerialize(const uint8_t** buffer, size_t* size, - SerializeIF::Endianness streamEndianness) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_FAILED; - for (uint16_t count = 0; count < fillCount; count++) { - result = registeredVariables[count]->deSerialize(buffer, size, - streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + SerializeIF::Endianness streamEndianness) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_FAILED; + for (uint16_t count = 0; count < fillCount; count++) { + result = registeredVariables[count]->deSerialize(buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; } - return result; + } + return result; } size_t PoolDataSetBase::getSerializedSize() const { - uint32_t size = 0; - for (uint16_t count = 0; count < fillCount; count++) { - size += registeredVariables[count]->getSerializedSize(); - } - return size; + uint32_t size = 0; + for (uint16_t count = 0; count < fillCount; count++) { + size += registeredVariables[count]->getSerializedSize(); + } + return size; } -void PoolDataSetBase::setContainer(PoolVariableIF **variablesContainer) { - this->registeredVariables = variablesContainer; +void PoolDataSetBase::setContainer(PoolVariableIF** variablesContainer) { + this->registeredVariables = variablesContainer; } -PoolVariableIF** PoolDataSetBase::getContainer() const { - return registeredVariables; -} +PoolVariableIF** PoolDataSetBase::getContainer() const { return registeredVariables; } -void PoolDataSetBase::setReadCommitProtectionBehaviour( - bool protectEveryReadCommit, MutexIF::TimeoutType timeoutType, - uint32_t mutexTimeout) { - this->protectEveryReadCommitCall = protectEveryReadCommit; - this->timeoutTypeForSingleVars = timeoutType; - this->mutexTimeoutForSingleVars = mutexTimeout; +void PoolDataSetBase::setReadCommitProtectionBehaviour(bool protectEveryReadCommit, + MutexIF::TimeoutType timeoutType, + uint32_t mutexTimeout) { + this->protectEveryReadCommitCall = protectEveryReadCommit; + this->timeoutTypeForSingleVars = timeoutType; + this->mutexTimeoutForSingleVars = mutexTimeout; } diff --git a/src/fsfw/datapool/PoolDataSetBase.h b/src/fsfw/datapool/PoolDataSetBase.h index 36cf2a30..1b4bacda 100644 --- a/src/fsfw/datapool/PoolDataSetBase.h +++ b/src/fsfw/datapool/PoolDataSetBase.h @@ -3,9 +3,8 @@ #include "PoolDataSetIF.h" #include "PoolVariableIF.h" - -#include "fsfw/serialize/SerializeIF.h" #include "fsfw/ipc/MutexIF.h" +#include "fsfw/serialize/SerializeIF.h" /** * @brief The DataSetBase class manages a set of locally checked out variables. @@ -30,152 +29,145 @@ * @author Bastian Baetz * @ingroup data_pool */ -class PoolDataSetBase: - public PoolDataSetIF, - public SerializeIF, - public HasReturnvaluesIF { -public: +class PoolDataSetBase : public PoolDataSetIF, public SerializeIF, public HasReturnvaluesIF { + public: + /** + * @brief Creates an empty dataset. Use registerVariable or + * supply a pointer to this dataset to PoolVariable + * initializations to register pool variables. + */ + PoolDataSetBase(PoolVariableIF** registeredVariablesArray, const size_t maxFillCount); - /** - * @brief Creates an empty dataset. Use registerVariable or - * supply a pointer to this dataset to PoolVariable - * initializations to register pool variables. - */ - PoolDataSetBase(PoolVariableIF** registeredVariablesArray, const size_t maxFillCount); + /* Forbidden for now */ + PoolDataSetBase(const PoolDataSetBase& otherSet) = delete; + const PoolDataSetBase& operator=(const PoolDataSetBase& otherSet) = delete; - /* Forbidden for now */ - PoolDataSetBase(const PoolDataSetBase& otherSet) = delete; - const PoolDataSetBase& operator=(const PoolDataSetBase& otherSet) = delete; + virtual ~PoolDataSetBase(); - virtual~ PoolDataSetBase(); + /** + * @brief The read call initializes reading out all registered variables. + * It is mandatory to call commit after every read call! + * @details + * It iterates through the list of registered variables and calls all read() + * functions of the registered pool variables (which read out their values + * from the data pool) which are not write-only. + * In case of an error (e.g. a wrong data type, or an invalid data pool id), + * the operation is aborted and @c INVALID_PARAMETER_DEFINITION returned. + * + * The data pool is locked during the whole read operation and + * freed afterwards. It is mandatory to call commit after a read call, + * even if the read operation is not successful! + * @return + * - @c RETURN_OK if all variables were read successfully. + * - @c INVALID_PARAMETER_DEFINITION if a pool entry does not exist or there + * is a type conflict. + * - @c SET_WAS_ALREADY_READ if read() is called twice without calling + * commit() in between + */ + virtual ReturnValue_t read(MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, + uint32_t lockTimeout = 20) override; + /** + * @brief The commit call initializes writing back the registered variables. + * @details + * It iterates through the list of registered variables and calls the + * commit() method of the remaining registered variables (which write back + * their values to the pool). + * + * The data pool is locked during the whole commit operation and + * freed afterwards. The state changes to "was committed" after this operation. + * + * If the set does contain at least one variable which is not write-only + * commit() can only be called after read(). If the set only contains + * variables which are write only, commit() can be called without a + * preceding read() call. Every read call must be followed by a commit call! + * @return - @c RETURN_OK if all variables were read successfully. + * - @c COMMITING_WITHOUT_READING if set was not read yet and + * contains non write-only variables + */ + virtual ReturnValue_t commit(MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, + uint32_t lockTimeout = 20) override; - /** - * @brief The read call initializes reading out all registered variables. - * It is mandatory to call commit after every read call! - * @details - * It iterates through the list of registered variables and calls all read() - * functions of the registered pool variables (which read out their values - * from the data pool) which are not write-only. - * In case of an error (e.g. a wrong data type, or an invalid data pool id), - * the operation is aborted and @c INVALID_PARAMETER_DEFINITION returned. - * - * The data pool is locked during the whole read operation and - * freed afterwards. It is mandatory to call commit after a read call, - * even if the read operation is not successful! - * @return - * - @c RETURN_OK if all variables were read successfully. - * - @c INVALID_PARAMETER_DEFINITION if a pool entry does not exist or there - * is a type conflict. - * - @c SET_WAS_ALREADY_READ if read() is called twice without calling - * commit() in between - */ - virtual ReturnValue_t read(MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, - uint32_t lockTimeout = 20) override; - /** - * @brief The commit call initializes writing back the registered variables. - * @details - * It iterates through the list of registered variables and calls the - * commit() method of the remaining registered variables (which write back - * their values to the pool). - * - * The data pool is locked during the whole commit operation and - * freed afterwards. The state changes to "was committed" after this operation. - * - * If the set does contain at least one variable which is not write-only - * commit() can only be called after read(). If the set only contains - * variables which are write only, commit() can be called without a - * preceding read() call. Every read call must be followed by a commit call! - * @return - @c RETURN_OK if all variables were read successfully. - * - @c COMMITING_WITHOUT_READING if set was not read yet and - * contains non write-only variables - */ - virtual ReturnValue_t commit(MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, - uint32_t lockTimeout = 20) override; + /** + * Register the passed pool variable instance into the data set. + * @param variable + * @return + */ + virtual ReturnValue_t registerVariable(PoolVariableIF* variable) override; - /** - * Register the passed pool variable instance into the data set. - * @param variable - * @return - */ - virtual ReturnValue_t registerVariable( PoolVariableIF* variable) override; + /** + * Provides the means to lock the underlying data structure to ensure + * thread-safety. Default implementation is empty + * @return Always returns -@c RETURN_OK + */ + virtual ReturnValue_t lockDataPool( + MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, + uint32_t timeoutMs = 20) override; + /** + * Provides the means to unlock the underlying data structure to ensure + * thread-safety. Default implementation is empty + * @return Always returns -@c RETURN_OK + */ + virtual ReturnValue_t unlockDataPool() override; - /** - * Provides the means to lock the underlying data structure to ensure - * thread-safety. Default implementation is empty - * @return Always returns -@c RETURN_OK - */ - virtual ReturnValue_t lockDataPool( - MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, - uint32_t timeoutMs = 20) override; - /** - * Provides the means to unlock the underlying data structure to ensure - * thread-safety. Default implementation is empty - * @return Always returns -@c RETURN_OK - */ - virtual ReturnValue_t unlockDataPool() override; + virtual uint16_t getFillCount() const; - virtual uint16_t getFillCount() const; + /* SerializeIF implementations */ + virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, const size_t maxSize, + SerializeIF::Endianness streamEndianness) const override; + virtual size_t getSerializedSize() const override; + virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + SerializeIF::Endianness streamEndianness) override; - /* SerializeIF implementations */ - virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, - const size_t maxSize, - SerializeIF::Endianness streamEndianness) const override; - virtual size_t getSerializedSize() const override; - virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - SerializeIF::Endianness streamEndianness) override; + /** + * Can be used to individually protect every read and commit call. + * @param protectEveryReadCommit + * @param mutexTimeout + */ + void setReadCommitProtectionBehaviour( + bool protectEveryReadCommit, MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, + uint32_t mutexTimeout = 20); - /** - * Can be used to individually protect every read and commit call. - * @param protectEveryReadCommit - * @param mutexTimeout - */ - void setReadCommitProtectionBehaviour(bool protectEveryReadCommit, - MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, - uint32_t mutexTimeout = 20); -protected: + protected: + /** + * @brief The fill_count attribute ensures that the variables + * register in the correct array position and that the maximum + * number of variables is not exceeded. + */ + uint16_t fillCount = 0; + /** + * States of the seet. + */ + enum class States { + STATE_SET_UNINITIALISED, //!< DATA_SET_UNINITIALISED + STATE_SET_WAS_READ //!< DATA_SET_WAS_READ + }; + /** + * @brief state manages the internal state of the data set, + * which is important e.g. for the behavior on destruction. + */ + States state = States::STATE_SET_UNINITIALISED; - /** - * @brief The fill_count attribute ensures that the variables - * register in the correct array position and that the maximum - * number of variables is not exceeded. - */ - uint16_t fillCount = 0; - /** - * States of the seet. - */ - enum class States { - STATE_SET_UNINITIALISED, //!< DATA_SET_UNINITIALISED - STATE_SET_WAS_READ //!< DATA_SET_WAS_READ - }; - /** - * @brief state manages the internal state of the data set, - * which is important e.g. for the behavior on destruction. - */ - States state = States::STATE_SET_UNINITIALISED; + /** + * @brief This array represents all pool variables registered in this set. + * Child classes can use a static or dynamic container to create + * an array of registered variables and assign the first entry here. + */ + PoolVariableIF** registeredVariables = nullptr; + const size_t maxFillCount = 0; - /** - * @brief This array represents all pool variables registered in this set. - * Child classes can use a static or dynamic container to create - * an array of registered variables and assign the first entry here. - */ - PoolVariableIF** registeredVariables = nullptr; - const size_t maxFillCount = 0; + void setContainer(PoolVariableIF** variablesContainer); + PoolVariableIF** getContainer() const; - void setContainer(PoolVariableIF** variablesContainer); - PoolVariableIF** getContainer() const; + private: + bool protectEveryReadCommitCall = false; + MutexIF::TimeoutType timeoutTypeForSingleVars = MutexIF::TimeoutType::WAITING; + uint32_t mutexTimeoutForSingleVars = 20; -private: - bool protectEveryReadCommitCall = false; - MutexIF::TimeoutType timeoutTypeForSingleVars = MutexIF::TimeoutType::WAITING; - uint32_t mutexTimeoutForSingleVars = 20; - - ReturnValue_t readVariable(uint16_t count); - void handleAlreadyReadDatasetCommit( - MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, - uint32_t timeoutMs = 20); - ReturnValue_t handleUnreadDatasetCommit( - MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, - uint32_t timeoutMs = 20); + ReturnValue_t readVariable(uint16_t count); + void handleAlreadyReadDatasetCommit( + MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, uint32_t timeoutMs = 20); + ReturnValue_t handleUnreadDatasetCommit( + MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, uint32_t timeoutMs = 20); }; #endif /* FSFW_DATAPOOL_POOLDATASETBASE_H_ */ diff --git a/src/fsfw/datapool/PoolDataSetIF.h b/src/fsfw/datapool/PoolDataSetIF.h index f905cc4d..3d1676af 100644 --- a/src/fsfw/datapool/PoolDataSetIF.h +++ b/src/fsfw/datapool/PoolDataSetIF.h @@ -1,36 +1,34 @@ #ifndef FSFW_DATAPOOL_POOLDATASETIF_H_ #define FSFW_DATAPOOL_POOLDATASETIF_H_ -#include "ReadCommitIF.h" #include "DataSetIF.h" +#include "ReadCommitIF.h" /** * @brief Extendes the DataSetIF by adding abstract functions to lock * and unlock a data pool and read/commit semantics. */ -class PoolDataSetIF: - virtual public DataSetIF, - virtual public ReadCommitIF { -public: - virtual~ PoolDataSetIF() {}; +class PoolDataSetIF : virtual public DataSetIF, virtual public ReadCommitIF { + public: + virtual ~PoolDataSetIF(){}; - /** - * @brief Most underlying data structures will have a pool like structure - * and will require a lock and unlock mechanism to ensure - * thread-safety - * @return Lock operation result - */ - virtual ReturnValue_t lockDataPool( - MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, - uint32_t timeoutMs = 20) = 0; + /** + * @brief Most underlying data structures will have a pool like structure + * and will require a lock and unlock mechanism to ensure + * thread-safety + * @return Lock operation result + */ + virtual ReturnValue_t lockDataPool( + MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, + uint32_t timeoutMs = 20) = 0; - /** - * @brief Unlock call corresponding to the lock call. - * @return Unlock operation result - */ - virtual ReturnValue_t unlockDataPool() = 0; + /** + * @brief Unlock call corresponding to the lock call. + * @return Unlock operation result + */ + virtual ReturnValue_t unlockDataPool() = 0; - virtual bool isValid() const = 0; + virtual bool isValid() const = 0; }; #endif /* FSFW_DATAPOOL_POOLDATASETIF_H_ */ diff --git a/src/fsfw/datapool/PoolEntry.cpp b/src/fsfw/datapool/PoolEntry.cpp index 0443aa11..fd110e6c 100644 --- a/src/fsfw/datapool/PoolEntry.cpp +++ b/src/fsfw/datapool/PoolEntry.cpp @@ -1,93 +1,91 @@ #include "fsfw/datapool/PoolEntry.h" -#include "fsfw/serviceinterface/ServiceInterface.h" -#include "fsfw/globalfunctions/arrayprinter.h" - -#include #include +#include + +#include "fsfw/globalfunctions/arrayprinter.h" +#include "fsfw/serviceinterface/ServiceInterface.h" template -PoolEntry::PoolEntry(std::initializer_list initValue, bool setValid ): - length(static_cast(initValue.size())), valid(setValid) { - this->address = new T[this->length]; - if(initValue.size() == 0) { - std::memset(this->address, 0, this->getByteSize()); - } - else { - std::copy(initValue.begin(), initValue.end(), this->address); - } +PoolEntry::PoolEntry(std::initializer_list initValue, bool setValid) + : length(static_cast(initValue.size())), valid(setValid) { + this->address = new T[this->length]; + if (initValue.size() == 0) { + std::memset(this->address, 0, this->getByteSize()); + } else { + std::copy(initValue.begin(), initValue.end(), this->address); + } } template -PoolEntry::PoolEntry(T* initValue, uint8_t setLength, bool setValid): - length(setLength), valid(setValid) { - this->address = new T[this->length]; - if (initValue != nullptr) { - std::memcpy(this->address, initValue, this->getByteSize() ); - } else { - std::memset(this->address, 0, this->getByteSize() ); - } +PoolEntry::PoolEntry(T* initValue, uint8_t setLength, bool setValid) + : length(setLength), valid(setValid) { + this->address = new T[this->length]; + if (initValue != nullptr) { + std::memcpy(this->address, initValue, this->getByteSize()); + } else { + std::memset(this->address, 0, this->getByteSize()); + } } -//As the data pool is global, this dtor is only be called on program exit. -//Warning! Never copy pool entries! +// As the data pool is global, this dtor is only be called on program exit. +// Warning! Never copy pool entries! template PoolEntry::~PoolEntry() { - delete[] this->address; + delete[] this->address; } template uint16_t PoolEntry::getByteSize() { - return ( sizeof(T) * this->length ); + return (sizeof(T) * this->length); } template uint8_t PoolEntry::getSize() { - return this->length; + return this->length; } template void* PoolEntry::getRawData() { - return this->address; + return this->address; } template void PoolEntry::setValid(bool isValid) { - this->valid = isValid; + this->valid = isValid; } template bool PoolEntry::getValid() { - return valid; + return valid; } template void PoolEntry::print() { - const char* validString = nullptr; - if(valid) { - validString = "Valid"; - } - else { - validString = "Invalid"; - } + const char* validString = nullptr; + if (valid) { + validString = "Valid"; + } else { + validString = "Invalid"; + } #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "PoolEntry information." << std::endl; - sif::info << "PoolEntry validity: " << validString << std::endl; + sif::info << "PoolEntry information." << std::endl; + sif::info << "PoolEntry validity: " << validString << std::endl; #else - sif::printInfo("PoolEntry information.\n"); - sif::printInfo("PoolEntry validity: %s\n", validString); + sif::printInfo("PoolEntry information.\n"); + sif::printInfo("PoolEntry validity: %s\n", validString); #endif - arrayprinter::print(reinterpret_cast(address), getByteSize()); + arrayprinter::print(reinterpret_cast(address), getByteSize()); } -template +template inline T* PoolEntry::getDataPtr() { - return this->address; + return this->address; } -template +template Type PoolEntry::getType() { - return PodTypeConversion::type; + return PodTypeConversion::type; } template class PoolEntry; diff --git a/src/fsfw/datapool/PoolEntry.h b/src/fsfw/datapool/PoolEntry.h index 30940320..d3d80f09 100644 --- a/src/fsfw/datapool/PoolEntry.h +++ b/src/fsfw/datapool/PoolEntry.h @@ -1,11 +1,11 @@ #ifndef FSFW_DATAPOOL_POOLENTRY_H_ #define FSFW_DATAPOOL_POOLENTRY_H_ -#include "PoolEntryIF.h" - +#include #include #include -#include + +#include "PoolEntryIF.h" /** * @brief This is a small helper class that defines a single data pool entry. @@ -27,111 +27,111 @@ */ template class PoolEntry : public PoolEntryIF { -public: - static_assert(not std::is_same::value, - "Do not use boolean for the PoolEntry type, use uint8_t " - "instead! The ECSS standard defines a boolean as a one bit " - "field. Therefore it is preferred to store a boolean as an " - "uint8_t"); - /** - * @brief In the classe's constructor, space is allocated on the heap and - * potential initialization values are copied to that space. - * @details - * Not passing any arguments will initialize an non-array pool entry - * with an initial invalid state and the value 0. - * Please note that if an initializer list is passed, the length of the - * initializer list needs to be correct for vector entries because - * required allocated space will be deduced from the initializer list length - * and the pool entry type. - * @param initValue - * Initializer list with values to initialize with, for example {0, 0} to - * initialize the a pool entry of a vector with two entries to 0. - * @param setValid - * Sets the initialization flag. It is invalid by default. - */ - PoolEntry(std::initializer_list initValue = {0}, bool setValid = false); + public: + static_assert(not std::is_same::value, + "Do not use boolean for the PoolEntry type, use uint8_t " + "instead! The ECSS standard defines a boolean as a one bit " + "field. Therefore it is preferred to store a boolean as an " + "uint8_t"); + /** + * @brief In the classe's constructor, space is allocated on the heap and + * potential initialization values are copied to that space. + * @details + * Not passing any arguments will initialize an non-array pool entry + * with an initial invalid state and the value 0. + * Please note that if an initializer list is passed, the length of the + * initializer list needs to be correct for vector entries because + * required allocated space will be deduced from the initializer list length + * and the pool entry type. + * @param initValue + * Initializer list with values to initialize with, for example {0, 0} to + * initialize the a pool entry of a vector with two entries to 0. + * @param setValid + * Sets the initialization flag. It is invalid by default. + */ + PoolEntry(std::initializer_list initValue = {0}, bool setValid = false); - /** - * @brief In the classe's constructor, space is allocated on the heap and - * potential init values are copied to that space. - * @param initValue - * A pointer to the single value or array that holds the init value. - * With the default value (nullptr), the entry is initalized with all 0. - * @param setLength - * Defines the array length of this entry. - * @param setValid - * Sets the initialization flag. It is invalid by default. - */ - PoolEntry(T* initValue, uint8_t setLength = 1, bool setValid = false); + /** + * @brief In the classe's constructor, space is allocated on the heap and + * potential init values are copied to that space. + * @param initValue + * A pointer to the single value or array that holds the init value. + * With the default value (nullptr), the entry is initalized with all 0. + * @param setLength + * Defines the array length of this entry. + * @param setValid + * Sets the initialization flag. It is invalid by default. + */ + PoolEntry(T* initValue, uint8_t setLength = 1, bool setValid = false); - //! Explicitely deleted copy ctor, copying is not allowed. - PoolEntry(const PoolEntry&) = delete; - //! Explicitely deleted copy assignment, copying is not allowed. - PoolEntry& operator=(const PoolEntry&) = delete; + //! Explicitely deleted copy ctor, copying is not allowed. + PoolEntry(const PoolEntry&) = delete; + //! Explicitely deleted copy assignment, copying is not allowed. + PoolEntry& operator=(const PoolEntry&) = delete; - /** - * @brief The allocated memory for the variable is freed - * in the destructor. - * @details - * As the data pool is global, this dtor is only called on program exit. - * PoolEntries shall never be copied, as a copy might delete the variable - * on the heap. - */ - ~PoolEntry(); + /** + * @brief The allocated memory for the variable is freed + * in the destructor. + * @details + * As the data pool is global, this dtor is only called on program exit. + * PoolEntries shall never be copied, as a copy might delete the variable + * on the heap. + */ + ~PoolEntry(); - /** - * Return typed pointer to start of data. - * @return - */ - T* getDataPtr(); + /** + * Return typed pointer to start of data. + * @return + */ + T* getDataPtr(); - /** - * @brief getSize returns the array size of the entry. - * @details - * For non-array pool entries return type size, for vector entries - * return type size times the number of entries. - */ - uint8_t getSize(); - /** - * @brief This operation returns the size in bytes. - * @details The size is calculated by sizeof(type) * array_size. - */ - uint16_t getByteSize(); - /** - * @brief This operation returns a the address pointer casted to void*. - */ - void* getRawData(); - /** - * @brief This method allows to set the valid information - * of the pool entry. - */ - void setValid( bool isValid ); - /** - * @brief This method allows to get the valid information - * of the pool entry. - */ - bool getValid(); - /** - * @brief This is a debug method that prints all values and the valid - * information to the screen. It prints all array entries in a row. - */ - void print(); - Type getType(); + /** + * @brief getSize returns the array size of the entry. + * @details + * For non-array pool entries return type size, for vector entries + * return type size times the number of entries. + */ + uint8_t getSize(); + /** + * @brief This operation returns the size in bytes. + * @details The size is calculated by sizeof(type) * array_size. + */ + uint16_t getByteSize(); + /** + * @brief This operation returns a the address pointer casted to void*. + */ + void* getRawData(); + /** + * @brief This method allows to set the valid information + * of the pool entry. + */ + void setValid(bool isValid); + /** + * @brief This method allows to get the valid information + * of the pool entry. + */ + bool getValid(); + /** + * @brief This is a debug method that prints all values and the valid + * information to the screen. It prints all array entries in a row. + */ + void print(); + Type getType(); -private: - /** - * @brief This attribute stores the length information. - */ - uint8_t length; - /** - * @brief Here, the validity information for a variable is stored. - * Every entry (single variable or vector) has one valid flag. - */ - uint8_t valid; - /** - * @brief This is the address pointing to the allocated memory. - */ - T* address; + private: + /** + * @brief This attribute stores the length information. + */ + uint8_t length; + /** + * @brief Here, the validity information for a variable is stored. + * Every entry (single variable or vector) has one valid flag. + */ + uint8_t valid; + /** + * @brief This is the address pointing to the allocated memory. + */ + T* address; }; #endif /* FSFW_DATAPOOL_POOLENTRY_H_ */ diff --git a/src/fsfw/datapool/PoolEntryIF.h b/src/fsfw/datapool/PoolEntryIF.h index d9db5237..99fd8024 100644 --- a/src/fsfw/datapool/PoolEntryIF.h +++ b/src/fsfw/datapool/PoolEntryIF.h @@ -1,9 +1,10 @@ #ifndef FSFW_DATAPOOL_POOLENTRYIF_H_ #define FSFW_DATAPOOL_POOLENTRYIF_H_ -#include "../globalfunctions/Type.h" #include +#include "../globalfunctions/Type.h" + /** * @brief This interface defines the access possibilities to a * single data pool entry. @@ -18,46 +19,45 @@ * */ class PoolEntryIF { -public: - /** - * @brief This is an empty virtual destructor, - * as it is required for C++ interfaces. - */ - virtual ~PoolEntryIF() { - } - /** - * @brief getSize returns the array size of the entry. - * A single variable parameter has size 1. - */ - virtual uint8_t getSize() = 0; - /** - * @brief This operation returns the size in bytes, which is calculated by - * sizeof(type) * array_size. - */ - virtual uint16_t getByteSize() = 0; - /** - * @brief This operation returns a the address pointer casted to void*. - */ - virtual void* getRawData() = 0; - /** - * @brief This method allows to set the valid information of the pool entry. - */ - virtual void setValid(bool isValid) = 0; - /** - * @brief This method allows to set the valid information of the pool entry. - */ - virtual bool getValid() = 0; - /** - * @brief This is a debug method that prints all values and the valid - * information to the screen. It prints all array entries in a row. - * @details - * Also displays whether the pool entry is valid or invalid. - */ - virtual void print() = 0; - /** - * Returns the type of the entry. - */ - virtual Type getType() = 0; + public: + /** + * @brief This is an empty virtual destructor, + * as it is required for C++ interfaces. + */ + virtual ~PoolEntryIF() {} + /** + * @brief getSize returns the array size of the entry. + * A single variable parameter has size 1. + */ + virtual uint8_t getSize() = 0; + /** + * @brief This operation returns the size in bytes, which is calculated by + * sizeof(type) * array_size. + */ + virtual uint16_t getByteSize() = 0; + /** + * @brief This operation returns a the address pointer casted to void*. + */ + virtual void* getRawData() = 0; + /** + * @brief This method allows to set the valid information of the pool entry. + */ + virtual void setValid(bool isValid) = 0; + /** + * @brief This method allows to set the valid information of the pool entry. + */ + virtual bool getValid() = 0; + /** + * @brief This is a debug method that prints all values and the valid + * information to the screen. It prints all array entries in a row. + * @details + * Also displays whether the pool entry is valid or invalid. + */ + virtual void print() = 0; + /** + * Returns the type of the entry. + */ + virtual Type getType() = 0; }; #endif /* FSFW_DATAPOOL_POOLENTRYIF_H_ */ diff --git a/src/fsfw/datapool/PoolReadGuard.h b/src/fsfw/datapool/PoolReadGuard.h index eb014f1e..24d98933 100644 --- a/src/fsfw/datapool/PoolReadGuard.h +++ b/src/fsfw/datapool/PoolReadGuard.h @@ -1,62 +1,56 @@ #ifndef FSFW_DATAPOOL_POOLREADHELPER_H_ #define FSFW_DATAPOOL_POOLREADHELPER_H_ -#include "ReadCommitIF.h" -#include "../serviceinterface/ServiceInterface.h" #include +#include "../serviceinterface/ServiceInterface.h" +#include "ReadCommitIF.h" + /** * @brief Helper class to read data sets or pool variables */ class PoolReadGuard { -public: - PoolReadGuard(ReadCommitIF* readObject, - MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, - uint32_t mutexTimeout = 20): - readObject(readObject), mutexTimeout(mutexTimeout) { - if(readObject != nullptr) { - readResult = readObject->read(timeoutType, mutexTimeout); - if(readResult != HasReturnvaluesIF::RETURN_OK) { + public: + PoolReadGuard(ReadCommitIF* readObject, + MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, + uint32_t mutexTimeout = 20) + : readObject(readObject), mutexTimeout(mutexTimeout) { + if (readObject != nullptr) { + readResult = readObject->read(timeoutType, mutexTimeout); + if (readResult != HasReturnvaluesIF::RETURN_OK) { #if FSFW_VERBOSE_LEVEL == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "PoolReadHelper: Read failed!" << std::endl; + sif::error << "PoolReadHelper: Read failed!" << std::endl; #else - sif::printError("PoolReadHelper: Read failed!\n"); + sif::printError("PoolReadHelper: Read failed!\n"); #endif /* FSFW_PRINT_VERBOSITY_LEVEL == 1 */ #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ - } - } + } } + } - ReturnValue_t getReadResult() const { - return readResult; + ReturnValue_t getReadResult() const { return readResult; } + + /** + * @brief Can be used to suppress commit on destruction. + */ + void setNoCommitMode(bool commit) { this->noCommit = commit; } + + /** + * @brief Default destructor which will take care of commiting changed values. + */ + ~PoolReadGuard() { + if (readObject != nullptr and not noCommit) { + readObject->commit(timeoutType, mutexTimeout); } + } - /** - * @brief Can be used to suppress commit on destruction. - */ - void setNoCommitMode(bool commit) { - this->noCommit = commit; - } - - /** - * @brief Default destructor which will take care of commiting changed values. - */ - ~PoolReadGuard() { - if(readObject != nullptr and not noCommit) { - readObject->commit(timeoutType, mutexTimeout); - } - - } - -private: - ReadCommitIF* readObject = nullptr; - ReturnValue_t readResult = HasReturnvaluesIF::RETURN_OK; - bool noCommit = false; - MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING; - uint32_t mutexTimeout = 20; + private: + ReadCommitIF* readObject = nullptr; + ReturnValue_t readResult = HasReturnvaluesIF::RETURN_OK; + bool noCommit = false; + MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING; + uint32_t mutexTimeout = 20; }; - - #endif /* FSFW_DATAPOOL_POOLREADHELPER_H_ */ diff --git a/src/fsfw/datapool/PoolVarList.h b/src/fsfw/datapool/PoolVarList.h index 0b2b0f06..8d4df8c7 100644 --- a/src/fsfw/datapool/PoolVarList.h +++ b/src/fsfw/datapool/PoolVarList.h @@ -5,25 +5,24 @@ #include "../datapoolglob/GlobalPoolVariable.h" template class PoolVarList { -private: - GlobPoolVar variables[n_var]; -public: - PoolVarList( const uint32_t set_id[n_var], DataSetIF* dataSet, - PoolVariableIF::ReadWriteMode_t setReadWriteMode ) { - //I really should have a look at the new init list c++ syntax. - if (dataSet == NULL) { - return; - } - for (uint8_t count = 0; count < n_var; count++) { - variables[count].dataPoolId = set_id[count]; - variables[count].readWriteMode = setReadWriteMode; - dataSet->registerVariable(&variables[count]); - } - } + private: + GlobPoolVar variables[n_var]; - GlobPoolVar &operator [](int i) { return variables[i]; } + public: + PoolVarList(const uint32_t set_id[n_var], DataSetIF* dataSet, + PoolVariableIF::ReadWriteMode_t setReadWriteMode) { + // I really should have a look at the new init list c++ syntax. + if (dataSet == NULL) { + return; + } + for (uint8_t count = 0; count < n_var; count++) { + variables[count].dataPoolId = set_id[count]; + variables[count].readWriteMode = setReadWriteMode; + dataSet->registerVariable(&variables[count]); + } + } + + GlobPoolVar& operator[](int i) { return variables[i]; } }; - - #endif /* FSFW_DATAPOOL_POOLVARLIST_H_ */ diff --git a/src/fsfw/datapool/PoolVariableIF.h b/src/fsfw/datapool/PoolVariableIF.h index dbb9db15..95cf898e 100644 --- a/src/fsfw/datapool/PoolVariableIF.h +++ b/src/fsfw/datapool/PoolVariableIF.h @@ -1,10 +1,9 @@ #ifndef FSFW_DATAPOOL_POOLVARIABLEIF_H_ #define FSFW_DATAPOOL_POOLVARIABLEIF_H_ -#include "ReadCommitIF.h" #include "../returnvalues/HasReturnvaluesIF.h" #include "../serialize/SerializeIF.h" - +#include "ReadCommitIF.h" /** * @brief This interface is used to control data pool @@ -19,48 +18,43 @@ * @author Bastian Baetz * @ingroup data_pool */ -class PoolVariableIF : - public SerializeIF, - public ReadCommitIF { +class PoolVariableIF : public SerializeIF, public ReadCommitIF { + public: + static constexpr uint8_t INTERFACE_ID = CLASS_ID::POOL_VARIABLE_IF; + static constexpr ReturnValue_t INVALID_READ_WRITE_MODE = MAKE_RETURN_CODE(0xA0); + static constexpr ReturnValue_t INVALID_POOL_ENTRY = MAKE_RETURN_CODE(0xA1); -public: - static constexpr uint8_t INTERFACE_ID = CLASS_ID::POOL_VARIABLE_IF; - static constexpr ReturnValue_t INVALID_READ_WRITE_MODE = MAKE_RETURN_CODE(0xA0); - static constexpr ReturnValue_t INVALID_POOL_ENTRY = MAKE_RETURN_CODE(0xA1); + static constexpr bool VALID = 1; + static constexpr bool INVALID = 0; + static constexpr uint32_t NO_PARAMETER = 0xffffffff; - static constexpr bool VALID = 1; - static constexpr bool INVALID = 0; - static constexpr uint32_t NO_PARAMETER = 0xffffffff; + enum ReadWriteMode_t { VAR_READ, VAR_WRITE, VAR_READ_WRITE }; - enum ReadWriteMode_t { - VAR_READ, VAR_WRITE, VAR_READ_WRITE - }; + /** + * @brief This is an empty virtual destructor, + * as it is proposed for C++ interfaces. + */ + virtual ~PoolVariableIF() {} + /** + * @brief This method returns if the variable is write-only, + * read-write or read-only. + */ + virtual ReadWriteMode_t getReadWriteMode() const = 0; + virtual void setReadWriteMode(ReadWriteMode_t newMode) = 0; - /** - * @brief This is an empty virtual destructor, - * as it is proposed for C++ interfaces. - */ - virtual ~PoolVariableIF() {} - /** - * @brief This method returns if the variable is write-only, - * read-write or read-only. - */ - virtual ReadWriteMode_t getReadWriteMode() const = 0; - virtual void setReadWriteMode(ReadWriteMode_t newMode) = 0; - - /** - * @brief This operation shall return the data pool id of the variable. - */ - virtual uint32_t getDataPoolId() const = 0; - /** - * @brief With this call, the valid information of the - * variable is returned. - */ - virtual bool isValid() const = 0; - /** - * @brief With this call, the valid information of the variable is set. - */ - virtual void setValid(bool validity) = 0; + /** + * @brief This operation shall return the data pool id of the variable. + */ + virtual uint32_t getDataPoolId() const = 0; + /** + * @brief With this call, the valid information of the + * variable is returned. + */ + virtual bool isValid() const = 0; + /** + * @brief With this call, the valid information of the variable is set. + */ + virtual void setValid(bool validity) = 0; }; using pool_rwm_t = PoolVariableIF::ReadWriteMode_t; diff --git a/src/fsfw/datapool/ReadCommitIF.h b/src/fsfw/datapool/ReadCommitIF.h index 3ad2b3c0..08554be1 100644 --- a/src/fsfw/datapool/ReadCommitIF.h +++ b/src/fsfw/datapool/ReadCommitIF.h @@ -1,34 +1,27 @@ #ifndef FSFW_DATAPOOL_READCOMMITIF_H_ #define FSFW_DATAPOOL_READCOMMITIF_H_ -#include "../returnvalues/HasReturnvaluesIF.h" #include "../ipc/MutexIF.h" +#include "../returnvalues/HasReturnvaluesIF.h" /** * @brief Common interface for all software objects which employ read-commit * semantics. */ class ReadCommitIF { - friend class ReadCommitIFAttorney; -public: - virtual ~ReadCommitIF() {} - virtual ReturnValue_t read(MutexIF::TimeoutType timeoutType, - uint32_t timeoutMs) = 0; - virtual ReturnValue_t commit(MutexIF::TimeoutType timeoutType, - uint32_t timeoutMs) = 0; + friend class ReadCommitIFAttorney; -protected: + public: + virtual ~ReadCommitIF() {} + virtual ReturnValue_t read(MutexIF::TimeoutType timeoutType, uint32_t timeoutMs) = 0; + virtual ReturnValue_t commit(MutexIF::TimeoutType timeoutType, uint32_t timeoutMs) = 0; - /* Optional and protected because this is interesting for classes grouping members with commit - and read semantics where the lock is only necessary once. */ - virtual ReturnValue_t readWithoutLock() { - return read(MutexIF::TimeoutType::WAITING, 20); - } + protected: + /* Optional and protected because this is interesting for classes grouping members with commit + and read semantics where the lock is only necessary once. */ + virtual ReturnValue_t readWithoutLock() { return read(MutexIF::TimeoutType::WAITING, 20); } - virtual ReturnValue_t commitWithoutLock() { - return commit(MutexIF::TimeoutType::WAITING, 20); - } + virtual ReturnValue_t commitWithoutLock() { return commit(MutexIF::TimeoutType::WAITING, 20); } }; - #endif /* FSFW_DATAPOOL_READCOMMITIF_H_ */ diff --git a/src/fsfw/datapool/ReadCommitIFAttorney.h b/src/fsfw/datapool/ReadCommitIFAttorney.h index 0291cf5c..ea39ffe5 100644 --- a/src/fsfw/datapool/ReadCommitIFAttorney.h +++ b/src/fsfw/datapool/ReadCommitIFAttorney.h @@ -9,24 +9,22 @@ * of the ReadCommitIF. */ class ReadCommitIFAttorney { -private: - static ReturnValue_t readWithoutLock(ReadCommitIF* readCommitIF) { - if(readCommitIF == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - return readCommitIF->readWithoutLock(); + private: + static ReturnValue_t readWithoutLock(ReadCommitIF* readCommitIF) { + if (readCommitIF == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; } + return readCommitIF->readWithoutLock(); + } - static ReturnValue_t commitWithoutLock(ReadCommitIF* readCommitIF) { - if(readCommitIF == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - return readCommitIF->commitWithoutLock(); + static ReturnValue_t commitWithoutLock(ReadCommitIF* readCommitIF) { + if (readCommitIF == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; } + return readCommitIF->commitWithoutLock(); + } - friend class PoolDataSetBase; + friend class PoolDataSetBase; }; - - #endif /* FSFW_DATAPOOL_READCOMMITIFATTORNEY_H_ */ diff --git a/src/fsfw/datapool/SharedDataSetIF.h b/src/fsfw/datapool/SharedDataSetIF.h index 4d23f87f..fc3ddcd8 100644 --- a/src/fsfw/datapool/SharedDataSetIF.h +++ b/src/fsfw/datapool/SharedDataSetIF.h @@ -4,13 +4,13 @@ #include "PoolDataSetIF.h" class SharedDataSetIF { -public: - virtual ~SharedDataSetIF() {}; + public: + virtual ~SharedDataSetIF(){}; -private: - virtual ReturnValue_t lockDataset(MutexIF::TimeoutType timeoutType, - dur_millis_t mutexTimeout) = 0; - virtual ReturnValue_t unlockDataset() = 0; + private: + virtual ReturnValue_t lockDataset(MutexIF::TimeoutType timeoutType, + dur_millis_t mutexTimeout) = 0; + virtual ReturnValue_t unlockDataset() = 0; }; #endif /* FRAMEWORK_DATAPOOL_SHAREDDATASETIF_H_ */ diff --git a/src/fsfw/datapoollocal.h b/src/fsfw/datapoollocal.h index 7a3c4c20..26021e08 100644 --- a/src/fsfw/datapoollocal.h +++ b/src/fsfw/datapoollocal.h @@ -2,10 +2,10 @@ #define FSFW_DATAPOOLLOCAL_DATAPOOLLOCAL_H_ /* Collected related headers */ +#include "fsfw/datapoollocal/LocalDataSet.h" #include "fsfw/datapoollocal/LocalPoolVariable.h" #include "fsfw/datapoollocal/LocalPoolVector.h" -#include "fsfw/datapoollocal/StaticLocalDataSet.h" -#include "fsfw/datapoollocal/LocalDataSet.h" #include "fsfw/datapoollocal/SharedLocalDataSet.h" +#include "fsfw/datapoollocal/StaticLocalDataSet.h" #endif /* FSFW_DATAPOOLLOCAL_DATAPOOLLOCAL_H_ */ diff --git a/src/fsfw/datapoollocal/AccessLocalPoolF.h b/src/fsfw/datapoollocal/AccessLocalPoolF.h index 55f46e21..4290336a 100644 --- a/src/fsfw/datapoollocal/AccessLocalPoolF.h +++ b/src/fsfw/datapoollocal/AccessLocalPoolF.h @@ -8,20 +8,19 @@ class MutexIF; * @brief Accessor class which can be used by classes which like to use the pool manager. */ class AccessPoolManagerIF { -public: - virtual ~AccessPoolManagerIF() {}; + public: + virtual ~AccessPoolManagerIF(){}; - virtual MutexIF* getLocalPoolMutex() = 0; + virtual MutexIF* getLocalPoolMutex() = 0; - /** - * Can be used to get a handle to the local data pool manager. - * This function is protected because it should only be used by the - * class imlementing the interface. - */ - virtual LocalDataPoolManager* getPoolManagerHandle() = 0; - -protected: + /** + * Can be used to get a handle to the local data pool manager. + * This function is protected because it should only be used by the + * class imlementing the interface. + */ + virtual LocalDataPoolManager* getPoolManagerHandle() = 0; + protected: }; #endif /* FSFW_DATAPOOLLOCAL_ACCESSLOCALPOOLF_H_ */ diff --git a/src/fsfw/datapoollocal/HasLocalDataPoolIF.h b/src/fsfw/datapoollocal/HasLocalDataPoolIF.h index 6051f068..a2925a46 100644 --- a/src/fsfw/datapoollocal/HasLocalDataPoolIF.h +++ b/src/fsfw/datapoollocal/HasLocalDataPoolIF.h @@ -1,15 +1,14 @@ #ifndef FSFW_DATAPOOLLOCAL_HASLOCALDATAPOOLIF_H_ #define FSFW_DATAPOOLLOCAL_HASLOCALDATAPOOLIF_H_ -#include "localPoolDefinitions.h" -#include "LocalDataPoolManager.h" +#include #include "../datapool/PoolEntryIF.h" -#include "../serviceinterface/ServiceInterface.h" -#include "../ipc/MessageQueueSenderIF.h" #include "../housekeeping/HousekeepingMessage.h" - -#include +#include "../ipc/MessageQueueSenderIF.h" +#include "../serviceinterface/ServiceInterface.h" +#include "LocalDataPoolManager.h" +#include "localPoolDefinitions.h" class AccessPoolManagerIF; class ProvidesDataPoolSubscriptionIF; @@ -17,9 +16,9 @@ class LocalPoolDataSetBase; class LocalPoolObjectBase; /** - * @brief This interface is implemented by classes which posses a local data pool (not the - * managing class). It defines the relationship between the local data pool owner - * and the LocalDataPoolManager. + * @brief This interface is implemented by classes which posses a local data pool (not + * the managing class). It defines the relationship between the local data pool owner and the + * LocalDataPoolManager. * @details * Any class implementing this interface shall also have a LocalDataPoolManager member class which * contains the actual pool data structure and exposes the public interface for it. @@ -41,147 +40,143 @@ class LocalPoolObjectBase; * } */ class HasLocalDataPoolIF { - friend class HasLocalDpIFManagerAttorney; - friend class HasLocalDpIFUserAttorney; -public: - virtual~ HasLocalDataPoolIF() {}; + friend class HasLocalDpIFManagerAttorney; + friend class HasLocalDpIFUserAttorney; - static constexpr uint32_t INVALID_LPID = localpool::INVALID_LPID; + public: + virtual ~HasLocalDataPoolIF(){}; - virtual object_id_t getObjectId() const = 0; + static constexpr uint32_t INVALID_LPID = localpool::INVALID_LPID; - /** Command queue for housekeeping messages. */ - virtual MessageQueueId_t getCommandQueue() const = 0; + virtual object_id_t getObjectId() const = 0; - /** - * Is used by pool owner to initialize the pool map once - * The manager instance shall also be passed to this function. - * It can be used to subscribe for periodic packets for for updates. - */ - virtual ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, - LocalDataPoolManager& poolManager) = 0; + /** Command queue for housekeeping messages. */ + virtual MessageQueueId_t getCommandQueue() const = 0; - /** - * Returns the minimum sampling frequency in milliseconds, which will - * usually be the period the pool owner performs its periodic operation. - * @return - */ - virtual dur_millis_t getPeriodicOperationFrequency() const = 0; + /** + * Is used by pool owner to initialize the pool map once + * The manager instance shall also be passed to this function. + * It can be used to subscribe for periodic packets for for updates. + */ + virtual ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) = 0; - /** - * @brief This function will be called by the manager if an update - * notification is received. - * @details HasLocalDataPoolIF - * Can be overriden by the child class to handle changed datasets. - * @param sid SID of the updated set - * @param storeId If a snapshot was requested, data will be located inside - * the IPC store with this store ID. - * @param clearMessage If this is set to true, the pool manager will take care of - * clearing the store automatically - */ - virtual void handleChangedDataset(sid_t sid, - store_address_t storeId = storeId::INVALID_STORE_ADDRESS, - bool* clearMessage = nullptr) { - if(clearMessage != nullptr) { - *clearMessage = true; - } + /** + * Returns the minimum sampling frequency in milliseconds, which will + * usually be the period the pool owner performs its periodic operation. + * @return + */ + virtual dur_millis_t getPeriodicOperationFrequency() const = 0; + + /** + * @brief This function will be called by the manager if an update + * notification is received. + * @details HasLocalDataPoolIF + * Can be overriden by the child class to handle changed datasets. + * @param sid SID of the updated set + * @param storeId If a snapshot was requested, data will be located inside + * the IPC store with this store ID. + * @param clearMessage If this is set to true, the pool manager will take care of + * clearing the store automatically + */ + virtual void handleChangedDataset(sid_t sid, + store_address_t storeId = storeId::INVALID_STORE_ADDRESS, + bool* clearMessage = nullptr) { + if (clearMessage != nullptr) { + *clearMessage = true; } + } - /** - * @brief This function will be called by the manager if an update - * notification is received. - * @details - * Can be overriden by the child class to handle changed pool variables. - * @param gpid GPID of the updated variable. - * @param storeId If a snapshot was requested, data will be located inside - * the IPC store with this store ID. - * @param clearMessage Relevant for snapshots. If the boolean this points to is set to true, - * the pool manager will take care of clearing the store automatically - * after the callback. - */ - virtual void handleChangedPoolVariable(gp_id_t gpid, - store_address_t storeId = storeId::INVALID_STORE_ADDRESS, - bool* clearMessage = nullptr) { - if(clearMessage != nullptr) { - *clearMessage = true; - } + /** + * @brief This function will be called by the manager if an update + * notification is received. + * @details + * Can be overriden by the child class to handle changed pool variables. + * @param gpid GPID of the updated variable. + * @param storeId If a snapshot was requested, data will be located inside + * the IPC store with this store ID. + * @param clearMessage Relevant for snapshots. If the boolean this points to is set to true, + * the pool manager will take care of clearing the store automatically + * after the callback. + */ + virtual void handleChangedPoolVariable(gp_id_t gpid, + store_address_t storeId = storeId::INVALID_STORE_ADDRESS, + bool* clearMessage = nullptr) { + if (clearMessage != nullptr) { + *clearMessage = true; } + } - /** - * These function can be implemented by pool owner, if they are required - * and used by the housekeeping message interface. - * */ - virtual ReturnValue_t addDataSet(sid_t sid) { - return HasReturnvaluesIF::RETURN_FAILED; - }; - virtual ReturnValue_t removeDataSet(sid_t sid) { - return HasReturnvaluesIF::RETURN_FAILED; - }; - virtual ReturnValue_t changeCollectionInterval(sid_t sid, float newIntervalSeconds) { - return HasReturnvaluesIF::RETURN_FAILED; - }; + /** + * These function can be implemented by pool owner, if they are required + * and used by the housekeeping message interface. + * */ + virtual ReturnValue_t addDataSet(sid_t sid) { return HasReturnvaluesIF::RETURN_FAILED; }; + virtual ReturnValue_t removeDataSet(sid_t sid) { return HasReturnvaluesIF::RETURN_FAILED; }; + virtual ReturnValue_t changeCollectionInterval(sid_t sid, float newIntervalSeconds) { + return HasReturnvaluesIF::RETURN_FAILED; + }; - /** - * This function can be used by data pool consumers to retrieve a handle - * which allows subscriptions to dataset and variable updates in form of messages. - * The consumers can then read the most recent variable value by calling read with - * an own pool variable or set instance or using the deserialized snapshot data. - * Returns the HK manager casted to the required interface by default. - * @return - */ - virtual ProvidesDataPoolSubscriptionIF* getSubscriptionInterface() { - return getHkManagerHandle(); - } + /** + * This function can be used by data pool consumers to retrieve a handle + * which allows subscriptions to dataset and variable updates in form of messages. + * The consumers can then read the most recent variable value by calling read with + * an own pool variable or set instance or using the deserialized snapshot data. + * Returns the HK manager casted to the required interface by default. + * @return + */ + virtual ProvidesDataPoolSubscriptionIF* getSubscriptionInterface() { + return getHkManagerHandle(); + } -protected: + protected: + /** + * Every class implementing this interface should have a local data pool manager. This + * function will return a reference to the manager. + * @return + */ + virtual LocalDataPoolManager* getHkManagerHandle() = 0; - /** - * Every class implementing this interface should have a local data pool manager. This - * function will return a reference to the manager. - * @return - */ - virtual LocalDataPoolManager* getHkManagerHandle() = 0; + /** + * Accessor handle required for internal handling. Not intended for users and therefore + * declared protected. Users should instead use pool variables, sets or the subscription + * interface to access pool entries. Returns the HK manager casted to a different interface + * by default. + * @return + */ + virtual AccessPoolManagerIF* getAccessorHandle() { return getHkManagerHandle(); } - /** - * Accessor handle required for internal handling. Not intended for users and therefore - * declared protected. Users should instead use pool variables, sets or the subscription - * interface to access pool entries. Returns the HK manager casted to a different interface - * by default. - * @return - */ - virtual AccessPoolManagerIF* getAccessorHandle() { - return getHkManagerHandle(); - } + /** + * This function is used by the pool manager to get a valid dataset + * from a SID. This function is protected to prevent users from + * using raw data set pointers which could not be thread-safe. Users + * should use the #ProvidesDataPoolSubscriptionIF. + * @param sid Corresponding structure ID + * @return + */ + virtual LocalPoolDataSetBase* getDataSetHandle(sid_t sid) = 0; - /** - * This function is used by the pool manager to get a valid dataset - * from a SID. This function is protected to prevent users from - * using raw data set pointers which could not be thread-safe. Users - * should use the #ProvidesDataPoolSubscriptionIF. - * @param sid Corresponding structure ID - * @return - */ - virtual LocalPoolDataSetBase* getDataSetHandle(sid_t sid) = 0; - - /** - * Similar to the function above, but used to get a local pool variable - * handle. This is only needed for update notifications, so it is not - * defined as abstract. This function is protected to prevent users from - * using raw pool variable pointers which could not be thread-safe. - * Users should use the #ProvidesDataPoolSubscriptionIF. - * @param localPoolId - * @return - */ - virtual LocalPoolObjectBase* getPoolObjectHandle(lp_id_t localPoolId) { + /** + * Similar to the function above, but used to get a local pool variable + * handle. This is only needed for update notifications, so it is not + * defined as abstract. This function is protected to prevent users from + * using raw pool variable pointers which could not be thread-safe. + * Users should use the #ProvidesDataPoolSubscriptionIF. + * @param localPoolId + * @return + */ + virtual LocalPoolObjectBase* getPoolObjectHandle(lp_id_t localPoolId) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "HasLocalDataPoolIF::getPoolObjectHandle: Not overriden. " - "Returning nullptr!" << std::endl; + sif::warning << "HasLocalDataPoolIF::getPoolObjectHandle: Not overriden. " + "Returning nullptr!" + << std::endl; #else - sif::printWarning("HasLocalDataPoolIF::getPoolObjectHandle: " - "Not overriden. Returning nullptr!\n"); + sif::printWarning( + "HasLocalDataPoolIF::getPoolObjectHandle: " + "Not overriden. Returning nullptr!\n"); #endif - return nullptr; - } + return nullptr; + } }; #endif /* FSFW_DATAPOOLLOCAL_HASLOCALDATAPOOLIF_H_ */ diff --git a/src/fsfw/datapoollocal/LocalDataPoolManager.cpp b/src/fsfw/datapoollocal/LocalDataPoolManager.cpp index 4a706657..9057de31 100644 --- a/src/fsfw/datapoollocal/LocalDataPoolManager.cpp +++ b/src/fsfw/datapoollocal/LocalDataPoolManager.cpp @@ -1,946 +1,873 @@ #include "fsfw/datapoollocal/LocalDataPoolManager.h" -#include "fsfw/datapoollocal.h" -#include "internal/LocalPoolDataSetAttorney.h" -#include "internal/HasLocalDpIFManagerAttorney.h" - -#include "fsfw/housekeeping/HousekeepingSetPacket.h" -#include "fsfw/objectmanager/ObjectManager.h" -#include "fsfw/housekeeping/HousekeepingSnapshot.h" -#include "fsfw/housekeeping/AcceptsHkPacketsIF.h" -#include "fsfw/timemanager/CCSDSTime.h" -#include "fsfw/ipc/MutexFactory.h" -#include "fsfw/ipc/MutexGuard.h" -#include "fsfw/ipc/QueueFactory.h" #include #include +#include "fsfw/datapoollocal.h" +#include "fsfw/housekeeping/AcceptsHkPacketsIF.h" +#include "fsfw/housekeeping/HousekeepingSetPacket.h" +#include "fsfw/housekeeping/HousekeepingSnapshot.h" +#include "fsfw/ipc/MutexFactory.h" +#include "fsfw/ipc/MutexGuard.h" +#include "fsfw/ipc/QueueFactory.h" +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/timemanager/CCSDSTime.h" +#include "internal/HasLocalDpIFManagerAttorney.h" +#include "internal/LocalPoolDataSetAttorney.h" + object_id_t LocalDataPoolManager::defaultHkDestination = objects::PUS_SERVICE_3_HOUSEKEEPING; LocalDataPoolManager::LocalDataPoolManager(HasLocalDataPoolIF* owner, MessageQueueIF* queueToUse, - bool appendValidityBuffer): - appendValidityBuffer(appendValidityBuffer) { - if(owner == nullptr) { - printWarningOrError(sif::OutputTypes::OUT_WARNING, - "LocalDataPoolManager", HasReturnvaluesIF::RETURN_FAILED, - "Invalid supplied owner"); - return; - } - this->owner = owner; - mutex = MutexFactory::instance()->createMutex(); - if(mutex == nullptr) { - printWarningOrError(sif::OutputTypes::OUT_ERROR, - "LocalDataPoolManager", HasReturnvaluesIF::RETURN_FAILED, - "Could not create mutex"); - } + bool appendValidityBuffer) + : appendValidityBuffer(appendValidityBuffer) { + if (owner == nullptr) { + printWarningOrError(sif::OutputTypes::OUT_WARNING, "LocalDataPoolManager", + HasReturnvaluesIF::RETURN_FAILED, "Invalid supplied owner"); + return; + } + this->owner = owner; + mutex = MutexFactory::instance()->createMutex(); + if (mutex == nullptr) { + printWarningOrError(sif::OutputTypes::OUT_ERROR, "LocalDataPoolManager", + HasReturnvaluesIF::RETURN_FAILED, "Could not create mutex"); + } - hkQueue = queueToUse; + hkQueue = queueToUse; } LocalDataPoolManager::~LocalDataPoolManager() { - if(mutex != nullptr) { - MutexFactory::instance()->deleteMutex(mutex); - } + if (mutex != nullptr) { + MutexFactory::instance()->deleteMutex(mutex); + } } ReturnValue_t LocalDataPoolManager::initialize(MessageQueueIF* queueToUse) { - if(queueToUse == nullptr) { - /* Error, all destinations invalid */ - printWarningOrError(sif::OutputTypes::OUT_ERROR, "initialize", - QUEUE_OR_DESTINATION_INVALID); + if (queueToUse == nullptr) { + /* Error, all destinations invalid */ + printWarningOrError(sif::OutputTypes::OUT_ERROR, "initialize", QUEUE_OR_DESTINATION_INVALID); + } + hkQueue = queueToUse; + + ipcStore = ObjectManager::instance()->get(objects::IPC_STORE); + if (ipcStore == nullptr) { + /* Error, all destinations invalid */ + printWarningOrError(sif::OutputTypes::OUT_ERROR, "initialize", HasReturnvaluesIF::RETURN_FAILED, + "Could not set IPC store."); + return HasReturnvaluesIF::RETURN_FAILED; + } + + if (defaultHkDestination != objects::NO_OBJECT) { + AcceptsHkPacketsIF* hkPacketReceiver = + ObjectManager::instance()->get(defaultHkDestination); + if (hkPacketReceiver != nullptr) { + hkDestinationId = hkPacketReceiver->getHkQueue(); + } else { + printWarningOrError(sif::OutputTypes::OUT_ERROR, "initialize", QUEUE_OR_DESTINATION_INVALID); + return QUEUE_OR_DESTINATION_INVALID; } - hkQueue = queueToUse; + } - ipcStore = ObjectManager::instance()->get(objects::IPC_STORE); - if(ipcStore == nullptr) { - /* Error, all destinations invalid */ - printWarningOrError(sif::OutputTypes::OUT_ERROR, - "initialize", HasReturnvaluesIF::RETURN_FAILED, - "Could not set IPC store."); - return HasReturnvaluesIF::RETURN_FAILED; - } - - - if(defaultHkDestination != objects::NO_OBJECT) { - AcceptsHkPacketsIF* hkPacketReceiver = ObjectManager::instance()-> - get(defaultHkDestination); - if(hkPacketReceiver != nullptr) { - hkDestinationId = hkPacketReceiver->getHkQueue(); - } - else { - printWarningOrError(sif::OutputTypes::OUT_ERROR, - "initialize", QUEUE_OR_DESTINATION_INVALID); - return QUEUE_OR_DESTINATION_INVALID; - } - } - - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t LocalDataPoolManager::initializeAfterTaskCreation( - uint8_t nonDiagInvlFactor) { - setNonDiagnosticIntervalFactor(nonDiagInvlFactor); - return initializeHousekeepingPoolEntriesOnce(); +ReturnValue_t LocalDataPoolManager::initializeAfterTaskCreation(uint8_t nonDiagInvlFactor) { + setNonDiagnosticIntervalFactor(nonDiagInvlFactor); + return initializeHousekeepingPoolEntriesOnce(); } ReturnValue_t LocalDataPoolManager::initializeHousekeepingPoolEntriesOnce() { - if(not mapInitialized) { - ReturnValue_t result = owner->initializeLocalDataPool(localPoolMap, - *this); - if(result == HasReturnvaluesIF::RETURN_OK) { - mapInitialized = true; - } - return result; + if (not mapInitialized) { + ReturnValue_t result = owner->initializeLocalDataPool(localPoolMap, *this); + if (result == HasReturnvaluesIF::RETURN_OK) { + mapInitialized = true; } + return result; + } - printWarningOrError(sif::OutputTypes::OUT_WARNING, - "initialize", HasReturnvaluesIF::RETURN_FAILED, - "The map should only be initialized once"); - return HasReturnvaluesIF::RETURN_OK; + printWarningOrError(sif::OutputTypes::OUT_WARNING, "initialize", HasReturnvaluesIF::RETURN_FAILED, + "The map should only be initialized once"); + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t LocalDataPoolManager::performHkOperation() { - ReturnValue_t status = HasReturnvaluesIF::RETURN_OK; - for(auto& receiver: hkReceivers) { - switch(receiver.reportingType) { - case(ReportingType::PERIODIC): { - if(receiver.dataType == DataType::LOCAL_POOL_VARIABLE) { - /* Periodic packets shall only be generated from datasets */ - continue; - } - performPeriodicHkGeneration(receiver); - break; + ReturnValue_t status = HasReturnvaluesIF::RETURN_OK; + for (auto& receiver : hkReceivers) { + switch (receiver.reportingType) { + case (ReportingType::PERIODIC): { + if (receiver.dataType == DataType::LOCAL_POOL_VARIABLE) { + /* Periodic packets shall only be generated from datasets */ + continue; } - case(ReportingType::UPDATE_HK): { - handleHkUpdate(receiver, status); - break; - } - case(ReportingType::UPDATE_NOTIFICATION): { - handleNotificationUpdate(receiver, status); - break; - } - case(ReportingType::UPDATE_SNAPSHOT): { - handleNotificationSnapshot(receiver, status); - break; - } - default: - // This should never happen. - return HasReturnvaluesIF::RETURN_FAILED; - } - } - resetHkUpdateResetHelper(); - return status; -} - -ReturnValue_t LocalDataPoolManager::handleHkUpdate(HkReceiver& receiver, - ReturnValue_t& status) { - if(receiver.dataType == DataType::LOCAL_POOL_VARIABLE) { - /* Update packets shall only be generated from datasets. */ + performPeriodicHkGeneration(receiver); + break; + } + case (ReportingType::UPDATE_HK): { + handleHkUpdate(receiver, status); + break; + } + case (ReportingType::UPDATE_NOTIFICATION): { + handleNotificationUpdate(receiver, status); + break; + } + case (ReportingType::UPDATE_SNAPSHOT): { + handleNotificationSnapshot(receiver, status); + break; + } + default: + // This should never happen. return HasReturnvaluesIF::RETURN_FAILED; } - LocalPoolDataSetBase* dataSet = HasLocalDpIFManagerAttorney::getDataSetHandle(owner, - receiver.dataId.sid); - if(dataSet == nullptr) { - return DATASET_NOT_FOUND; + } + resetHkUpdateResetHelper(); + return status; +} + +ReturnValue_t LocalDataPoolManager::handleHkUpdate(HkReceiver& receiver, ReturnValue_t& status) { + if (receiver.dataType == DataType::LOCAL_POOL_VARIABLE) { + /* Update packets shall only be generated from datasets. */ + return HasReturnvaluesIF::RETURN_FAILED; + } + LocalPoolDataSetBase* dataSet = + HasLocalDpIFManagerAttorney::getDataSetHandle(owner, receiver.dataId.sid); + if (dataSet == nullptr) { + return DATASET_NOT_FOUND; + } + if (dataSet->hasChanged()) { + /* Prepare and send update notification */ + ReturnValue_t result = generateHousekeepingPacket(receiver.dataId.sid, dataSet, true); + if (result != HasReturnvaluesIF::RETURN_OK) { + status = result; } - if(dataSet->hasChanged()) { - /* Prepare and send update notification */ - ReturnValue_t result = generateHousekeepingPacket( - receiver.dataId.sid, dataSet, true); - if(result != HasReturnvaluesIF::RETURN_OK) { - status = result; - } - } - handleChangeResetLogic(receiver.dataType, receiver.dataId, - dataSet); - return HasReturnvaluesIF::RETURN_OK; + } + handleChangeResetLogic(receiver.dataType, receiver.dataId, dataSet); + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t LocalDataPoolManager::handleNotificationUpdate(HkReceiver& receiver, - ReturnValue_t& status) { - MarkChangedIF* toReset = nullptr; - if(receiver.dataType == DataType::LOCAL_POOL_VARIABLE) { - LocalPoolObjectBase* poolObj = HasLocalDpIFManagerAttorney::getPoolObjectHandle(owner, - receiver.dataId.localPoolId); - if(poolObj == nullptr) { - printWarningOrError(sif::OutputTypes::OUT_WARNING, - "handleNotificationUpdate", POOLOBJECT_NOT_FOUND); - return POOLOBJECT_NOT_FOUND; - } - if(poolObj->hasChanged()) { - /* Prepare and send update notification. */ - CommandMessage notification; - HousekeepingMessage::setUpdateNotificationVariableCommand(¬ification, - gp_id_t(owner->getObjectId(), receiver.dataId.localPoolId)); - ReturnValue_t result = hkQueue->sendMessage(receiver.destinationQueue, ¬ification); - if(result != HasReturnvaluesIF::RETURN_OK) { - status = result; - } - toReset = poolObj; - } + ReturnValue_t& status) { + MarkChangedIF* toReset = nullptr; + if (receiver.dataType == DataType::LOCAL_POOL_VARIABLE) { + LocalPoolObjectBase* poolObj = + HasLocalDpIFManagerAttorney::getPoolObjectHandle(owner, receiver.dataId.localPoolId); + if (poolObj == nullptr) { + printWarningOrError(sif::OutputTypes::OUT_WARNING, "handleNotificationUpdate", + POOLOBJECT_NOT_FOUND); + return POOLOBJECT_NOT_FOUND; + } + if (poolObj->hasChanged()) { + /* Prepare and send update notification. */ + CommandMessage notification; + HousekeepingMessage::setUpdateNotificationVariableCommand( + ¬ification, gp_id_t(owner->getObjectId(), receiver.dataId.localPoolId)); + ReturnValue_t result = hkQueue->sendMessage(receiver.destinationQueue, ¬ification); + if (result != HasReturnvaluesIF::RETURN_OK) { + status = result; + } + toReset = poolObj; + } + } else { + LocalPoolDataSetBase* dataSet = + HasLocalDpIFManagerAttorney::getDataSetHandle(owner, receiver.dataId.sid); + if (dataSet == nullptr) { + printWarningOrError(sif::OutputTypes::OUT_WARNING, "handleNotificationUpdate", + DATASET_NOT_FOUND); + return DATASET_NOT_FOUND; } - else { - LocalPoolDataSetBase* dataSet = HasLocalDpIFManagerAttorney::getDataSetHandle(owner, - receiver.dataId.sid); - if(dataSet == nullptr) { - printWarningOrError(sif::OutputTypes::OUT_WARNING, - "handleNotificationUpdate", DATASET_NOT_FOUND); - return DATASET_NOT_FOUND; - } - if(dataSet->hasChanged()) { - /* Prepare and send update notification */ - CommandMessage notification; - HousekeepingMessage::setUpdateNotificationSetCommand(¬ification, - receiver.dataId.sid); - ReturnValue_t result = hkQueue->sendMessage( - receiver.destinationQueue, ¬ification); - if(result != HasReturnvaluesIF::RETURN_OK) { - status = result; - } - toReset = dataSet; - } + if (dataSet->hasChanged()) { + /* Prepare and send update notification */ + CommandMessage notification; + HousekeepingMessage::setUpdateNotificationSetCommand(¬ification, receiver.dataId.sid); + ReturnValue_t result = hkQueue->sendMessage(receiver.destinationQueue, ¬ification); + if (result != HasReturnvaluesIF::RETURN_OK) { + status = result; + } + toReset = dataSet; } - if(toReset != nullptr) { - handleChangeResetLogic(receiver.dataType, receiver.dataId, toReset); - } - return HasReturnvaluesIF::RETURN_OK; + } + if (toReset != nullptr) { + handleChangeResetLogic(receiver.dataType, receiver.dataId, toReset); + } + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t LocalDataPoolManager::handleNotificationSnapshot( - HkReceiver& receiver, ReturnValue_t& status) { - MarkChangedIF* toReset = nullptr; - /* Check whether data has changed and send messages in case it has */ - if(receiver.dataType == DataType::LOCAL_POOL_VARIABLE) { - LocalPoolObjectBase* poolObj = HasLocalDpIFManagerAttorney::getPoolObjectHandle(owner, - receiver.dataId.localPoolId); - if(poolObj == nullptr) { - printWarningOrError(sif::OutputTypes::OUT_WARNING, - "handleNotificationSnapshot", POOLOBJECT_NOT_FOUND); - return POOLOBJECT_NOT_FOUND; - } - - if (not poolObj->hasChanged()) { - return HasReturnvaluesIF::RETURN_OK; - } - - /* Prepare and send update snapshot */ - timeval now; - Clock::getClock_timeval(&now); - CCSDSTime::CDS_short cds; - CCSDSTime::convertToCcsds(&cds, &now); - HousekeepingSnapshot updatePacket(reinterpret_cast(&cds), sizeof(cds), - HasLocalDpIFManagerAttorney::getPoolObjectHandle( - owner,receiver.dataId.localPoolId)); - - store_address_t storeId; - ReturnValue_t result = addUpdateToStore(updatePacket, storeId); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - - CommandMessage notification; - HousekeepingMessage::setUpdateSnapshotVariableCommand(¬ification, - gp_id_t(owner->getObjectId(), receiver.dataId.localPoolId), storeId); - result = hkQueue->sendMessage(receiver.destinationQueue, - ¬ification); - if (result != HasReturnvaluesIF::RETURN_OK) { - status = result; - } - toReset = poolObj; +ReturnValue_t LocalDataPoolManager::handleNotificationSnapshot(HkReceiver& receiver, + ReturnValue_t& status) { + MarkChangedIF* toReset = nullptr; + /* Check whether data has changed and send messages in case it has */ + if (receiver.dataType == DataType::LOCAL_POOL_VARIABLE) { + LocalPoolObjectBase* poolObj = + HasLocalDpIFManagerAttorney::getPoolObjectHandle(owner, receiver.dataId.localPoolId); + if (poolObj == nullptr) { + printWarningOrError(sif::OutputTypes::OUT_WARNING, "handleNotificationSnapshot", + POOLOBJECT_NOT_FOUND); + return POOLOBJECT_NOT_FOUND; } - else { - LocalPoolDataSetBase* dataSet = HasLocalDpIFManagerAttorney::getDataSetHandle(owner, - receiver.dataId.sid); - if(dataSet == nullptr) { - printWarningOrError(sif::OutputTypes::OUT_WARNING, - "handleNotificationSnapshot", DATASET_NOT_FOUND); - return DATASET_NOT_FOUND; - } - - if(not dataSet->hasChanged()) { - return HasReturnvaluesIF::RETURN_OK; - } - - /* Prepare and send update snapshot */ - timeval now; - Clock::getClock_timeval(&now); - CCSDSTime::CDS_short cds; - CCSDSTime::convertToCcsds(&cds, &now); - HousekeepingSnapshot updatePacket(reinterpret_cast(&cds), - sizeof(cds), HasLocalDpIFManagerAttorney::getDataSetHandle(owner, - receiver.dataId.sid)); - - store_address_t storeId; - ReturnValue_t result = addUpdateToStore(updatePacket, storeId); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - - CommandMessage notification; - HousekeepingMessage::setUpdateSnapshotSetCommand( - ¬ification, receiver.dataId.sid, storeId); - result = hkQueue->sendMessage(receiver.destinationQueue, ¬ification); - if(result != HasReturnvaluesIF::RETURN_OK) { - status = result; - } - toReset = dataSet; + if (not poolObj->hasChanged()) { + return HasReturnvaluesIF::RETURN_OK; } - if(toReset != nullptr) { - handleChangeResetLogic(receiver.dataType, - receiver.dataId, toReset); - } - return HasReturnvaluesIF::RETURN_OK; -} -ReturnValue_t LocalDataPoolManager::addUpdateToStore( - HousekeepingSnapshot& updatePacket, store_address_t& storeId) { - size_t updatePacketSize = updatePacket.getSerializedSize(); - uint8_t *storePtr = nullptr; - ReturnValue_t result = ipcStore->getFreeElement(&storeId, - updatePacket.getSerializedSize(), &storePtr); + /* Prepare and send update snapshot */ + timeval now; + Clock::getClock_timeval(&now); + CCSDSTime::CDS_short cds; + CCSDSTime::convertToCcsds(&cds, &now); + HousekeepingSnapshot updatePacket( + reinterpret_cast(&cds), sizeof(cds), + HasLocalDpIFManagerAttorney::getPoolObjectHandle(owner, receiver.dataId.localPoolId)); + + store_address_t storeId; + ReturnValue_t result = addUpdateToStore(updatePacket, storeId); if (result != HasReturnvaluesIF::RETURN_OK) { - return result; + return result; } - size_t serializedSize = 0; - result = updatePacket.serialize(&storePtr, &serializedSize, - updatePacketSize, SerializeIF::Endianness::MACHINE); - return result;; + + CommandMessage notification; + HousekeepingMessage::setUpdateSnapshotVariableCommand( + ¬ification, gp_id_t(owner->getObjectId(), receiver.dataId.localPoolId), storeId); + result = hkQueue->sendMessage(receiver.destinationQueue, ¬ification); + if (result != HasReturnvaluesIF::RETURN_OK) { + status = result; + } + toReset = poolObj; + } else { + LocalPoolDataSetBase* dataSet = + HasLocalDpIFManagerAttorney::getDataSetHandle(owner, receiver.dataId.sid); + if (dataSet == nullptr) { + printWarningOrError(sif::OutputTypes::OUT_WARNING, "handleNotificationSnapshot", + DATASET_NOT_FOUND); + return DATASET_NOT_FOUND; + } + + if (not dataSet->hasChanged()) { + return HasReturnvaluesIF::RETURN_OK; + } + + /* Prepare and send update snapshot */ + timeval now; + Clock::getClock_timeval(&now); + CCSDSTime::CDS_short cds; + CCSDSTime::convertToCcsds(&cds, &now); + HousekeepingSnapshot updatePacket( + reinterpret_cast(&cds), sizeof(cds), + HasLocalDpIFManagerAttorney::getDataSetHandle(owner, receiver.dataId.sid)); + + store_address_t storeId; + ReturnValue_t result = addUpdateToStore(updatePacket, storeId); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + + CommandMessage notification; + HousekeepingMessage::setUpdateSnapshotSetCommand(¬ification, receiver.dataId.sid, storeId); + result = hkQueue->sendMessage(receiver.destinationQueue, ¬ification); + if (result != HasReturnvaluesIF::RETURN_OK) { + status = result; + } + toReset = dataSet; + } + if (toReset != nullptr) { + handleChangeResetLogic(receiver.dataType, receiver.dataId, toReset); + } + return HasReturnvaluesIF::RETURN_OK; } -void LocalDataPoolManager::handleChangeResetLogic( - DataType type, DataId dataId, MarkChangedIF* toReset) { - if(hkUpdateResetList == nullptr) { - /* Config error */ - return; - } - HkUpdateResetList& listRef = *hkUpdateResetList; - for(auto& changeInfo: listRef) { - if(changeInfo.dataType != type) { - continue; - } - if((changeInfo.dataType == DataType::DATA_SET) and - (changeInfo.dataId.sid != dataId.sid)) { - continue; - } - if((changeInfo.dataType == DataType::LOCAL_POOL_VARIABLE) and - (changeInfo.dataId.localPoolId != dataId.localPoolId)) { - continue; - } +ReturnValue_t LocalDataPoolManager::addUpdateToStore(HousekeepingSnapshot& updatePacket, + store_address_t& storeId) { + size_t updatePacketSize = updatePacket.getSerializedSize(); + uint8_t* storePtr = nullptr; + ReturnValue_t result = + ipcStore->getFreeElement(&storeId, updatePacket.getSerializedSize(), &storePtr); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + size_t serializedSize = 0; + result = updatePacket.serialize(&storePtr, &serializedSize, updatePacketSize, + SerializeIF::Endianness::MACHINE); + return result; + ; +} - /* Only one update recipient, we can reset changes status immediately */ - if(changeInfo.updateCounter <= 1) { - toReset->setChanged(false); - } - /* All recipients have been notified, reset the changed flag */ - else if(changeInfo.currentUpdateCounter <= 1) { - toReset->setChanged(false); - changeInfo.currentUpdateCounter = 0; - } - /* Not all recipiens have been notified yet, decrement */ - else { - changeInfo.currentUpdateCounter--; - } - return; +void LocalDataPoolManager::handleChangeResetLogic(DataType type, DataId dataId, + MarkChangedIF* toReset) { + if (hkUpdateResetList == nullptr) { + /* Config error */ + return; + } + HkUpdateResetList& listRef = *hkUpdateResetList; + for (auto& changeInfo : listRef) { + if (changeInfo.dataType != type) { + continue; } + if ((changeInfo.dataType == DataType::DATA_SET) and (changeInfo.dataId.sid != dataId.sid)) { + continue; + } + if ((changeInfo.dataType == DataType::LOCAL_POOL_VARIABLE) and + (changeInfo.dataId.localPoolId != dataId.localPoolId)) { + continue; + } + + /* Only one update recipient, we can reset changes status immediately */ + if (changeInfo.updateCounter <= 1) { + toReset->setChanged(false); + } + /* All recipients have been notified, reset the changed flag */ + else if (changeInfo.currentUpdateCounter <= 1) { + toReset->setChanged(false); + changeInfo.currentUpdateCounter = 0; + } + /* Not all recipiens have been notified yet, decrement */ + else { + changeInfo.currentUpdateCounter--; + } + return; + } } void LocalDataPoolManager::resetHkUpdateResetHelper() { - if(hkUpdateResetList == nullptr) { - return; - } + if (hkUpdateResetList == nullptr) { + return; + } - for(auto& changeInfo: *hkUpdateResetList) { - changeInfo.currentUpdateCounter = changeInfo.updateCounter; - } + for (auto& changeInfo : *hkUpdateResetList) { + changeInfo.currentUpdateCounter = changeInfo.updateCounter; + } } -ReturnValue_t LocalDataPoolManager::subscribeForPeriodicPacket(sid_t sid, - bool enableReporting, float collectionInterval, bool isDiagnostics, - object_id_t packetDestination) { - AcceptsHkPacketsIF* hkReceiverObject = ObjectManager::instance()-> - get(packetDestination); - if(hkReceiverObject == nullptr) { - printWarningOrError(sif::OutputTypes::OUT_WARNING, - "subscribeForPeriodicPacket", QUEUE_OR_DESTINATION_INVALID); - return QUEUE_OR_DESTINATION_INVALID; - } +ReturnValue_t LocalDataPoolManager::subscribeForPeriodicPacket(sid_t sid, bool enableReporting, + float collectionInterval, + bool isDiagnostics, + object_id_t packetDestination) { + AcceptsHkPacketsIF* hkReceiverObject = + ObjectManager::instance()->get(packetDestination); + if (hkReceiverObject == nullptr) { + printWarningOrError(sif::OutputTypes::OUT_WARNING, "subscribeForPeriodicPacket", + QUEUE_OR_DESTINATION_INVALID); + return QUEUE_OR_DESTINATION_INVALID; + } - struct HkReceiver hkReceiver; - hkReceiver.dataId.sid = sid; - hkReceiver.reportingType = ReportingType::PERIODIC; - hkReceiver.dataType = DataType::DATA_SET; - hkReceiver.destinationQueue = hkReceiverObject->getHkQueue(); + struct HkReceiver hkReceiver; + hkReceiver.dataId.sid = sid; + hkReceiver.reportingType = ReportingType::PERIODIC; + hkReceiver.dataType = DataType::DATA_SET; + hkReceiver.destinationQueue = hkReceiverObject->getHkQueue(); - LocalPoolDataSetBase* dataSet = HasLocalDpIFManagerAttorney::getDataSetHandle(owner, sid); - if(dataSet != nullptr) { - LocalPoolDataSetAttorney::setReportingEnabled(*dataSet, enableReporting); - LocalPoolDataSetAttorney::setDiagnostic(*dataSet, isDiagnostics); - LocalPoolDataSetAttorney::initializePeriodicHelper(*dataSet, collectionInterval, - owner->getPeriodicOperationFrequency()); - } + LocalPoolDataSetBase* dataSet = HasLocalDpIFManagerAttorney::getDataSetHandle(owner, sid); + if (dataSet != nullptr) { + LocalPoolDataSetAttorney::setReportingEnabled(*dataSet, enableReporting); + LocalPoolDataSetAttorney::setDiagnostic(*dataSet, isDiagnostics); + LocalPoolDataSetAttorney::initializePeriodicHelper(*dataSet, collectionInterval, + owner->getPeriodicOperationFrequency()); + } - hkReceivers.push_back(hkReceiver); - return HasReturnvaluesIF::RETURN_OK; + hkReceivers.push_back(hkReceiver); + return HasReturnvaluesIF::RETURN_OK; } +ReturnValue_t LocalDataPoolManager::subscribeForUpdatePacket(sid_t sid, bool isDiagnostics, + bool reportingEnabled, + object_id_t packetDestination) { + AcceptsHkPacketsIF* hkReceiverObject = + ObjectManager::instance()->get(packetDestination); + if (hkReceiverObject == nullptr) { + printWarningOrError(sif::OutputTypes::OUT_WARNING, "subscribeForPeriodicPacket", + QUEUE_OR_DESTINATION_INVALID); + return QUEUE_OR_DESTINATION_INVALID; + } -ReturnValue_t LocalDataPoolManager::subscribeForUpdatePacket(sid_t sid, - bool isDiagnostics, bool reportingEnabled, - object_id_t packetDestination) { - AcceptsHkPacketsIF* hkReceiverObject = - ObjectManager::instance()->get(packetDestination); - if(hkReceiverObject == nullptr) { - printWarningOrError(sif::OutputTypes::OUT_WARNING, - "subscribeForPeriodicPacket", QUEUE_OR_DESTINATION_INVALID); - return QUEUE_OR_DESTINATION_INVALID; - } + struct HkReceiver hkReceiver; + hkReceiver.dataId.sid = sid; + hkReceiver.reportingType = ReportingType::UPDATE_HK; + hkReceiver.dataType = DataType::DATA_SET; + hkReceiver.destinationQueue = hkReceiverObject->getHkQueue(); - struct HkReceiver hkReceiver; - hkReceiver.dataId.sid = sid; - hkReceiver.reportingType = ReportingType::UPDATE_HK; - hkReceiver.dataType = DataType::DATA_SET; - hkReceiver.destinationQueue = hkReceiverObject->getHkQueue(); + LocalPoolDataSetBase* dataSet = HasLocalDpIFManagerAttorney::getDataSetHandle(owner, sid); + if (dataSet != nullptr) { + LocalPoolDataSetAttorney::setReportingEnabled(*dataSet, true); + LocalPoolDataSetAttorney::setDiagnostic(*dataSet, isDiagnostics); + } - LocalPoolDataSetBase* dataSet = HasLocalDpIFManagerAttorney::getDataSetHandle(owner, sid); - if(dataSet != nullptr) { - LocalPoolDataSetAttorney::setReportingEnabled(*dataSet, true); - LocalPoolDataSetAttorney::setDiagnostic(*dataSet, isDiagnostics); - } + hkReceivers.push_back(hkReceiver); - hkReceivers.push_back(hkReceiver); - - handleHkUpdateResetListInsertion(hkReceiver.dataType, hkReceiver.dataId); - return HasReturnvaluesIF::RETURN_OK; + handleHkUpdateResetListInsertion(hkReceiver.dataType, hkReceiver.dataId); + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t LocalDataPoolManager::subscribeForSetUpdateMessage( - const uint32_t setId, object_id_t destinationObject, - MessageQueueId_t targetQueueId, bool generateSnapshot) { - struct HkReceiver hkReceiver; - hkReceiver.dataType = DataType::DATA_SET; - hkReceiver.dataId.sid = sid_t(owner->getObjectId(), setId); - hkReceiver.destinationQueue = targetQueueId; - hkReceiver.objectId = destinationObject; - if(generateSnapshot) { - hkReceiver.reportingType = ReportingType::UPDATE_SNAPSHOT; - } - else { - hkReceiver.reportingType = ReportingType::UPDATE_NOTIFICATION; - } +ReturnValue_t LocalDataPoolManager::subscribeForSetUpdateMessage(const uint32_t setId, + object_id_t destinationObject, + MessageQueueId_t targetQueueId, + bool generateSnapshot) { + struct HkReceiver hkReceiver; + hkReceiver.dataType = DataType::DATA_SET; + hkReceiver.dataId.sid = sid_t(owner->getObjectId(), setId); + hkReceiver.destinationQueue = targetQueueId; + hkReceiver.objectId = destinationObject; + if (generateSnapshot) { + hkReceiver.reportingType = ReportingType::UPDATE_SNAPSHOT; + } else { + hkReceiver.reportingType = ReportingType::UPDATE_NOTIFICATION; + } - hkReceivers.push_back(hkReceiver); + hkReceivers.push_back(hkReceiver); - handleHkUpdateResetListInsertion(hkReceiver.dataType, hkReceiver.dataId); - return HasReturnvaluesIF::RETURN_OK; + handleHkUpdateResetListInsertion(hkReceiver.dataType, hkReceiver.dataId); + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t LocalDataPoolManager::subscribeForVariableUpdateMessage( - const lp_id_t localPoolId, object_id_t destinationObject, - MessageQueueId_t targetQueueId, bool generateSnapshot) { - struct HkReceiver hkReceiver; - hkReceiver.dataType = DataType::LOCAL_POOL_VARIABLE; - hkReceiver.dataId.localPoolId = localPoolId; - hkReceiver.destinationQueue = targetQueueId; - hkReceiver.objectId = destinationObject; - if(generateSnapshot) { - hkReceiver.reportingType = ReportingType::UPDATE_SNAPSHOT; - } - else { - hkReceiver.reportingType = ReportingType::UPDATE_NOTIFICATION; - } + const lp_id_t localPoolId, object_id_t destinationObject, MessageQueueId_t targetQueueId, + bool generateSnapshot) { + struct HkReceiver hkReceiver; + hkReceiver.dataType = DataType::LOCAL_POOL_VARIABLE; + hkReceiver.dataId.localPoolId = localPoolId; + hkReceiver.destinationQueue = targetQueueId; + hkReceiver.objectId = destinationObject; + if (generateSnapshot) { + hkReceiver.reportingType = ReportingType::UPDATE_SNAPSHOT; + } else { + hkReceiver.reportingType = ReportingType::UPDATE_NOTIFICATION; + } - hkReceivers.push_back(hkReceiver); + hkReceivers.push_back(hkReceiver); - handleHkUpdateResetListInsertion(hkReceiver.dataType, hkReceiver.dataId); - return HasReturnvaluesIF::RETURN_OK; + handleHkUpdateResetListInsertion(hkReceiver.dataType, hkReceiver.dataId); + return HasReturnvaluesIF::RETURN_OK; } -void LocalDataPoolManager::handleHkUpdateResetListInsertion(DataType dataType, - DataId dataId) { - if(hkUpdateResetList == nullptr) { - hkUpdateResetList = new std::vector(); - } - - for(auto& updateResetStruct: *hkUpdateResetList) { - if(dataType == DataType::DATA_SET) { - if(updateResetStruct.dataId.sid == dataId.sid) { - updateResetStruct.updateCounter++; - updateResetStruct.currentUpdateCounter++; - return; - } - } - else { - if(updateResetStruct.dataId.localPoolId == dataId.localPoolId) { - updateResetStruct.updateCounter++; - updateResetStruct.currentUpdateCounter++; - return; - } - } +void LocalDataPoolManager::handleHkUpdateResetListInsertion(DataType dataType, DataId dataId) { + if (hkUpdateResetList == nullptr) { + hkUpdateResetList = new std::vector(); + } + for (auto& updateResetStruct : *hkUpdateResetList) { + if (dataType == DataType::DATA_SET) { + if (updateResetStruct.dataId.sid == dataId.sid) { + updateResetStruct.updateCounter++; + updateResetStruct.currentUpdateCounter++; + return; + } + } else { + if (updateResetStruct.dataId.localPoolId == dataId.localPoolId) { + updateResetStruct.updateCounter++; + updateResetStruct.currentUpdateCounter++; + return; + } } - HkUpdateResetHelper hkUpdateResetHelper; - hkUpdateResetHelper.currentUpdateCounter = 1; - hkUpdateResetHelper.updateCounter = 1; - hkUpdateResetHelper.dataType = dataType; - if(dataType == DataType::DATA_SET) { - hkUpdateResetHelper.dataId.sid = dataId.sid; - } - else { - hkUpdateResetHelper.dataId.localPoolId = dataId.localPoolId; - } - hkUpdateResetList->push_back(hkUpdateResetHelper); + } + HkUpdateResetHelper hkUpdateResetHelper; + hkUpdateResetHelper.currentUpdateCounter = 1; + hkUpdateResetHelper.updateCounter = 1; + hkUpdateResetHelper.dataType = dataType; + if (dataType == DataType::DATA_SET) { + hkUpdateResetHelper.dataId.sid = dataId.sid; + } else { + hkUpdateResetHelper.dataId.localPoolId = dataId.localPoolId; + } + hkUpdateResetList->push_back(hkUpdateResetHelper); } -ReturnValue_t LocalDataPoolManager::handleHousekeepingMessage( - CommandMessage* message) { - Command_t command = message->getCommand(); - sid_t sid = HousekeepingMessage::getSid(message); - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - switch(command) { +ReturnValue_t LocalDataPoolManager::handleHousekeepingMessage(CommandMessage* message) { + Command_t command = message->getCommand(); + sid_t sid = HousekeepingMessage::getSid(message); + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + switch (command) { // Houskeeping interface handling. - case(HousekeepingMessage::ENABLE_PERIODIC_DIAGNOSTICS_GENERATION): { - result = togglePeriodicGeneration(sid, true, true); - break; + case (HousekeepingMessage::ENABLE_PERIODIC_DIAGNOSTICS_GENERATION): { + result = togglePeriodicGeneration(sid, true, true); + break; } - case(HousekeepingMessage::DISABLE_PERIODIC_DIAGNOSTICS_GENERATION): { - result = togglePeriodicGeneration(sid, false, true); - break; + case (HousekeepingMessage::DISABLE_PERIODIC_DIAGNOSTICS_GENERATION): { + result = togglePeriodicGeneration(sid, false, true); + break; } - case(HousekeepingMessage::ENABLE_PERIODIC_HK_REPORT_GENERATION): { - result = togglePeriodicGeneration(sid, true, false); - break; + case (HousekeepingMessage::ENABLE_PERIODIC_HK_REPORT_GENERATION): { + result = togglePeriodicGeneration(sid, true, false); + break; } - case(HousekeepingMessage::DISABLE_PERIODIC_HK_REPORT_GENERATION): { - result = togglePeriodicGeneration(sid, false, false); - break; + case (HousekeepingMessage::DISABLE_PERIODIC_HK_REPORT_GENERATION): { + result = togglePeriodicGeneration(sid, false, false); + break; } - case(HousekeepingMessage::REPORT_DIAGNOSTICS_REPORT_STRUCTURES): { - result = generateSetStructurePacket(sid, true); - if(result == HasReturnvaluesIF::RETURN_OK) { - return result; - } - break; + case (HousekeepingMessage::REPORT_DIAGNOSTICS_REPORT_STRUCTURES): { + result = generateSetStructurePacket(sid, true); + if (result == HasReturnvaluesIF::RETURN_OK) { + return result; + } + break; } - case(HousekeepingMessage::REPORT_HK_REPORT_STRUCTURES): { - result = generateSetStructurePacket(sid, false); - if(result == HasReturnvaluesIF::RETURN_OK) { - return result; - } - break; + case (HousekeepingMessage::REPORT_HK_REPORT_STRUCTURES): { + result = generateSetStructurePacket(sid, false); + if (result == HasReturnvaluesIF::RETURN_OK) { + return result; + } + break; } - case(HousekeepingMessage::MODIFY_DIAGNOSTICS_REPORT_COLLECTION_INTERVAL): - case(HousekeepingMessage::MODIFY_PARAMETER_REPORT_COLLECTION_INTERVAL): { - float newCollIntvl = 0; - HousekeepingMessage::getCollectionIntervalModificationCommand(message, - &newCollIntvl); - if(command == HousekeepingMessage:: - MODIFY_DIAGNOSTICS_REPORT_COLLECTION_INTERVAL) { - result = changeCollectionInterval(sid, newCollIntvl, true); - } - else { - result = changeCollectionInterval(sid, newCollIntvl, false); - } - break; + case (HousekeepingMessage::MODIFY_DIAGNOSTICS_REPORT_COLLECTION_INTERVAL): + case (HousekeepingMessage::MODIFY_PARAMETER_REPORT_COLLECTION_INTERVAL): { + float newCollIntvl = 0; + HousekeepingMessage::getCollectionIntervalModificationCommand(message, &newCollIntvl); + if (command == HousekeepingMessage::MODIFY_DIAGNOSTICS_REPORT_COLLECTION_INTERVAL) { + result = changeCollectionInterval(sid, newCollIntvl, true); + } else { + result = changeCollectionInterval(sid, newCollIntvl, false); + } + break; } - case(HousekeepingMessage::GENERATE_ONE_PARAMETER_REPORT): - case(HousekeepingMessage::GENERATE_ONE_DIAGNOSTICS_REPORT): { - LocalPoolDataSetBase* dataSet = HasLocalDpIFManagerAttorney::getDataSetHandle(owner, sid); - if(dataSet == nullptr) { - printWarningOrError(sif::OutputTypes::OUT_WARNING, "handleHousekeepingMessage", - DATASET_NOT_FOUND); - return DATASET_NOT_FOUND; - } - if(command == HousekeepingMessage::GENERATE_ONE_PARAMETER_REPORT - and LocalPoolDataSetAttorney::isDiagnostics(*dataSet)) { - result = WRONG_HK_PACKET_TYPE; - break; - } - else if(command == HousekeepingMessage::GENERATE_ONE_DIAGNOSTICS_REPORT - and not LocalPoolDataSetAttorney::isDiagnostics(*dataSet)) { - result = WRONG_HK_PACKET_TYPE; - break; - } - return generateHousekeepingPacket(HousekeepingMessage::getSid(message), - dataSet, true); + case (HousekeepingMessage::GENERATE_ONE_PARAMETER_REPORT): + case (HousekeepingMessage::GENERATE_ONE_DIAGNOSTICS_REPORT): { + LocalPoolDataSetBase* dataSet = HasLocalDpIFManagerAttorney::getDataSetHandle(owner, sid); + if (dataSet == nullptr) { + printWarningOrError(sif::OutputTypes::OUT_WARNING, "handleHousekeepingMessage", + DATASET_NOT_FOUND); + return DATASET_NOT_FOUND; + } + if (command == HousekeepingMessage::GENERATE_ONE_PARAMETER_REPORT and + LocalPoolDataSetAttorney::isDiagnostics(*dataSet)) { + result = WRONG_HK_PACKET_TYPE; + break; + } else if (command == HousekeepingMessage::GENERATE_ONE_DIAGNOSTICS_REPORT and + not LocalPoolDataSetAttorney::isDiagnostics(*dataSet)) { + result = WRONG_HK_PACKET_TYPE; + break; + } + return generateHousekeepingPacket(HousekeepingMessage::getSid(message), dataSet, true); } /* Notification handling */ - case(HousekeepingMessage::UPDATE_NOTIFICATION_SET): { - owner->handleChangedDataset(sid); - return HasReturnvaluesIF::RETURN_OK; + case (HousekeepingMessage::UPDATE_NOTIFICATION_SET): { + owner->handleChangedDataset(sid); + return HasReturnvaluesIF::RETURN_OK; } - case(HousekeepingMessage::UPDATE_NOTIFICATION_VARIABLE): { - gp_id_t globPoolId = HousekeepingMessage::getUpdateNotificationVariableCommand(message); - owner->handleChangedPoolVariable(globPoolId); - return HasReturnvaluesIF::RETURN_OK; + case (HousekeepingMessage::UPDATE_NOTIFICATION_VARIABLE): { + gp_id_t globPoolId = HousekeepingMessage::getUpdateNotificationVariableCommand(message); + owner->handleChangedPoolVariable(globPoolId); + return HasReturnvaluesIF::RETURN_OK; } - case(HousekeepingMessage::UPDATE_SNAPSHOT_SET): { - store_address_t storeId; - HousekeepingMessage::getUpdateSnapshotSetCommand(message, &storeId); - bool clearMessage = true; - owner->handleChangedDataset(sid, storeId, &clearMessage); - if(clearMessage) { - message->clear(); - } - return HasReturnvaluesIF::RETURN_OK; + case (HousekeepingMessage::UPDATE_SNAPSHOT_SET): { + store_address_t storeId; + HousekeepingMessage::getUpdateSnapshotSetCommand(message, &storeId); + bool clearMessage = true; + owner->handleChangedDataset(sid, storeId, &clearMessage); + if (clearMessage) { + message->clear(); + } + return HasReturnvaluesIF::RETURN_OK; } - case(HousekeepingMessage::UPDATE_SNAPSHOT_VARIABLE): { - store_address_t storeId; - gp_id_t globPoolId = HousekeepingMessage::getUpdateSnapshotVariableCommand(message, - &storeId); - bool clearMessage = true; - owner->handleChangedPoolVariable(globPoolId, storeId, &clearMessage); - if(clearMessage) { - message->clear(); - } - return HasReturnvaluesIF::RETURN_OK; + case (HousekeepingMessage::UPDATE_SNAPSHOT_VARIABLE): { + store_address_t storeId; + gp_id_t globPoolId = HousekeepingMessage::getUpdateSnapshotVariableCommand(message, &storeId); + bool clearMessage = true; + owner->handleChangedPoolVariable(globPoolId, storeId, &clearMessage); + if (clearMessage) { + message->clear(); + } + return HasReturnvaluesIF::RETURN_OK; } default: - return CommandMessageIF::UNKNOWN_COMMAND; - } + return CommandMessageIF::UNKNOWN_COMMAND; + } - CommandMessage reply; - if(result != HasReturnvaluesIF::RETURN_OK) { - HousekeepingMessage::setHkRequestFailureReply(&reply, sid, result); - } - else { - HousekeepingMessage::setHkRequestSuccessReply(&reply, sid); - } - hkQueue->sendMessage(hkDestinationId, &reply); - return result; + CommandMessage reply; + if (result != HasReturnvaluesIF::RETURN_OK) { + HousekeepingMessage::setHkRequestFailureReply(&reply, sid, result); + } else { + HousekeepingMessage::setHkRequestSuccessReply(&reply, sid); + } + hkQueue->sendMessage(hkDestinationId, &reply); + return result; } -ReturnValue_t LocalDataPoolManager::printPoolEntry( - lp_id_t localPoolId) { - auto poolIter = localPoolMap.find(localPoolId); - if (poolIter == localPoolMap.end()) { - printWarningOrError(sif::OutputTypes::OUT_WARNING, "printPoolEntry", - localpool::POOL_ENTRY_NOT_FOUND); - return localpool::POOL_ENTRY_NOT_FOUND; - } - poolIter->second->print(); - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t LocalDataPoolManager::printPoolEntry(lp_id_t localPoolId) { + auto poolIter = localPoolMap.find(localPoolId); + if (poolIter == localPoolMap.end()) { + printWarningOrError(sif::OutputTypes::OUT_WARNING, "printPoolEntry", + localpool::POOL_ENTRY_NOT_FOUND); + return localpool::POOL_ENTRY_NOT_FOUND; + } + poolIter->second->print(); + return HasReturnvaluesIF::RETURN_OK; } -MutexIF* LocalDataPoolManager::getMutexHandle() { - return mutex; -} +MutexIF* LocalDataPoolManager::getMutexHandle() { return mutex; } -HasLocalDataPoolIF* LocalDataPoolManager::getOwner() { - return owner; -} +HasLocalDataPoolIF* LocalDataPoolManager::getOwner() { return owner; } ReturnValue_t LocalDataPoolManager::generateHousekeepingPacket(sid_t sid, - LocalPoolDataSetBase* dataSet, bool forDownlink, - MessageQueueId_t destination) { - if(dataSet == nullptr) { - /* Configuration error. */ - printWarningOrError(sif::OutputTypes::OUT_WARNING, - "generateHousekeepingPacket", - DATASET_NOT_FOUND); - return DATASET_NOT_FOUND; - } + LocalPoolDataSetBase* dataSet, + bool forDownlink, + MessageQueueId_t destination) { + if (dataSet == nullptr) { + /* Configuration error. */ + printWarningOrError(sif::OutputTypes::OUT_WARNING, "generateHousekeepingPacket", + DATASET_NOT_FOUND); + return DATASET_NOT_FOUND; + } - store_address_t storeId; - HousekeepingPacketDownlink hkPacket(sid, dataSet); - size_t serializedSize = 0; - ReturnValue_t result = serializeHkPacketIntoStore(hkPacket, storeId, - forDownlink, &serializedSize); - if(result != HasReturnvaluesIF::RETURN_OK or serializedSize == 0) { - return result; - } + store_address_t storeId; + HousekeepingPacketDownlink hkPacket(sid, dataSet); + size_t serializedSize = 0; + ReturnValue_t result = + serializeHkPacketIntoStore(hkPacket, storeId, forDownlink, &serializedSize); + if (result != HasReturnvaluesIF::RETURN_OK or serializedSize == 0) { + return result; + } - /* Now we set a HK message and send it the HK packet destination. */ - CommandMessage hkMessage; - if(LocalPoolDataSetAttorney::isDiagnostics(*dataSet)) { - HousekeepingMessage::setHkDiagnosticsReply(&hkMessage, sid, storeId); - } - else { - HousekeepingMessage::setHkReportReply(&hkMessage, sid, storeId); - } + /* Now we set a HK message and send it the HK packet destination. */ + CommandMessage hkMessage; + if (LocalPoolDataSetAttorney::isDiagnostics(*dataSet)) { + HousekeepingMessage::setHkDiagnosticsReply(&hkMessage, sid, storeId); + } else { + HousekeepingMessage::setHkReportReply(&hkMessage, sid, storeId); + } - if(hkQueue == nullptr) { - /* Error, no queue available to send packet with. */ - printWarningOrError(sif::OutputTypes::OUT_WARNING, - "generateHousekeepingPacket", - QUEUE_OR_DESTINATION_INVALID); - return QUEUE_OR_DESTINATION_INVALID; - } - if(destination == MessageQueueIF::NO_QUEUE) { - if(hkDestinationId == MessageQueueIF::NO_QUEUE) { - /* Error, all destinations invalid */ - printWarningOrError(sif::OutputTypes::OUT_WARNING, - "generateHousekeepingPacket", - QUEUE_OR_DESTINATION_INVALID); - } - destination = hkDestinationId; + if (hkQueue == nullptr) { + /* Error, no queue available to send packet with. */ + printWarningOrError(sif::OutputTypes::OUT_WARNING, "generateHousekeepingPacket", + QUEUE_OR_DESTINATION_INVALID); + return QUEUE_OR_DESTINATION_INVALID; + } + if (destination == MessageQueueIF::NO_QUEUE) { + if (hkDestinationId == MessageQueueIF::NO_QUEUE) { + /* Error, all destinations invalid */ + printWarningOrError(sif::OutputTypes::OUT_WARNING, "generateHousekeepingPacket", + QUEUE_OR_DESTINATION_INVALID); } + destination = hkDestinationId; + } - return hkQueue->sendMessage(destination, &hkMessage); + return hkQueue->sendMessage(destination, &hkMessage); } -ReturnValue_t LocalDataPoolManager::serializeHkPacketIntoStore( - HousekeepingPacketDownlink& hkPacket, - store_address_t& storeId, bool forDownlink, - size_t* serializedSize) { - uint8_t* dataPtr = nullptr; - const size_t maxSize = hkPacket.getSerializedSize(); - ReturnValue_t result = ipcStore->getFreeElement(&storeId, - maxSize, &dataPtr); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } +ReturnValue_t LocalDataPoolManager::serializeHkPacketIntoStore(HousekeepingPacketDownlink& hkPacket, + store_address_t& storeId, + bool forDownlink, + size_t* serializedSize) { + uint8_t* dataPtr = nullptr; + const size_t maxSize = hkPacket.getSerializedSize(); + ReturnValue_t result = ipcStore->getFreeElement(&storeId, maxSize, &dataPtr); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - if(forDownlink) { - return hkPacket.serialize(&dataPtr, serializedSize, maxSize, - SerializeIF::Endianness::BIG); - } - return hkPacket.serialize(&dataPtr, serializedSize, maxSize, - SerializeIF::Endianness::MACHINE); + if (forDownlink) { + return hkPacket.serialize(&dataPtr, serializedSize, maxSize, SerializeIF::Endianness::BIG); + } + return hkPacket.serialize(&dataPtr, serializedSize, maxSize, SerializeIF::Endianness::MACHINE); } -void LocalDataPoolManager::setNonDiagnosticIntervalFactor( - uint8_t nonDiagInvlFactor) { - this->nonDiagnosticIntervalFactor = nonDiagInvlFactor; +void LocalDataPoolManager::setNonDiagnosticIntervalFactor(uint8_t nonDiagInvlFactor) { + this->nonDiagnosticIntervalFactor = nonDiagInvlFactor; } void LocalDataPoolManager::performPeriodicHkGeneration(HkReceiver& receiver) { - sid_t sid = receiver.dataId.sid; - LocalPoolDataSetBase* dataSet = HasLocalDpIFManagerAttorney::getDataSetHandle(owner, sid); - if(dataSet == nullptr) { - printWarningOrError(sif::OutputTypes::OUT_WARNING, - "performPeriodicHkGeneration", - DATASET_NOT_FOUND); - return; - } + sid_t sid = receiver.dataId.sid; + LocalPoolDataSetBase* dataSet = HasLocalDpIFManagerAttorney::getDataSetHandle(owner, sid); + if (dataSet == nullptr) { + printWarningOrError(sif::OutputTypes::OUT_WARNING, "performPeriodicHkGeneration", + DATASET_NOT_FOUND); + return; + } - if(not LocalPoolDataSetAttorney::getReportingEnabled(*dataSet)) { - return; - } + if (not LocalPoolDataSetAttorney::getReportingEnabled(*dataSet)) { + return; + } - PeriodicHousekeepingHelper* periodicHelper = - LocalPoolDataSetAttorney::getPeriodicHelper(*dataSet); + PeriodicHousekeepingHelper* periodicHelper = + LocalPoolDataSetAttorney::getPeriodicHelper(*dataSet); - if(periodicHelper == nullptr) { - /* Configuration error */ - return; - } + if (periodicHelper == nullptr) { + /* Configuration error */ + return; + } - if(not periodicHelper->checkOpNecessary()) { - return; - } + if (not periodicHelper->checkOpNecessary()) { + return; + } - ReturnValue_t result = generateHousekeepingPacket( - sid, dataSet, true); - if(result != HasReturnvaluesIF::RETURN_OK) { - /* Configuration error */ + ReturnValue_t result = generateHousekeepingPacket(sid, dataSet, true); + if (result != HasReturnvaluesIF::RETURN_OK) { + /* Configuration error */ #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "LocalDataPoolManager::performHkOperation: HK generation failed." << - std::endl; + sif::warning << "LocalDataPoolManager::performHkOperation: HK generation failed." << std::endl; #else - sif::printWarning("LocalDataPoolManager::performHkOperation: HK generation failed.\n"); + sif::printWarning("LocalDataPoolManager::performHkOperation: HK generation failed.\n"); #endif - } + } } +ReturnValue_t LocalDataPoolManager::togglePeriodicGeneration(sid_t sid, bool enable, + bool isDiagnostics) { + LocalPoolDataSetBase* dataSet = HasLocalDpIFManagerAttorney::getDataSetHandle(owner, sid); + if (dataSet == nullptr) { + printWarningOrError(sif::OutputTypes::OUT_WARNING, "togglePeriodicGeneration", + DATASET_NOT_FOUND); + return DATASET_NOT_FOUND; + } -ReturnValue_t LocalDataPoolManager::togglePeriodicGeneration(sid_t sid, - bool enable, bool isDiagnostics) { - LocalPoolDataSetBase* dataSet = HasLocalDpIFManagerAttorney::getDataSetHandle(owner, sid); - if(dataSet == nullptr) { - printWarningOrError(sif::OutputTypes::OUT_WARNING, "togglePeriodicGeneration", - DATASET_NOT_FOUND); - return DATASET_NOT_FOUND; - } + if ((LocalPoolDataSetAttorney::isDiagnostics(*dataSet) and not isDiagnostics) or + (not LocalPoolDataSetAttorney::isDiagnostics(*dataSet) and isDiagnostics)) { + return WRONG_HK_PACKET_TYPE; + } - if((LocalPoolDataSetAttorney::isDiagnostics(*dataSet) and not isDiagnostics) or - (not LocalPoolDataSetAttorney::isDiagnostics(*dataSet) and isDiagnostics)) { - return WRONG_HK_PACKET_TYPE; - } + if ((LocalPoolDataSetAttorney::getReportingEnabled(*dataSet) and enable) or + (not LocalPoolDataSetAttorney::getReportingEnabled(*dataSet) and not enable)) { + return REPORTING_STATUS_UNCHANGED; + } - if((LocalPoolDataSetAttorney::getReportingEnabled(*dataSet) and enable) or - (not LocalPoolDataSetAttorney::getReportingEnabled(*dataSet) and not enable)) { - return REPORTING_STATUS_UNCHANGED; - } - - LocalPoolDataSetAttorney::setReportingEnabled(*dataSet, enable); - return HasReturnvaluesIF::RETURN_OK; + LocalPoolDataSetAttorney::setReportingEnabled(*dataSet, enable); + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t LocalDataPoolManager::changeCollectionInterval(sid_t sid, - float newCollectionInterval, bool isDiagnostics) { - LocalPoolDataSetBase* dataSet = HasLocalDpIFManagerAttorney::getDataSetHandle(owner, sid); - if(dataSet == nullptr) { - printWarningOrError(sif::OutputTypes::OUT_WARNING, "changeCollectionInterval", - DATASET_NOT_FOUND); - return DATASET_NOT_FOUND; - } +ReturnValue_t LocalDataPoolManager::changeCollectionInterval(sid_t sid, float newCollectionInterval, + bool isDiagnostics) { + LocalPoolDataSetBase* dataSet = HasLocalDpIFManagerAttorney::getDataSetHandle(owner, sid); + if (dataSet == nullptr) { + printWarningOrError(sif::OutputTypes::OUT_WARNING, "changeCollectionInterval", + 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; - } + bool targetIsDiagnostics = LocalPoolDataSetAttorney::isDiagnostics(*dataSet); + if ((targetIsDiagnostics and not isDiagnostics) or (not targetIsDiagnostics and isDiagnostics)) { + return WRONG_HK_PACKET_TYPE; + } - PeriodicHousekeepingHelper* periodicHelper = - LocalPoolDataSetAttorney::getPeriodicHelper(*dataSet); + PeriodicHousekeepingHelper* periodicHelper = + LocalPoolDataSetAttorney::getPeriodicHelper(*dataSet); - if(periodicHelper == nullptr) { - /* Configuration error, set might not have a corresponding pool manager */ - return PERIODIC_HELPER_INVALID; - } + if (periodicHelper == nullptr) { + /* Configuration error, set might not have a corresponding pool manager */ + return PERIODIC_HELPER_INVALID; + } - periodicHelper->changeCollectionInterval(newCollectionInterval); - return HasReturnvaluesIF::RETURN_OK; + periodicHelper->changeCollectionInterval(newCollectionInterval); + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t LocalDataPoolManager::generateSetStructurePacket(sid_t sid, - bool isDiagnostics) { - /* Get and check dataset first. */ - LocalPoolDataSetBase* dataSet = HasLocalDpIFManagerAttorney::getDataSetHandle(owner, sid); - if(dataSet == nullptr) { - printWarningOrError(sif::OutputTypes::OUT_WARNING, - "performPeriodicHkGeneration", DATASET_NOT_FOUND); - return DATASET_NOT_FOUND; - } +ReturnValue_t LocalDataPoolManager::generateSetStructurePacket(sid_t sid, bool isDiagnostics) { + /* Get and check dataset first. */ + LocalPoolDataSetBase* dataSet = HasLocalDpIFManagerAttorney::getDataSetHandle(owner, sid); + if (dataSet == nullptr) { + printWarningOrError(sif::OutputTypes::OUT_WARNING, "performPeriodicHkGeneration", + 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; + } - bool targetIsDiagnostics = LocalPoolDataSetAttorney::isDiagnostics(*dataSet); - if((targetIsDiagnostics and not isDiagnostics) or - (not targetIsDiagnostics and isDiagnostics)) { - return WRONG_HK_PACKET_TYPE; - } + bool valid = dataSet->isValid(); + bool reportingEnabled = LocalPoolDataSetAttorney::getReportingEnabled(*dataSet); + float collectionInterval = + LocalPoolDataSetAttorney::getPeriodicHelper(*dataSet)->getCollectionIntervalInSeconds(); - bool valid = dataSet->isValid(); - bool reportingEnabled = LocalPoolDataSetAttorney::getReportingEnabled(*dataSet); - float collectionInterval = LocalPoolDataSetAttorney::getPeriodicHelper(*dataSet)-> - getCollectionIntervalInSeconds(); - - // Generate set packet which can be serialized. - HousekeepingSetPacket setPacket(sid, - reportingEnabled, valid, collectionInterval, dataSet); - size_t expectedSize = setPacket.getSerializedSize(); - uint8_t* storePtr = nullptr; - store_address_t storeId; - ReturnValue_t result = ipcStore->getFreeElement(&storeId, - expectedSize,&storePtr); - if(result != HasReturnvaluesIF::RETURN_OK) { - printWarningOrError(sif::OutputTypes::OUT_ERROR, - "generateSetStructurePacket", HasReturnvaluesIF::RETURN_FAILED, - "Could not get free element from IPC store."); - return result; - } - - // Serialize set packet into store. - size_t size = 0; - result = setPacket.serialize(&storePtr, &size, expectedSize, - SerializeIF::Endianness::BIG); - if(expectedSize != size) { - printWarningOrError(sif::OutputTypes::OUT_WARNING, - "generateSetStructurePacket", HasReturnvaluesIF::RETURN_FAILED, - "Expected size is not equal to serialized size"); - } - - // Send structure reporting reply. - CommandMessage reply; - if(isDiagnostics) { - HousekeepingMessage::setDiagnosticsStuctureReportReply(&reply, - sid, storeId); - } - else { - HousekeepingMessage::setHkStuctureReportReply(&reply, - sid, storeId); - } - - hkQueue->reply(&reply); + // Generate set packet which can be serialized. + HousekeepingSetPacket setPacket(sid, reportingEnabled, valid, collectionInterval, dataSet); + size_t expectedSize = setPacket.getSerializedSize(); + uint8_t* storePtr = nullptr; + store_address_t storeId; + ReturnValue_t result = ipcStore->getFreeElement(&storeId, expectedSize, &storePtr); + if (result != HasReturnvaluesIF::RETURN_OK) { + printWarningOrError(sif::OutputTypes::OUT_ERROR, "generateSetStructurePacket", + HasReturnvaluesIF::RETURN_FAILED, + "Could not get free element from IPC store."); return result; + } + + // Serialize set packet into store. + size_t size = 0; + result = setPacket.serialize(&storePtr, &size, expectedSize, SerializeIF::Endianness::BIG); + if (expectedSize != size) { + printWarningOrError(sif::OutputTypes::OUT_WARNING, "generateSetStructurePacket", + HasReturnvaluesIF::RETURN_FAILED, + "Expected size is not equal to serialized size"); + } + + // Send structure reporting reply. + CommandMessage reply; + if (isDiagnostics) { + HousekeepingMessage::setDiagnosticsStuctureReportReply(&reply, sid, storeId); + } else { + HousekeepingMessage::setHkStuctureReportReply(&reply, sid, storeId); + } + + hkQueue->reply(&reply); + return result; } void LocalDataPoolManager::clearReceiversList() { - /* Clear the vector completely and releases allocated memory. */ - HkReceivers().swap(hkReceivers); - /* Also clear the reset helper if it exists */ - if(hkUpdateResetList != nullptr) { - HkUpdateResetList().swap(*hkUpdateResetList); - } + /* Clear the vector completely and releases allocated memory. */ + HkReceivers().swap(hkReceivers); + /* Also clear the reset helper if it exists */ + if (hkUpdateResetList != nullptr) { + HkUpdateResetList().swap(*hkUpdateResetList); + } } -MutexIF* LocalDataPoolManager::getLocalPoolMutex() { - return this->mutex; -} +MutexIF* LocalDataPoolManager::getLocalPoolMutex() { return this->mutex; } -object_id_t LocalDataPoolManager::getCreatorObjectId() const { - return owner->getObjectId(); -} +object_id_t LocalDataPoolManager::getCreatorObjectId() const { return owner->getObjectId(); } void LocalDataPoolManager::printWarningOrError(sif::OutputTypes outputType, - const char* functionName, ReturnValue_t error, const char* errorPrint) { + const char* functionName, ReturnValue_t error, + const char* errorPrint) { #if FSFW_VERBOSE_LEVEL >= 1 - if(errorPrint == nullptr) { - if(error == DATASET_NOT_FOUND) { - errorPrint = "Dataset not found"; - } - else if(error == POOLOBJECT_NOT_FOUND) { - errorPrint = "Pool Object not found"; - } - else if(error == HasReturnvaluesIF::RETURN_FAILED) { - if(outputType == sif::OutputTypes::OUT_WARNING) { - errorPrint = "Generic Warning"; - } - else { - errorPrint = "Generic error"; - } - } - else if(error == QUEUE_OR_DESTINATION_INVALID) { - errorPrint = "Queue or destination not set"; - } - else if(error == localpool::POOL_ENTRY_TYPE_CONFLICT) { - errorPrint = "Pool entry type conflict"; - } - else if(error == localpool::POOL_ENTRY_NOT_FOUND) { - errorPrint = "Pool entry not found"; - } - else { - errorPrint = "Unknown error"; - } - } - object_id_t objectId = 0xffffffff; - if(owner != nullptr) { - objectId = owner->getObjectId(); + if (errorPrint == nullptr) { + if (error == DATASET_NOT_FOUND) { + errorPrint = "Dataset not found"; + } else if (error == POOLOBJECT_NOT_FOUND) { + errorPrint = "Pool Object not found"; + } else if (error == HasReturnvaluesIF::RETURN_FAILED) { + if (outputType == sif::OutputTypes::OUT_WARNING) { + errorPrint = "Generic Warning"; + } else { + errorPrint = "Generic error"; + } + } else if (error == QUEUE_OR_DESTINATION_INVALID) { + errorPrint = "Queue or destination not set"; + } else if (error == localpool::POOL_ENTRY_TYPE_CONFLICT) { + errorPrint = "Pool entry type conflict"; + } else if (error == localpool::POOL_ENTRY_NOT_FOUND) { + errorPrint = "Pool entry not found"; + } else { + errorPrint = "Unknown error"; } + } + object_id_t objectId = 0xffffffff; + if (owner != nullptr) { + objectId = owner->getObjectId(); + } - if(outputType == sif::OutputTypes::OUT_WARNING) { + if (outputType == sif::OutputTypes::OUT_WARNING) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "LocalDataPoolManager::" << functionName << ": Object ID 0x" << - std::setw(8) << std::setfill('0') << std::hex << objectId << " | " << errorPrint << - std::dec << std::setfill(' ') << std::endl; + sif::warning << "LocalDataPoolManager::" << functionName << ": Object ID 0x" << std::setw(8) + << std::setfill('0') << std::hex << objectId << " | " << errorPrint << std::dec + << std::setfill(' ') << std::endl; #else - sif::printWarning("LocalDataPoolManager::%s: Object ID 0x%08x | %s\n", - functionName, objectId, errorPrint); + sif::printWarning("LocalDataPoolManager::%s: Object ID 0x%08x | %s\n", functionName, objectId, + errorPrint); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ - } - else if(outputType == sif::OutputTypes::OUT_ERROR) { + } else if (outputType == sif::OutputTypes::OUT_ERROR) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "LocalDataPoolManager::" << functionName << ": Object ID 0x" << - std::setw(8) << std::setfill('0') << std::hex << objectId << " | " << errorPrint << - std::dec << std::setfill(' ') << std::endl; + sif::error << "LocalDataPoolManager::" << functionName << ": Object ID 0x" << std::setw(8) + << std::setfill('0') << std::hex << objectId << " | " << errorPrint << std::dec + << std::setfill(' ') << std::endl; #else - sif::printError("LocalDataPoolManager::%s: Object ID 0x%08x | %s\n", - functionName, objectId, errorPrint); + sif::printError("LocalDataPoolManager::%s: Object ID 0x%08x | %s\n", functionName, objectId, + errorPrint); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ - } + } #endif /* #if FSFW_VERBOSE_LEVEL >= 1 */ } -LocalDataPoolManager* LocalDataPoolManager::getPoolManagerHandle() { - return this; -} +LocalDataPoolManager* LocalDataPoolManager::getPoolManagerHandle() { return this; } diff --git a/src/fsfw/datapoollocal/LocalDataPoolManager.h b/src/fsfw/datapoollocal/LocalDataPoolManager.h index 9f91613b..e7ec0b6f 100644 --- a/src/fsfw/datapoollocal/LocalDataPoolManager.h +++ b/src/fsfw/datapoollocal/LocalDataPoolManager.h @@ -1,23 +1,22 @@ #ifndef FSFW_DATAPOOLLOCAL_LOCALDATAPOOLMANAGER_H_ #define FSFW_DATAPOOLLOCAL_LOCALDATAPOOLMANAGER_H_ -#include "ProvidesDataPoolSubscriptionIF.h" -#include "AccessLocalPoolF.h" +#include +#include -#include "fsfw/serviceinterface/ServiceInterface.h" -#include "fsfw/housekeeping/HousekeepingPacketDownlink.h" -#include "fsfw/housekeeping/HousekeepingMessage.h" -#include "fsfw/housekeeping/PeriodicHousekeepingHelper.h" +#include "AccessLocalPoolF.h" +#include "ProvidesDataPoolSubscriptionIF.h" #include "fsfw/datapool/DataSetIF.h" #include "fsfw/datapool/PoolEntry.h" -#include "fsfw/objectmanager/SystemObjectIF.h" -#include "fsfw/ipc/MutexIF.h" +#include "fsfw/housekeeping/HousekeepingMessage.h" +#include "fsfw/housekeeping/HousekeepingPacketDownlink.h" +#include "fsfw/housekeeping/PeriodicHousekeepingHelper.h" #include "fsfw/ipc/CommandMessage.h" #include "fsfw/ipc/MessageQueueIF.h" #include "fsfw/ipc/MutexGuard.h" - -#include -#include +#include "fsfw/ipc/MutexIF.h" +#include "fsfw/objectmanager/SystemObjectIF.h" +#include "fsfw/serviceinterface/ServiceInterface.h" namespace Factory { void setStaticFrameworkObjectIds(); @@ -52,364 +51,356 @@ class LocalDataPool; * Each pool entry has a valid state too. * @author R. Mueller */ -class LocalDataPoolManager: - public ProvidesDataPoolSubscriptionIF, - public AccessPoolManagerIF { - friend void (Factory::setStaticFrameworkObjectIds)(); - //! Some classes using the pool manager directly need to access class internals of the - //! manager. The attorney provides granular control of access to these internals. - friend class LocalDpManagerAttorney; -public: - static constexpr uint8_t INTERFACE_ID = CLASS_ID::HOUSEKEEPING_MANAGER; +class LocalDataPoolManager : public ProvidesDataPoolSubscriptionIF, public AccessPoolManagerIF { + friend void(Factory::setStaticFrameworkObjectIds)(); + //! Some classes using the pool manager directly need to access class internals of the + //! manager. The attorney provides granular control of access to these internals. + friend class LocalDpManagerAttorney; - static constexpr ReturnValue_t QUEUE_OR_DESTINATION_INVALID = MAKE_RETURN_CODE(0); - static constexpr ReturnValue_t WRONG_HK_PACKET_TYPE = MAKE_RETURN_CODE(1); - static constexpr ReturnValue_t REPORTING_STATUS_UNCHANGED = MAKE_RETURN_CODE(2); - static constexpr ReturnValue_t PERIODIC_HELPER_INVALID = MAKE_RETURN_CODE(3); - static constexpr ReturnValue_t POOLOBJECT_NOT_FOUND = MAKE_RETURN_CODE(4); - static constexpr ReturnValue_t DATASET_NOT_FOUND = MAKE_RETURN_CODE(5); + public: + static constexpr uint8_t INTERFACE_ID = CLASS_ID::HOUSEKEEPING_MANAGER; + static constexpr ReturnValue_t QUEUE_OR_DESTINATION_INVALID = MAKE_RETURN_CODE(0); + static constexpr ReturnValue_t WRONG_HK_PACKET_TYPE = MAKE_RETURN_CODE(1); + static constexpr ReturnValue_t REPORTING_STATUS_UNCHANGED = MAKE_RETURN_CODE(2); + static constexpr ReturnValue_t PERIODIC_HELPER_INVALID = MAKE_RETURN_CODE(3); + static constexpr ReturnValue_t POOLOBJECT_NOT_FOUND = MAKE_RETURN_CODE(4); + static constexpr ReturnValue_t DATASET_NOT_FOUND = MAKE_RETURN_CODE(5); - /** - * This constructor is used by a class which wants to implement - * a personal local data pool. The queueToUse can be supplied if it - * is already known. - * - * initialize() has to be called in any case before using the object! - * @param owner - * @param queueToUse - * @param appendValidityBuffer Specify whether a buffer containing the - * validity state is generated when serializing or deserializing packets. - */ - LocalDataPoolManager(HasLocalDataPoolIF* owner, MessageQueueIF* queueToUse, - bool appendValidityBuffer = true); - virtual~ LocalDataPoolManager(); + /** + * This constructor is used by a class which wants to implement + * a personal local data pool. The queueToUse can be supplied if it + * is already known. + * + * initialize() has to be called in any case before using the object! + * @param owner + * @param queueToUse + * @param appendValidityBuffer Specify whether a buffer containing the + * validity state is generated when serializing or deserializing packets. + */ + LocalDataPoolManager(HasLocalDataPoolIF* owner, MessageQueueIF* queueToUse, + bool appendValidityBuffer = true); + virtual ~LocalDataPoolManager(); - /** - * Assigns the queue to use. Make sure to call this in the #initialize - * function of the owner. - * @param queueToUse - * @param nonDiagInvlFactor See #setNonDiagnosticIntervalFactor doc - * @return - */ - ReturnValue_t initialize(MessageQueueIF* queueToUse); + /** + * Assigns the queue to use. Make sure to call this in the #initialize + * function of the owner. + * @param queueToUse + * @param nonDiagInvlFactor See #setNonDiagnosticIntervalFactor doc + * @return + */ + ReturnValue_t initialize(MessageQueueIF* queueToUse); - /** - * Initializes the map by calling the map initialization function and - * setting the periodic factor for non-diagnostic packets. - * Don't forget to call this in the #initializeAfterTaskCreation call of - * the owner, otherwise the map will be invalid! - * @param nonDiagInvlFactor - * @return - */ - ReturnValue_t initializeAfterTaskCreation( - uint8_t nonDiagInvlFactor = 5); + /** + * Initializes the map by calling the map initialization function and + * setting the periodic factor for non-diagnostic packets. + * Don't forget to call this in the #initializeAfterTaskCreation call of + * the owner, otherwise the map will be invalid! + * @param nonDiagInvlFactor + * @return + */ + ReturnValue_t initializeAfterTaskCreation(uint8_t nonDiagInvlFactor = 5); - /** - * @brief This should be called in the periodic handler of the owner. - * @details - * This in generally called in the #performOperation function of the owner. - * It performs all the periodic functionalities of the data pool manager, - * for example generating periodic HK packets. - * Marked virtual as an adaption point for custom data pool managers. - * @return - */ - virtual ReturnValue_t performHkOperation(); + /** + * @brief This should be called in the periodic handler of the owner. + * @details + * This in generally called in the #performOperation function of the owner. + * It performs all the periodic functionalities of the data pool manager, + * for example generating periodic HK packets. + * Marked virtual as an adaption point for custom data pool managers. + * @return + */ + virtual ReturnValue_t performHkOperation(); - /** - * @brief Subscribe for the generation of periodic packets. - * @details - * This subscription mechanism will generally be used by the data creator - * to generate housekeeping packets which are downlinked directly. - * @return - */ - ReturnValue_t subscribeForPeriodicPacket(sid_t sid, bool enableReporting, - float collectionInterval, bool isDiagnostics, - object_id_t packetDestination = defaultHkDestination) override; + /** + * @brief Subscribe for the generation of periodic packets. + * @details + * This subscription mechanism will generally be used by the data creator + * to generate housekeeping packets which are downlinked directly. + * @return + */ + ReturnValue_t subscribeForPeriodicPacket( + sid_t sid, bool enableReporting, float collectionInterval, bool isDiagnostics, + object_id_t packetDestination = defaultHkDestination) override; - /** - * @brief Subscribe for the generation of packets if the dataset - * is marked as changed. - * @details - * This subscription mechanism will generally be used by the data creator. - * @param sid - * @param isDiagnostics - * @param packetDestination - * @return - */ - ReturnValue_t subscribeForUpdatePacket(sid_t sid, bool reportingEnabled, - bool isDiagnostics, - object_id_t packetDestination = defaultHkDestination) override; + /** + * @brief Subscribe for the generation of packets if the dataset + * is marked as changed. + * @details + * This subscription mechanism will generally be used by the data creator. + * @param sid + * @param isDiagnostics + * @param packetDestination + * @return + */ + ReturnValue_t subscribeForUpdatePacket( + sid_t sid, bool reportingEnabled, bool isDiagnostics, + object_id_t packetDestination = defaultHkDestination) override; - /** - * @brief Subscribe for a notification message which will be sent - * if a dataset has changed. - * @details - * This subscription mechanism will generally be used internally by - * other software components. - * @param setId Set ID of the set to receive update messages from. - * @param destinationObject - * @param targetQueueId - * @param generateSnapshot If this is set to true, a copy of the current - * data with a timestamp will be generated and sent via message. - * Otherwise, only an notification message is sent. - * @return - */ - ReturnValue_t subscribeForSetUpdateMessage(const uint32_t setId, - object_id_t destinationObject, - MessageQueueId_t targetQueueId, - bool generateSnapshot) override; + /** + * @brief Subscribe for a notification message which will be sent + * if a dataset has changed. + * @details + * This subscription mechanism will generally be used internally by + * other software components. + * @param setId Set ID of the set to receive update messages from. + * @param destinationObject + * @param targetQueueId + * @param generateSnapshot If this is set to true, a copy of the current + * data with a timestamp will be generated and sent via message. + * Otherwise, only an notification message is sent. + * @return + */ + ReturnValue_t subscribeForSetUpdateMessage(const uint32_t setId, object_id_t destinationObject, + MessageQueueId_t targetQueueId, + bool generateSnapshot) override; - /** - * @brief Subscribe for an notification message which will be sent if a - * pool variable has changed. - * @details - * This subscription mechanism will generally be used internally by - * other software components. - * @param localPoolId Pool ID of the pool variable - * @param destinationObject - * @param targetQueueId - * @param generateSnapshot If this is set to true, a copy of the current - * data with a timestamp will be generated and sent via message. - * Otherwise, only an notification message is sent. - * @return - */ - ReturnValue_t subscribeForVariableUpdateMessage(const lp_id_t localPoolId, - object_id_t destinationObject, - MessageQueueId_t targetQueueId, - bool generateSnapshot) override; + /** + * @brief Subscribe for an notification message which will be sent if a + * pool variable has changed. + * @details + * This subscription mechanism will generally be used internally by + * other software components. + * @param localPoolId Pool ID of the pool variable + * @param destinationObject + * @param targetQueueId + * @param generateSnapshot If this is set to true, a copy of the current + * data with a timestamp will be generated and sent via message. + * Otherwise, only an notification message is sent. + * @return + */ + ReturnValue_t subscribeForVariableUpdateMessage(const lp_id_t localPoolId, + object_id_t destinationObject, + MessageQueueId_t targetQueueId, + 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); + /** + * 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. - * @details - * This most commonly is used to handle messages for the housekeeping - * interface, but the manager is also able to handle update notifications - * and calls a special function which can be overriden by a child class - * to handle data set or pool variable updates. This is relevant - * for classes like controllers which have their own local datapool - * but pull their data from other local datapools. - * @param message - * @return - */ - virtual ReturnValue_t handleHousekeepingMessage(CommandMessage* message); + /** + * @brief The manager is also able to handle housekeeping messages. + * @details + * This most commonly is used to handle messages for the housekeeping + * interface, but the manager is also able to handle update notifications + * and calls a special function which can be overriden by a child class + * to handle data set or pool variable updates. This is relevant + * for classes like controllers which have their own local datapool + * but pull their data from other local datapools. + * @param message + * @return + */ + virtual ReturnValue_t handleHousekeepingMessage(CommandMessage* message); - /** - * Generate a housekeeping packet with a given SID. - * @param sid - * @return - */ - ReturnValue_t generateHousekeepingPacket(sid_t sid, - LocalPoolDataSetBase* dataSet, bool forDownlink, - MessageQueueId_t destination = MessageQueueIF::NO_QUEUE); + /** + * Generate a housekeeping packet with a given SID. + * @param sid + * @return + */ + ReturnValue_t generateHousekeepingPacket(sid_t sid, LocalPoolDataSetBase* dataSet, + bool forDownlink, + MessageQueueId_t destination = MessageQueueIF::NO_QUEUE); - HasLocalDataPoolIF* getOwner(); + HasLocalDataPoolIF* getOwner(); - ReturnValue_t printPoolEntry(lp_id_t localPoolId); + ReturnValue_t printPoolEntry(lp_id_t localPoolId); - /** - * Different types of housekeeping reporting are possible. - * 1. PERIODIC: - * HK packets are generated in fixed intervals and sent to - * destination. Fromat will be raw. - * 2. UPDATE_NOTIFICATION: - * Notification will be sent out if HK data has changed. - * 3. UPDATE_SNAPSHOT: - * HK packets are only generated if explicitely requested. - * Propably not necessary, just use multiple local data sets or - * shared datasets. - */ - enum class ReportingType: uint8_t { - //! Periodic generation of HK packets. - PERIODIC, - //! Housekeeping packet will be generated if values have changed. - UPDATE_HK, - //! Update notification will be sent out as message. - UPDATE_NOTIFICATION, - //! Notification will be sent out as message and a snapshot of the - //! current data will be generated. - UPDATE_SNAPSHOT, - }; + /** + * Different types of housekeeping reporting are possible. + * 1. PERIODIC: + * HK packets are generated in fixed intervals and sent to + * destination. Fromat will be raw. + * 2. UPDATE_NOTIFICATION: + * Notification will be sent out if HK data has changed. + * 3. UPDATE_SNAPSHOT: + * HK packets are only generated if explicitely requested. + * Propably not necessary, just use multiple local data sets or + * shared datasets. + */ + enum class ReportingType : uint8_t { + //! Periodic generation of HK packets. + PERIODIC, + //! Housekeeping packet will be generated if values have changed. + UPDATE_HK, + //! Update notification will be sent out as message. + UPDATE_NOTIFICATION, + //! Notification will be sent out as message and a snapshot of the + //! current data will be generated. + UPDATE_SNAPSHOT, + }; - /** Different data types are possible in the HK receiver map. For example, updates can be - requested for full datasets or for single pool variables. Periodic reporting is only possible - for data sets. */ - enum class DataType: uint8_t { - LOCAL_POOL_VARIABLE, - DATA_SET - }; + /** Different data types are possible in the HK receiver map. For example, updates can be + requested for full datasets or for single pool variables. Periodic reporting is only possible + for data sets. */ + enum class DataType : uint8_t { LOCAL_POOL_VARIABLE, DATA_SET }; - /* Copying forbidden */ - LocalDataPoolManager(const LocalDataPoolManager &) = delete; - LocalDataPoolManager operator=(const LocalDataPoolManager&) = delete; + /* Copying forbidden */ + LocalDataPoolManager(const LocalDataPoolManager&) = delete; + LocalDataPoolManager operator=(const LocalDataPoolManager&) = delete; - /** - * This function can be used to clear the receivers list. This is - * intended for test functions and not for regular operations, because - * the insertion operations allocate dynamically. - */ - void clearReceiversList(); + /** + * This function can be used to clear the receivers list. This is + * intended for test functions and not for regular operations, because + * the insertion operations allocate dynamically. + */ + void clearReceiversList(); - object_id_t getCreatorObjectId() const; + object_id_t getCreatorObjectId() const; - /** - * Get the pointer to the mutex. Can be used to lock the data pool - * externally. Use with care and don't forget to unlock locked mutexes! - * For now, only friend classes can accss this function. - * @return - */ - MutexIF* getMutexHandle(); + /** + * Get the pointer to the mutex. Can be used to lock the data pool + * externally. Use with care and don't forget to unlock locked mutexes! + * For now, only friend classes can accss this function. + * @return + */ + MutexIF* getMutexHandle(); - virtual LocalDataPoolManager* getPoolManagerHandle() override; + virtual LocalDataPoolManager* getPoolManagerHandle() override; -protected: + protected: + /** Core data structure for the actual pool data */ + localpool::DataPool localPoolMap; + /** Every housekeeping data manager has a mutex to protect access + to it's data pool. */ + MutexIF* mutex = nullptr; - /** Core data structure for the actual pool data */ - localpool::DataPool localPoolMap; - /** Every housekeeping data manager has a mutex to protect access - to it's data pool. */ - MutexIF* mutex = nullptr; + /** The class which actually owns the manager (and its datapool). */ + HasLocalDataPoolIF* owner = nullptr; - /** The class which actually owns the manager (and its datapool). */ - HasLocalDataPoolIF* owner = nullptr; + uint8_t nonDiagnosticIntervalFactor = 0; - uint8_t nonDiagnosticIntervalFactor = 0; + /** Default receiver for periodic HK packets */ + static object_id_t defaultHkDestination; + MessageQueueId_t hkDestinationId = MessageQueueIF::NO_QUEUE; - /** Default receiver for periodic HK packets */ - static object_id_t defaultHkDestination; - MessageQueueId_t hkDestinationId = MessageQueueIF::NO_QUEUE; + union DataId { + DataId() : sid(){}; + sid_t sid; + lp_id_t localPoolId; + }; - union DataId { - DataId(): sid() {}; - sid_t sid; - lp_id_t localPoolId; - }; + /** The data pool manager will keep an internal map of HK receivers. */ + struct HkReceiver { + /** Object ID of receiver */ + object_id_t objectId = objects::NO_OBJECT; - /** The data pool manager will keep an internal map of HK receivers. */ - struct HkReceiver { - /** Object ID of receiver */ - object_id_t objectId = objects::NO_OBJECT; + DataType dataType = DataType::DATA_SET; + DataId dataId; - DataType dataType = DataType::DATA_SET; - DataId dataId; + ReportingType reportingType = ReportingType::PERIODIC; + MessageQueueId_t destinationQueue = MessageQueueIF::NO_QUEUE; + }; - ReportingType reportingType = ReportingType::PERIODIC; - MessageQueueId_t destinationQueue = MessageQueueIF::NO_QUEUE; - }; + /** This vector will contain the list of HK receivers. */ + using HkReceivers = std::vector; - /** This vector will contain the list of HK receivers. */ - using HkReceivers = std::vector; + HkReceivers hkReceivers; - HkReceivers hkReceivers; + struct HkUpdateResetHelper { + DataType dataType = DataType::DATA_SET; + DataId dataId; + uint8_t updateCounter; + uint8_t currentUpdateCounter; + }; - struct HkUpdateResetHelper { - DataType dataType = DataType::DATA_SET; - DataId dataId; - uint8_t updateCounter; - uint8_t currentUpdateCounter; - }; + using HkUpdateResetList = std::vector; + /** This list is used to manage creating multiple update packets and only resetting + the update flag if all of them were created. Will only be created when needed. */ + HkUpdateResetList* hkUpdateResetList = nullptr; - using HkUpdateResetList = std::vector; - /** This list is used to manage creating multiple update packets and only resetting - the update flag if all of them were created. Will only be created when needed. */ - HkUpdateResetList* hkUpdateResetList = nullptr; + /** This is the map holding the actual data. Should only be initialized + * once ! */ + bool mapInitialized = false; + /** This specifies whether a validity buffer is appended at the end + * of generated housekeeping packets. */ + bool appendValidityBuffer = true; - /** This is the map holding the actual data. Should only be initialized - * once ! */ - bool mapInitialized = false; - /** This specifies whether a validity buffer is appended at the end - * of generated housekeeping packets. */ - bool appendValidityBuffer = true; + /** + * @brief Queue used for communication, for example commands. + * Is also used to send messages. Can be set either in the constructor + * or in the initialize() function. + */ + MessageQueueIF* hkQueue = nullptr; - /** - * @brief Queue used for communication, for example commands. - * Is also used to send messages. Can be set either in the constructor - * or in the initialize() function. - */ - MessageQueueIF* hkQueue = nullptr; + /** Global IPC store is used to store all packets. */ + StorageManagerIF* ipcStore = nullptr; - /** Global IPC store is used to store all packets. */ - StorageManagerIF* ipcStore = nullptr; + /** + * Read a variable by supplying its local pool ID and assign the pool + * entry to the supplied PoolEntry pointer. The type of the pool entry + * is deduced automatically. This call is not thread-safe! + * For now, only classes designated by the LocalDpManagerAttorney may use this function. + * @tparam T Type of the pool entry + * @param localPoolId Pool ID of the variable to read + * @param poolVar [out] Corresponding pool entry will be assigned to the + * supplied pointer. + * @return + */ + template + ReturnValue_t fetchPoolEntry(lp_id_t localPoolId, PoolEntry** poolEntry); - /** - * Read a variable by supplying its local pool ID and assign the pool - * entry to the supplied PoolEntry pointer. The type of the pool entry - * is deduced automatically. This call is not thread-safe! - * For now, only classes designated by the LocalDpManagerAttorney may use this function. - * @tparam T Type of the pool entry - * @param localPoolId Pool ID of the variable to read - * @param poolVar [out] Corresponding pool entry will be assigned to the - * supplied pointer. - * @return - */ - template ReturnValue_t fetchPoolEntry(lp_id_t localPoolId, PoolEntry **poolEntry); + /** + * This function is used to fill the local data pool map with pool + * entries. It should only be called once by the pool owner. + * @param localDataPoolMap + * @return + */ + ReturnValue_t initializeHousekeepingPoolEntriesOnce(); - /** - * This function is used to fill the local data pool map with pool - * entries. It should only be called once by the pool owner. - * @param localDataPoolMap - * @return - */ - ReturnValue_t initializeHousekeepingPoolEntriesOnce(); + MutexIF* getLocalPoolMutex() override; - MutexIF* getLocalPoolMutex() override; + ReturnValue_t serializeHkPacketIntoStore(HousekeepingPacketDownlink& hkPacket, + store_address_t& storeId, bool forDownlink, + size_t* serializedSize); - ReturnValue_t serializeHkPacketIntoStore(HousekeepingPacketDownlink& hkPacket, - store_address_t& storeId, bool forDownlink, size_t* serializedSize); + void performPeriodicHkGeneration(HkReceiver& hkReceiver); + 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); - void performPeriodicHkGeneration(HkReceiver& hkReceiver); - 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); + void handleHkUpdateResetListInsertion(DataType dataType, DataId dataId); + void handleChangeResetLogic(DataType type, DataId dataId, MarkChangedIF* toReset); + void resetHkUpdateResetHelper(); - void handleHkUpdateResetListInsertion(DataType dataType, DataId dataId); - void handleChangeResetLogic(DataType type, - DataId dataId, MarkChangedIF* toReset); - void resetHkUpdateResetHelper(); + ReturnValue_t handleHkUpdate(HkReceiver& hkReceiver, ReturnValue_t& status); + ReturnValue_t handleNotificationUpdate(HkReceiver& hkReceiver, ReturnValue_t& status); + ReturnValue_t handleNotificationSnapshot(HkReceiver& hkReceiver, ReturnValue_t& status); + ReturnValue_t addUpdateToStore(HousekeepingSnapshot& updatePacket, store_address_t& storeId); - ReturnValue_t handleHkUpdate(HkReceiver& hkReceiver, ReturnValue_t& status); - ReturnValue_t handleNotificationUpdate(HkReceiver& hkReceiver, ReturnValue_t& status); - ReturnValue_t handleNotificationSnapshot(HkReceiver& hkReceiver, ReturnValue_t& status); - ReturnValue_t addUpdateToStore(HousekeepingSnapshot& updatePacket, store_address_t& storeId); - - void printWarningOrError(sif::OutputTypes outputType, const char* functionName, - ReturnValue_t errorCode = HasReturnvaluesIF::RETURN_FAILED, - const char* errorPrint = nullptr); + void printWarningOrError(sif::OutputTypes outputType, const char* functionName, + ReturnValue_t errorCode = HasReturnvaluesIF::RETURN_FAILED, + const char* errorPrint = nullptr); }; +template +inline ReturnValue_t LocalDataPoolManager::fetchPoolEntry(lp_id_t localPoolId, + PoolEntry** poolEntry) { + if (poolEntry == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } -template inline -ReturnValue_t LocalDataPoolManager::fetchPoolEntry(lp_id_t localPoolId, PoolEntry **poolEntry) { - if(poolEntry == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } + auto poolIter = localPoolMap.find(localPoolId); + if (poolIter == localPoolMap.end()) { + printWarningOrError(sif::OutputTypes::OUT_WARNING, "fetchPoolEntry", + localpool::POOL_ENTRY_NOT_FOUND); + return localpool::POOL_ENTRY_NOT_FOUND; + } - auto poolIter = localPoolMap.find(localPoolId); - if (poolIter == localPoolMap.end()) { - printWarningOrError(sif::OutputTypes::OUT_WARNING, "fetchPoolEntry", - localpool::POOL_ENTRY_NOT_FOUND); - return localpool::POOL_ENTRY_NOT_FOUND; - } - - *poolEntry = dynamic_cast< PoolEntry* >(poolIter->second); - if(*poolEntry == nullptr) { - printWarningOrError(sif::OutputTypes::OUT_WARNING, "fetchPoolEntry", - localpool::POOL_ENTRY_TYPE_CONFLICT); - return localpool::POOL_ENTRY_TYPE_CONFLICT; - } - return HasReturnvaluesIF::RETURN_OK; + *poolEntry = dynamic_cast*>(poolIter->second); + if (*poolEntry == nullptr) { + printWarningOrError(sif::OutputTypes::OUT_WARNING, "fetchPoolEntry", + localpool::POOL_ENTRY_TYPE_CONFLICT); + return localpool::POOL_ENTRY_TYPE_CONFLICT; + } + return HasReturnvaluesIF::RETURN_OK; } - #endif /* FSFW_DATAPOOLLOCAL_LOCALDATAPOOLMANAGER_H_ */ diff --git a/src/fsfw/datapoollocal/LocalDataSet.cpp b/src/fsfw/datapoollocal/LocalDataSet.cpp index 260f8500..2908ce51 100644 --- a/src/fsfw/datapoollocal/LocalDataSet.cpp +++ b/src/fsfw/datapoollocal/LocalDataSet.cpp @@ -1,23 +1,21 @@ #include "fsfw/datapoollocal/LocalDataSet.h" -#include "fsfw/datapoollocal/LocalDataPoolManager.h" - -#include "fsfw/serialize/SerializeAdapter.h" #include #include +#include "fsfw/datapoollocal/LocalDataPoolManager.h" +#include "fsfw/serialize/SerializeAdapter.h" + LocalDataSet::LocalDataSet(HasLocalDataPoolIF *hkOwner, uint32_t setId, - const size_t maxNumberOfVariables): - LocalPoolDataSetBase(hkOwner, setId, nullptr, maxNumberOfVariables), - poolVarList(maxNumberOfVariables) { - this->setContainer(poolVarList.data()); + const size_t maxNumberOfVariables) + : LocalPoolDataSetBase(hkOwner, setId, nullptr, maxNumberOfVariables), + poolVarList(maxNumberOfVariables) { + this->setContainer(poolVarList.data()); } -LocalDataSet::LocalDataSet(sid_t sid, const size_t maxNumberOfVariables): - LocalPoolDataSetBase(sid, nullptr, maxNumberOfVariables), - poolVarList(maxNumberOfVariables) { - this->setContainer(poolVarList.data()); +LocalDataSet::LocalDataSet(sid_t sid, const size_t maxNumberOfVariables) + : LocalPoolDataSetBase(sid, nullptr, maxNumberOfVariables), poolVarList(maxNumberOfVariables) { + this->setContainer(poolVarList.data()); } LocalDataSet::~LocalDataSet() {} - diff --git a/src/fsfw/datapoollocal/LocalDataSet.h b/src/fsfw/datapoollocal/LocalDataSet.h index 92bad9b5..f369cb2c 100644 --- a/src/fsfw/datapoollocal/LocalDataSet.h +++ b/src/fsfw/datapoollocal/LocalDataSet.h @@ -1,9 +1,10 @@ #ifndef FSFW_DATAPOOLLOCAL_LOCALDATASET_H_ #define FSFW_DATAPOOLLOCAL_LOCALDATASET_H_ -#include "LocalPoolDataSetBase.h" #include +#include "LocalPoolDataSetBase.h" + /** * @brief This dataset type can be used to group related pool variables if the number of * variables should not be fixed. @@ -17,20 +18,20 @@ * @tparam capacity Capacity of the static dataset, which is usually known * beforehand. */ -class LocalDataSet: public LocalPoolDataSetBase { -public: - LocalDataSet(HasLocalDataPoolIF* hkOwner, uint32_t setId, - const size_t maxSize); +class LocalDataSet : public LocalPoolDataSetBase { + public: + LocalDataSet(HasLocalDataPoolIF* hkOwner, uint32_t setId, const size_t maxSize); - LocalDataSet(sid_t sid, const size_t maxSize); + LocalDataSet(sid_t sid, const size_t maxSize); - virtual~ LocalDataSet(); + virtual ~LocalDataSet(); - //! Copying forbidden for now. - LocalDataSet(const LocalDataSet&) = delete; - LocalDataSet& operator=(const LocalDataSet&) = delete; -private: - std::vector poolVarList; + //! Copying forbidden for now. + LocalDataSet(const LocalDataSet&) = delete; + LocalDataSet& operator=(const LocalDataSet&) = delete; + + private: + std::vector poolVarList; }; #endif /* FSFW_DATAPOOLLOCAL_LOCALDATASET_H_ */ diff --git a/src/fsfw/datapoollocal/LocalPoolDataSetBase.cpp b/src/fsfw/datapoollocal/LocalPoolDataSetBase.cpp index d1ac0c7f..e2fe7d39 100644 --- a/src/fsfw/datapoollocal/LocalPoolDataSetBase.cpp +++ b/src/fsfw/datapoollocal/LocalPoolDataSetBase.cpp @@ -1,323 +1,293 @@ -#include "fsfw/datapoollocal.h" -#include "internal/HasLocalDpIFUserAttorney.h" - -#include "fsfw/serviceinterface/ServiceInterface.h" -#include "fsfw/objectmanager/ObjectManager.h" -#include "fsfw/globalfunctions/bitutility.h" -#include "fsfw/datapoollocal/LocalDataPoolManager.h" -#include "fsfw/housekeeping/PeriodicHousekeepingHelper.h" -#include "fsfw/serialize/SerializeAdapter.h" - #include #include -LocalPoolDataSetBase::LocalPoolDataSetBase(HasLocalDataPoolIF *hkOwner, - uint32_t setId, PoolVariableIF** registeredVariablesArray, - const size_t maxNumberOfVariables, bool periodicHandling): - PoolDataSetBase(registeredVariablesArray, maxNumberOfVariables) { - if(hkOwner == nullptr) { - // Configuration error. +#include "fsfw/datapoollocal.h" +#include "fsfw/datapoollocal/LocalDataPoolManager.h" +#include "fsfw/globalfunctions/bitutility.h" +#include "fsfw/housekeeping/PeriodicHousekeepingHelper.h" +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/serialize/SerializeAdapter.h" +#include "fsfw/serviceinterface/ServiceInterface.h" +#include "internal/HasLocalDpIFUserAttorney.h" + +LocalPoolDataSetBase::LocalPoolDataSetBase(HasLocalDataPoolIF *hkOwner, uint32_t setId, + PoolVariableIF **registeredVariablesArray, + const size_t maxNumberOfVariables, bool periodicHandling) + : PoolDataSetBase(registeredVariablesArray, maxNumberOfVariables) { + if (hkOwner == nullptr) { + // Configuration error. #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "LocalPoolDataSetBase::LocalPoolDataSetBase: Owner " - << "invalid!" << std::endl; + sif::error << "LocalPoolDataSetBase::LocalPoolDataSetBase: Owner " + << "invalid!" << std::endl; #else - sif::printError("LocalPoolDataSetBase::LocalPoolDataSetBase: Owner " - "invalid!\n\r"); + sif::printError( + "LocalPoolDataSetBase::LocalPoolDataSetBase: Owner " + "invalid!\n\r"); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ - return; - } - AccessPoolManagerIF* accessor = HasLocalDpIFUserAttorney::getAccessorHandle(hkOwner); + return; + } + AccessPoolManagerIF *accessor = HasLocalDpIFUserAttorney::getAccessorHandle(hkOwner); - if(accessor != nullptr) { - poolManager = accessor->getPoolManagerHandle(); - mutexIfSingleDataCreator = accessor->getLocalPoolMutex(); - } + if (accessor != nullptr) { + poolManager = accessor->getPoolManagerHandle(); + mutexIfSingleDataCreator = accessor->getLocalPoolMutex(); + } - this->sid.objectId = hkOwner->getObjectId(); - this->sid.ownerSetId = setId; + this->sid.objectId = hkOwner->getObjectId(); + this->sid.ownerSetId = setId; - /* Data creators get a periodic helper for periodic HK data generation. */ - if(periodicHandling) { - periodicHelper = new PeriodicHousekeepingHelper(this); - } + /* Data creators get a periodic helper for periodic HK data generation. */ + if (periodicHandling) { + periodicHelper = new PeriodicHousekeepingHelper(this); + } } -LocalPoolDataSetBase::LocalPoolDataSetBase(sid_t sid, PoolVariableIF** registeredVariablesArray, - const size_t maxNumberOfVariables): - PoolDataSetBase(registeredVariablesArray, maxNumberOfVariables) { - HasLocalDataPoolIF* hkOwner = ObjectManager::instance()->get( - sid.objectId); - if(hkOwner != nullptr) { - AccessPoolManagerIF* accessor = HasLocalDpIFUserAttorney::getAccessorHandle(hkOwner); - if(accessor != nullptr) { - mutexIfSingleDataCreator = accessor->getLocalPoolMutex(); - poolManager = accessor->getPoolManagerHandle(); - } +LocalPoolDataSetBase::LocalPoolDataSetBase(sid_t sid, PoolVariableIF **registeredVariablesArray, + const size_t maxNumberOfVariables) + : PoolDataSetBase(registeredVariablesArray, maxNumberOfVariables) { + HasLocalDataPoolIF *hkOwner = ObjectManager::instance()->get(sid.objectId); + if (hkOwner != nullptr) { + AccessPoolManagerIF *accessor = HasLocalDpIFUserAttorney::getAccessorHandle(hkOwner); + if (accessor != nullptr) { + mutexIfSingleDataCreator = accessor->getLocalPoolMutex(); + poolManager = accessor->getPoolManagerHandle(); } + } - this->sid = sid; + this->sid = sid; } LocalPoolDataSetBase::LocalPoolDataSetBase(PoolVariableIF **registeredVariablesArray, - const size_t maxNumberOfVariables, bool protectEveryReadCommitCall): - PoolDataSetBase(registeredVariablesArray, maxNumberOfVariables) { - this->setReadCommitProtectionBehaviour(protectEveryReadCommitCall); + const size_t maxNumberOfVariables, + bool protectEveryReadCommitCall) + : PoolDataSetBase(registeredVariablesArray, maxNumberOfVariables) { + this->setReadCommitProtectionBehaviour(protectEveryReadCommitCall); } - LocalPoolDataSetBase::~LocalPoolDataSetBase() { - /* We only delete objects which were created in the class constructor */ - if(periodicHelper != nullptr) { - delete periodicHelper; - } - /* In case set was read but not comitted, we commit all variables with an invalid state */ - if(state == States::STATE_SET_WAS_READ) { - for (uint16_t count = 0; count < fillCount; count++) { - if(registeredVariables[count] != nullptr) { - registeredVariables[count]->setValid(false); - registeredVariables[count]->commit(MutexIF::TimeoutType::WAITING, 20); - } - } - } -} - -ReturnValue_t LocalPoolDataSetBase::lockDataPool( - MutexIF::TimeoutType timeoutType, - uint32_t timeoutMs) { - if(mutexIfSingleDataCreator != nullptr) { - return mutexIfSingleDataCreator->lockMutex(timeoutType, timeoutMs); - } - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t LocalPoolDataSetBase::serializeWithValidityBuffer(uint8_t **buffer, - size_t *size, size_t maxSize, - SerializeIF::Endianness streamEndianness) const { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - const uint8_t validityMaskSize = std::ceil(static_cast(fillCount)/8.0); - uint8_t* validityPtr = nullptr; -#ifdef _MSC_VER - /* Use a std::vector here because MSVC will (rightly) not create a fixed size array - with a non constant size specifier */ - std::vector validityMask(validityMaskSize); - validityPtr = validityMask.data(); -#else - uint8_t validityMask[validityMaskSize] = {0}; - validityPtr = validityMask; -#endif - uint8_t validBufferIndex = 0; - uint8_t validBufferIndexBit = 0; + /* We only delete objects which were created in the class constructor */ + if (periodicHelper != nullptr) { + delete periodicHelper; + } + /* In case set was read but not comitted, we commit all variables with an invalid state */ + if (state == States::STATE_SET_WAS_READ) { for (uint16_t count = 0; count < fillCount; count++) { - if(registeredVariables[count]->isValid()) { - /* Set bit at correct position */ - bitutil::set(validityPtr + validBufferIndex, validBufferIndexBit); - } - if(validBufferIndexBit == 7) { - validBufferIndex ++; - validBufferIndexBit = 0; - } - else { - validBufferIndexBit ++; - } + if (registeredVariables[count] != nullptr) { + registeredVariables[count]->setValid(false); + registeredVariables[count]->commit(MutexIF::TimeoutType::WAITING, 20); + } + } + } +} - result = registeredVariables[count]->serialize(buffer, size, maxSize, - streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } +ReturnValue_t LocalPoolDataSetBase::lockDataPool(MutexIF::TimeoutType timeoutType, + uint32_t timeoutMs) { + if (mutexIfSingleDataCreator != nullptr) { + return mutexIfSingleDataCreator->lockMutex(timeoutType, timeoutMs); + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t LocalPoolDataSetBase::serializeWithValidityBuffer( + uint8_t **buffer, size_t *size, size_t maxSize, + SerializeIF::Endianness streamEndianness) const { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + const uint8_t validityMaskSize = std::ceil(static_cast(fillCount) / 8.0); + uint8_t *validityPtr = nullptr; +#ifdef _MSC_VER + /* Use a std::vector here because MSVC will (rightly) not create a fixed size array + with a non constant size specifier */ + std::vector validityMask(validityMaskSize); + validityPtr = validityMask.data(); +#else + uint8_t validityMask[validityMaskSize] = {0}; + validityPtr = validityMask; +#endif + uint8_t validBufferIndex = 0; + uint8_t validBufferIndexBit = 0; + for (uint16_t count = 0; count < fillCount; count++) { + if (registeredVariables[count]->isValid()) { + /* Set bit at correct position */ + bitutil::set(validityPtr + validBufferIndex, validBufferIndexBit); + } + if (validBufferIndexBit == 7) { + validBufferIndex++; + validBufferIndexBit = 0; + } else { + validBufferIndexBit++; } - if(*size + validityMaskSize > maxSize) { - return SerializeIF::BUFFER_TOO_SHORT; + result = registeredVariables[count]->serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; } - // copy validity buffer to end - std::memcpy(*buffer, validityPtr, validityMaskSize); - *size += validityMaskSize; - return result; + } + + if (*size + validityMaskSize > maxSize) { + return SerializeIF::BUFFER_TOO_SHORT; + } + // copy validity buffer to end + std::memcpy(*buffer, validityPtr, validityMaskSize); + *size += validityMaskSize; + return result; } ReturnValue_t LocalPoolDataSetBase::deSerializeWithValidityBuffer( - const uint8_t **buffer, size_t *size, - SerializeIF::Endianness streamEndianness) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_FAILED; - for (uint16_t count = 0; count < fillCount; count++) { - result = registeredVariables[count]->deSerialize(buffer, size, - streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + const uint8_t **buffer, size_t *size, SerializeIF::Endianness streamEndianness) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_FAILED; + for (uint16_t count = 0; count < fillCount; count++) { + result = registeredVariables[count]->deSerialize(buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; } + } - if(*size < std::ceil(static_cast(fillCount) / 8.0)) { - return SerializeIF::STREAM_TOO_SHORT; + if (*size < std::ceil(static_cast(fillCount) / 8.0)) { + return SerializeIF::STREAM_TOO_SHORT; + } + + uint8_t validBufferIndex = 0; + uint8_t validBufferIndexBit = 0; + for (uint16_t count = 0; count < fillCount; count++) { + // set validity buffer here. + bool nextVarValid = false; + bitutil::get(*buffer + validBufferIndex, validBufferIndexBit, nextVarValid); + registeredVariables[count]->setValid(nextVarValid); + + if (validBufferIndexBit == 7) { + validBufferIndex++; + validBufferIndexBit = 0; + } else { + validBufferIndexBit++; } - - uint8_t validBufferIndex = 0; - uint8_t validBufferIndexBit = 0; - for (uint16_t count = 0; count < fillCount; count++) { - // set validity buffer here. - bool nextVarValid = false; - bitutil::get(*buffer + validBufferIndex, validBufferIndexBit, nextVarValid); - registeredVariables[count]->setValid(nextVarValid); - - if(validBufferIndexBit == 7) { - validBufferIndex ++; - validBufferIndexBit = 0; - } - else { - validBufferIndexBit ++; - } - } - return result; + } + return result; } ReturnValue_t LocalPoolDataSetBase::unlockDataPool() { - if(mutexIfSingleDataCreator != nullptr) { - return mutexIfSingleDataCreator->unlockMutex(); - } - return HasReturnvaluesIF::RETURN_OK; + if (mutexIfSingleDataCreator != nullptr) { + return mutexIfSingleDataCreator->unlockMutex(); + } + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t LocalPoolDataSetBase::serializeLocalPoolIds(uint8_t** buffer, - size_t* size, size_t maxSize,SerializeIF::Endianness streamEndianness, - bool serializeFillCount) const { - /* Serialize fill count as uint8_t */ - uint8_t fillCount = this->fillCount; - if(serializeFillCount) { - SerializeAdapter::serialize(&fillCount, buffer, size, maxSize, - streamEndianness); - } - for (uint16_t count = 0; count < fillCount; count++) { - lp_id_t currentPoolId = registeredVariables[count]->getDataPoolId(); - auto result = SerializeAdapter::serialize(¤tPoolId, buffer, - size, maxSize, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { +ReturnValue_t LocalPoolDataSetBase::serializeLocalPoolIds(uint8_t **buffer, size_t *size, + size_t maxSize, + SerializeIF::Endianness streamEndianness, + bool serializeFillCount) const { + /* Serialize fill count as uint8_t */ + uint8_t fillCount = this->fillCount; + if (serializeFillCount) { + SerializeAdapter::serialize(&fillCount, buffer, size, maxSize, streamEndianness); + } + for (uint16_t count = 0; count < fillCount; count++) { + lp_id_t currentPoolId = registeredVariables[count]->getDataPoolId(); + auto result = + SerializeAdapter::serialize(¤tPoolId, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "LocalPoolDataSetBase::serializeLocalPoolIds: " - << "Serialization error!" << std::endl; + sif::warning << "LocalPoolDataSetBase::serializeLocalPoolIds: " + << "Serialization error!" << std::endl; #else - sif::printWarning("LocalPoolDataSetBase::serializeLocalPoolIds: " - "Serialization error!\n\r"); + sif::printWarning( + "LocalPoolDataSetBase::serializeLocalPoolIds: " + "Serialization error!\n\r"); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ - return result; - } + return result; } - return HasReturnvaluesIF::RETURN_OK; + } + return HasReturnvaluesIF::RETURN_OK; } - -uint8_t LocalPoolDataSetBase::getLocalPoolIdsSerializedSize( - bool serializeFillCount) const { - if(serializeFillCount) { - return fillCount * sizeof(lp_id_t) + sizeof(uint8_t); - } - else { - return fillCount * sizeof(lp_id_t); - } +uint8_t LocalPoolDataSetBase::getLocalPoolIdsSerializedSize(bool serializeFillCount) const { + if (serializeFillCount) { + return fillCount * sizeof(lp_id_t) + sizeof(uint8_t); + } else { + return fillCount * sizeof(lp_id_t); + } } size_t LocalPoolDataSetBase::getSerializedSize() const { - if(withValidityBuffer) { - uint8_t validityMaskSize = std::ceil(static_cast(fillCount)/8.0); - return validityMaskSize + PoolDataSetBase::getSerializedSize(); - } - else { - return PoolDataSetBase::getSerializedSize(); - } + if (withValidityBuffer) { + uint8_t validityMaskSize = std::ceil(static_cast(fillCount) / 8.0); + return validityMaskSize + PoolDataSetBase::getSerializedSize(); + } else { + return PoolDataSetBase::getSerializedSize(); + } } -void LocalPoolDataSetBase::setValidityBufferGeneration( - bool withValidityBuffer) { - this->withValidityBuffer = withValidityBuffer; +void LocalPoolDataSetBase::setValidityBufferGeneration(bool withValidityBuffer) { + this->withValidityBuffer = withValidityBuffer; } -ReturnValue_t LocalPoolDataSetBase::deSerialize(const uint8_t **buffer, - size_t *size, SerializeIF::Endianness streamEndianness) { - if(withValidityBuffer) { - return this->deSerializeWithValidityBuffer(buffer, size, - streamEndianness); - } - else { - return PoolDataSetBase::deSerialize(buffer, size, streamEndianness); - } +ReturnValue_t LocalPoolDataSetBase::deSerialize(const uint8_t **buffer, size_t *size, + SerializeIF::Endianness streamEndianness) { + if (withValidityBuffer) { + return this->deSerializeWithValidityBuffer(buffer, size, streamEndianness); + } else { + return PoolDataSetBase::deSerialize(buffer, size, streamEndianness); + } } -ReturnValue_t LocalPoolDataSetBase::serialize(uint8_t **buffer, size_t *size, - size_t maxSize, SerializeIF::Endianness streamEndianness) const { - if(withValidityBuffer) { - return this->serializeWithValidityBuffer(buffer, size, - maxSize, streamEndianness); - } - else { - return PoolDataSetBase::serialize(buffer, size, maxSize, - streamEndianness); - } +ReturnValue_t LocalPoolDataSetBase::serialize(uint8_t **buffer, size_t *size, size_t maxSize, + SerializeIF::Endianness streamEndianness) const { + if (withValidityBuffer) { + return this->serializeWithValidityBuffer(buffer, size, maxSize, streamEndianness); + } else { + return PoolDataSetBase::serialize(buffer, size, maxSize, streamEndianness); + } } -void LocalPoolDataSetBase::setDiagnostic(bool isDiagnostics) { - this->diagnostic = isDiagnostics; -} +void LocalPoolDataSetBase::setDiagnostic(bool isDiagnostics) { this->diagnostic = isDiagnostics; } -bool LocalPoolDataSetBase::isDiagnostics() const { - return diagnostic; -} +bool LocalPoolDataSetBase::isDiagnostics() const { return diagnostic; } void LocalPoolDataSetBase::setReportingEnabled(bool reportingEnabled) { - this->reportingEnabled = reportingEnabled; + this->reportingEnabled = reportingEnabled; } -bool LocalPoolDataSetBase::getReportingEnabled() const { - return reportingEnabled; -} +bool LocalPoolDataSetBase::getReportingEnabled() const { return reportingEnabled; } void LocalPoolDataSetBase::initializePeriodicHelper(float collectionInterval, - dur_millis_t minimumPeriodicInterval, uint8_t nonDiagIntervalFactor) { - periodicHelper->initialize(collectionInterval, minimumPeriodicInterval, nonDiagIntervalFactor); + dur_millis_t minimumPeriodicInterval, + uint8_t nonDiagIntervalFactor) { + periodicHelper->initialize(collectionInterval, minimumPeriodicInterval, nonDiagIntervalFactor); } -void LocalPoolDataSetBase::setChanged(bool changed) { - this->changed = changed; -} +void LocalPoolDataSetBase::setChanged(bool changed) { this->changed = changed; } -bool LocalPoolDataSetBase::hasChanged() const { - return changed; -} +bool LocalPoolDataSetBase::hasChanged() const { return changed; } -sid_t LocalPoolDataSetBase::getSid() const { - return sid; -} +sid_t LocalPoolDataSetBase::getSid() const { return sid; } -bool LocalPoolDataSetBase::isValid() const { - return this->valid; -} +bool LocalPoolDataSetBase::isValid() const { return this->valid; } void LocalPoolDataSetBase::setValidity(bool valid, bool setEntriesRecursively) { - if(setEntriesRecursively) { - for(size_t idx = 0; idx < this->getFillCount(); idx++) { - registeredVariables[idx]->setValid(valid); - } + if (setEntriesRecursively) { + for (size_t idx = 0; idx < this->getFillCount(); idx++) { + registeredVariables[idx]->setValid(valid); } - this->valid = valid; + } + this->valid = valid; } object_id_t LocalPoolDataSetBase::getCreatorObjectId() { - if(poolManager != nullptr) { - return poolManager->getCreatorObjectId(); - } - return objects::NO_OBJECT; + if (poolManager != nullptr) { + return poolManager->getCreatorObjectId(); + } + return objects::NO_OBJECT; } void LocalPoolDataSetBase::setAllVariablesReadOnly() { - for(size_t idx = 0; idx < this->getFillCount(); idx++) { - registeredVariables[idx]->setReadWriteMode(pool_rwm_t::VAR_READ); - } + for (size_t idx = 0; idx < this->getFillCount(); idx++) { + registeredVariables[idx]->setReadWriteMode(pool_rwm_t::VAR_READ); + } } float LocalPoolDataSetBase::getCollectionInterval() const { - if(periodicHelper != nullptr) { - return periodicHelper->getCollectionIntervalInSeconds(); - } - else { - return 0.0; - } + if (periodicHelper != nullptr) { + return periodicHelper->getCollectionIntervalInSeconds(); + } else { + return 0.0; + } } diff --git a/src/fsfw/datapoollocal/LocalPoolDataSetBase.h b/src/fsfw/datapoollocal/LocalPoolDataSetBase.h index 822e2cb8..c2de2c54 100644 --- a/src/fsfw/datapoollocal/LocalPoolDataSetBase.h +++ b/src/fsfw/datapoollocal/LocalPoolDataSetBase.h @@ -1,13 +1,12 @@ #ifndef FSFW_DATAPOOLLOCAL_LOCALPOOLDATASETBASE_H_ #define FSFW_DATAPOOLLOCAL_LOCALPOOLDATASETBASE_H_ -#include "MarkChangedIF.h" -#include "localPoolDefinitions.h" +#include +#include "MarkChangedIF.h" #include "fsfw/datapool/DataSetIF.h" #include "fsfw/datapool/PoolDataSetBase.h" - -#include +#include "localPoolDefinitions.h" class LocalDataPoolManager; class HasLocalDataPoolIF; @@ -41,201 +40,194 @@ class PeriodicHousekeepingHelper; * * @ingroup data_pool */ -class LocalPoolDataSetBase: - public PoolDataSetBase, - public MarkChangedIF { - friend class LocalPoolDataSetAttorney; - friend class PeriodicHousekeepingHelper; -public: - /** - * @brief Constructor for the creator of local pool data. - * @details - * This constructor also initializes the components required for - * periodic handling. - */ - LocalPoolDataSetBase(HasLocalDataPoolIF *hkOwner, - uint32_t setId, PoolVariableIF** registeredVariablesArray, - const size_t maxNumberOfVariables, bool periodicHandling = true); +class LocalPoolDataSetBase : public PoolDataSetBase, public MarkChangedIF { + friend class LocalPoolDataSetAttorney; + friend class PeriodicHousekeepingHelper; - /** - * @brief Constructor for users of the local pool data, which need - * to access data created by one HK manager. - * @details - * Unlike the first constructor, no component for periodic handling - * will be initiated. - * @param sid Unique identifier of dataset consisting of object ID and - * set ID. - * @param registeredVariablesArray - * @param maxNumberOfVariables - */ - LocalPoolDataSetBase(sid_t sid, PoolVariableIF** registeredVariablesArray, - const size_t maxNumberOfVariables); + public: + /** + * @brief Constructor for the creator of local pool data. + * @details + * This constructor also initializes the components required for + * periodic handling. + */ + LocalPoolDataSetBase(HasLocalDataPoolIF* hkOwner, uint32_t setId, + PoolVariableIF** registeredVariablesArray, const size_t maxNumberOfVariables, + bool periodicHandling = true); - /** - * @brief Simple constructor, if the dataset is not the owner by - * a class with a HK manager. - * @details - * This constructor won't create components required for periodic handling - * and it also won't try to deduce the HK manager because no SID is - * supplied. This function should therefore be called by classes which need - * to access pool variables from different creators. - * - * If the class is intended to access pool variables from different - * creators, the third argument should be set to true. The mutex - * properties can be set with #setReadCommitProtectionBehaviour . - * @param registeredVariablesArray - * @param maxNumberOfVariables - * @param protectEveryReadCommitCall If the pool variables are created by - * multiple creators, this flag can be set to protect all read and - * commit calls separately. - */ - LocalPoolDataSetBase(PoolVariableIF** registeredVariablesArray, - const size_t maxNumberOfVariables, - bool protectEveryReadCommitCall = true); + /** + * @brief Constructor for users of the local pool data, which need + * to access data created by one HK manager. + * @details + * Unlike the first constructor, no component for periodic handling + * will be initiated. + * @param sid Unique identifier of dataset consisting of object ID and + * set ID. + * @param registeredVariablesArray + * @param maxNumberOfVariables + */ + LocalPoolDataSetBase(sid_t sid, PoolVariableIF** registeredVariablesArray, + const size_t maxNumberOfVariables); - /** - * @brief The destructor automatically manages writing the valid - * information of variables. - * @details - * In case the data set was read out, but not committed (indicated by state), - * the destructor parses all variables that are still registered to the set. - * For each, the valid flag in the data pool is set to "invalid". - */ - ~LocalPoolDataSetBase(); + /** + * @brief Simple constructor, if the dataset is not the owner by + * a class with a HK manager. + * @details + * This constructor won't create components required for periodic handling + * and it also won't try to deduce the HK manager because no SID is + * supplied. This function should therefore be called by classes which need + * to access pool variables from different creators. + * + * If the class is intended to access pool variables from different + * creators, the third argument should be set to true. The mutex + * properties can be set with #setReadCommitProtectionBehaviour . + * @param registeredVariablesArray + * @param maxNumberOfVariables + * @param protectEveryReadCommitCall If the pool variables are created by + * multiple creators, this flag can be set to protect all read and + * commit calls separately. + */ + LocalPoolDataSetBase(PoolVariableIF** registeredVariablesArray, const size_t maxNumberOfVariables, + bool protectEveryReadCommitCall = true); - /* The copy constructor and assingment constructor are forbidden for now. - The use-cases are limited and the first step would be to implement them properly for the - base class */ - LocalPoolDataSetBase(const LocalPoolDataSetBase& otherSet) = delete; - const LocalPoolDataSetBase& operator=(const LocalPoolDataSetBase& otherSet) = delete; + /** + * @brief The destructor automatically manages writing the valid + * information of variables. + * @details + * In case the data set was read out, but not committed (indicated by state), + * the destructor parses all variables that are still registered to the set. + * For each, the valid flag in the data pool is set to "invalid". + */ + ~LocalPoolDataSetBase(); - /** - * Helper functions used to set all currently contained variables to read-only. - * It is recommended to call this in set constructors intended to be used - * by data consumers to prevent accidentally changing pool data. - */ - void setAllVariablesReadOnly(); - void setValidityBufferGeneration(bool withValidityBuffer); + /* The copy constructor and assingment constructor are forbidden for now. + The use-cases are limited and the first step would be to implement them properly for the + base class */ + LocalPoolDataSetBase(const LocalPoolDataSetBase& otherSet) = delete; + const LocalPoolDataSetBase& operator=(const LocalPoolDataSetBase& otherSet) = delete; - sid_t getSid() const; + /** + * Helper functions used to set all currently contained variables to read-only. + * It is recommended to call this in set constructors intended to be used + * by data consumers to prevent accidentally changing pool data. + */ + void setAllVariablesReadOnly(); + void setValidityBufferGeneration(bool withValidityBuffer); - /** SerializeIF overrides */ - ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, - SerializeIF::Endianness streamEndianness) const override; - ReturnValue_t deSerialize(const uint8_t** buffer, size_t *size, - SerializeIF::Endianness streamEndianness) override; - size_t getSerializedSize() const override; + sid_t getSid() const; - /** - * Special version of the serilization function which appends a - * validity buffer at the end. Each bit of this validity buffer - * denotes whether the container data set entries are valid from left - * to right, MSB first. (length = ceil(N/8), N = number of pool variables) - * @param buffer - * @param size - * @param maxSize - * @param bigEndian - * @param withValidityBuffer - * @return - */ - ReturnValue_t serializeWithValidityBuffer(uint8_t** buffer, - size_t* size, size_t maxSize, - SerializeIF::Endianness streamEndianness) const; - ReturnValue_t deSerializeWithValidityBuffer(const uint8_t** buffer, - size_t *size, SerializeIF::Endianness streamEndianness); - ReturnValue_t serializeLocalPoolIds(uint8_t** buffer, - size_t* size, size_t maxSize, - SerializeIF::Endianness streamEndianness, - bool serializeFillCount = true) const; - uint8_t getLocalPoolIdsSerializedSize(bool serializeFillCount = true) const; + /** SerializeIF overrides */ + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + SerializeIF::Endianness streamEndianness) const override; + ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + SerializeIF::Endianness streamEndianness) override; + size_t getSerializedSize() const override; - /** - * Set the dataset valid or invalid. These calls are mutex protected. - * @param setEntriesRecursively - * If this is true, all contained datasets will also be set recursively. - */ - void setValidity(bool valid, bool setEntriesRecursively); - bool isValid() const override; + /** + * Special version of the serilization function which appends a + * validity buffer at the end. Each bit of this validity buffer + * denotes whether the container data set entries are valid from left + * to right, MSB first. (length = ceil(N/8), N = number of pool variables) + * @param buffer + * @param size + * @param maxSize + * @param bigEndian + * @param withValidityBuffer + * @return + */ + ReturnValue_t serializeWithValidityBuffer(uint8_t** buffer, size_t* size, size_t maxSize, + SerializeIF::Endianness streamEndianness) const; + ReturnValue_t deSerializeWithValidityBuffer(const uint8_t** buffer, size_t* size, + SerializeIF::Endianness streamEndianness); + ReturnValue_t serializeLocalPoolIds(uint8_t** buffer, size_t* size, size_t maxSize, + SerializeIF::Endianness streamEndianness, + bool serializeFillCount = true) const; + uint8_t getLocalPoolIdsSerializedSize(bool serializeFillCount = true) const; - /** - * These calls are mutex protected. - * @param changed - */ - void setChanged(bool changed) override; - bool hasChanged() const override; + /** + * Set the dataset valid or invalid. These calls are mutex protected. + * @param setEntriesRecursively + * If this is true, all contained datasets will also be set recursively. + */ + void setValidity(bool valid, bool setEntriesRecursively); + bool isValid() const override; - object_id_t getCreatorObjectId(); + /** + * These calls are mutex protected. + * @param changed + */ + void setChanged(bool changed) override; + bool hasChanged() const override; - bool getReportingEnabled() const; + object_id_t getCreatorObjectId(); - /** - * Returns the current periodic HK generation interval this set - * belongs to a HK manager and the interval is not 0. Otherwise, - * returns 0.0 - * @return - */ - float getCollectionInterval() const; + bool getReportingEnabled() const; -protected: - sid_t sid; - //! This mutex is used if the data is created by one object only. - MutexIF* mutexIfSingleDataCreator = nullptr; + /** + * Returns the current periodic HK generation interval this set + * belongs to a HK manager and the interval is not 0. Otherwise, + * returns 0.0 + * @return + */ + float getCollectionInterval() const; - bool diagnostic = false; - void setDiagnostic(bool diagnostics); - bool isDiagnostics() const; + protected: + sid_t sid; + //! This mutex is used if the data is created by one object only. + MutexIF* mutexIfSingleDataCreator = nullptr; - /** - * Used for periodic generation. - */ - bool reportingEnabled = false; - void setReportingEnabled(bool enabled); + bool diagnostic = false; + void setDiagnostic(bool diagnostics); + bool isDiagnostics() const; - void initializePeriodicHelper(float collectionInterval, dur_millis_t minimumPeriodicInterval, - uint8_t nonDiagIntervalFactor = 5); + /** + * Used for periodic generation. + */ + bool reportingEnabled = false; + void setReportingEnabled(bool enabled); - /** - * If the valid state of a dataset is always relevant to the whole - * data set we can use this flag. - */ - bool valid = false; + void initializePeriodicHelper(float collectionInterval, dur_millis_t minimumPeriodicInterval, + uint8_t nonDiagIntervalFactor = 5); - /** - * Can be used to mark the dataset as changed, which is used - * by the LocalDataPoolManager to send out update messages. - */ - bool changed = false; + /** + * If the valid state of a dataset is always relevant to the whole + * data set we can use this flag. + */ + bool valid = false; - /** - * Specify whether the validity buffer is serialized too when serializing - * or deserializing the packet. Each bit of the validity buffer will - * contain the validity state of the pool variables from left to right. - * The size of validity buffer thus will be ceil(N / 8) with N = number of - * pool variables. - */ - bool withValidityBuffer = true; + /** + * Can be used to mark the dataset as changed, which is used + * by the LocalDataPoolManager to send out update messages. + */ + bool changed = false; - /** - * @brief This is a small helper function to facilitate locking - * the global data pool. - * @details - * It makes use of the lockDataPool method offered by the DataPool class. - */ - ReturnValue_t lockDataPool(MutexIF::TimeoutType timeoutType, - uint32_t timeoutMs) override; + /** + * Specify whether the validity buffer is serialized too when serializing + * or deserializing the packet. Each bit of the validity buffer will + * contain the validity state of the pool variables from left to right. + * The size of validity buffer thus will be ceil(N / 8) with N = number of + * pool variables. + */ + bool withValidityBuffer = true; - /** - * @brief This is a small helper function to facilitate - * unlocking the global data pool - * @details - * It makes use of the freeDataPoolLock method offered by the DataPool class. - */ - ReturnValue_t unlockDataPool() override; + /** + * @brief This is a small helper function to facilitate locking + * the global data pool. + * @details + * It makes use of the lockDataPool method offered by the DataPool class. + */ + ReturnValue_t lockDataPool(MutexIF::TimeoutType timeoutType, uint32_t timeoutMs) override; - PeriodicHousekeepingHelper* periodicHelper = nullptr; - LocalDataPoolManager* poolManager = nullptr; + /** + * @brief This is a small helper function to facilitate + * unlocking the global data pool + * @details + * It makes use of the freeDataPoolLock method offered by the DataPool class. + */ + ReturnValue_t unlockDataPool() override; + PeriodicHousekeepingHelper* periodicHelper = nullptr; + LocalDataPoolManager* poolManager = nullptr; }; - #endif /* FSFW_DATAPOOLLOCAL_LOCALPOOLDATASETBASE_H_ */ diff --git a/src/fsfw/datapoollocal/LocalPoolObjectBase.cpp b/src/fsfw/datapoollocal/LocalPoolObjectBase.cpp index 96b849c6..c974601c 100644 --- a/src/fsfw/datapoollocal/LocalPoolObjectBase.cpp +++ b/src/fsfw/datapoollocal/LocalPoolObjectBase.cpp @@ -1,141 +1,125 @@ #include "fsfw/datapoollocal/LocalPoolObjectBase.h" -#include "fsfw/datapoollocal/LocalDataPoolManager.h" + #include "fsfw/datapoollocal/AccessLocalPoolF.h" #include "fsfw/datapoollocal/HasLocalDataPoolIF.h" +#include "fsfw/datapoollocal/LocalDataPoolManager.h" +#include "fsfw/objectmanager/ObjectManager.h" #include "internal/HasLocalDpIFUserAttorney.h" -#include "fsfw/objectmanager/ObjectManager.h" - - LocalPoolObjectBase::LocalPoolObjectBase(lp_id_t poolId, HasLocalDataPoolIF* hkOwner, - DataSetIF* dataSet, pool_rwm_t setReadWriteMode): - localPoolId(poolId), readWriteMode(setReadWriteMode) { - if(poolId == PoolVariableIF::NO_PARAMETER) { + DataSetIF* dataSet, pool_rwm_t setReadWriteMode) + : localPoolId(poolId), readWriteMode(setReadWriteMode) { + if (poolId == PoolVariableIF::NO_PARAMETER) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "LocalPoolVar::LocalPoolVar: 0 passed as pool ID, " - << "which is the NO_PARAMETER value!" << std::endl; + sif::warning << "LocalPoolVar::LocalPoolVar: 0 passed as pool ID, " + << "which is the NO_PARAMETER value!" << std::endl; #endif - } - if(hkOwner == nullptr) { + } + if (hkOwner == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "LocalPoolVar::LocalPoolVar: The supplied pool " - << "owner is a invalid!" << std::endl; + sif::error << "LocalPoolVar::LocalPoolVar: The supplied pool " + << "owner is a invalid!" << std::endl; #endif - return; - } - AccessPoolManagerIF* poolManAccessor = HasLocalDpIFUserAttorney::getAccessorHandle(hkOwner); - hkManager = poolManAccessor->getPoolManagerHandle(); + return; + } + AccessPoolManagerIF* poolManAccessor = HasLocalDpIFUserAttorney::getAccessorHandle(hkOwner); + hkManager = poolManAccessor->getPoolManagerHandle(); - if (dataSet != nullptr) { - dataSet->registerVariable(this); - } + if (dataSet != nullptr) { + dataSet->registerVariable(this); + } } -LocalPoolObjectBase::LocalPoolObjectBase(object_id_t poolOwner, lp_id_t poolId, DataSetIF *dataSet, - pool_rwm_t setReadWriteMode): - localPoolId(poolId), readWriteMode(setReadWriteMode) { - if(poolId == PoolVariableIF::NO_PARAMETER) { +LocalPoolObjectBase::LocalPoolObjectBase(object_id_t poolOwner, lp_id_t poolId, DataSetIF* dataSet, + pool_rwm_t setReadWriteMode) + : localPoolId(poolId), readWriteMode(setReadWriteMode) { + if (poolId == PoolVariableIF::NO_PARAMETER) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "LocalPoolVar::LocalPoolVar: 0 passed as pool ID, " - "which is the NO_PARAMETER value!" << std::endl; + sif::warning << "LocalPoolVar::LocalPoolVar: 0 passed as pool ID, " + "which is the NO_PARAMETER value!" + << std::endl; #else - sif::printWarning("LocalPoolVar::LocalPoolVar: 0 passed as pool ID, " - "which is the NO_PARAMETER value!\n"); + sif::printWarning( + "LocalPoolVar::LocalPoolVar: 0 passed as pool ID, " + "which is the NO_PARAMETER value!\n"); #endif - } - HasLocalDataPoolIF* hkOwner = ObjectManager::instance()->get(poolOwner); - if(hkOwner == nullptr) { + } + HasLocalDataPoolIF* hkOwner = ObjectManager::instance()->get(poolOwner); + if (hkOwner == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "LocalPoolVariable: The supplied pool owner did not implement the correct " - "interface HasLocalDataPoolIF!" << std::endl; + sif::error << "LocalPoolVariable: The supplied pool owner did not implement the correct " + "interface HasLocalDataPoolIF!" + << std::endl; #else - sif::printError( "LocalPoolVariable: The supplied pool owner did not implement the correct " - "interface HasLocalDataPoolIF!\n"); + sif::printError( + "LocalPoolVariable: The supplied pool owner did not implement the correct " + "interface HasLocalDataPoolIF!\n"); #endif - return; - } + return; + } - AccessPoolManagerIF* accessor = HasLocalDpIFUserAttorney::getAccessorHandle(hkOwner); - if(accessor != nullptr) { - hkManager = accessor->getPoolManagerHandle(); - } + AccessPoolManagerIF* accessor = HasLocalDpIFUserAttorney::getAccessorHandle(hkOwner); + if (accessor != nullptr) { + hkManager = accessor->getPoolManagerHandle(); + } - if(dataSet != nullptr) { - dataSet->registerVariable(this); - } + if (dataSet != nullptr) { + dataSet->registerVariable(this); + } } -pool_rwm_t LocalPoolObjectBase::getReadWriteMode() const { - return readWriteMode; -} +pool_rwm_t LocalPoolObjectBase::getReadWriteMode() const { return readWriteMode; } -bool LocalPoolObjectBase::isValid() const { - return valid; -} +bool LocalPoolObjectBase::isValid() const { return valid; } -void LocalPoolObjectBase::setValid(bool valid) { - this->valid = valid; -} +void LocalPoolObjectBase::setValid(bool valid) { this->valid = valid; } -lp_id_t LocalPoolObjectBase::getDataPoolId() const { - return localPoolId; -} +lp_id_t LocalPoolObjectBase::getDataPoolId() const { return localPoolId; } -void LocalPoolObjectBase::setDataPoolId(lp_id_t poolId) { - this->localPoolId = poolId; -} +void LocalPoolObjectBase::setDataPoolId(lp_id_t poolId) { this->localPoolId = poolId; } -void LocalPoolObjectBase::setChanged(bool changed) { - this->changed = changed; -} +void LocalPoolObjectBase::setChanged(bool changed) { this->changed = changed; } -bool LocalPoolObjectBase::hasChanged() const { - return changed; -} +bool LocalPoolObjectBase::hasChanged() const { return changed; } void LocalPoolObjectBase::setReadWriteMode(pool_rwm_t newReadWriteMode) { - this->readWriteMode = newReadWriteMode; + this->readWriteMode = newReadWriteMode; } -void LocalPoolObjectBase::reportReadCommitError(const char* variableType, - ReturnValue_t error, bool read, object_id_t objectId, lp_id_t lpId) { +void LocalPoolObjectBase::reportReadCommitError(const char* variableType, ReturnValue_t error, + bool read, object_id_t objectId, lp_id_t lpId) { #if FSFW_DISABLE_PRINTOUT == 0 - const char* variablePrintout = variableType; - if(variablePrintout == nullptr) { - variablePrintout = "Unknown Type"; - } - const char* type = nullptr; - if(read) { - type = "read"; - } - else { - type = "commit"; - } + const char* variablePrintout = variableType; + if (variablePrintout == nullptr) { + variablePrintout = "Unknown Type"; + } + const char* type = nullptr; + if (read) { + type = "read"; + } else { + type = "commit"; + } - const char* errMsg = nullptr; - if(error == localpool::POOL_ENTRY_NOT_FOUND) { - errMsg = "Pool entry not found"; - } - else if(error == localpool::POOL_ENTRY_TYPE_CONFLICT) { - errMsg = "Pool entry type conflict"; - } - else if(error == PoolVariableIF::INVALID_READ_WRITE_MODE) { - errMsg = "Pool variable wrong read-write mode"; - } - else if(error == PoolVariableIF::INVALID_POOL_ENTRY) { - errMsg = "Pool entry invalid"; - } - else { - errMsg = "Unknown error code"; - } + const char* errMsg = nullptr; + if (error == localpool::POOL_ENTRY_NOT_FOUND) { + errMsg = "Pool entry not found"; + } else if (error == localpool::POOL_ENTRY_TYPE_CONFLICT) { + errMsg = "Pool entry type conflict"; + } else if (error == PoolVariableIF::INVALID_READ_WRITE_MODE) { + errMsg = "Pool variable wrong read-write mode"; + } else if (error == PoolVariableIF::INVALID_POOL_ENTRY) { + errMsg = "Pool entry invalid"; + } else { + errMsg = "Unknown error code"; + } #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << variablePrintout << ": " << type << " call | " << errMsg << " | Owner: 0x" - << std::hex << std::setw(8) << std::setfill('0') << objectId << std::dec - << " LPID: " << lpId << std::endl; + sif::warning << variablePrintout << ": " << type << " call | " << errMsg << " | Owner: 0x" + << std::hex << std::setw(8) << std::setfill('0') << objectId << std::dec + << " LPID: " << lpId << std::endl; #else - sif::printWarning("%s: %s call | %s | Owner: 0x%08x LPID: %lu\n", - variablePrintout, type, errMsg, objectId, lpId); + sif::printWarning("%s: %s call | %s | Owner: 0x%08x LPID: %lu\n", variablePrintout, type, errMsg, + objectId, lpId); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* FSFW_DISABLE_PRINTOUT == 0 */ } diff --git a/src/fsfw/datapoollocal/LocalPoolObjectBase.h b/src/fsfw/datapoollocal/LocalPoolObjectBase.h index 72275646..56e190df 100644 --- a/src/fsfw/datapoollocal/LocalPoolObjectBase.h +++ b/src/fsfw/datapoollocal/LocalPoolObjectBase.h @@ -2,11 +2,10 @@ #define FSFW_DATAPOOLLOCAL_LOCALPOOLOBJECTBASE_H_ #include "MarkChangedIF.h" -#include "localPoolDefinitions.h" - -#include "fsfw/objectmanager/SystemObjectIF.h" #include "fsfw/datapool/PoolVariableIF.h" +#include "fsfw/objectmanager/SystemObjectIF.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "localPoolDefinitions.h" class LocalDataPoolManager; class DataSetIF; @@ -16,56 +15,54 @@ class HasLocalDataPoolIF; * @brief This class serves as a non-template base for pool objects like pool variables * or pool vectors. */ -class LocalPoolObjectBase: public PoolVariableIF, - public HasReturnvaluesIF, - public MarkChangedIF { -public: - LocalPoolObjectBase(lp_id_t poolId, HasLocalDataPoolIF* hkOwner, DataSetIF* dataSet, - pool_rwm_t setReadWriteMode); +class LocalPoolObjectBase : public PoolVariableIF, public HasReturnvaluesIF, public MarkChangedIF { + public: + LocalPoolObjectBase(lp_id_t poolId, HasLocalDataPoolIF* hkOwner, DataSetIF* dataSet, + pool_rwm_t setReadWriteMode); - LocalPoolObjectBase(object_id_t poolOwner, lp_id_t poolId, DataSetIF* dataSet = nullptr, - pool_rwm_t setReadWriteMode = pool_rwm_t::VAR_READ_WRITE); + LocalPoolObjectBase(object_id_t poolOwner, lp_id_t poolId, DataSetIF* dataSet = nullptr, + pool_rwm_t setReadWriteMode = pool_rwm_t::VAR_READ_WRITE); - void setReadWriteMode(pool_rwm_t newReadWriteMode); - pool_rwm_t getReadWriteMode() const; + void setReadWriteMode(pool_rwm_t newReadWriteMode); + pool_rwm_t getReadWriteMode() const; - bool isValid() const override; - void setValid(bool valid) override; + bool isValid() const override; + void setValid(bool valid) override; - void setChanged(bool changed) override; - bool hasChanged() const override; + void setChanged(bool changed) override; + bool hasChanged() const override; - lp_id_t getDataPoolId() const override; - void setDataPoolId(lp_id_t poolId); + lp_id_t getDataPoolId() const override; + void setDataPoolId(lp_id_t poolId); -protected: - /** - * @brief To access the correct data pool entry on read and commit calls, - * the data pool id is stored. - */ - uint32_t localPoolId = PoolVariableIF::NO_PARAMETER; - /** - * @brief The valid information as it was stored in the data pool - * is copied to this attribute. - */ - bool valid = false; + protected: + /** + * @brief To access the correct data pool entry on read and commit calls, + * the data pool id is stored. + */ + uint32_t localPoolId = PoolVariableIF::NO_PARAMETER; + /** + * @brief The valid information as it was stored in the data pool + * is copied to this attribute. + */ + bool valid = false; - /** - * @brief A local pool variable can be marked as changed. - */ - bool changed = false; + /** + * @brief A local pool variable can be marked as changed. + */ + bool changed = false; - /** - * @brief The information whether the class is read-write or - * read-only is stored here. - */ - ReadWriteMode_t readWriteMode = pool_rwm_t::VAR_READ_WRITE; + /** + * @brief The information whether the class is read-write or + * read-only is stored here. + */ + ReadWriteMode_t readWriteMode = pool_rwm_t::VAR_READ_WRITE; - //! @brief Pointer to the class which manages the HK pool. - LocalDataPoolManager* hkManager = nullptr; + //! @brief Pointer to the class which manages the HK pool. + LocalDataPoolManager* hkManager = nullptr; - void reportReadCommitError(const char* variableType, - ReturnValue_t error, bool read, object_id_t objectId, lp_id_t lpId); + void reportReadCommitError(const char* variableType, ReturnValue_t error, bool read, + object_id_t objectId, lp_id_t lpId); }; #endif /* FSFW_DATAPOOLLOCAL_LOCALPOOLOBJECTBASE_H_ */ diff --git a/src/fsfw/datapoollocal/LocalPoolVariable.h b/src/fsfw/datapoollocal/LocalPoolVariable.h index 76629489..818e4883 100644 --- a/src/fsfw/datapoollocal/LocalPoolVariable.h +++ b/src/fsfw/datapoollocal/LocalPoolVariable.h @@ -1,17 +1,16 @@ #ifndef FSFW_DATAPOOLLOCAL_LOCALPOOLVARIABLE_H_ #define FSFW_DATAPOOLLOCAL_LOCALPOOLVARIABLE_H_ -#include "LocalPoolObjectBase.h" -#include "HasLocalDataPoolIF.h" -#include "LocalDataPoolManager.h" -#include "AccessLocalPoolF.h" -#include "internal/LocalDpManagerAttorney.h" - -#include "../datapool/PoolVariableIF.h" #include "../datapool/DataSetIF.h" -#include "../serviceinterface/ServiceInterface.h" +#include "../datapool/PoolVariableIF.h" #include "../objectmanager/ObjectManagerIF.h" #include "../serialize/SerializeAdapter.h" +#include "../serviceinterface/ServiceInterface.h" +#include "AccessLocalPoolF.h" +#include "HasLocalDataPoolIF.h" +#include "LocalDataPoolManager.h" +#include "LocalPoolObjectBase.h" +#include "internal/LocalDpManagerAttorney.h" /** * @brief Local Pool Variable class which is used to access the local pools. @@ -24,168 +23,163 @@ * all plain data types are supported, but in principle any type is possible. * @ingroup data_pool */ -template -class LocalPoolVariable: public LocalPoolObjectBase { -public: - //! Default ctor is forbidden. - LocalPoolVariable() = delete; +template +class LocalPoolVariable : public LocalPoolObjectBase { + public: + //! Default ctor is forbidden. + LocalPoolVariable() = delete; - /** - * This constructor is used by the data creators to have pool variable - * instances which can also be stored in datasets. - * - * It does not fetch the current value from the data pool, which - * has to be done by calling the read() operation. - * Datasets can be used to access multiple local pool entries in an - * efficient way. A pointer to a dataset can be passed to register - * the pool variable in that dataset directly. - * @param poolId ID of the local pool entry. - * @param hkOwner Pointer of the owner. This will generally be the calling - * class itself which passes "this". - * @param dataSet The data set in which the variable shall register itself. - * If nullptr, the variable is not registered. - * @param setReadWriteMode Specify the read-write mode of the pool variable. - */ - LocalPoolVariable(HasLocalDataPoolIF* hkOwner, lp_id_t poolId, - DataSetIF* dataSet = nullptr, - pool_rwm_t setReadWriteMode = pool_rwm_t::VAR_READ_WRITE); + /** + * This constructor is used by the data creators to have pool variable + * instances which can also be stored in datasets. + * + * It does not fetch the current value from the data pool, which + * has to be done by calling the read() operation. + * Datasets can be used to access multiple local pool entries in an + * efficient way. A pointer to a dataset can be passed to register + * the pool variable in that dataset directly. + * @param poolId ID of the local pool entry. + * @param hkOwner Pointer of the owner. This will generally be the calling + * class itself which passes "this". + * @param dataSet The data set in which the variable shall register itself. + * If nullptr, the variable is not registered. + * @param setReadWriteMode Specify the read-write mode of the pool variable. + */ + LocalPoolVariable(HasLocalDataPoolIF* hkOwner, lp_id_t poolId, DataSetIF* dataSet = nullptr, + pool_rwm_t setReadWriteMode = pool_rwm_t::VAR_READ_WRITE); - /** - * This constructor is used by data users like controllers to have - * access to the local pool variables of data creators by supplying - * the respective creator object ID. - * - * It does not fetch the current value from the data pool, which - * has to be done by calling the read() operation. - * Datasets can be used to access multiple local pool entries in an - * efficient way. A pointer to a dataset can be passed to register - * the pool variable in that dataset directly. - * @param poolId ID of the local pool entry. - * @param hkOwner object ID of the pool owner. - * @param dataSet The data set in which the variable shall register itself. - * If nullptr, the variable is not registered. - * @param setReadWriteMode Specify the read-write mode of the pool variable. - * - */ - LocalPoolVariable(object_id_t poolOwner, lp_id_t poolId, - DataSetIF* dataSet = nullptr, - pool_rwm_t setReadWriteMode = pool_rwm_t::VAR_READ_WRITE); - /** - * Variation which takes the global unique identifier of a pool variable. - * @param globalPoolId - * @param dataSet - * @param setReadWriteMode - */ - LocalPoolVariable(gp_id_t globalPoolId, DataSetIF* dataSet = nullptr, - pool_rwm_t setReadWriteMode = pool_rwm_t::VAR_READ_WRITE); + /** + * This constructor is used by data users like controllers to have + * access to the local pool variables of data creators by supplying + * the respective creator object ID. + * + * It does not fetch the current value from the data pool, which + * has to be done by calling the read() operation. + * Datasets can be used to access multiple local pool entries in an + * efficient way. A pointer to a dataset can be passed to register + * the pool variable in that dataset directly. + * @param poolId ID of the local pool entry. + * @param hkOwner object ID of the pool owner. + * @param dataSet The data set in which the variable shall register itself. + * If nullptr, the variable is not registered. + * @param setReadWriteMode Specify the read-write mode of the pool variable. + * + */ + LocalPoolVariable(object_id_t poolOwner, lp_id_t poolId, DataSetIF* dataSet = nullptr, + pool_rwm_t setReadWriteMode = pool_rwm_t::VAR_READ_WRITE); + /** + * Variation which takes the global unique identifier of a pool variable. + * @param globalPoolId + * @param dataSet + * @param setReadWriteMode + */ + LocalPoolVariable(gp_id_t globalPoolId, DataSetIF* dataSet = nullptr, + pool_rwm_t setReadWriteMode = pool_rwm_t::VAR_READ_WRITE); - virtual~ LocalPoolVariable() {}; + virtual ~LocalPoolVariable(){}; - /** - * @brief This is the local copy of the data pool entry. - * @details The user can work on this attribute - * just like he would on a simple local variable. - */ - T value = 0; + /** + * @brief This is the local copy of the data pool entry. + * @details The user can work on this attribute + * just like he would on a simple local variable. + */ + T value = 0; - ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, - SerializeIF::Endianness streamEndianness) const override; - virtual size_t getSerializedSize() const override; - virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - SerializeIF::Endianness streamEndianness) override; + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + SerializeIF::Endianness streamEndianness) const override; + virtual size_t getSerializedSize() const override; + virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + SerializeIF::Endianness streamEndianness) override; - /** - * @brief This is a call to read the array's values - * from the global data pool. - * @details - * When executed, this operation tries to fetch the pool entry with matching - * data pool id from the data pool and copies all array values and the valid - * information to its local attributes. - * In case of a failure (wrong type, size or pool id not found), the - * variable is set to zero and invalid. - * The read call is protected with a lock. - * It is recommended to use DataSets to read and commit multiple variables - * at once to avoid the overhead of unnecessary lock und unlock operations. - * - */ - ReturnValue_t read(MutexIF::TimeoutType timeoutType = - MutexIF::TimeoutType::WAITING, - uint32_t timeoutMs = 20) override; - /** - * @brief The commit call copies the array values back to the data pool. - * @details - * It checks type and size, as well as if the variable is writable. If so, - * the value is copied and the local valid flag is written back as well. - * The read call is protected with a lock. - * It is recommended to use DataSets to read and commit multiple variables - * at once to avoid the overhead of unnecessary lock und unlock operations. - */ - ReturnValue_t commit(MutexIF::TimeoutType timeoutType = - MutexIF::TimeoutType::WAITING, - uint32_t timeoutMs = 20) override; + /** + * @brief This is a call to read the array's values + * from the global data pool. + * @details + * When executed, this operation tries to fetch the pool entry with matching + * data pool id from the data pool and copies all array values and the valid + * information to its local attributes. + * In case of a failure (wrong type, size or pool id not found), the + * variable is set to zero and invalid. + * The read call is protected with a lock. + * It is recommended to use DataSets to read and commit multiple variables + * at once to avoid the overhead of unnecessary lock und unlock operations. + * + */ + ReturnValue_t read(MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, + uint32_t timeoutMs = 20) override; + /** + * @brief The commit call copies the array values back to the data pool. + * @details + * It checks type and size, as well as if the variable is writable. If so, + * the value is copied and the local valid flag is written back as well. + * The read call is protected with a lock. + * It is recommended to use DataSets to read and commit multiple variables + * at once to avoid the overhead of unnecessary lock und unlock operations. + */ + ReturnValue_t commit(MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, + uint32_t timeoutMs = 20) override; - /** - * @brief This commit function can be used to set the pool variable valid - * as well. - * @param setValid - * @param timeoutType - * @param timeoutMs - * @return - */ - ReturnValue_t commit(bool setValid, MutexIF::TimeoutType timeoutType = - MutexIF::TimeoutType::WAITING, - uint32_t timeoutMs = 20); + /** + * @brief This commit function can be used to set the pool variable valid + * as well. + * @param setValid + * @param timeoutType + * @param timeoutMs + * @return + */ + ReturnValue_t commit(bool setValid, + MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, + uint32_t timeoutMs = 20); - LocalPoolVariable &operator=(const T& newValue); - LocalPoolVariable &operator=(const LocalPoolVariable& newPoolVariable); + LocalPoolVariable& operator=(const T& newValue); + LocalPoolVariable& operator=(const LocalPoolVariable& newPoolVariable); - //! Explicit type conversion operator. Allows casting the class to - //! its template type to perform operations on value. - explicit operator T() const; + //! Explicit type conversion operator. Allows casting the class to + //! its template type to perform operations on value. + explicit operator T() const; - bool operator==(const LocalPoolVariable& other) const; - bool operator==(const T& other) const; + bool operator==(const LocalPoolVariable& other) const; + bool operator==(const T& other) const; - bool operator!=(const LocalPoolVariable& other) const; - bool operator!=(const T& other) const; + bool operator!=(const LocalPoolVariable& other) const; + bool operator!=(const T& other) const; - bool operator<(const LocalPoolVariable& other) const; - bool operator<(const T& other) const; + bool operator<(const LocalPoolVariable& other) const; + bool operator<(const T& other) const; - bool operator>(const LocalPoolVariable& other) const; - bool operator>(const T& other) const; + bool operator>(const LocalPoolVariable& other) const; + bool operator>(const T& other) const; -protected: - /** - * @brief Like #read, but without a lock protection of the global pool. - * @details - * The operation does NOT provide any mutual exclusive protection by itself. - * This can be used if the lock is handled externally to avoid the overhead - * of consecutive lock und unlock operations. - * Declared protected to discourage free public usage. - */ - ReturnValue_t readWithoutLock() override; - /** - * @brief Like #commit, but without a lock protection of the global pool. - * @details - * The operation does NOT provide any mutual exclusive protection by itself. - * This can be used if the lock is handled externally to avoid the overhead - * of consecutive lock und unlock operations. - * Declared protected to discourage free public usage. - */ - ReturnValue_t commitWithoutLock() override; + protected: + /** + * @brief Like #read, but without a lock protection of the global pool. + * @details + * The operation does NOT provide any mutual exclusive protection by itself. + * This can be used if the lock is handled externally to avoid the overhead + * of consecutive lock und unlock operations. + * Declared protected to discourage free public usage. + */ + ReturnValue_t readWithoutLock() override; + /** + * @brief Like #commit, but without a lock protection of the global pool. + * @details + * The operation does NOT provide any mutual exclusive protection by itself. + * This can be used if the lock is handled externally to avoid the overhead + * of consecutive lock und unlock operations. + * Declared protected to discourage free public usage. + */ + ReturnValue_t commitWithoutLock() override; #if FSFW_CPP_OSTREAM_ENABLED == 1 - // std::ostream is the type for object std::cout - template - friend std::ostream& operator<< (std::ostream &out, - const LocalPoolVariable &var); + // std::ostream is the type for object std::cout + template + friend std::ostream& operator<<(std::ostream& out, const LocalPoolVariable& var); #endif }; #include "LocalPoolVariable.tpp" -template +template using lp_var_t = LocalPoolVariable; using lp_bool_t = LocalPoolVariable; diff --git a/src/fsfw/datapoollocal/LocalPoolVector.h b/src/fsfw/datapoollocal/LocalPoolVector.h index 591dd6f3..aaaa051d 100644 --- a/src/fsfw/datapoollocal/LocalPoolVector.h +++ b/src/fsfw/datapoollocal/LocalPoolVector.h @@ -1,16 +1,14 @@ #ifndef FSFW_DATAPOOLLOCAL_LOCALPOOLVECTOR_H_ #define FSFW_DATAPOOLLOCAL_LOCALPOOLVECTOR_H_ -#include "LocalPoolObjectBase.h" -#include "internal/LocalDpManagerAttorney.h" - #include "../datapool/DataSetIF.h" #include "../datapool/PoolEntry.h" #include "../datapool/PoolVariableIF.h" #include "../datapoollocal/LocalDataPoolManager.h" #include "../serialize/SerializeAdapter.h" #include "../serviceinterface/ServiceInterface.h" - +#include "LocalPoolObjectBase.h" +#include "internal/LocalDpManagerAttorney.h" /** * @brief This is the access class for array-type data pool entries. @@ -32,157 +30,146 @@ * dynamic memory allocation. * @ingroup data_pool */ -template -class LocalPoolVector: public LocalPoolObjectBase { -public: - LocalPoolVector() = delete; - /** - * This constructor is used by the data creators to have pool variable - * instances which can also be stored in datasets. - * It does not fetch the current value from the data pool. This is performed - * by the read() operation (which is not thread-safe). - * Datasets can be used to access local pool entires in a thread-safe way. - * @param poolId ID of the local pool entry. - * @param hkOwner Pointer of the owner. This will generally be the calling - * class itself which passes "this". - * @param setReadWriteMode Specify the read-write mode of the pool variable. - * @param dataSet The data set in which the variable shall register itself. - * If nullptr, the variable is not registered. - */ - LocalPoolVector(HasLocalDataPoolIF* hkOwner, lp_id_t poolId, - DataSetIF* dataSet = nullptr, - pool_rwm_t setReadWriteMode = pool_rwm_t::VAR_READ_WRITE); +template +class LocalPoolVector : public LocalPoolObjectBase { + public: + LocalPoolVector() = delete; + /** + * This constructor is used by the data creators to have pool variable + * instances which can also be stored in datasets. + * It does not fetch the current value from the data pool. This is performed + * by the read() operation (which is not thread-safe). + * Datasets can be used to access local pool entires in a thread-safe way. + * @param poolId ID of the local pool entry. + * @param hkOwner Pointer of the owner. This will generally be the calling + * class itself which passes "this". + * @param setReadWriteMode Specify the read-write mode of the pool variable. + * @param dataSet The data set in which the variable shall register itself. + * If nullptr, the variable is not registered. + */ + LocalPoolVector(HasLocalDataPoolIF* hkOwner, lp_id_t poolId, DataSetIF* dataSet = nullptr, + pool_rwm_t setReadWriteMode = pool_rwm_t::VAR_READ_WRITE); - /** - * This constructor is used by data users like controllers to have - * access to the local pool variables of data creators by supplying - * the respective creator object ID. - * It does not fetch the current value from the data pool. This is performed - * by the read() operation (which is not thread-safe). - * Datasets can be used to access local pool entires in a thread-safe way. - * @param poolId ID of the local pool entry. - * @param hkOwner Pointer of the owner. This will generally be the calling - * class itself which passes "this". - * @param setReadWriteMode Specify the read-write mode of the pool variable. - * @param dataSet The data set in which the variable shall register itself. - * If nullptr, the variable is not registered. - */ - LocalPoolVector(object_id_t poolOwner, lp_id_t poolId, - DataSetIF* dataSet = nullptr, - pool_rwm_t setReadWriteMode = pool_rwm_t::VAR_READ_WRITE); - /** - * Variation which takes the unique global identifier of a local pool - * vector. - * @param globalPoolId - * @param dataSet - * @param setReadWriteMode - */ - LocalPoolVector(gp_id_t globalPoolId, DataSetIF* dataSet = nullptr, - pool_rwm_t setReadWriteMode = pool_rwm_t::VAR_READ_WRITE); + /** + * This constructor is used by data users like controllers to have + * access to the local pool variables of data creators by supplying + * the respective creator object ID. + * It does not fetch the current value from the data pool. This is performed + * by the read() operation (which is not thread-safe). + * Datasets can be used to access local pool entires in a thread-safe way. + * @param poolId ID of the local pool entry. + * @param hkOwner Pointer of the owner. This will generally be the calling + * class itself which passes "this". + * @param setReadWriteMode Specify the read-write mode of the pool variable. + * @param dataSet The data set in which the variable shall register itself. + * If nullptr, the variable is not registered. + */ + LocalPoolVector(object_id_t poolOwner, lp_id_t poolId, DataSetIF* dataSet = nullptr, + pool_rwm_t setReadWriteMode = pool_rwm_t::VAR_READ_WRITE); + /** + * Variation which takes the unique global identifier of a local pool + * vector. + * @param globalPoolId + * @param dataSet + * @param setReadWriteMode + */ + LocalPoolVector(gp_id_t globalPoolId, DataSetIF* dataSet = nullptr, + pool_rwm_t setReadWriteMode = pool_rwm_t::VAR_READ_WRITE); - /** - * @brief This is the local copy of the data pool entry. - * @details - * The user can work on this attribute just like he would on a local - * array of this type. - */ - T value[vectorSize]= {}; - /** - * @brief The classes destructor is empty. - * @details If commit() was not called, the local value is - * discarded and not written back to the data pool. - */ - ~LocalPoolVector() {}; - /** - * @brief The operation returns the number of array entries - * in this variable. - */ - uint8_t getSize() { - return vectorSize; - } + /** + * @brief This is the local copy of the data pool entry. + * @details + * The user can work on this attribute just like he would on a local + * array of this type. + */ + T value[vectorSize] = {}; + /** + * @brief The classes destructor is empty. + * @details If commit() was not called, the local value is + * discarded and not written back to the data pool. + */ + ~LocalPoolVector(){}; + /** + * @brief The operation returns the number of array entries + * in this variable. + */ + uint8_t getSize() { return vectorSize; } - T& operator [](size_t i); - const T &operator [](size_t i) const; + T& operator[](size_t i); + const T& operator[](size_t i) const; - virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, - const size_t maxSize, - SerializeIF::Endianness streamEndiannes) const override; - virtual size_t getSerializedSize() const override; - virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - SerializeIF::Endianness streamEndianness) override; + virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, const size_t maxSize, + SerializeIF::Endianness streamEndiannes) const override; + virtual size_t getSerializedSize() const override; + virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + SerializeIF::Endianness streamEndianness) override; - /** - * @brief This is a call to read the array's values - * from the global data pool. - * @details - * When executed, this operation tries to fetch the pool entry with matching - * data pool id from the data pool and copies all array values and the valid - * information to its local attributes. - * In case of a failure (wrong type, size or pool id not found), the - * variable is set to zero and invalid. - * The read call is protected with a lock. - * It is recommended to use DataSets to read and commit multiple variables - * at once to avoid the overhead of unnecessary lock und unlock operations. - */ - ReturnValue_t read(MutexIF::TimeoutType timeoutType = - MutexIF::TimeoutType::WAITING, - uint32_t timeoutMs = 20) override; + /** + * @brief This is a call to read the array's values + * from the global data pool. + * @details + * When executed, this operation tries to fetch the pool entry with matching + * data pool id from the data pool and copies all array values and the valid + * information to its local attributes. + * In case of a failure (wrong type, size or pool id not found), the + * variable is set to zero and invalid. + * The read call is protected with a lock. + * It is recommended to use DataSets to read and commit multiple variables + * at once to avoid the overhead of unnecessary lock und unlock operations. + */ + ReturnValue_t read(MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, + uint32_t timeoutMs = 20) override; - /** - * @brief The commit call copies the array values back to the data pool. - * @details - * It checks type and size, as well as if the variable is writable. If so, - * the value is copied and the local valid flag is written back as well. - * The read call is protected with a lock. - * It is recommended to use DataSets to read and commit multiple variables - * at once to avoid the overhead of unnecessary lock und unlock operations. - */ - ReturnValue_t commit(MutexIF::TimeoutType timeoutType = - MutexIF::TimeoutType::WAITING, - uint32_t timeoutMs = 20) override; + /** + * @brief The commit call copies the array values back to the data pool. + * @details + * It checks type and size, as well as if the variable is writable. If so, + * the value is copied and the local valid flag is written back as well. + * The read call is protected with a lock. + * It is recommended to use DataSets to read and commit multiple variables + * at once to avoid the overhead of unnecessary lock und unlock operations. + */ + ReturnValue_t commit(MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, + uint32_t timeoutMs = 20) override; - /** - * @brief This commit call also sets the validity of the pool entry. - * @details - */ - ReturnValue_t commit(bool valid, MutexIF::TimeoutType timeoutType = - MutexIF::TimeoutType::WAITING, - uint32_t timeoutMs = 20); + /** + * @brief This commit call also sets the validity of the pool entry. + * @details + */ + ReturnValue_t commit(bool valid, MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, + uint32_t timeoutMs = 20); -protected: - /** - * @brief Like #read, but without a lock protection of the global pool. - * @details - * The operation does NOT provide any mutual exclusive protection by itself. - * This can be used if the lock is handled externally to avoid the overhead - * of consecutive lock und unlock operations. - * Declared protected to discourage free public usage. - */ - ReturnValue_t readWithoutLock() override; - /** - * @brief Like #commit, but without a lock protection of the global pool. - * @details - * The operation does NOT provide any mutual exclusive protection by itself. - * This can be used if the lock is handled externally to avoid the overhead - * of consecutive lock und unlock operations. - * Declared protected to discourage free public usage. - */ - ReturnValue_t commitWithoutLock() override; - -private: + protected: + /** + * @brief Like #read, but without a lock protection of the global pool. + * @details + * The operation does NOT provide any mutual exclusive protection by itself. + * This can be used if the lock is handled externally to avoid the overhead + * of consecutive lock und unlock operations. + * Declared protected to discourage free public usage. + */ + ReturnValue_t readWithoutLock() override; + /** + * @brief Like #commit, but without a lock protection of the global pool. + * @details + * The operation does NOT provide any mutual exclusive protection by itself. + * This can be used if the lock is handled externally to avoid the overhead + * of consecutive lock und unlock operations. + * Declared protected to discourage free public usage. + */ + ReturnValue_t commitWithoutLock() override; + private: #if FSFW_CPP_OSTREAM_ENABLED == 1 - // std::ostream is the type for object std::cout - template - friend std::ostream& operator<< (std::ostream &out, - const LocalPoolVector &var); + // std::ostream is the type for object std::cout + template + friend std::ostream& operator<<(std::ostream& out, const LocalPoolVector& var); #endif - }; #include "LocalPoolVector.tpp" -template +template using lp_vec_t = LocalPoolVector; #endif /* FSFW_DATAPOOLLOCAL_LOCALPOOLVECTOR_H_ */ diff --git a/src/fsfw/datapoollocal/MarkChangedIF.h b/src/fsfw/datapoollocal/MarkChangedIF.h index e575d1d3..21667dda 100644 --- a/src/fsfw/datapoollocal/MarkChangedIF.h +++ b/src/fsfw/datapoollocal/MarkChangedIF.h @@ -5,13 +5,11 @@ * Common interface for local pool entities which can be marked as changed. */ class MarkChangedIF { -public: - virtual~ MarkChangedIF() {}; + public: + virtual ~MarkChangedIF(){}; - virtual bool hasChanged() const = 0; - virtual void setChanged(bool changed) = 0; + virtual bool hasChanged() const = 0; + virtual void setChanged(bool changed) = 0; }; - - #endif /* FSFW_DATAPOOLLOCAL_MARKCHANGEDIF_H_ */ diff --git a/src/fsfw/datapoollocal/ProvidesDataPoolSubscriptionIF.h b/src/fsfw/datapoollocal/ProvidesDataPoolSubscriptionIF.h index 1c34099a..1f13a09d 100644 --- a/src/fsfw/datapoollocal/ProvidesDataPoolSubscriptionIF.h +++ b/src/fsfw/datapoollocal/ProvidesDataPoolSubscriptionIF.h @@ -1,70 +1,73 @@ #ifndef FSFW_DATAPOOLLOCAL_PROVIDESDATAPOOLSUBSCRIPTION_H_ #define FSFW_DATAPOOLLOCAL_PROVIDESDATAPOOLSUBSCRIPTION_H_ -#include "localPoolDefinitions.h" #include "../ipc/messageQueueDefinitions.h" #include "../returnvalues/HasReturnvaluesIF.h" - +#include "localPoolDefinitions.h" class ProvidesDataPoolSubscriptionIF { -public: - virtual ~ProvidesDataPoolSubscriptionIF(){}; + public: + virtual ~ProvidesDataPoolSubscriptionIF(){}; - /** - * @brief Subscribe for the generation of periodic packets. - * @details - * This subscription mechanism will generally be used by the data creator - * to generate housekeeping packets which are downlinked directly. - * @return - */ - virtual ReturnValue_t subscribeForPeriodicPacket(sid_t sid, bool enableReporting, - float collectionInterval, bool isDiagnostics, object_id_t packetDestination) = 0; - /** - * @brief Subscribe for the generation of packets if the dataset - * is marked as changed. - * @details - * This subscription mechanism will generally be used by the data creator. - * @param sid - * @param isDiagnostics - * @param packetDestination - * @return - */ - virtual ReturnValue_t subscribeForUpdatePacket(sid_t sid, bool reportingEnabled, - bool isDiagnostics, object_id_t packetDestination) = 0; - /** - * @brief Subscribe for a notification message which will be sent - * if a dataset has changed. - * @details - * This subscription mechanism will generally be used internally by - * other software components. - * @param setId Set ID of the set to receive update messages from. - * @param destinationObject Object ID of the receiver. - * @param targetQueueId Receiver queue ID - * @param generateSnapshot If this is set to true, a copy of the current data with a - * timestamp will be generated and sent via message. - * Otherwise, only an notification message is sent. - * @return - */ - virtual ReturnValue_t subscribeForSetUpdateMessage(const uint32_t setId, - object_id_t destinationObject, MessageQueueId_t targetQueueId, - bool generateSnapshot) = 0; - /** - * @brief Subscribe for an notification message which will be sent if a - * pool variable has changed. - * @details - * This subscription mechanism will generally be used internally by - * other software components. - * @param localPoolId Pool ID of the pool variable - * @param destinationObject Object ID of the receiver - * @param targetQueueId Receiver queue ID - * @param generateSnapshot If this is set to true, a copy of the current data with a - * timestamp will be generated and sent via message. Otherwise, - * only an notification message is sent. - * @return - */ - virtual ReturnValue_t subscribeForVariableUpdateMessage(const lp_id_t localPoolId, - object_id_t destinationObject, MessageQueueId_t targetQueueId, - bool generateSnapshot) = 0; + /** + * @brief Subscribe for the generation of periodic packets. + * @details + * This subscription mechanism will generally be used by the data creator + * to generate housekeeping packets which are downlinked directly. + * @return + */ + virtual ReturnValue_t subscribeForPeriodicPacket(sid_t sid, bool enableReporting, + float collectionInterval, bool isDiagnostics, + object_id_t packetDestination) = 0; + /** + * @brief Subscribe for the generation of packets if the dataset + * is marked as changed. + * @details + * This subscription mechanism will generally be used by the data creator. + * @param sid + * @param isDiagnostics + * @param packetDestination + * @return + */ + virtual ReturnValue_t subscribeForUpdatePacket(sid_t sid, bool reportingEnabled, + bool isDiagnostics, + object_id_t packetDestination) = 0; + /** + * @brief Subscribe for a notification message which will be sent + * if a dataset has changed. + * @details + * This subscription mechanism will generally be used internally by + * other software components. + * @param setId Set ID of the set to receive update messages from. + * @param destinationObject Object ID of the receiver. + * @param targetQueueId Receiver queue ID + * @param generateSnapshot If this is set to true, a copy of the current data with a + * timestamp will be generated and sent via message. + * Otherwise, only an notification message is sent. + * @return + */ + virtual ReturnValue_t subscribeForSetUpdateMessage(const uint32_t setId, + object_id_t destinationObject, + MessageQueueId_t targetQueueId, + bool generateSnapshot) = 0; + /** + * @brief Subscribe for an notification message which will be sent if a + * pool variable has changed. + * @details + * This subscription mechanism will generally be used internally by + * other software components. + * @param localPoolId Pool ID of the pool variable + * @param destinationObject Object ID of the receiver + * @param targetQueueId Receiver queue ID + * @param generateSnapshot If this is set to true, a copy of the current data with a + * timestamp will be generated and sent via message. Otherwise, + * only an notification message is sent. + * @return + */ + virtual ReturnValue_t subscribeForVariableUpdateMessage(const lp_id_t localPoolId, + object_id_t destinationObject, + MessageQueueId_t targetQueueId, + bool generateSnapshot) = 0; }; #endif /* FSFW_DATAPOOLLOCAL_PROVIDESDATAPOOLSUBSCRIPTION_H_ */ diff --git a/src/fsfw/datapoollocal/SharedLocalDataSet.cpp b/src/fsfw/datapoollocal/SharedLocalDataSet.cpp index 2ee00aca..248c1577 100644 --- a/src/fsfw/datapoollocal/SharedLocalDataSet.cpp +++ b/src/fsfw/datapoollocal/SharedLocalDataSet.cpp @@ -1,37 +1,33 @@ #include "fsfw/datapoollocal/SharedLocalDataSet.h" - -SharedLocalDataSet::SharedLocalDataSet(object_id_t objectId, sid_t sid, - const size_t maxSize): SystemObject(objectId), - LocalPoolDataSetBase(sid, nullptr, maxSize), poolVarVector(maxSize) { - this->setContainer(poolVarVector.data()); - datasetLock = MutexFactory::instance()->createMutex(); +SharedLocalDataSet::SharedLocalDataSet(object_id_t objectId, sid_t sid, const size_t maxSize) + : SystemObject(objectId), LocalPoolDataSetBase(sid, nullptr, maxSize), poolVarVector(maxSize) { + this->setContainer(poolVarVector.data()); + datasetLock = MutexFactory::instance()->createMutex(); } -SharedLocalDataSet::SharedLocalDataSet(object_id_t objectId, - HasLocalDataPoolIF *owner, uint32_t setId, - const size_t maxSize): SystemObject(objectId), - LocalPoolDataSetBase(owner, setId, nullptr, maxSize), poolVarVector(maxSize) { - this->setContainer(poolVarVector.data()); - datasetLock = MutexFactory::instance()->createMutex(); +SharedLocalDataSet::SharedLocalDataSet(object_id_t objectId, HasLocalDataPoolIF *owner, + uint32_t setId, const size_t maxSize) + : SystemObject(objectId), + LocalPoolDataSetBase(owner, setId, nullptr, maxSize), + poolVarVector(maxSize) { + this->setContainer(poolVarVector.data()); + datasetLock = MutexFactory::instance()->createMutex(); } ReturnValue_t SharedLocalDataSet::lockDataset(MutexIF::TimeoutType timeoutType, - dur_millis_t mutexTimeout) { - if(datasetLock != nullptr) { - return datasetLock->lockMutex(timeoutType, mutexTimeout); - } - return HasReturnvaluesIF::RETURN_FAILED; + dur_millis_t mutexTimeout) { + if (datasetLock != nullptr) { + return datasetLock->lockMutex(timeoutType, mutexTimeout); + } + return HasReturnvaluesIF::RETURN_FAILED; } - -SharedLocalDataSet::~SharedLocalDataSet() { - MutexFactory::instance()->deleteMutex(datasetLock); -} +SharedLocalDataSet::~SharedLocalDataSet() { MutexFactory::instance()->deleteMutex(datasetLock); } ReturnValue_t SharedLocalDataSet::unlockDataset() { - if(datasetLock != nullptr) { - return datasetLock->unlockMutex(); - } - return HasReturnvaluesIF::RETURN_FAILED; + if (datasetLock != nullptr) { + return datasetLock->unlockMutex(); + } + return HasReturnvaluesIF::RETURN_FAILED; } diff --git a/src/fsfw/datapoollocal/SharedLocalDataSet.h b/src/fsfw/datapoollocal/SharedLocalDataSet.h index 8d12610a..e65bad19 100644 --- a/src/fsfw/datapoollocal/SharedLocalDataSet.h +++ b/src/fsfw/datapoollocal/SharedLocalDataSet.h @@ -1,10 +1,11 @@ #ifndef FSFW_DATAPOOLLOCAL_SHAREDLOCALDATASET_H_ #define FSFW_DATAPOOLLOCAL_SHAREDLOCALDATASET_H_ -#include "LocalPoolDataSetBase.h" +#include + #include "../datapool/SharedDataSetIF.h" #include "../objectmanager/SystemObject.h" -#include +#include "LocalPoolDataSetBase.h" /** * This local dataset variation can be used if the dataset is used concurrently across @@ -14,25 +15,23 @@ * The user is completely responsible for lockingand unlocking the dataset when using the * shared dataset. */ -class SharedLocalDataSet: - public SystemObject, - public LocalPoolDataSetBase, - public SharedDataSetIF { -public: - SharedLocalDataSet(object_id_t objectId, HasLocalDataPoolIF* owner, uint32_t setId, - const size_t maxSize); - SharedLocalDataSet(object_id_t objectId, sid_t sid, const size_t maxSize); +class SharedLocalDataSet : public SystemObject, + public LocalPoolDataSetBase, + public SharedDataSetIF { + public: + SharedLocalDataSet(object_id_t objectId, HasLocalDataPoolIF* owner, uint32_t setId, + const size_t maxSize); + SharedLocalDataSet(object_id_t objectId, sid_t sid, const size_t maxSize); - virtual~ SharedLocalDataSet(); + virtual ~SharedLocalDataSet(); - ReturnValue_t lockDataset(MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, - dur_millis_t mutexTimeout = 20) override; - ReturnValue_t unlockDataset() override; -private: + ReturnValue_t lockDataset(MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING, + dur_millis_t mutexTimeout = 20) override; + ReturnValue_t unlockDataset() override; - MutexIF* datasetLock = nullptr; - std::vector poolVarVector; + private: + MutexIF* datasetLock = nullptr; + std::vector poolVarVector; }; - #endif /* FSFW_DATAPOOLLOCAL_SHAREDLOCALDATASET_H_ */ diff --git a/src/fsfw/datapoollocal/StaticLocalDataSet.h b/src/fsfw/datapoollocal/StaticLocalDataSet.h index 08ef6de6..dd264e58 100644 --- a/src/fsfw/datapoollocal/StaticLocalDataSet.h +++ b/src/fsfw/datapoollocal/StaticLocalDataSet.h @@ -1,13 +1,13 @@ #ifndef FSFW_DATAPOOLLOCAL_STATICLOCALDATASET_H_ #define FSFW_DATAPOOLLOCAL_STATICLOCALDATASET_H_ +#include + +#include "../objectmanager/SystemObjectIF.h" #include "LocalPoolDataSetBase.h" #include "LocalPoolVariable.h" #include "LocalPoolVector.h" -#include "../objectmanager/SystemObjectIF.h" -#include - /** * @brief This dataset type can be used to group related pool variables if the number of * variables is fixed. @@ -22,31 +22,31 @@ * beforehand. */ template -class StaticLocalDataSet: public LocalPoolDataSetBase { -public: - /** - * Constructor used by data owner and creator like device handlers. - * This constructor also initialized the components required for - * periodic handling. - * @param hkOwner - * @param setId - */ - StaticLocalDataSet(HasLocalDataPoolIF* hkOwner, uint32_t setId): - LocalPoolDataSetBase(hkOwner, setId, nullptr, NUM_VARIABLES) { - this->setContainer(poolVarList.data()); - } +class StaticLocalDataSet : public LocalPoolDataSetBase { + public: + /** + * Constructor used by data owner and creator like device handlers. + * This constructor also initialized the components required for + * periodic handling. + * @param hkOwner + * @param setId + */ + StaticLocalDataSet(HasLocalDataPoolIF* hkOwner, uint32_t setId) + : LocalPoolDataSetBase(hkOwner, setId, nullptr, NUM_VARIABLES) { + this->setContainer(poolVarList.data()); + } - /** - * Constructor used by data users like controllers. - * @param hkOwner - * @param setId - */ - StaticLocalDataSet(sid_t sid): LocalPoolDataSetBase(sid, nullptr, NUM_VARIABLES) { - this->setContainer(poolVarList.data()); - } + /** + * Constructor used by data users like controllers. + * @param hkOwner + * @param setId + */ + StaticLocalDataSet(sid_t sid) : LocalPoolDataSetBase(sid, nullptr, NUM_VARIABLES) { + this->setContainer(poolVarList.data()); + } -private: - std::array poolVarList; + private: + std::array poolVarList; }; #endif /* FSFW_DATAPOOLLOCAL_STATICLOCALDATASET_H_ */ diff --git a/src/fsfw/datapoollocal/internal/HasLocalDpIFManagerAttorney.cpp b/src/fsfw/datapoollocal/internal/HasLocalDpIFManagerAttorney.cpp index a275626b..14fd9bbc 100644 --- a/src/fsfw/datapoollocal/internal/HasLocalDpIFManagerAttorney.cpp +++ b/src/fsfw/datapoollocal/internal/HasLocalDpIFManagerAttorney.cpp @@ -1,18 +1,19 @@ #include "HasLocalDpIFManagerAttorney.h" -#include "fsfw/datapoollocal/LocalPoolObjectBase.h" -#include "fsfw/datapoollocal/LocalPoolDataSetBase.h" + #include "fsfw/datapoollocal/HasLocalDataPoolIF.h" +#include "fsfw/datapoollocal/LocalPoolDataSetBase.h" +#include "fsfw/datapoollocal/LocalPoolObjectBase.h" LocalPoolDataSetBase* HasLocalDpIFManagerAttorney::getDataSetHandle(HasLocalDataPoolIF* clientIF, - sid_t sid) { - return clientIF->getDataSetHandle(sid); + sid_t sid) { + return clientIF->getDataSetHandle(sid); } LocalPoolObjectBase* HasLocalDpIFManagerAttorney::getPoolObjectHandle(HasLocalDataPoolIF* clientIF, - lp_id_t localPoolId) { - return clientIF->getPoolObjectHandle(localPoolId); + lp_id_t localPoolId) { + return clientIF->getPoolObjectHandle(localPoolId); } object_id_t HasLocalDpIFManagerAttorney::getObjectId(HasLocalDataPoolIF* clientIF) { - return clientIF->getObjectId(); + return clientIF->getObjectId(); } diff --git a/src/fsfw/datapoollocal/internal/HasLocalDpIFManagerAttorney.h b/src/fsfw/datapoollocal/internal/HasLocalDpIFManagerAttorney.h index a82ee489..f8547e10 100644 --- a/src/fsfw/datapoollocal/internal/HasLocalDpIFManagerAttorney.h +++ b/src/fsfw/datapoollocal/internal/HasLocalDpIFManagerAttorney.h @@ -8,15 +8,14 @@ class LocalPoolDataSetBase; class LocalPoolObjectBase; class HasLocalDpIFManagerAttorney { + static LocalPoolDataSetBase* getDataSetHandle(HasLocalDataPoolIF* clientIF, sid_t sid); - static LocalPoolDataSetBase* getDataSetHandle(HasLocalDataPoolIF* clientIF, sid_t sid); + static LocalPoolObjectBase* getPoolObjectHandle(HasLocalDataPoolIF* clientIF, + lp_id_t localPoolId); - static LocalPoolObjectBase* getPoolObjectHandle(HasLocalDataPoolIF* clientIF, - lp_id_t localPoolId); + static object_id_t getObjectId(HasLocalDataPoolIF* clientIF); - static object_id_t getObjectId(HasLocalDataPoolIF* clientIF); - - friend class LocalDataPoolManager; + friend class LocalDataPoolManager; }; #endif /* FSFW_DATAPOOLLOCAL_HASLOCALDPIFMANAGERATTORNEY_H_ */ diff --git a/src/fsfw/datapoollocal/internal/HasLocalDpIFUserAttorney.cpp b/src/fsfw/datapoollocal/internal/HasLocalDpIFUserAttorney.cpp index 8c52fbfb..baa2d9a1 100644 --- a/src/fsfw/datapoollocal/internal/HasLocalDpIFUserAttorney.cpp +++ b/src/fsfw/datapoollocal/internal/HasLocalDpIFUserAttorney.cpp @@ -1,7 +1,8 @@ #include "HasLocalDpIFUserAttorney.h" + #include "fsfw/datapoollocal/AccessLocalPoolF.h" #include "fsfw/datapoollocal/HasLocalDataPoolIF.h" -AccessPoolManagerIF* HasLocalDpIFUserAttorney::getAccessorHandle(HasLocalDataPoolIF *clientIF) { - return clientIF->getAccessorHandle(); +AccessPoolManagerIF* HasLocalDpIFUserAttorney::getAccessorHandle(HasLocalDataPoolIF* clientIF) { + return clientIF->getAccessorHandle(); } diff --git a/src/fsfw/datapoollocal/internal/HasLocalDpIFUserAttorney.h b/src/fsfw/datapoollocal/internal/HasLocalDpIFUserAttorney.h index 77eaa8bd..72ea0a94 100644 --- a/src/fsfw/datapoollocal/internal/HasLocalDpIFUserAttorney.h +++ b/src/fsfw/datapoollocal/internal/HasLocalDpIFUserAttorney.h @@ -5,14 +5,11 @@ class HasLocalDataPoolIF; class AccessPoolManagerIF; class HasLocalDpIFUserAttorney { -private: - - static AccessPoolManagerIF* getAccessorHandle(HasLocalDataPoolIF* clientIF); - - friend class LocalPoolObjectBase; - friend class LocalPoolDataSetBase; + private: + static AccessPoolManagerIF* getAccessorHandle(HasLocalDataPoolIF* clientIF); + friend class LocalPoolObjectBase; + friend class LocalPoolDataSetBase; }; - #endif /* FSFW_DATAPOOLLOCAL_HASLOCALDPIFUSERATTORNEY_H_ */ diff --git a/src/fsfw/datapoollocal/internal/LocalDpManagerAttorney.h b/src/fsfw/datapoollocal/internal/LocalDpManagerAttorney.h index 994f0613..95051a3e 100644 --- a/src/fsfw/datapoollocal/internal/LocalDpManagerAttorney.h +++ b/src/fsfw/datapoollocal/internal/LocalDpManagerAttorney.h @@ -14,18 +14,19 @@ * See: https://en.wikibooks.org/wiki/More_C%2B%2B_Idioms/Friendship_and_the_Attorney-Client */ class LocalDpManagerAttorney { -private: - template static ReturnValue_t fetchPoolEntry(LocalDataPoolManager& manager, - lp_id_t localPoolId, PoolEntry **poolEntry) { - return manager.fetchPoolEntry(localPoolId, poolEntry); - } + private: + template + static ReturnValue_t fetchPoolEntry(LocalDataPoolManager& manager, lp_id_t localPoolId, + PoolEntry** poolEntry) { + return manager.fetchPoolEntry(localPoolId, poolEntry); + } - static MutexIF* getMutexHandle(LocalDataPoolManager& manager) { - return manager.getMutexHandle(); - } + static MutexIF* getMutexHandle(LocalDataPoolManager& manager) { return manager.getMutexHandle(); } - template friend class LocalPoolVariable; - template friend class LocalPoolVector; + template + friend class LocalPoolVariable; + template + friend class LocalPoolVector; }; #endif /* FSFW_DATAPOOLLOCAL_LOCALDPMANAGERATTORNEY_H_ */ diff --git a/src/fsfw/datapoollocal/internal/LocalPoolDataSetAttorney.h b/src/fsfw/datapoollocal/internal/LocalPoolDataSetAttorney.h index 9e46cffd..e7dbd0c7 100644 --- a/src/fsfw/datapoollocal/internal/LocalPoolDataSetAttorney.h +++ b/src/fsfw/datapoollocal/internal/LocalPoolDataSetAttorney.h @@ -4,35 +4,31 @@ #include "fsfw/datapoollocal/LocalPoolDataSetBase.h" class LocalPoolDataSetAttorney { -private: - static void setDiagnostic(LocalPoolDataSetBase& set, bool diagnostics) { - set.setDiagnostic(diagnostics); - } + private: + static void setDiagnostic(LocalPoolDataSetBase& set, bool diagnostics) { + set.setDiagnostic(diagnostics); + } - static bool isDiagnostics(LocalPoolDataSetBase& set) { - return set.isDiagnostics(); - } + static bool isDiagnostics(LocalPoolDataSetBase& set) { return set.isDiagnostics(); } - static void initializePeriodicHelper(LocalPoolDataSetBase& set, float collectionInterval, - uint32_t minimumPeriodicIntervalMs, uint8_t nonDiagIntervalFactor = 5) { - set.initializePeriodicHelper(collectionInterval, minimumPeriodicIntervalMs, - nonDiagIntervalFactor); - } + static void initializePeriodicHelper(LocalPoolDataSetBase& set, float collectionInterval, + uint32_t minimumPeriodicIntervalMs, + uint8_t nonDiagIntervalFactor = 5) { + set.initializePeriodicHelper(collectionInterval, minimumPeriodicIntervalMs, + nonDiagIntervalFactor); + } - static void setReportingEnabled(LocalPoolDataSetBase& set, bool enabled) { - set.setReportingEnabled(enabled); - } + static void setReportingEnabled(LocalPoolDataSetBase& set, bool enabled) { + set.setReportingEnabled(enabled); + } - static bool getReportingEnabled(LocalPoolDataSetBase& set) { - return set.getReportingEnabled(); - } + static bool getReportingEnabled(LocalPoolDataSetBase& set) { return set.getReportingEnabled(); } - static PeriodicHousekeepingHelper* getPeriodicHelper(LocalPoolDataSetBase& set) { - return set.periodicHelper; - } + static PeriodicHousekeepingHelper* getPeriodicHelper(LocalPoolDataSetBase& set) { + return set.periodicHelper; + } - friend class LocalDataPoolManager; + friend class LocalDataPoolManager; }; - #endif /* FSFW_DATAPOOLLOCAL_LOCALPOOLDATASETATTORNEY_H_ */ diff --git a/src/fsfw/datapoollocal/localPoolDefinitions.h b/src/fsfw/datapoollocal/localPoolDefinitions.h index daab8b9c..07bfbfa8 100644 --- a/src/fsfw/datapoollocal/localPoolDefinitions.h +++ b/src/fsfw/datapoollocal/localPoolDefinitions.h @@ -1,13 +1,13 @@ #ifndef FSFW_DATAPOOLLOCAL_LOCALPOOLDEFINITIONS_H_ #define FSFW_DATAPOOLLOCAL_LOCALPOOLDEFINITIONS_H_ +#include +#include + #include "../datapool/PoolEntryIF.h" #include "../objectmanager/SystemObjectIF.h" #include "../objectmanager/frameworkObjects.h" -#include -#include - /** * @brief Type definition for local pool entries. */ @@ -23,51 +23,42 @@ static constexpr ReturnValue_t POOL_ENTRY_TYPE_CONFLICT = MAKE_RETURN_CODE(0x01) /** This is the core data structure of the local data pools. Users should insert all desired pool variables, using the std::map interface. */ -using DataPool = std::map; +using DataPool = std::map; using DataPoolMapIter = DataPool::iterator; -} +} // namespace localpool /** * Used as a unique identifier for data sets. Consists of 4 byte object ID and 4 byte set ID. */ union sid_t { - static constexpr uint64_t INVALID_SID = -1; - static constexpr uint32_t INVALID_OBJECT_ID = objects::NO_OBJECT; - static constexpr uint32_t INVALID_SET_ID = -1; + static constexpr uint64_t INVALID_SID = -1; + static constexpr uint32_t INVALID_OBJECT_ID = objects::NO_OBJECT; + static constexpr uint32_t INVALID_SET_ID = -1; + sid_t() : raw(INVALID_SID) {} - sid_t(): raw(INVALID_SID) {} + sid_t(object_id_t objectId, uint32_t setId) : objectId(objectId), ownerSetId(setId) {} - sid_t(object_id_t objectId, uint32_t setId): - objectId(objectId), - ownerSetId(setId) {} - - struct { - object_id_t objectId ; - /** - * A generic 32 bit ID to identify unique HK packets for a single - * object. For example, the DeviceCommandId_t is used for - * DeviceHandlers - */ - uint32_t ownerSetId; - }; + struct { + object_id_t objectId; /** - * Alternative access to the raw value. This is also the size of the type. + * A generic 32 bit ID to identify unique HK packets for a single + * object. For example, the DeviceCommandId_t is used for + * DeviceHandlers */ - uint64_t raw; + uint32_t ownerSetId; + }; + /** + * Alternative access to the raw value. This is also the size of the type. + */ + uint64_t raw; - bool notSet() const { - return raw == INVALID_SID; - } + bool notSet() const { return raw == INVALID_SID; } - bool operator==(const sid_t& other) const { - return raw == other.raw; - } + bool operator==(const sid_t& other) const { return raw == other.raw; } - bool operator!=(const sid_t& other) const { - return not (raw == other.raw); - } + bool operator!=(const sid_t& other) const { return not(raw == other.raw); } }; /** @@ -75,34 +66,27 @@ union sid_t { * and 4 byte local pool ID. */ union gp_id_t { - static constexpr uint64_t INVALID_GPID = -1; - static constexpr uint32_t INVALID_OBJECT_ID = objects::NO_OBJECT; - static constexpr uint32_t INVALID_LPID = localpool::INVALID_LPID; + static constexpr uint64_t INVALID_GPID = -1; + static constexpr uint32_t INVALID_OBJECT_ID = objects::NO_OBJECT; + static constexpr uint32_t INVALID_LPID = localpool::INVALID_LPID; - gp_id_t(): raw(INVALID_GPID) {} + gp_id_t() : raw(INVALID_GPID) {} - gp_id_t(object_id_t objectId, lp_id_t localPoolId): - objectId(objectId), - localPoolId(localPoolId) {} + gp_id_t(object_id_t objectId, lp_id_t localPoolId) + : objectId(objectId), localPoolId(localPoolId) {} - struct { - object_id_t objectId; - lp_id_t localPoolId; - }; + struct { + object_id_t objectId; + lp_id_t localPoolId; + }; - uint64_t raw; + uint64_t raw; - bool notSet() const { - return raw == INVALID_GPID; - } + bool notSet() const { return raw == INVALID_GPID; } - bool operator==(const gp_id_t& other) const { - return raw == other.raw; - } + bool operator==(const gp_id_t& other) const { return raw == other.raw; } - bool operator!=(const gp_id_t& other) const { - return not (raw == other.raw); - } + bool operator!=(const gp_id_t& other) const { return not(raw == other.raw); } }; #endif /* FSFW_DATAPOOLLOCAL_LOCALPOOLDEFINITIONS_H_ */ diff --git a/src/fsfw/devicehandlers/AcceptsDeviceResponsesIF.h b/src/fsfw/devicehandlers/AcceptsDeviceResponsesIF.h index 8e13ba0c..69d74fa2 100644 --- a/src/fsfw/devicehandlers/AcceptsDeviceResponsesIF.h +++ b/src/fsfw/devicehandlers/AcceptsDeviceResponsesIF.h @@ -8,12 +8,12 @@ * to the queue ID, which is returned in the implemented abstract method. */ class AcceptsDeviceResponsesIF { -public: - /** - * Default empty virtual destructor. - */ - virtual ~AcceptsDeviceResponsesIF() {} - virtual MessageQueueId_t getDeviceQueue() = 0; + public: + /** + * Default empty virtual destructor. + */ + virtual ~AcceptsDeviceResponsesIF() {} + virtual MessageQueueId_t getDeviceQueue() = 0; }; #endif /* FSFW_DEVICEHANDLERS_ACCEPTSDEVICERESPONSESIF_H_ */ diff --git a/src/fsfw/devicehandlers/AssemblyBase.cpp b/src/fsfw/devicehandlers/AssemblyBase.cpp index 146adfcb..c29022e5 100644 --- a/src/fsfw/devicehandlers/AssemblyBase.cpp +++ b/src/fsfw/devicehandlers/AssemblyBase.cpp @@ -1,273 +1,268 @@ #include "fsfw/devicehandlers/AssemblyBase.h" -AssemblyBase::AssemblyBase(object_id_t objectId, object_id_t parentId, - uint16_t commandQueueDepth) : - SubsystemBase(objectId, parentId, MODE_OFF, commandQueueDepth), - internalState(STATE_NONE), recoveryState(RECOVERY_IDLE), - recoveringDevice(childrenMap.end()), targetMode(MODE_OFF), - targetSubmode(SUBMODE_NONE) { - recoveryOffTimer.setTimeout(POWER_OFF_TIME_MS); +AssemblyBase::AssemblyBase(object_id_t objectId, object_id_t parentId, uint16_t commandQueueDepth) + : SubsystemBase(objectId, parentId, MODE_OFF, commandQueueDepth), + internalState(STATE_NONE), + recoveryState(RECOVERY_IDLE), + recoveringDevice(childrenMap.end()), + targetMode(MODE_OFF), + targetSubmode(SUBMODE_NONE) { + recoveryOffTimer.setTimeout(POWER_OFF_TIME_MS); } -AssemblyBase::~AssemblyBase() { -} +AssemblyBase::~AssemblyBase() {} ReturnValue_t AssemblyBase::handleCommandMessage(CommandMessage* message) { - return handleHealthReply(message); + return handleHealthReply(message); } void AssemblyBase::performChildOperation() { - if (isInTransition()) { - handleChildrenTransition(); - } else { - handleChildrenChanged(); - } + if (isInTransition()) { + handleChildrenTransition(); + } else { + handleChildrenChanged(); + } } void AssemblyBase::startTransition(Mode_t mode, Submode_t submode) { - doStartTransition(mode, submode); - if (modeHelper.isForced()) { - triggerEvent(FORCING_MODE, mode, submode); - } else { - triggerEvent(CHANGING_MODE, mode, submode); - } + doStartTransition(mode, submode); + if (modeHelper.isForced()) { + triggerEvent(FORCING_MODE, mode, submode); + } else { + triggerEvent(CHANGING_MODE, mode, submode); + } } void AssemblyBase::doStartTransition(Mode_t mode, Submode_t submode) { - targetMode = mode; - targetSubmode = submode; - internalState = STATE_SINGLE_STEP; - ReturnValue_t result = commandChildren(mode, submode); - if (result == NEED_SECOND_STEP) { - internalState = STATE_NEED_SECOND_STEP; - } + targetMode = mode; + targetSubmode = submode; + internalState = STATE_SINGLE_STEP; + ReturnValue_t result = commandChildren(mode, submode); + if (result == NEED_SECOND_STEP) { + internalState = STATE_NEED_SECOND_STEP; + } } bool AssemblyBase::isInTransition() { - return (internalState != STATE_NONE) || (recoveryState != RECOVERY_IDLE); + return (internalState != STATE_NONE) || (recoveryState != RECOVERY_IDLE); } bool AssemblyBase::handleChildrenChanged() { - if (childrenChangedMode) { - ReturnValue_t result = checkChildrenState(); - if (result != RETURN_OK) { - handleChildrenLostMode(result); - } - return true; - } else { - return handleChildrenChangedHealth(); - } + if (childrenChangedMode) { + ReturnValue_t result = checkChildrenState(); + if (result != RETURN_OK) { + handleChildrenLostMode(result); + } + return true; + } else { + return handleChildrenChangedHealth(); + } } void AssemblyBase::handleChildrenLostMode(ReturnValue_t result) { - triggerEvent(CANT_KEEP_MODE, mode, submode); - startTransition(MODE_OFF, SUBMODE_NONE); + triggerEvent(CANT_KEEP_MODE, mode, submode); + startTransition(MODE_OFF, SUBMODE_NONE); } bool AssemblyBase::handleChildrenChangedHealth() { - auto iter = childrenMap.begin(); - for (; iter != childrenMap.end(); iter++) { - if (iter->second.healthChanged) { - iter->second.healthChanged = false; - break; - } - } - if (iter == childrenMap.end()) { - return false; - } - HealthState healthState = healthHelper.healthTable->getHealth(iter->first); - if (healthState == HasHealthIF::NEEDS_RECOVERY) { - triggerEvent(TRYING_RECOVERY); - recoveryState = RECOVERY_STARTED; - recoveringDevice = iter; - doStartTransition(targetMode, targetSubmode); - } else { - triggerEvent(CHILD_CHANGED_HEALTH); - doStartTransition(mode, submode); - } - if (modeHelper.isForced()) { - triggerEvent(FORCING_MODE, targetMode, targetSubmode); - } - return true; + auto iter = childrenMap.begin(); + for (; iter != childrenMap.end(); iter++) { + if (iter->second.healthChanged) { + iter->second.healthChanged = false; + break; + } + } + if (iter == childrenMap.end()) { + return false; + } + HealthState healthState = healthHelper.healthTable->getHealth(iter->first); + if (healthState == HasHealthIF::NEEDS_RECOVERY) { + triggerEvent(TRYING_RECOVERY); + recoveryState = RECOVERY_STARTED; + recoveringDevice = iter; + doStartTransition(targetMode, targetSubmode); + } else { + triggerEvent(CHILD_CHANGED_HEALTH); + doStartTransition(mode, submode); + } + if (modeHelper.isForced()) { + triggerEvent(FORCING_MODE, targetMode, targetSubmode); + } + return true; } void AssemblyBase::handleChildrenTransition() { - if (commandsOutstanding <= 0) { - switch (internalState) { - case STATE_NEED_SECOND_STEP: - internalState = STATE_SECOND_STEP; - commandChildren(targetMode, targetSubmode); - return; - case STATE_OVERWRITE_HEALTH: { - internalState = STATE_SINGLE_STEP; - ReturnValue_t result = commandChildren(mode, submode); - if (result == NEED_SECOND_STEP) { - internalState = STATE_NEED_SECOND_STEP; - } - return; - } - case STATE_NONE: - //Valid state, used in recovery. - case STATE_SINGLE_STEP: - case STATE_SECOND_STEP: - if (checkAndHandleRecovery()) { - return; - } - break; - } - ReturnValue_t result = checkChildrenState(); - if (result == RETURN_OK) { - handleModeReached(); - } else { - handleModeTransitionFailed(result); - } - } + if (commandsOutstanding <= 0) { + switch (internalState) { + case STATE_NEED_SECOND_STEP: + internalState = STATE_SECOND_STEP; + commandChildren(targetMode, targetSubmode); + return; + case STATE_OVERWRITE_HEALTH: { + internalState = STATE_SINGLE_STEP; + ReturnValue_t result = commandChildren(mode, submode); + if (result == NEED_SECOND_STEP) { + internalState = STATE_NEED_SECOND_STEP; + } + return; + } + case STATE_NONE: + // Valid state, used in recovery. + case STATE_SINGLE_STEP: + case STATE_SECOND_STEP: + if (checkAndHandleRecovery()) { + return; + } + break; + } + ReturnValue_t result = checkChildrenState(); + if (result == RETURN_OK) { + handleModeReached(); + } else { + handleModeTransitionFailed(result); + } + } } void AssemblyBase::handleModeReached() { - internalState = STATE_NONE; - setMode(targetMode, targetSubmode); + internalState = STATE_NONE; + setMode(targetMode, targetSubmode); } void AssemblyBase::handleModeTransitionFailed(ReturnValue_t result) { -//always accept transition to OFF, there is nothing we can do except sending an info event -//In theory this should never happen, but we would risk an infinite loop otherwise - if (targetMode == MODE_OFF) { - triggerEvent(CHILD_PROBLEMS, result); - internalState = STATE_NONE; - setMode(targetMode, targetSubmode); - } else { - if (handleChildrenChangedHealth()) { - //If any health change is pending, handle that first. - return; - } - triggerEvent(MODE_TRANSITION_FAILED, result); - startTransition(MODE_OFF, SUBMODE_NONE); - } + // always accept transition to OFF, there is nothing we can do except sending an info event + // In theory this should never happen, but we would risk an infinite loop otherwise + if (targetMode == MODE_OFF) { + triggerEvent(CHILD_PROBLEMS, result); + internalState = STATE_NONE; + setMode(targetMode, targetSubmode); + } else { + if (handleChildrenChangedHealth()) { + // If any health change is pending, handle that first. + return; + } + triggerEvent(MODE_TRANSITION_FAILED, result); + startTransition(MODE_OFF, SUBMODE_NONE); + } } -void AssemblyBase::sendHealthCommand(MessageQueueId_t sendTo, - HealthState health) { - CommandMessage command; - HealthMessage::setHealthMessage(&command, HealthMessage::HEALTH_SET, - health); - if (commandQueue->sendMessage(sendTo, &command) == RETURN_OK) { - commandsOutstanding++; - } +void AssemblyBase::sendHealthCommand(MessageQueueId_t sendTo, HealthState health) { + CommandMessage command; + HealthMessage::setHealthMessage(&command, HealthMessage::HEALTH_SET, health); + if (commandQueue->sendMessage(sendTo, &command) == RETURN_OK) { + commandsOutstanding++; + } } ReturnValue_t AssemblyBase::checkChildrenState() { - if (targetMode == MODE_OFF) { - return checkChildrenStateOff(); - } else { - return checkChildrenStateOn(targetMode, targetSubmode); - } + if (targetMode == MODE_OFF) { + return checkChildrenStateOff(); + } else { + return checkChildrenStateOn(targetMode, targetSubmode); + } } ReturnValue_t AssemblyBase::checkChildrenStateOff() { - for (const auto& childIter: childrenMap) { - if (checkChildOff(childIter.first) != RETURN_OK) { - return NOT_ENOUGH_CHILDREN_IN_CORRECT_STATE; - } - } - return RETURN_OK; + for (const auto& childIter : childrenMap) { + if (checkChildOff(childIter.first) != RETURN_OK) { + return NOT_ENOUGH_CHILDREN_IN_CORRECT_STATE; + } + } + return RETURN_OK; } ReturnValue_t AssemblyBase::checkChildOff(uint32_t objectId) { - ChildInfo childInfo = childrenMap.find(objectId)->second; - if (healthHelper.healthTable->isCommandable(objectId)) { - if (childInfo.submode != SUBMODE_NONE) { - return RETURN_FAILED; - } else { - if ((childInfo.mode != MODE_OFF) - && (childInfo.mode != DeviceHandlerIF::MODE_ERROR_ON)) { - return RETURN_FAILED; - } - } - } - return RETURN_OK; + ChildInfo childInfo = childrenMap.find(objectId)->second; + if (healthHelper.healthTable->isCommandable(objectId)) { + if (childInfo.submode != SUBMODE_NONE) { + return RETURN_FAILED; + } else { + if ((childInfo.mode != MODE_OFF) && (childInfo.mode != DeviceHandlerIF::MODE_ERROR_ON)) { + return RETURN_FAILED; + } + } + } + return RETURN_OK; } ReturnValue_t AssemblyBase::checkModeCommand(Mode_t mode, Submode_t submode, - uint32_t* msToReachTheMode) { + uint32_t* msToReachTheMode) { + // always accept transition to OFF + if (mode == MODE_OFF) { + if (submode != SUBMODE_NONE) { + return INVALID_SUBMODE; + } + return RETURN_OK; + } -//always accept transition to OFF - if (mode == MODE_OFF) { - if (submode != SUBMODE_NONE) { - return INVALID_SUBMODE; - } - return RETURN_OK; - } + if ((mode != MODE_ON) && (mode != DeviceHandlerIF::MODE_NORMAL)) { + return INVALID_MODE; + } - if ((mode != MODE_ON) && (mode != DeviceHandlerIF::MODE_NORMAL)) { - return INVALID_MODE; - } + if (internalState != STATE_NONE) { + return IN_TRANSITION; + } - if (internalState != STATE_NONE) { - return IN_TRANSITION; - } - - return isModeCombinationValid(mode, submode); + return isModeCombinationValid(mode, submode); } ReturnValue_t AssemblyBase::handleHealthReply(CommandMessage* message) { - if (message->getCommand() == HealthMessage::HEALTH_INFO) { - HealthState health = HealthMessage::getHealth(message); - if (health != EXTERNAL_CONTROL) { - updateChildChangedHealth(message->getSender(), true); - } - return RETURN_OK; - } - if (message->getCommand() == HealthMessage::REPLY_HEALTH_SET - || (message->getCommand() == CommandMessage::REPLY_REJECTED - && message->getParameter2() == HealthMessage::HEALTH_SET)) { - if (isInTransition()) { - commandsOutstanding--; - } - return RETURN_OK; - } - return RETURN_FAILED; + if (message->getCommand() == HealthMessage::HEALTH_INFO) { + HealthState health = HealthMessage::getHealth(message); + if (health != EXTERNAL_CONTROL) { + updateChildChangedHealth(message->getSender(), true); + } + return RETURN_OK; + } + if (message->getCommand() == HealthMessage::REPLY_HEALTH_SET || + (message->getCommand() == CommandMessage::REPLY_REJECTED && + message->getParameter2() == HealthMessage::HEALTH_SET)) { + if (isInTransition()) { + commandsOutstanding--; + } + return RETURN_OK; + } + return RETURN_FAILED; } bool AssemblyBase::checkAndHandleRecovery() { - switch (recoveryState) { - case RECOVERY_STARTED: - recoveryState = RECOVERY_WAIT; - recoveryOffTimer.resetTimer(); - return true; - case RECOVERY_WAIT: - if (recoveryOffTimer.isBusy()) { - return true; - } - triggerEvent(RECOVERY_STEP, 0); - sendHealthCommand(recoveringDevice->second.commandQueue, HEALTHY); - internalState = STATE_NONE; - recoveryState = RECOVERY_ONGOING; - //Don't check state! - return true; - case RECOVERY_ONGOING: - triggerEvent(RECOVERY_STEP, 1); - recoveryState = RECOVERY_ONGOING_2; - recoveringDevice->second.healthChanged = false; - //Device should be healthy again, so restart a transition. - //Might be including second step, but that's already handled. - doStartTransition(targetMode, targetSubmode); - return true; - case RECOVERY_ONGOING_2: - triggerEvent(RECOVERY_DONE); - //Now we're through, but not sure if it was successful. - recoveryState = RECOVERY_IDLE; - return false; - case RECOVERY_IDLE: - default: - return false; - } + switch (recoveryState) { + case RECOVERY_STARTED: + recoveryState = RECOVERY_WAIT; + recoveryOffTimer.resetTimer(); + return true; + case RECOVERY_WAIT: + if (recoveryOffTimer.isBusy()) { + return true; + } + triggerEvent(RECOVERY_STEP, 0); + sendHealthCommand(recoveringDevice->second.commandQueue, HEALTHY); + internalState = STATE_NONE; + recoveryState = RECOVERY_ONGOING; + // Don't check state! + return true; + case RECOVERY_ONGOING: + triggerEvent(RECOVERY_STEP, 1); + recoveryState = RECOVERY_ONGOING_2; + recoveringDevice->second.healthChanged = false; + // Device should be healthy again, so restart a transition. + // Might be including second step, but that's already handled. + doStartTransition(targetMode, targetSubmode); + return true; + case RECOVERY_ONGOING_2: + triggerEvent(RECOVERY_DONE); + // Now we're through, but not sure if it was successful. + recoveryState = RECOVERY_IDLE; + return false; + case RECOVERY_IDLE: + default: + return false; + } } -void AssemblyBase::overwriteDeviceHealth(object_id_t objectId, - HasHealthIF::HealthState oldHealth) { - triggerEvent(OVERWRITING_HEALTH, objectId, oldHealth); - internalState = STATE_OVERWRITE_HEALTH; - modeHelper.setForced(true); - sendHealthCommand(childrenMap[objectId].commandQueue, EXTERNAL_CONTROL); +void AssemblyBase::overwriteDeviceHealth(object_id_t objectId, HasHealthIF::HealthState oldHealth) { + triggerEvent(OVERWRITING_HEALTH, objectId, oldHealth); + internalState = STATE_OVERWRITE_HEALTH; + modeHelper.setForced(true); + sendHealthCommand(childrenMap[objectId].commandQueue, EXTERNAL_CONTROL); } diff --git a/src/fsfw/devicehandlers/AssemblyBase.h b/src/fsfw/devicehandlers/AssemblyBase.h index 7d54f14d..3e235928 100644 --- a/src/fsfw/devicehandlers/AssemblyBase.h +++ b/src/fsfw/devicehandlers/AssemblyBase.h @@ -1,9 +1,9 @@ #ifndef FSFW_DEVICEHANDLERS_ASSEMBLYBASE_H_ #define FSFW_DEVICEHANDLERS_ASSEMBLYBASE_H_ -#include "DeviceHandlerBase.h" #include "../container/FixedArrayList.h" #include "../subsystem/SubsystemBase.h" +#include "DeviceHandlerBase.h" /** * @brief Base class to implement reconfiguration and failure handling for @@ -32,149 +32,142 @@ * (This will call the function in SubsystemBase) * */ -class AssemblyBase: public SubsystemBase { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::ASSEMBLY_BASE; - static const ReturnValue_t NEED_SECOND_STEP = MAKE_RETURN_CODE(0x01); - static const ReturnValue_t NEED_TO_RECONFIGURE = MAKE_RETURN_CODE(0x02); - static const ReturnValue_t MODE_FALLBACK = MAKE_RETURN_CODE(0x03); - static const ReturnValue_t CHILD_NOT_COMMANDABLE = MAKE_RETURN_CODE(0x04); - 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); +class AssemblyBase : public SubsystemBase { + public: + static const uint8_t INTERFACE_ID = CLASS_ID::ASSEMBLY_BASE; + static const ReturnValue_t NEED_SECOND_STEP = MAKE_RETURN_CODE(0x01); + static const ReturnValue_t NEED_TO_RECONFIGURE = MAKE_RETURN_CODE(0x02); + static const ReturnValue_t MODE_FALLBACK = MAKE_RETURN_CODE(0x03); + static const ReturnValue_t CHILD_NOT_COMMANDABLE = MAKE_RETURN_CODE(0x04); + 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); - AssemblyBase(object_id_t objectId, object_id_t parentId, - uint16_t commandQueueDepth = 8); - virtual ~AssemblyBase(); + AssemblyBase(object_id_t objectId, object_id_t parentId, uint16_t commandQueueDepth = 8); + virtual ~AssemblyBase(); -protected: - /** - * Command children to reach [mode,submode] combination - * Can be done by setting #commandsOutstanding correctly, - * or using executeTable() - * @param mode - * @param submode - * @return - * - @c RETURN_OK if ok - * - @c NEED_SECOND_STEP if children need to be commanded again - */ - virtual ReturnValue_t commandChildren(Mode_t mode, Submode_t submode) = 0; + protected: + /** + * Command children to reach [mode,submode] combination + * Can be done by setting #commandsOutstanding correctly, + * or using executeTable() + * @param mode + * @param submode + * @return + * - @c RETURN_OK if ok + * - @c NEED_SECOND_STEP if children need to be commanded again + */ + virtual ReturnValue_t commandChildren(Mode_t mode, Submode_t submode) = 0; - /** - * Check whether desired assembly mode was achieved by checking the modes - * or/and health states of child device handlers. - * The assembly template class will also call this function if a health - * or mode change of a child device handler was detected. - * @param wantedMode - * @param wantedSubmode - * @return - */ - virtual ReturnValue_t checkChildrenStateOn(Mode_t wantedMode, - Submode_t wantedSubmode) = 0; + /** + * Check whether desired assembly mode was achieved by checking the modes + * or/and health states of child device handlers. + * The assembly template class will also call this function if a health + * or mode change of a child device handler was detected. + * @param wantedMode + * @param wantedSubmode + * @return + */ + virtual ReturnValue_t checkChildrenStateOn(Mode_t wantedMode, Submode_t wantedSubmode) = 0; - /** - * Check whether a combination of mode and submode is valid. - * - * Ground Controller like precise return values from HasModesIF. - * So, please return any of them. - * - * @param mode The targeted mode - * @param submode The targeted submmode - * @return Any information why this combination is invalid from HasModesIF - * like HasModesIF::INVALID_SUBMODE. - * On success return HasReturnvaluesIF::RETURN_OK - */ - virtual ReturnValue_t isModeCombinationValid(Mode_t mode, - Submode_t submode) = 0; + /** + * Check whether a combination of mode and submode is valid. + * + * Ground Controller like precise return values from HasModesIF. + * So, please return any of them. + * + * @param mode The targeted mode + * @param submode The targeted submmode + * @return Any information why this combination is invalid from HasModesIF + * like HasModesIF::INVALID_SUBMODE. + * On success return HasReturnvaluesIF::RETURN_OK + */ + virtual ReturnValue_t isModeCombinationValid(Mode_t mode, Submode_t submode) = 0; - enum InternalState { - STATE_NONE, - STATE_OVERWRITE_HEALTH, - STATE_NEED_SECOND_STEP, - STATE_SINGLE_STEP, - STATE_SECOND_STEP, - } internalState; + enum InternalState { + STATE_NONE, + STATE_OVERWRITE_HEALTH, + STATE_NEED_SECOND_STEP, + STATE_SINGLE_STEP, + STATE_SECOND_STEP, + } internalState; - enum RecoveryState { - RECOVERY_IDLE, - RECOVERY_STARTED, - RECOVERY_ONGOING, - RECOVERY_ONGOING_2, - RECOVERY_WAIT - } recoveryState; //!< Indicates if one of the children requested a recovery. - ChildrenMap::iterator recoveringDevice; + enum RecoveryState { + RECOVERY_IDLE, + RECOVERY_STARTED, + RECOVERY_ONGOING, + RECOVERY_ONGOING_2, + RECOVERY_WAIT + } recoveryState; //!< Indicates if one of the children requested a recovery. + ChildrenMap::iterator recoveringDevice; - /** - * the mode the current transition is trying to achieve. - * Can be different from the modehelper.commandedMode! - */ - Mode_t targetMode; + /** + * the mode the current transition is trying to achieve. + * Can be different from the modehelper.commandedMode! + */ + Mode_t targetMode; - /** - * the submode the current transition is trying to achieve. - * Can be different from the modehelper.commandedSubmode! - */ - Submode_t targetSubmode; + /** + * the submode the current transition is trying to achieve. + * Can be different from the modehelper.commandedSubmode! + */ + Submode_t targetSubmode; - Countdown recoveryOffTimer; + Countdown recoveryOffTimer; - static const uint32_t POWER_OFF_TIME_MS = 1000; + static const uint32_t POWER_OFF_TIME_MS = 1000; - virtual ReturnValue_t handleCommandMessage(CommandMessage *message); + virtual ReturnValue_t handleCommandMessage(CommandMessage *message); - virtual ReturnValue_t handleHealthReply(CommandMessage *message); + virtual ReturnValue_t handleHealthReply(CommandMessage *message); - virtual void performChildOperation(); + virtual void performChildOperation(); - bool handleChildrenChanged(); + bool handleChildrenChanged(); - /** - * This method is called if the children changed its mode in a way that - * the current mode can't be kept. - * Default behavior is to go to MODE_OFF. - * @param result The failure code which was returned by checkChildrenState. - */ - virtual void handleChildrenLostMode(ReturnValue_t result); + /** + * This method is called if the children changed its mode in a way that + * the current mode can't be kept. + * Default behavior is to go to MODE_OFF. + * @param result The failure code which was returned by checkChildrenState. + */ + virtual void handleChildrenLostMode(ReturnValue_t result); - bool handleChildrenChangedHealth(); + bool handleChildrenChangedHealth(); - 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); - virtual void startTransition(Mode_t mode, Submode_t submode); + virtual void startTransition(Mode_t mode, Submode_t 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(); - virtual void handleModeReached(); + virtual void handleModeReached(); - virtual void handleModeTransitionFailed(ReturnValue_t result); + virtual void handleModeTransitionFailed(ReturnValue_t result); - void sendHealthCommand(MessageQueueId_t sendTo, HealthState health); + void sendHealthCommand(MessageQueueId_t sendTo, HealthState health); - virtual ReturnValue_t checkChildrenStateOff(); + virtual ReturnValue_t checkChildrenStateOff(); - ReturnValue_t checkChildrenState(); + ReturnValue_t checkChildrenState(); - virtual ReturnValue_t checkChildOff(uint32_t objectId); + virtual ReturnValue_t checkChildOff(uint32_t objectId); - /** - * Manages recovery of a device - * @return true if recovery is still ongoing, false else. - */ - bool checkAndHandleRecovery(); - - /** - * Helper method to overwrite health state of one of the children. - * Also sets state to STATE_OVERWRITE_HEATH. - * @param objectId Must be a registered child. - */ - void overwriteDeviceHealth(object_id_t objectId, - HasHealthIF::HealthState oldHealth); + /** + * Manages recovery of a device + * @return true if recovery is still ongoing, false else. + */ + bool checkAndHandleRecovery(); + /** + * Helper method to overwrite health state of one of the children. + * Also sets state to STATE_OVERWRITE_HEATH. + * @param objectId Must be a registered child. + */ + void overwriteDeviceHealth(object_id_t objectId, HasHealthIF::HealthState oldHealth); }; #endif /* FSFW_DEVICEHANDLERS_ASSEMBLYBASE_H_ */ diff --git a/src/fsfw/devicehandlers/ChildHandlerBase.cpp b/src/fsfw/devicehandlers/ChildHandlerBase.cpp index e6508727..be4f4798 100644 --- a/src/fsfw/devicehandlers/ChildHandlerBase.cpp +++ b/src/fsfw/devicehandlers/ChildHandlerBase.cpp @@ -1,46 +1,43 @@ #include "fsfw/devicehandlers/ChildHandlerBase.h" + #include "fsfw/subsystem/SubsystemBase.h" -ChildHandlerBase::ChildHandlerBase(object_id_t setObjectId, - object_id_t deviceCommunication, CookieIF * cookie, - object_id_t hkDestination, uint32_t thermalStatePoolId, - uint32_t thermalRequestPoolId, - object_id_t parent, - FailureIsolationBase* customFdir, size_t cmdQueueSize) : - DeviceHandlerBase(setObjectId, deviceCommunication, cookie, - (customFdir == nullptr? &childHandlerFdir : customFdir), - cmdQueueSize), - parentId(parent), childHandlerFdir(setObjectId) { - this->setHkDestination(hkDestination); - this->setThermalStateRequestPoolIds(thermalStatePoolId, - thermalRequestPoolId); - +ChildHandlerBase::ChildHandlerBase(object_id_t setObjectId, object_id_t deviceCommunication, + CookieIF* cookie, object_id_t hkDestination, + uint32_t thermalStatePoolId, uint32_t thermalRequestPoolId, + object_id_t parent, FailureIsolationBase* customFdir, + size_t cmdQueueSize) + : DeviceHandlerBase(setObjectId, deviceCommunication, cookie, + (customFdir == nullptr ? &childHandlerFdir : customFdir), cmdQueueSize), + parentId(parent), + childHandlerFdir(setObjectId) { + this->setHkDestination(hkDestination); + this->setThermalStateRequestPoolIds(thermalStatePoolId, thermalRequestPoolId); } -ChildHandlerBase::~ChildHandlerBase() { -} +ChildHandlerBase::~ChildHandlerBase() {} ReturnValue_t ChildHandlerBase::initialize() { - ReturnValue_t result = DeviceHandlerBase::initialize(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + ReturnValue_t result = DeviceHandlerBase::initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - MessageQueueId_t parentQueue = 0; + MessageQueueId_t parentQueue = 0; - if (parentId != objects::NO_OBJECT) { - SubsystemBase *parent = ObjectManager::instance()->get(parentId); - if (parent == NULL) { - return RETURN_FAILED; - } - parentQueue = parent->getCommandQueue(); + if (parentId != objects::NO_OBJECT) { + SubsystemBase* parent = ObjectManager::instance()->get(parentId); + if (parent == NULL) { + return RETURN_FAILED; + } + parentQueue = parent->getCommandQueue(); - parent->registerChild(getObjectId()); - } + parent->registerChild(getObjectId()); + } - healthHelper.setParentQueue(parentQueue); + healthHelper.setParentQueue(parentQueue); - modeHelper.setParentQueue(parentQueue); + modeHelper.setParentQueue(parentQueue); - return RETURN_OK; + return RETURN_OK; } diff --git a/src/fsfw/devicehandlers/ChildHandlerBase.h b/src/fsfw/devicehandlers/ChildHandlerBase.h index eed4c95e..19d48a24 100644 --- a/src/fsfw/devicehandlers/ChildHandlerBase.h +++ b/src/fsfw/devicehandlers/ChildHandlerBase.h @@ -1,26 +1,23 @@ #ifndef FSFW_DEVICEHANDLER_CHILDHANDLERBASE_H_ #define FSFW_DEVICEHANDLER_CHILDHANDLERBASE_H_ -#include "DeviceHandlerBase.h" #include "ChildHandlerFDIR.h" +#include "DeviceHandlerBase.h" -class ChildHandlerBase: public DeviceHandlerBase { -public: - ChildHandlerBase(object_id_t setObjectId, object_id_t deviceCommunication, - CookieIF * cookie, object_id_t hkDestination, - uint32_t thermalStatePoolId, uint32_t thermalRequestPoolId, - object_id_t parent = objects::NO_OBJECT, - FailureIsolationBase* customFdir = nullptr, - size_t cmdQueueSize = 20); +class ChildHandlerBase : public DeviceHandlerBase { + public: + ChildHandlerBase(object_id_t setObjectId, object_id_t deviceCommunication, CookieIF* cookie, + object_id_t hkDestination, uint32_t thermalStatePoolId, + uint32_t thermalRequestPoolId, object_id_t parent = objects::NO_OBJECT, + FailureIsolationBase* customFdir = nullptr, size_t cmdQueueSize = 20); - virtual ~ChildHandlerBase(); + virtual ~ChildHandlerBase(); - virtual ReturnValue_t initialize(); - -protected: - const uint32_t parentId; - ChildHandlerFDIR childHandlerFdir; + virtual ReturnValue_t initialize(); + protected: + const uint32_t parentId; + ChildHandlerFDIR childHandlerFdir; }; #endif /* FSFW_DEVICEHANDLER_CHILDHANDLERBASE_H_ */ diff --git a/src/fsfw/devicehandlers/ChildHandlerFDIR.cpp b/src/fsfw/devicehandlers/ChildHandlerFDIR.cpp index e1d1321d..1339ea35 100644 --- a/src/fsfw/devicehandlers/ChildHandlerFDIR.cpp +++ b/src/fsfw/devicehandlers/ChildHandlerFDIR.cpp @@ -1,11 +1,9 @@ #include "fsfw/devicehandlers/ChildHandlerFDIR.h" -ChildHandlerFDIR::ChildHandlerFDIR(object_id_t owner, - object_id_t faultTreeParent, uint32_t recoveryCount) : - DeviceHandlerFailureIsolation(owner, faultTreeParent) { - recoveryCounter.setFailureThreshold(recoveryCount); -} - -ChildHandlerFDIR::~ChildHandlerFDIR() { +ChildHandlerFDIR::ChildHandlerFDIR(object_id_t owner, object_id_t faultTreeParent, + uint32_t recoveryCount) + : DeviceHandlerFailureIsolation(owner, faultTreeParent) { + recoveryCounter.setFailureThreshold(recoveryCount); } +ChildHandlerFDIR::~ChildHandlerFDIR() {} diff --git a/src/fsfw/devicehandlers/ChildHandlerFDIR.h b/src/fsfw/devicehandlers/ChildHandlerFDIR.h index 13d1345c..6af1ca23 100644 --- a/src/fsfw/devicehandlers/ChildHandlerFDIR.h +++ b/src/fsfw/devicehandlers/ChildHandlerFDIR.h @@ -8,13 +8,14 @@ * Does not have a default fault tree parent and * allows to make the recovery count settable to 0. */ -class ChildHandlerFDIR: public DeviceHandlerFailureIsolation { -public: - ChildHandlerFDIR(object_id_t owner, object_id_t faultTreeParent = - NO_FAULT_TREE_PARENT, uint32_t recoveryCount = 0); - virtual ~ChildHandlerFDIR(); -protected: - static const object_id_t NO_FAULT_TREE_PARENT = 0; +class ChildHandlerFDIR : public DeviceHandlerFailureIsolation { + public: + ChildHandlerFDIR(object_id_t owner, object_id_t faultTreeParent = NO_FAULT_TREE_PARENT, + uint32_t recoveryCount = 0); + virtual ~ChildHandlerFDIR(); + + protected: + static const object_id_t NO_FAULT_TREE_PARENT = 0; }; #endif /* FRAMEWORK_DEVICEHANDLERS_CHILDHANDLERFDIR_H_ */ diff --git a/src/fsfw/devicehandlers/CookieIF.h b/src/fsfw/devicehandlers/CookieIF.h index 5911bfdb..aca5d942 100644 --- a/src/fsfw/devicehandlers/CookieIF.h +++ b/src/fsfw/devicehandlers/CookieIF.h @@ -27,8 +27,8 @@ using address_t = uint32_t; * @ingroup comm */ class CookieIF { -public: - virtual ~CookieIF() {}; + public: + virtual ~CookieIF(){}; }; #endif /* FSFW_DEVICEHANDLER_COOKIE_H_ */ diff --git a/src/fsfw/devicehandlers/DeviceCommunicationIF.h b/src/fsfw/devicehandlers/DeviceCommunicationIF.h index 527e4700..7a860411 100644 --- a/src/fsfw/devicehandlers/DeviceCommunicationIF.h +++ b/src/fsfw/devicehandlers/DeviceCommunicationIF.h @@ -1,10 +1,9 @@ #ifndef FSFW_DEVICES_DEVICECOMMUNICATIONIF_H_ #define FSFW_DEVICES_DEVICECOMMUNICATIONIF_H_ +#include "../returnvalues/HasReturnvaluesIF.h" #include "CookieIF.h" #include "DeviceHandlerIF.h" - -#include "../returnvalues/HasReturnvaluesIF.h" /** * @defgroup interfaces Interfaces * @brief Interfaces for flight software objects @@ -35,95 +34,92 @@ * @ingroup interfaces * @ingroup comm */ -class DeviceCommunicationIF: public HasReturnvaluesIF { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::DEVICE_COMMUNICATION_IF; +class DeviceCommunicationIF : public HasReturnvaluesIF { + public: + static const uint8_t INTERFACE_ID = CLASS_ID::DEVICE_COMMUNICATION_IF; - //! This is returned in readReceivedMessage() if no reply was reived. - static const ReturnValue_t NO_REPLY_RECEIVED = MAKE_RETURN_CODE(0x01); + //! This is returned in readReceivedMessage() if no reply was reived. + static const ReturnValue_t NO_REPLY_RECEIVED = MAKE_RETURN_CODE(0x01); - //! General protocol error. Define more concrete errors in child handler - static const ReturnValue_t PROTOCOL_ERROR = MAKE_RETURN_CODE(0x02); - //! If cookie is a null pointer - static const ReturnValue_t NULLPOINTER = MAKE_RETURN_CODE(0x03); - static const ReturnValue_t INVALID_COOKIE_TYPE = MAKE_RETURN_CODE(0x04); - // is this needed if there is no open/close call? - static const ReturnValue_t NOT_ACTIVE = MAKE_RETURN_CODE(0x05); - static const ReturnValue_t TOO_MUCH_DATA = MAKE_RETURN_CODE(0x06); + //! General protocol error. Define more concrete errors in child handler + static const ReturnValue_t PROTOCOL_ERROR = MAKE_RETURN_CODE(0x02); + //! If cookie is a null pointer + static const ReturnValue_t NULLPOINTER = MAKE_RETURN_CODE(0x03); + static const ReturnValue_t INVALID_COOKIE_TYPE = MAKE_RETURN_CODE(0x04); + // is this needed if there is no open/close call? + static const ReturnValue_t NOT_ACTIVE = MAKE_RETURN_CODE(0x05); + static const ReturnValue_t TOO_MUCH_DATA = MAKE_RETURN_CODE(0x06); - virtual ~DeviceCommunicationIF() {} + virtual ~DeviceCommunicationIF() {} - /** - * @brief Device specific initialization, using the cookie. - * @details - * The cookie is already prepared in the factory. If the communication - * interface needs to be set up in some way and requires cookie information, - * this can be performed in this function, which is called on device handler - * initialization. - * @param cookie - * @return - * - @c RETURN_OK if initialization was successfull - * - Everything else triggers failure event with returnvalue as parameter 1 - */ - virtual ReturnValue_t initializeInterface(CookieIF * cookie) = 0; + /** + * @brief Device specific initialization, using the cookie. + * @details + * The cookie is already prepared in the factory. If the communication + * interface needs to be set up in some way and requires cookie information, + * this can be performed in this function, which is called on device handler + * initialization. + * @param cookie + * @return + * - @c RETURN_OK if initialization was successfull + * - Everything else triggers failure event with returnvalue as parameter 1 + */ + virtual ReturnValue_t initializeInterface(CookieIF *cookie) = 0; - /** - * Called by DHB in the SEND_WRITE doSendWrite(). - * This function is used to send data to the physical device - * by implementing and calling related drivers or wrapper functions. - * @param cookie - * @param data - * @param len If this is 0, nothing shall be sent. - * @return - * - @c RETURN_OK for successfull send - * - Everything else triggers failure event with returnvalue as parameter 1 - */ - virtual ReturnValue_t sendMessage(CookieIF *cookie, - const uint8_t * sendData, size_t sendLen) = 0; + /** + * Called by DHB in the SEND_WRITE doSendWrite(). + * This function is used to send data to the physical device + * by implementing and calling related drivers or wrapper functions. + * @param cookie + * @param data + * @param len If this is 0, nothing shall be sent. + * @return + * - @c RETURN_OK for successfull send + * - Everything else triggers failure event with returnvalue as parameter 1 + */ + virtual ReturnValue_t sendMessage(CookieIF *cookie, const uint8_t *sendData, size_t sendLen) = 0; - /** - * Called by DHB in the GET_WRITE doGetWrite(). - * Get send confirmation that the data in sendMessage() was sent successfully. - * @param cookie - * @return - * - @c RETURN_OK if data was sent successfully but a reply is expected - * - NO_REPLY_EXPECTED if data was sent successfully and no reply is expected - * - Everything else to indicate failure - */ - virtual ReturnValue_t getSendSuccess(CookieIF *cookie) = 0; + /** + * Called by DHB in the GET_WRITE doGetWrite(). + * Get send confirmation that the data in sendMessage() was sent successfully. + * @param cookie + * @return + * - @c RETURN_OK if data was sent successfully but a reply is expected + * - NO_REPLY_EXPECTED if data was sent successfully and no reply is expected + * - Everything else to indicate failure + */ + virtual ReturnValue_t getSendSuccess(CookieIF *cookie) = 0; - /** - * Called by DHB in the SEND_WRITE doSendRead(). - * It is assumed that it is always possible to request a reply - * from a device. If a requestLen of 0 is supplied, no reply was enabled - * and communication specific action should be taken (e.g. read nothing - * or read everything). - * - * @param cookie - * @param requestLen Size of data to read - * @return - @c RETURN_OK to confirm the request for data has been sent. - * - Everything else triggers failure event with - * returnvalue as parameter 1 - */ - virtual ReturnValue_t requestReceiveMessage(CookieIF *cookie, - size_t requestLen) = 0; + /** + * Called by DHB in the SEND_WRITE doSendRead(). + * It is assumed that it is always possible to request a reply + * from a device. If a requestLen of 0 is supplied, no reply was enabled + * and communication specific action should be taken (e.g. read nothing + * or read everything). + * + * @param cookie + * @param requestLen Size of data to read + * @return - @c RETURN_OK to confirm the request for data has been sent. + * - Everything else triggers failure event with + * returnvalue as parameter 1 + */ + virtual ReturnValue_t requestReceiveMessage(CookieIF *cookie, size_t requestLen) = 0; - /** - * Called by DHB in the GET_WRITE doGetRead(). - * This function is used to receive data from the physical device - * by implementing and calling related drivers or wrapper functions. - * @param cookie - * @param buffer [out] Set reply here (by using *buffer = ...) - * @param size [out] size pointer to set (by using *size = ...). - * Set to 0 if no reply was received - * @return - @c RETURN_OK for successfull receive - * - @c NO_REPLY_RECEIVED if not reply was received. Setting size to - * 0 has the same effect - * - Everything else triggers failure event with - * returnvalue as parameter 1 - */ - virtual ReturnValue_t readReceivedMessage(CookieIF *cookie, - uint8_t **buffer, size_t *size) = 0; + /** + * Called by DHB in the GET_WRITE doGetRead(). + * This function is used to receive data from the physical device + * by implementing and calling related drivers or wrapper functions. + * @param cookie + * @param buffer [out] Set reply here (by using *buffer = ...) + * @param size [out] size pointer to set (by using *size = ...). + * Set to 0 if no reply was received + * @return - @c RETURN_OK for successfull receive + * - @c NO_REPLY_RECEIVED if not reply was received. Setting size to + * 0 has the same effect + * - Everything else triggers failure event with + * returnvalue as parameter 1 + */ + virtual ReturnValue_t readReceivedMessage(CookieIF *cookie, uint8_t **buffer, size_t *size) = 0; }; #endif /* FSFW_DEVICES_DEVICECOMMUNICATIONIF_H_ */ diff --git a/src/fsfw/devicehandlers/DeviceHandlerBase.cpp b/src/fsfw/devicehandlers/DeviceHandlerBase.cpp index 535113fd..08d7c1d8 100644 --- a/src/fsfw/devicehandlers/DeviceHandlerBase.cpp +++ b/src/fsfw/devicehandlers/DeviceHandlerBase.cpp @@ -1,1588 +1,1486 @@ #include "fsfw/devicehandlers/DeviceHandlerBase.h" + +#include "fsfw/datapoollocal/LocalPoolVariable.h" #include "fsfw/devicehandlers/AcceptsDeviceResponsesIF.h" #include "fsfw/devicehandlers/DeviceTmReportingWrapper.h" - -#include "fsfw/serviceinterface/ServiceInterface.h" -#include "fsfw/objectmanager/ObjectManager.h" -#include "fsfw/storagemanager/StorageManagerIF.h" -#include "fsfw/thermal/ThermalComponentIF.h" #include "fsfw/globalfunctions/CRC.h" #include "fsfw/housekeeping/HousekeepingMessage.h" #include "fsfw/ipc/MessageQueueMessage.h" #include "fsfw/ipc/QueueFactory.h" +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/storagemanager/StorageManagerIF.h" #include "fsfw/subsystem/SubsystemBase.h" -#include "fsfw/datapoollocal/LocalPoolVariable.h" +#include "fsfw/thermal/ThermalComponentIF.h" object_id_t DeviceHandlerBase::powerSwitcherId = objects::NO_OBJECT; object_id_t DeviceHandlerBase::rawDataReceiverId = objects::NO_OBJECT; object_id_t DeviceHandlerBase::defaultFdirParentId = objects::NO_OBJECT; DeviceHandlerBase::DeviceHandlerBase(object_id_t setObjectId, object_id_t deviceCommunication, - CookieIF* comCookie, FailureIsolationBase* fdirInstance, size_t cmdQueueSize): - SystemObject(setObjectId), mode(MODE_OFF), submode(SUBMODE_NONE), - wiretappingMode(OFF), storedRawData(StorageManagerIF::INVALID_ADDRESS), - deviceCommunicationId(deviceCommunication), comCookie(comCookie), - healthHelper(this,setObjectId), modeHelper(this), parameterHelper(this), - actionHelper(this, nullptr), poolManager(this, nullptr), - childTransitionFailure(RETURN_OK), fdirInstance(fdirInstance), - defaultFDIRUsed(fdirInstance == nullptr), - switchOffWasReported(false), childTransitionDelay(5000), - transitionSourceMode(_MODE_POWER_DOWN), - transitionSourceSubMode(SUBMODE_NONE) { - commandQueue = QueueFactory::instance()->createMessageQueue(cmdQueueSize, - MessageQueueMessage::MAX_MESSAGE_SIZE); - insertInCommandMap(RAW_COMMAND_ID); - cookieInfo.state = COOKIE_UNUSED; - cookieInfo.pendingCommand = deviceCommandMap.end(); - if (comCookie == nullptr) { - printWarningOrError(sif::OutputTypes::OUT_ERROR, "DeviceHandlerBase", - HasReturnvaluesIF::RETURN_FAILED, "Invalid cookie"); - } - if (this->fdirInstance == nullptr) { - this->fdirInstance = new DeviceHandlerFailureIsolation(setObjectId, - defaultFdirParentId); - } + CookieIF* comCookie, FailureIsolationBase* fdirInstance, + size_t cmdQueueSize) + : SystemObject(setObjectId), + mode(MODE_OFF), + submode(SUBMODE_NONE), + wiretappingMode(OFF), + storedRawData(StorageManagerIF::INVALID_ADDRESS), + deviceCommunicationId(deviceCommunication), + comCookie(comCookie), + healthHelper(this, setObjectId), + modeHelper(this), + parameterHelper(this), + actionHelper(this, nullptr), + poolManager(this, nullptr), + childTransitionFailure(RETURN_OK), + fdirInstance(fdirInstance), + defaultFDIRUsed(fdirInstance == nullptr), + switchOffWasReported(false), + childTransitionDelay(5000), + transitionSourceMode(_MODE_POWER_DOWN), + transitionSourceSubMode(SUBMODE_NONE) { + commandQueue = QueueFactory::instance()->createMessageQueue( + cmdQueueSize, MessageQueueMessage::MAX_MESSAGE_SIZE); + insertInCommandMap(RAW_COMMAND_ID); + cookieInfo.state = COOKIE_UNUSED; + cookieInfo.pendingCommand = deviceCommandMap.end(); + if (comCookie == nullptr) { + printWarningOrError(sif::OutputTypes::OUT_ERROR, "DeviceHandlerBase", + HasReturnvaluesIF::RETURN_FAILED, "Invalid cookie"); + } + if (this->fdirInstance == nullptr) { + this->fdirInstance = new DeviceHandlerFailureIsolation(setObjectId, defaultFdirParentId); + } } void DeviceHandlerBase::setHkDestination(object_id_t hkDestination) { - this->hkDestination = hkDestination; + this->hkDestination = hkDestination; } -void DeviceHandlerBase::setThermalStateRequestPoolIds( - lp_id_t thermalStatePoolId, lp_id_t heaterRequestPoolId, - uint32_t thermalSetId) { - thermalSet = new DeviceHandlerThermalSet(this, thermalSetId, - thermalStatePoolId, heaterRequestPoolId); +void DeviceHandlerBase::setThermalStateRequestPoolIds(lp_id_t thermalStatePoolId, + lp_id_t heaterRequestPoolId, + uint32_t thermalSetId) { + thermalSet = + new DeviceHandlerThermalSet(this, thermalSetId, thermalStatePoolId, heaterRequestPoolId); } - DeviceHandlerBase::~DeviceHandlerBase() { - delete comCookie; - if (defaultFDIRUsed) { - delete fdirInstance; - } - QueueFactory::instance()->deleteMessageQueue(commandQueue); + delete comCookie; + if (defaultFDIRUsed) { + delete fdirInstance; + } + QueueFactory::instance()->deleteMessageQueue(commandQueue); } ReturnValue_t DeviceHandlerBase::performOperation(uint8_t counter) { - this->pstStep = counter; - this->lastStep = this->pstStep; + this->pstStep = counter; + this->lastStep = this->pstStep; - if (getComAction() == CommunicationAction::NOTHING) { - return HasReturnvaluesIF::RETURN_OK; - } + if (getComAction() == CommunicationAction::NOTHING) { + return HasReturnvaluesIF::RETURN_OK; + } - if (getComAction() == CommunicationAction::PERFORM_OPERATION) { - cookieInfo.state = COOKIE_UNUSED; - readCommandQueue(); - doStateMachine(); - checkSwitchState(); - decrementDeviceReplyMap(); - fdirInstance->checkForFailures(); - performOperationHook(); - return RETURN_OK; - } - - if (mode == MODE_OFF) { - return RETURN_OK; - } - - switch (getComAction()) { - case CommunicationAction::SEND_WRITE: - if (cookieInfo.state == COOKIE_UNUSED) { - /* If no external command was specified, build internal command. */ - buildInternalCommand(); - } - doSendWrite(); - break; - case CommunicationAction::GET_WRITE: - doGetWrite(); - break; - case CommunicationAction::SEND_READ: - doSendRead(); - break; - case CommunicationAction::GET_READ: - doGetRead(); - /* This will be performed after datasets have been updated by the - custom device implementation. */ - poolManager.performHkOperation(); - break; - default: - break; - } + if (getComAction() == CommunicationAction::PERFORM_OPERATION) { + cookieInfo.state = COOKIE_UNUSED; + readCommandQueue(); + doStateMachine(); + checkSwitchState(); + decrementDeviceReplyMap(); + fdirInstance->checkForFailures(); + performOperationHook(); return RETURN_OK; + } + + if (mode == MODE_OFF) { + return RETURN_OK; + } + + switch (getComAction()) { + case CommunicationAction::SEND_WRITE: + if (cookieInfo.state == COOKIE_UNUSED) { + /* If no external command was specified, build internal command. */ + buildInternalCommand(); + } + doSendWrite(); + break; + case CommunicationAction::GET_WRITE: + doGetWrite(); + break; + case CommunicationAction::SEND_READ: + doSendRead(); + break; + case CommunicationAction::GET_READ: + doGetRead(); + /* This will be performed after datasets have been updated by the + custom device implementation. */ + poolManager.performHkOperation(); + break; + default: + break; + } + return RETURN_OK; } ReturnValue_t DeviceHandlerBase::initialize() { - ReturnValue_t result = SystemObject::initialize(); - if (result != RETURN_OK) { - return result; - } + ReturnValue_t result = SystemObject::initialize(); + if (result != RETURN_OK) { + return result; + } - communicationInterface = ObjectManager::instance()->get( - deviceCommunicationId); - if (communicationInterface == nullptr) { - printWarningOrError(sif::OutputTypes::OUT_ERROR, "initialize", - ObjectManagerIF::CHILD_INIT_FAILED, - "Passed communication IF invalid"); - return ObjectManagerIF::CHILD_INIT_FAILED; - } + communicationInterface = + ObjectManager::instance()->get(deviceCommunicationId); + if (communicationInterface == nullptr) { + printWarningOrError(sif::OutputTypes::OUT_ERROR, "initialize", + ObjectManagerIF::CHILD_INIT_FAILED, "Passed communication IF invalid"); + return ObjectManagerIF::CHILD_INIT_FAILED; + } - result = communicationInterface->initializeInterface(comCookie); - if (result != RETURN_OK) { - printWarningOrError(sif::OutputTypes::OUT_ERROR, "initialize", - ObjectManagerIF::CHILD_INIT_FAILED, - "ComIF initialization failed"); - return result; - } + result = communicationInterface->initializeInterface(comCookie); + if (result != RETURN_OK) { + printWarningOrError(sif::OutputTypes::OUT_ERROR, "initialize", + ObjectManagerIF::CHILD_INIT_FAILED, "ComIF initialization failed"); + return result; + } - IPCStore = ObjectManager::instance()->get(objects::IPC_STORE); - if (IPCStore == nullptr) { - printWarningOrError(sif::OutputTypes::OUT_ERROR, "initialize", - ObjectManagerIF::CHILD_INIT_FAILED, "IPC Store not set up"); - return ObjectManagerIF::CHILD_INIT_FAILED; - } + IPCStore = ObjectManager::instance()->get(objects::IPC_STORE); + if (IPCStore == nullptr) { + printWarningOrError(sif::OutputTypes::OUT_ERROR, "initialize", + ObjectManagerIF::CHILD_INIT_FAILED, "IPC Store not set up"); + return ObjectManagerIF::CHILD_INIT_FAILED; + } - if(rawDataReceiverId != objects::NO_OBJECT) { - AcceptsDeviceResponsesIF *rawReceiver = ObjectManager::instance()-> - get(rawDataReceiverId); + if (rawDataReceiverId != objects::NO_OBJECT) { + AcceptsDeviceResponsesIF* rawReceiver = + ObjectManager::instance()->get(rawDataReceiverId); - if (rawReceiver == nullptr) { - printWarningOrError(sif::OutputTypes::OUT_ERROR, - "initialize", ObjectManagerIF::CHILD_INIT_FAILED, - "Raw receiver object ID set but no valid object found."); + if (rawReceiver == nullptr) { + printWarningOrError(sif::OutputTypes::OUT_ERROR, "initialize", + ObjectManagerIF::CHILD_INIT_FAILED, + "Raw receiver object ID set but no valid object found."); #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Make sure the raw receiver object is set up properly" - " and implements AcceptsDeviceResponsesIF" << std::endl; + sif::error << "Make sure the raw receiver object is set up properly" + " and implements AcceptsDeviceResponsesIF" + << std::endl; #else - sif::printError("Make sure the raw receiver object is set up " - "properly and implements AcceptsDeviceResponsesIF\n"); + sif::printError( + "Make sure the raw receiver object is set up " + "properly and implements AcceptsDeviceResponsesIF\n"); #endif - return ObjectManagerIF::CHILD_INIT_FAILED; - } - defaultRawReceiver = rawReceiver->getDeviceQueue(); + return ObjectManagerIF::CHILD_INIT_FAILED; } + defaultRawReceiver = rawReceiver->getDeviceQueue(); + } - if(powerSwitcherId != objects::NO_OBJECT) { - powerSwitcher = ObjectManager::instance()->get(powerSwitcherId); - if (powerSwitcher == nullptr) { - printWarningOrError(sif::OutputTypes::OUT_ERROR, - "initialize", ObjectManagerIF::CHILD_INIT_FAILED, - "Power switcher set but no valid object found."); + if (powerSwitcherId != objects::NO_OBJECT) { + powerSwitcher = ObjectManager::instance()->get(powerSwitcherId); + if (powerSwitcher == nullptr) { + printWarningOrError(sif::OutputTypes::OUT_ERROR, "initialize", + ObjectManagerIF::CHILD_INIT_FAILED, + "Power switcher set but no valid object found."); #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Make sure the power switcher object is set up " - << "properly and implements PowerSwitchIF" << std::endl; + sif::error << "Make sure the power switcher object is set up " + << "properly and implements PowerSwitchIF" << std::endl; #else - sif::printError("Make sure the power switcher object is set up " - "properly and implements PowerSwitchIF\n"); + sif::printError( + "Make sure the power switcher object is set up " + "properly and implements PowerSwitchIF\n"); #endif - return ObjectManagerIF::CHILD_INIT_FAILED; - } + return ObjectManagerIF::CHILD_INIT_FAILED; } + } - result = healthHelper.initialize(); - if (result != RETURN_OK) { - return result; + result = healthHelper.initialize(); + if (result != RETURN_OK) { + return result; + } + + result = modeHelper.initialize(); + if (result != RETURN_OK) { + return result; + } + result = actionHelper.initialize(commandQueue); + if (result != RETURN_OK) { + return result; + } + result = fdirInstance->initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + + result = parameterHelper.initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + + result = poolManager.initialize(commandQueue); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + + fillCommandAndReplyMap(); + + if (thermalSet != nullptr) { + // Set temperature target state to NON_OP. + result = thermalSet->read(); + if (result == HasReturnvaluesIF::RETURN_OK) { + thermalSet->heaterRequest.value = ThermalComponentIF::STATE_REQUEST_NON_OPERATIONAL; + thermalSet->heaterRequest.setValid(true); + thermalSet->commit(); } + } - result = modeHelper.initialize(); - if (result != RETURN_OK) { - return result; - } - result = actionHelper.initialize(commandQueue); - if (result != RETURN_OK) { - return result; - } - result = fdirInstance->initialize(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - - result = parameterHelper.initialize(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - - result = poolManager.initialize(commandQueue); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - - fillCommandAndReplyMap(); - - if(thermalSet != nullptr) { - //Set temperature target state to NON_OP. - result = thermalSet->read(); - if(result == HasReturnvaluesIF::RETURN_OK) { - thermalSet->heaterRequest.value = - ThermalComponentIF::STATE_REQUEST_NON_OPERATIONAL; - thermalSet->heaterRequest.setValid(true); - thermalSet->commit(); - } - - } - - return RETURN_OK; + return RETURN_OK; } void DeviceHandlerBase::decrementDeviceReplyMap() { - for (std::pair& replyPair: deviceReplyMap) { - if (replyPair.second.delayCycles != 0) { - replyPair.second.delayCycles--; - if (replyPair.second.delayCycles == 0) { - if (replyPair.second.periodic) { - replyPair.second.delayCycles = replyPair.second.maxDelayCycles; - } - replyToReply(replyPair.first, replyPair.second, TIMEOUT); - missedReply(replyPair.first); - } + for (std::pair& replyPair : deviceReplyMap) { + if (replyPair.second.delayCycles != 0) { + replyPair.second.delayCycles--; + if (replyPair.second.delayCycles == 0) { + if (replyPair.second.periodic) { + replyPair.second.delayCycles = replyPair.second.maxDelayCycles; } + replyToReply(replyPair.first, replyPair.second, TIMEOUT); + missedReply(replyPair.first); + } } + } } void DeviceHandlerBase::readCommandQueue() { + if (dontCheckQueue()) { + return; + } - if (dontCheckQueue()) { - return; - } + CommandMessage command; + ReturnValue_t result = commandQueue->receiveMessage(&command); + if (result != RETURN_OK) { + return; + } - CommandMessage command; - ReturnValue_t result = commandQueue->receiveMessage(&command); - if (result != RETURN_OK) { - return; - } + result = healthHelper.handleHealthCommand(&command); + if (result == RETURN_OK) { + return; + } - result = healthHelper.handleHealthCommand(&command); - if (result == RETURN_OK) { - return; - } + result = modeHelper.handleModeCommand(&command); + if (result == RETURN_OK) { + return; + } - result = modeHelper.handleModeCommand(&command); - if (result == RETURN_OK) { - return; - } + result = actionHelper.handleActionMessage(&command); + if (result == RETURN_OK) { + return; + } - result = actionHelper.handleActionMessage(&command); - if (result == RETURN_OK) { - return; - } + result = parameterHelper.handleParameterMessage(&command); + if (result == RETURN_OK) { + return; + } - result = parameterHelper.handleParameterMessage(&command); - if (result == RETURN_OK) { - return; - } + result = poolManager.handleHousekeepingMessage(&command); + if (result == RETURN_OK) { + return; + } - result = poolManager.handleHousekeepingMessage(&command); - if (result == RETURN_OK) { - return; - } + result = handleDeviceHandlerMessage(&command); + if (result == RETURN_OK) { + return; + } - result = handleDeviceHandlerMessage(&command); - if (result == RETURN_OK) { - return; - } - - result = letChildHandleMessage(&command); - if (result == RETURN_OK) { - return; - } - - replyReturnvalueToCommand(CommandMessage::UNKNOWN_COMMAND); + result = letChildHandleMessage(&command); + if (result == RETURN_OK) { + return; + } + replyReturnvalueToCommand(CommandMessage::UNKNOWN_COMMAND); } void DeviceHandlerBase::doStateMachine() { - switch (mode) { + switch (mode) { case _MODE_START_UP: case _MODE_SHUT_DOWN: case _MODE_TO_NORMAL: case _MODE_TO_ON: case _MODE_TO_RAW: { - Mode_t currentMode = mode; - callChildStatemachine(); - //Only do timeout if child did not change anything - if (mode != currentMode) { - break; - } - uint32_t currentUptime; - Clock::getUptime(¤tUptime); - if (currentUptime - timeoutStart >= childTransitionDelay) { + Mode_t currentMode = mode; + callChildStatemachine(); + // Only do timeout if child did not change anything + if (mode != currentMode) { + break; + } + uint32_t currentUptime; + Clock::getUptime(¤tUptime); + if (currentUptime - timeoutStart >= childTransitionDelay) { #if FSFW_VERBOSE_LEVEL >= 1 && FSFW_OBJ_EVENT_TRANSLATION == 0 - char printout[60]; - sprintf(printout, "Transition timeout (%lu) occured !", - static_cast(childTransitionDelay)); - /* Common configuration error for development, so print it */ - printWarningOrError(sif::OutputTypes::OUT_WARNING, "doStateMachine", - RETURN_FAILED, printout); + char printout[60]; + sprintf(printout, "Transition timeout (%lu) occured !", + static_cast(childTransitionDelay)); + /* Common configuration error for development, so print it */ + printWarningOrError(sif::OutputTypes::OUT_WARNING, "doStateMachine", RETURN_FAILED, + printout); #endif - triggerEvent(MODE_TRANSITION_FAILED, childTransitionFailure, 0); - setMode(transitionSourceMode, transitionSourceSubMode); - break; - } - } - break; + triggerEvent(MODE_TRANSITION_FAILED, childTransitionFailure, 0); + setMode(transitionSourceMode, transitionSourceSubMode); + break; + } + } break; case _MODE_POWER_DOWN: - commandSwitch(PowerSwitchIF::SWITCH_OFF); - setMode(_MODE_WAIT_OFF); - break; + commandSwitch(PowerSwitchIF::SWITCH_OFF); + setMode(_MODE_WAIT_OFF); + break; case _MODE_POWER_ON: - commandSwitch(PowerSwitchIF::SWITCH_ON); - setMode(_MODE_WAIT_ON); - break; + commandSwitch(PowerSwitchIF::SWITCH_ON); + setMode(_MODE_WAIT_ON); + break; case _MODE_WAIT_ON: { - uint32_t currentUptime; - Clock::getUptime(¤tUptime); - if (powerSwitcher != nullptr and currentUptime - timeoutStart >= - powerSwitcher->getSwitchDelayMs()) { - triggerEvent(MODE_TRANSITION_FAILED, PowerSwitchIF::SWITCH_TIMEOUT, - 0); - setMode(_MODE_POWER_DOWN); - callChildStatemachine(); - break; - } - ReturnValue_t switchState = getStateOfSwitches(); - if ((switchState == PowerSwitchIF::SWITCH_ON) - || (switchState == NO_SWITCH)) { - //NOTE: TransitionSourceMode and -SubMode are set by handleCommandedModeTransition - childTransitionFailure = CHILD_TIMEOUT; - setMode(_MODE_START_UP); - callChildStatemachine(); - } - } - break; + uint32_t currentUptime; + Clock::getUptime(¤tUptime); + if (powerSwitcher != nullptr and + currentUptime - timeoutStart >= powerSwitcher->getSwitchDelayMs()) { + triggerEvent(MODE_TRANSITION_FAILED, PowerSwitchIF::SWITCH_TIMEOUT, 0); + setMode(_MODE_POWER_DOWN); + callChildStatemachine(); + break; + } + ReturnValue_t switchState = getStateOfSwitches(); + if ((switchState == PowerSwitchIF::SWITCH_ON) || (switchState == NO_SWITCH)) { + // NOTE: TransitionSourceMode and -SubMode are set by handleCommandedModeTransition + childTransitionFailure = CHILD_TIMEOUT; + setMode(_MODE_START_UP); + callChildStatemachine(); + } + } break; case _MODE_WAIT_OFF: { - uint32_t currentUptime; - Clock::getUptime(¤tUptime); + uint32_t currentUptime; + Clock::getUptime(¤tUptime); - if(powerSwitcher == nullptr) { - setMode(MODE_OFF); - break; - } + if (powerSwitcher == nullptr) { + setMode(MODE_OFF); + break; + } - if (currentUptime - timeoutStart >= powerSwitcher->getSwitchDelayMs()) { - triggerEvent(MODE_TRANSITION_FAILED, PowerSwitchIF::SWITCH_TIMEOUT, - 0); - setMode(MODE_ERROR_ON); - break; - } - ReturnValue_t switchState = getStateOfSwitches(); - if ((switchState == PowerSwitchIF::SWITCH_OFF) - || (switchState == NO_SWITCH)) { - setMode(_MODE_SWITCH_IS_OFF); - } - } - break; + if (currentUptime - timeoutStart >= powerSwitcher->getSwitchDelayMs()) { + triggerEvent(MODE_TRANSITION_FAILED, PowerSwitchIF::SWITCH_TIMEOUT, 0); + setMode(MODE_ERROR_ON); + break; + } + ReturnValue_t switchState = getStateOfSwitches(); + if ((switchState == PowerSwitchIF::SWITCH_OFF) || (switchState == NO_SWITCH)) { + setMode(_MODE_SWITCH_IS_OFF); + } + } break; case MODE_OFF: - doOffActivity(); - break; + doOffActivity(); + break; case MODE_ON: - doOnActivity(); - break; + doOnActivity(); + break; case MODE_RAW: case MODE_NORMAL: case MODE_ERROR_ON: - break; + break; case _MODE_SWITCH_IS_OFF: - setMode(MODE_OFF, SUBMODE_NONE); - break; + setMode(MODE_OFF, SUBMODE_NONE); + break; default: - triggerEvent(OBJECT_IN_INVALID_MODE, mode, submode); - setMode(_MODE_POWER_DOWN, 0); - break; - } + triggerEvent(OBJECT_IN_INVALID_MODE, mode, submode); + setMode(_MODE_POWER_DOWN, 0); + break; + } } -ReturnValue_t DeviceHandlerBase::isModeCombinationValid(Mode_t mode, - Submode_t submode) { - switch (mode) { +ReturnValue_t DeviceHandlerBase::isModeCombinationValid(Mode_t mode, Submode_t submode) { + switch (mode) { case MODE_OFF: case MODE_ON: case MODE_NORMAL: case MODE_RAW: - if (submode == SUBMODE_NONE) { - return RETURN_OK; - } else { - return INVALID_SUBMODE; - } + if (submode == SUBMODE_NONE) { + return RETURN_OK; + } else { + return INVALID_SUBMODE; + } default: - return HasModesIF::INVALID_MODE; - } + return HasModesIF::INVALID_MODE; + } } ReturnValue_t DeviceHandlerBase::insertInCommandAndReplyMap( - DeviceCommandId_t deviceCommand, uint16_t maxDelayCycles, - LocalPoolDataSetBase* replyDataSet, size_t replyLen, bool periodic, - bool hasDifferentReplyId, DeviceCommandId_t replyId) { - //No need to check, as we may try to insert multiple times. - insertInCommandMap(deviceCommand); - if (hasDifferentReplyId) { - return insertInReplyMap(replyId, maxDelayCycles, - replyDataSet, replyLen, periodic); - } else { - return insertInReplyMap(deviceCommand, maxDelayCycles, - replyDataSet, replyLen, periodic); - } + DeviceCommandId_t deviceCommand, uint16_t maxDelayCycles, LocalPoolDataSetBase* replyDataSet, + size_t replyLen, bool periodic, bool hasDifferentReplyId, DeviceCommandId_t replyId) { + // No need to check, as we may try to insert multiple times. + insertInCommandMap(deviceCommand); + if (hasDifferentReplyId) { + return insertInReplyMap(replyId, maxDelayCycles, replyDataSet, replyLen, periodic); + } else { + return insertInReplyMap(deviceCommand, maxDelayCycles, replyDataSet, replyLen, periodic); + } } ReturnValue_t DeviceHandlerBase::insertInReplyMap(DeviceCommandId_t replyId, - uint16_t maxDelayCycles, LocalPoolDataSetBase* dataSet, - size_t replyLen, bool periodic) { - DeviceReplyInfo info; - info.maxDelayCycles = maxDelayCycles; - info.periodic = periodic; - info.delayCycles = 0; - info.replyLen = replyLen; - info.dataSet = dataSet; - info.command = deviceCommandMap.end(); - auto resultPair = deviceReplyMap.emplace(replyId, info); - if (resultPair.second) { - return RETURN_OK; - } else { - return RETURN_FAILED; - } + uint16_t maxDelayCycles, + LocalPoolDataSetBase* dataSet, size_t replyLen, + bool periodic) { + DeviceReplyInfo info; + info.maxDelayCycles = maxDelayCycles; + info.periodic = periodic; + info.delayCycles = 0; + info.replyLen = replyLen; + info.dataSet = dataSet; + info.command = deviceCommandMap.end(); + auto resultPair = deviceReplyMap.emplace(replyId, info); + if (resultPair.second) { + return RETURN_OK; + } else { + return RETURN_FAILED; + } } ReturnValue_t DeviceHandlerBase::insertInCommandMap(DeviceCommandId_t deviceCommand) { - DeviceCommandInfo info; - info.expectedReplies = 0; - info.isExecuting = false; - info.sendReplyTo = NO_COMMANDER; - auto resultPair = deviceCommandMap.emplace(deviceCommand, info); - if (resultPair.second) { - return RETURN_OK; - } else { - return RETURN_FAILED; - } + DeviceCommandInfo info; + info.expectedReplies = 0; + info.isExecuting = false; + info.sendReplyTo = NO_COMMANDER; + auto resultPair = deviceCommandMap.emplace(deviceCommand, info); + if (resultPair.second) { + return RETURN_OK; + } else { + return RETURN_FAILED; + } } -size_t DeviceHandlerBase::getNextReplyLength(DeviceCommandId_t commandId){ - DeviceReplyIter iter = deviceReplyMap.find(commandId); - if(iter != deviceReplyMap.end()) { - return iter->second.replyLen; - }else{ - return 0; - } +size_t DeviceHandlerBase::getNextReplyLength(DeviceCommandId_t commandId) { + DeviceReplyIter iter = deviceReplyMap.find(commandId); + if (iter != deviceReplyMap.end()) { + return iter->second.replyLen; + } else { + return 0; + } } ReturnValue_t DeviceHandlerBase::updateReplyMapEntry(DeviceCommandId_t deviceReply, - uint16_t delayCycles, uint16_t maxDelayCycles, bool periodic) { - auto replyIter = deviceReplyMap.find(deviceReply); - if (replyIter == deviceReplyMap.end()) { - triggerEvent(INVALID_DEVICE_COMMAND, deviceReply); - return COMMAND_NOT_SUPPORTED; - } else { - DeviceReplyInfo *info = &(replyIter->second); - if (maxDelayCycles != 0) { - info->maxDelayCycles = maxDelayCycles; - } - info->delayCycles = delayCycles; - info->periodic = periodic; - return RETURN_OK; + uint16_t delayCycles, uint16_t maxDelayCycles, + bool periodic) { + auto replyIter = deviceReplyMap.find(deviceReply); + if (replyIter == deviceReplyMap.end()) { + triggerEvent(INVALID_DEVICE_COMMAND, deviceReply); + return COMMAND_NOT_SUPPORTED; + } else { + DeviceReplyInfo* info = &(replyIter->second); + if (maxDelayCycles != 0) { + info->maxDelayCycles = maxDelayCycles; } + info->delayCycles = delayCycles; + info->periodic = periodic; + return RETURN_OK; + } } ReturnValue_t DeviceHandlerBase::updatePeriodicReply(bool enable, DeviceCommandId_t deviceReply) { - auto replyIter = deviceReplyMap.find(deviceReply); - if (replyIter == deviceReplyMap.end()) { - triggerEvent(INVALID_DEVICE_COMMAND, deviceReply); - return COMMAND_NOT_SUPPORTED; - } else { - DeviceReplyInfo *info = &(replyIter->second); - if(not info->periodic) { - return COMMAND_NOT_SUPPORTED; - } - if(enable) { - info->delayCycles = info->maxDelayCycles; - } - else { - info->delayCycles = 0; - } + auto replyIter = deviceReplyMap.find(deviceReply); + if (replyIter == deviceReplyMap.end()) { + triggerEvent(INVALID_DEVICE_COMMAND, deviceReply); + return COMMAND_NOT_SUPPORTED; + } else { + DeviceReplyInfo* info = &(replyIter->second); + if (not info->periodic) { + return COMMAND_NOT_SUPPORTED; } - return HasReturnvaluesIF::RETURN_OK; + if (enable) { + info->delayCycles = info->maxDelayCycles; + } else { + info->delayCycles = 0; + } + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t DeviceHandlerBase::setReplyDataset(DeviceCommandId_t replyId, - LocalPoolDataSetBase *dataSet) { - auto replyIter = deviceReplyMap.find(replyId); - if(replyIter == deviceReplyMap.end()) { - return HasReturnvaluesIF::RETURN_FAILED; - } - replyIter->second.dataSet = dataSet; - return HasReturnvaluesIF::RETURN_OK; + LocalPoolDataSetBase* dataSet) { + auto replyIter = deviceReplyMap.find(replyId); + if (replyIter == deviceReplyMap.end()) { + return HasReturnvaluesIF::RETURN_FAILED; + } + replyIter->second.dataSet = dataSet; + return HasReturnvaluesIF::RETURN_OK; } void DeviceHandlerBase::callChildStatemachine() { - if (mode == _MODE_START_UP) { - doStartUp(); - } else if (mode == _MODE_SHUT_DOWN) { - doShutDown(); - } else if (mode & TRANSITION_MODE_CHILD_ACTION_MASK) { - doTransition(transitionSourceMode, transitionSourceSubMode); - } + if (mode == _MODE_START_UP) { + doStartUp(); + } else if (mode == _MODE_SHUT_DOWN) { + doShutDown(); + } else if (mode & TRANSITION_MODE_CHILD_ACTION_MASK) { + doTransition(transitionSourceMode, transitionSourceSubMode); + } } void DeviceHandlerBase::setTransition(Mode_t modeTo, Submode_t submodeTo) { - triggerEvent(CHANGING_MODE, modeTo, submodeTo); - childTransitionDelay = getTransitionDelayMs(mode, modeTo); - transitionSourceMode = mode; - transitionSourceSubMode = submode; - childTransitionFailure = CHILD_TIMEOUT; + triggerEvent(CHANGING_MODE, modeTo, submodeTo); + childTransitionDelay = getTransitionDelayMs(mode, modeTo); + transitionSourceMode = mode; + transitionSourceSubMode = submode; + childTransitionFailure = CHILD_TIMEOUT; - // transitionTargetMode is set by setMode - setMode((modeTo | TRANSITION_MODE_CHILD_ACTION_MASK), submodeTo); + // transitionTargetMode is set by setMode + setMode((modeTo | TRANSITION_MODE_CHILD_ACTION_MASK), submodeTo); } void DeviceHandlerBase::setMode(Mode_t newMode, uint8_t newSubmode) { - /* TODO: This will probably be done by the LocalDataPoolManager now */ - //changeHK(mode, submode, false); - submode = newSubmode; - mode = newMode; - modeChanged(); - setNormalDatapoolEntriesInvalid(); - if (!isTransitionalMode()) { - modeHelper.modeChanged(newMode, newSubmode); - announceMode(false); - } - Clock::getUptime(&timeoutStart); - - if (mode == MODE_OFF and thermalSet != nullptr) { - ReturnValue_t result = thermalSet->read(); - if(result == HasReturnvaluesIF::RETURN_OK) { - if (thermalSet->heaterRequest.value != - ThermalComponentIF::STATE_REQUEST_IGNORE) { - thermalSet->heaterRequest.value = ThermalComponentIF:: - STATE_REQUEST_NON_OPERATIONAL; - } - thermalSet->heaterRequest.commit(PoolVariableIF::VALID); - } + /* TODO: This will probably be done by the LocalDataPoolManager now */ + // changeHK(mode, submode, false); + submode = newSubmode; + mode = newMode; + modeChanged(); + setNormalDatapoolEntriesInvalid(); + if (!isTransitionalMode()) { + modeHelper.modeChanged(newMode, newSubmode); + announceMode(false); + } + Clock::getUptime(&timeoutStart); + if (mode == MODE_OFF and thermalSet != nullptr) { + ReturnValue_t result = thermalSet->read(); + if (result == HasReturnvaluesIF::RETURN_OK) { + if (thermalSet->heaterRequest.value != ThermalComponentIF::STATE_REQUEST_IGNORE) { + thermalSet->heaterRequest.value = ThermalComponentIF::STATE_REQUEST_NON_OPERATIONAL; + } + thermalSet->heaterRequest.commit(PoolVariableIF::VALID); } - /* TODO: This will probably be done by the LocalDataPoolManager now */ - //changeHK(mode, submode, true); + } + /* TODO: This will probably be done by the LocalDataPoolManager now */ + // changeHK(mode, submode, true); } -void DeviceHandlerBase::setMode(Mode_t newMode) { - setMode(newMode, submode); +void DeviceHandlerBase::setMode(Mode_t newMode) { setMode(newMode, submode); } + +void DeviceHandlerBase::replyReturnvalueToCommand(ReturnValue_t status, uint32_t parameter) { + // This is actually the reply protocol for raw and misc DH commands. + if (status == RETURN_OK) { + CommandMessage reply(CommandMessage::REPLY_COMMAND_OK, 0, parameter); + commandQueue->reply(&reply); + } else { + CommandMessage reply(CommandMessage::REPLY_REJECTED, status, parameter); + commandQueue->reply(&reply); + } } -void DeviceHandlerBase::replyReturnvalueToCommand(ReturnValue_t status, - uint32_t parameter) { - //This is actually the reply protocol for raw and misc DH commands. - if (status == RETURN_OK) { - CommandMessage reply(CommandMessage::REPLY_COMMAND_OK, 0, parameter); - commandQueue->reply(&reply); +void DeviceHandlerBase::replyToCommand(ReturnValue_t status, uint32_t parameter) { + // Check if we reply to a raw command. + if (cookieInfo.pendingCommand->first == RAW_COMMAND_ID) { + if (status == NO_REPLY_EXPECTED) { + status = RETURN_OK; + } + replyReturnvalueToCommand(status, parameter); + // Always delete data from a raw command. + IPCStore->deleteData(storedRawData); + return; + } + // Check if we were externally commanded. + if (cookieInfo.pendingCommand->second.sendReplyTo != NO_COMMANDER) { + MessageQueueId_t queueId = cookieInfo.pendingCommand->second.sendReplyTo; + if (status == NO_REPLY_EXPECTED) { + actionHelper.finish(true, queueId, cookieInfo.pendingCommand->first, RETURN_OK); } else { - CommandMessage reply(CommandMessage::REPLY_REJECTED, status, parameter); - commandQueue->reply(&reply); - } -} - -void DeviceHandlerBase::replyToCommand(ReturnValue_t status, - uint32_t parameter) { - // Check if we reply to a raw command. - if (cookieInfo.pendingCommand->first == RAW_COMMAND_ID) { - if (status == NO_REPLY_EXPECTED) { - status = RETURN_OK; - } - replyReturnvalueToCommand(status, parameter); - // Always delete data from a raw command. - IPCStore->deleteData(storedRawData); - return; - } - // Check if we were externally commanded. - if (cookieInfo.pendingCommand->second.sendReplyTo != NO_COMMANDER) { - MessageQueueId_t queueId = cookieInfo.pendingCommand->second.sendReplyTo; - if (status == NO_REPLY_EXPECTED) { - actionHelper.finish(true, queueId, cookieInfo.pendingCommand->first, - RETURN_OK); - } else { - actionHelper.step(1, queueId, cookieInfo.pendingCommand->first, - status); - } + actionHelper.step(1, queueId, cookieInfo.pendingCommand->first, status); } + } } void DeviceHandlerBase::replyToReply(const DeviceCommandId_t command, DeviceReplyInfo& replyInfo, - ReturnValue_t status) { - // No need to check if iter exists, as this is checked by callers. - // If someone else uses the method, add check. - if (replyInfo.command == deviceCommandMap.end()) { - //Is most likely periodic reply. Silent return. - return; - } - DeviceCommandInfo* info = &replyInfo.command->second; - if (info == nullptr){ - printWarningOrError(sif::OutputTypes::OUT_ERROR, - "replyToReply", HasReturnvaluesIF::RETURN_FAILED, - "Command pointer not found"); - return; - } + ReturnValue_t status) { + // No need to check if iter exists, as this is checked by callers. + // If someone else uses the method, add check. + if (replyInfo.command == deviceCommandMap.end()) { + // Is most likely periodic reply. Silent return. + return; + } + DeviceCommandInfo* info = &replyInfo.command->second; + if (info == nullptr) { + printWarningOrError(sif::OutputTypes::OUT_ERROR, "replyToReply", + HasReturnvaluesIF::RETURN_FAILED, "Command pointer not found"); + return; + } - if (info->expectedReplies > 0){ - // Check before to avoid underflow - info->expectedReplies--; - } - // Check if more replies are expected. If so, do nothing. - if (info->expectedReplies == 0) { - // Check if it was transition or internal command. - // Don't send any replies in that case. - if (info->sendReplyTo != NO_COMMANDER) { - bool success = false; - if(status == HasReturnvaluesIF::RETURN_OK) { - success = true; - } - actionHelper.finish(success, info->sendReplyTo, command, status); - } - info->isExecuting = false; + if (info->expectedReplies > 0) { + // Check before to avoid underflow + info->expectedReplies--; + } + // Check if more replies are expected. If so, do nothing. + if (info->expectedReplies == 0) { + // Check if it was transition or internal command. + // Don't send any replies in that case. + if (info->sendReplyTo != NO_COMMANDER) { + bool success = false; + if (status == HasReturnvaluesIF::RETURN_OK) { + success = true; + } + actionHelper.finish(success, info->sendReplyTo, command, status); } + info->isExecuting = false; + } } void DeviceHandlerBase::doSendWrite() { - if (cookieInfo.state == COOKIE_WRITE_READY) { + if (cookieInfo.state == COOKIE_WRITE_READY) { + ReturnValue_t result = communicationInterface->sendMessage(comCookie, rawPacket, rawPacketLen); - ReturnValue_t result = communicationInterface->sendMessage(comCookie, - rawPacket, rawPacketLen); - - if (result == RETURN_OK) { - cookieInfo.state = COOKIE_WRITE_SENT; - } else { - // always generate a failure event, so that FDIR knows what's up - triggerEvent(DEVICE_SENDING_COMMAND_FAILED, result, - cookieInfo.pendingCommand->first); - replyToCommand(result); - cookieInfo.state = COOKIE_UNUSED; - cookieInfo.pendingCommand->second.isExecuting = false; - } + if (result == RETURN_OK) { + cookieInfo.state = COOKIE_WRITE_SENT; + } else { + // always generate a failure event, so that FDIR knows what's up + triggerEvent(DEVICE_SENDING_COMMAND_FAILED, result, cookieInfo.pendingCommand->first); + replyToCommand(result); + cookieInfo.state = COOKIE_UNUSED; + cookieInfo.pendingCommand->second.isExecuting = false; } + } } void DeviceHandlerBase::doGetWrite() { - if (cookieInfo.state != COOKIE_WRITE_SENT) { - return; + if (cookieInfo.state != COOKIE_WRITE_SENT) { + return; + } + cookieInfo.state = COOKIE_UNUSED; + ReturnValue_t result = communicationInterface->getSendSuccess(comCookie); + if (result == RETURN_OK) { + if (wiretappingMode == RAW) { + replyRawData(rawPacket, rawPacketLen, requestedRawTraffic, true); } - cookieInfo.state = COOKIE_UNUSED; - ReturnValue_t result = communicationInterface->getSendSuccess(comCookie); - if (result == RETURN_OK) { - if (wiretappingMode == RAW) { - replyRawData(rawPacket, rawPacketLen, requestedRawTraffic, true); - } - //We need to distinguish here, because a raw command never expects a reply. - //(Could be done in eRIRM, but then child implementations need to be careful. - result = enableReplyInReplyMap(cookieInfo.pendingCommand); - } else { - //always generate a failure event, so that FDIR knows what's up - triggerEvent(DEVICE_SENDING_COMMAND_FAILED, result, - cookieInfo.pendingCommand->first); - } - if (result != RETURN_OK) { - cookieInfo.pendingCommand->second.isExecuting = false; - } - replyToCommand(result); + // We need to distinguish here, because a raw command never expects a reply. + //(Could be done in eRIRM, but then child implementations need to be careful. + result = enableReplyInReplyMap(cookieInfo.pendingCommand); + } else { + // always generate a failure event, so that FDIR knows what's up + triggerEvent(DEVICE_SENDING_COMMAND_FAILED, result, cookieInfo.pendingCommand->first); + } + if (result != RETURN_OK) { + cookieInfo.pendingCommand->second.isExecuting = false; + } + replyToCommand(result); } void DeviceHandlerBase::doSendRead() { - ReturnValue_t result; + ReturnValue_t result; - size_t replyLen = 0; - if(cookieInfo.pendingCommand != deviceCommandMap.end()) { - replyLen = getNextReplyLength(cookieInfo.pendingCommand->first); - } + size_t replyLen = 0; + if (cookieInfo.pendingCommand != deviceCommandMap.end()) { + replyLen = getNextReplyLength(cookieInfo.pendingCommand->first); + } - result = communicationInterface->requestReceiveMessage(comCookie, replyLen); + result = communicationInterface->requestReceiveMessage(comCookie, replyLen); - if (result == RETURN_OK) { - cookieInfo.state = COOKIE_READ_SENT; - } else { - triggerEvent(DEVICE_REQUESTING_REPLY_FAILED, result); - //We can't inform anyone, because we don't know which command was sent last. - //So, we need to wait for a timeout. - //but I think we can allow to ignore one missedReply. - ignoreMissedRepliesCount++; - cookieInfo.state = COOKIE_UNUSED; - } + if (result == RETURN_OK) { + cookieInfo.state = COOKIE_READ_SENT; + } else { + triggerEvent(DEVICE_REQUESTING_REPLY_FAILED, result); + // We can't inform anyone, because we don't know which command was sent last. + // So, we need to wait for a timeout. + // but I think we can allow to ignore one missedReply. + ignoreMissedRepliesCount++; + cookieInfo.state = COOKIE_UNUSED; + } } void DeviceHandlerBase::doGetRead() { - size_t receivedDataLen = 0; - uint8_t *receivedData = nullptr; - - if (cookieInfo.state != COOKIE_READ_SENT) { - cookieInfo.state = COOKIE_UNUSED; - return; - } + size_t receivedDataLen = 0; + uint8_t* receivedData = nullptr; + if (cookieInfo.state != COOKIE_READ_SENT) { cookieInfo.state = COOKIE_UNUSED; + return; + } - ReturnValue_t result = communicationInterface->readReceivedMessage( - comCookie, &receivedData, &receivedDataLen); + cookieInfo.state = COOKIE_UNUSED; - if (result != RETURN_OK) { - triggerEvent(DEVICE_REQUESTING_REPLY_FAILED, result); - //I think we can allow to ignore one missedReply. - ignoreMissedRepliesCount++; - return; - } - - if (receivedDataLen == 0 or result == DeviceCommunicationIF::NO_REPLY_RECEIVED) - return; - - if (wiretappingMode == RAW) { - replyRawData(receivedData, receivedDataLen, requestedRawTraffic); - } - - if (mode == MODE_RAW) { - if (defaultRawReceiver != MessageQueueIF::NO_QUEUE) { - replyRawReplyIfnotWiretapped(receivedData, receivedDataLen); - } - } - else { - parseReply(receivedData, receivedDataLen); + ReturnValue_t result = + communicationInterface->readReceivedMessage(comCookie, &receivedData, &receivedDataLen); + + if (result != RETURN_OK) { + triggerEvent(DEVICE_REQUESTING_REPLY_FAILED, result); + // I think we can allow to ignore one missedReply. + ignoreMissedRepliesCount++; + return; + } + + if (receivedDataLen == 0 or result == DeviceCommunicationIF::NO_REPLY_RECEIVED) return; + + if (wiretappingMode == RAW) { + replyRawData(receivedData, receivedDataLen, requestedRawTraffic); + } + + if (mode == MODE_RAW) { + if (defaultRawReceiver != MessageQueueIF::NO_QUEUE) { + replyRawReplyIfnotWiretapped(receivedData, receivedDataLen); } + } else { + parseReply(receivedData, receivedDataLen); + } } -void DeviceHandlerBase::parseReply(const uint8_t* receivedData, - size_t receivedDataLen) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_FAILED; - DeviceCommandId_t foundId = DeviceHandlerIF::NO_COMMAND_ID; - size_t foundLen = 0; - /* The loop may not execute more often than the number of received bytes - (worst case). This approach avoids infinite loops due to buggy scanForReply routines. */ - uint32_t remainingLength = receivedDataLen; - for (uint32_t count = 0; count < receivedDataLen; count++) { - result = scanForReply(receivedData, remainingLength, &foundId, &foundLen); - switch (result) { - case RETURN_OK: - handleReply(receivedData, foundId, foundLen); - if(foundLen == 0) { - printWarningOrError(sif::OutputTypes::OUT_WARNING, - "parseReply", ObjectManagerIF::CHILD_INIT_FAILED, - "Found length is one, parsing might be stuck"); - } - break; - case APERIODIC_REPLY: { - result = interpretDeviceReply(foundId, receivedData); - if (result != RETURN_OK) { - replyRawReplyIfnotWiretapped(receivedData, foundLen); - triggerEvent(DEVICE_INTERPRETING_REPLY_FAILED, result, - foundId); - } - if(foundLen == 0) { - printWarningOrError(sif::OutputTypes::OUT_ERROR, - "parseReply", ObjectManagerIF::CHILD_INIT_FAILED, - "Power switcher set but no valid object found."); -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "DeviceHandlerBase::parseReply: foundLen is 0!" - " Packet parsing will be stuck." << std::endl; -#endif - } - break; +void DeviceHandlerBase::parseReply(const uint8_t* receivedData, size_t receivedDataLen) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_FAILED; + DeviceCommandId_t foundId = DeviceHandlerIF::NO_COMMAND_ID; + size_t foundLen = 0; + /* The loop may not execute more often than the number of received bytes + (worst case). This approach avoids infinite loops due to buggy scanForReply routines. */ + uint32_t remainingLength = receivedDataLen; + for (uint32_t count = 0; count < receivedDataLen; count++) { + result = scanForReply(receivedData, remainingLength, &foundId, &foundLen); + switch (result) { + case RETURN_OK: + handleReply(receivedData, foundId, foundLen); + if (foundLen == 0) { + printWarningOrError(sif::OutputTypes::OUT_WARNING, "parseReply", + ObjectManagerIF::CHILD_INIT_FAILED, + "Found length is one, parsing might be stuck"); } - case IGNORE_REPLY_DATA: - continue; - case IGNORE_FULL_PACKET: - return; - default: - // We need to wait for timeout.. don't know what command failed - // and who sent it. - replyRawReplyIfnotWiretapped(receivedData, foundLen); - triggerEvent(DEVICE_READING_REPLY_FAILED, result, foundLen); - break; - } - receivedData += foundLen; - if (remainingLength > foundLen) { - remainingLength -= foundLen; - } else { - return; - } - } -} - -void DeviceHandlerBase::handleReply(const uint8_t* receivedData, - DeviceCommandId_t foundId, uint32_t foundLen) { - ReturnValue_t result; - DeviceReplyMap::iterator iter = deviceReplyMap.find(foundId); - - if (iter == deviceReplyMap.end()) { - replyRawReplyIfnotWiretapped(receivedData, foundLen); - triggerEvent(DEVICE_UNKNOWN_REPLY, foundId); - return; - } - - DeviceReplyInfo *info = &(iter->second); - - if (info->delayCycles != 0) { + break; + case APERIODIC_REPLY: { result = interpretDeviceReply(foundId, receivedData); - - if(result == IGNORE_REPLY_DATA) { - return; - } - - if (info->periodic) { - info->delayCycles = info->maxDelayCycles; - } - else { - info->delayCycles = 0; - } - if (result != RETURN_OK) { - // Report failed interpretation to FDIR. - replyRawReplyIfnotWiretapped(receivedData, foundLen); - triggerEvent(DEVICE_INTERPRETING_REPLY_FAILED, result, foundId); + replyRawReplyIfnotWiretapped(receivedData, foundLen); + triggerEvent(DEVICE_INTERPRETING_REPLY_FAILED, result, foundId); } - replyToReply(iter->first, iter->second, result); - } - else { - /* Other completion failure messages are created by timeout. - Powering down the device might take some time during which periodic - replies may still come in. */ - if (mode != _MODE_WAIT_OFF) { - triggerEvent(DEVICE_UNREQUESTED_REPLY, foundId); + if (foundLen == 0) { + printWarningOrError(sif::OutputTypes::OUT_ERROR, "parseReply", + ObjectManagerIF::CHILD_INIT_FAILED, + "Power switcher set but no valid object found."); +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "DeviceHandlerBase::parseReply: foundLen is 0!" + " Packet parsing will be stuck." + << std::endl; +#endif } + break; + } + case IGNORE_REPLY_DATA: + continue; + case IGNORE_FULL_PACKET: + return; + default: + // We need to wait for timeout.. don't know what command failed + // and who sent it. + replyRawReplyIfnotWiretapped(receivedData, foundLen); + triggerEvent(DEVICE_READING_REPLY_FAILED, result, foundLen); + break; } -} - -ReturnValue_t DeviceHandlerBase::getStorageData(store_address_t storageAddress, - uint8_t** data, uint32_t * len) { - size_t lenTmp; - - if (IPCStore == nullptr) { - *data = nullptr; - *len = 0; - return RETURN_FAILED; - } - ReturnValue_t result = IPCStore->modifyData(storageAddress, data, &lenTmp); - if (result == RETURN_OK) { - *len = lenTmp; - return RETURN_OK; + receivedData += foundLen; + if (remainingLength > foundLen) { + remainingLength -= foundLen; } else { - triggerEvent(StorageManagerIF::GET_DATA_FAILED, result, - storageAddress.raw); - *data = nullptr; - *len = 0; - return result; + return; } + } } -void DeviceHandlerBase::replyRawData(const uint8_t *data, size_t len, - MessageQueueId_t sendTo, bool isCommand) { - if (IPCStore == nullptr or len == 0 or sendTo == MessageQueueIF::NO_QUEUE) { - return; +void DeviceHandlerBase::handleReply(const uint8_t* receivedData, DeviceCommandId_t foundId, + uint32_t foundLen) { + ReturnValue_t result; + DeviceReplyMap::iterator iter = deviceReplyMap.find(foundId); + + if (iter == deviceReplyMap.end()) { + replyRawReplyIfnotWiretapped(receivedData, foundLen); + triggerEvent(DEVICE_UNKNOWN_REPLY, foundId); + return; + } + + DeviceReplyInfo* info = &(iter->second); + + if (info->delayCycles != 0) { + result = interpretDeviceReply(foundId, receivedData); + + if (result == IGNORE_REPLY_DATA) { + return; + } + + if (info->periodic) { + info->delayCycles = info->maxDelayCycles; + } else { + info->delayCycles = 0; } - store_address_t address; - ReturnValue_t result = IPCStore->addData(&address, data, len); if (result != RETURN_OK) { - triggerEvent(StorageManagerIF::STORE_DATA_FAILED, result); - return; + // Report failed interpretation to FDIR. + replyRawReplyIfnotWiretapped(receivedData, foundLen); + triggerEvent(DEVICE_INTERPRETING_REPLY_FAILED, result, foundId); } - - CommandMessage command; - - DeviceHandlerMessage::setDeviceHandlerRawReplyMessage(&command, - getObjectId(), address, isCommand); - - result = commandQueue->sendMessage(sendTo, &command); - - if (result != RETURN_OK) { - IPCStore->deleteData(address); - // Silently discard data, this indicates heavy TM traffic which - // should not be increased by additional events. + replyToReply(iter->first, iter->second, result); + } else { + /* Other completion failure messages are created by timeout. + Powering down the device might take some time during which periodic + replies may still come in. */ + if (mode != _MODE_WAIT_OFF) { + triggerEvent(DEVICE_UNREQUESTED_REPLY, foundId); } + } } -//Default child implementations +ReturnValue_t DeviceHandlerBase::getStorageData(store_address_t storageAddress, uint8_t** data, + uint32_t* len) { + size_t lenTmp; + + if (IPCStore == nullptr) { + *data = nullptr; + *len = 0; + return RETURN_FAILED; + } + ReturnValue_t result = IPCStore->modifyData(storageAddress, data, &lenTmp); + if (result == RETURN_OK) { + *len = lenTmp; + return RETURN_OK; + } else { + triggerEvent(StorageManagerIF::GET_DATA_FAILED, result, storageAddress.raw); + *data = nullptr; + *len = 0; + return result; + } +} + +void DeviceHandlerBase::replyRawData(const uint8_t* data, size_t len, MessageQueueId_t sendTo, + bool isCommand) { + if (IPCStore == nullptr or len == 0 or sendTo == MessageQueueIF::NO_QUEUE) { + return; + } + store_address_t address; + ReturnValue_t result = IPCStore->addData(&address, data, len); + + if (result != RETURN_OK) { + triggerEvent(StorageManagerIF::STORE_DATA_FAILED, result); + return; + } + + CommandMessage command; + + DeviceHandlerMessage::setDeviceHandlerRawReplyMessage(&command, getObjectId(), address, + isCommand); + + result = commandQueue->sendMessage(sendTo, &command); + + if (result != RETURN_OK) { + IPCStore->deleteData(address); + // Silently discard data, this indicates heavy TM traffic which + // should not be increased by additional events. + } +} + +// Default child implementations DeviceHandlerIF::CommunicationAction DeviceHandlerBase::getComAction() { - switch (pstStep) { + switch (pstStep) { case 0: - return CommunicationAction::PERFORM_OPERATION; - break; + return CommunicationAction::PERFORM_OPERATION; + break; case 1: - return CommunicationAction::SEND_WRITE; - break; + return CommunicationAction::SEND_WRITE; + break; case 2: - return CommunicationAction::GET_WRITE; - break; + return CommunicationAction::GET_WRITE; + break; case 3: - return CommunicationAction::SEND_READ; - break; + return CommunicationAction::SEND_READ; + break; case 4: - return CommunicationAction::GET_READ; - break; + return CommunicationAction::GET_READ; + break; default: - break; - } - return CommunicationAction::NOTHING; + break; + } + return CommunicationAction::NOTHING; } -MessageQueueId_t DeviceHandlerBase::getCommandQueue() const { - return commandQueue->getId(); -} +MessageQueueId_t DeviceHandlerBase::getCommandQueue() const { return commandQueue->getId(); } void DeviceHandlerBase::buildRawDeviceCommand(CommandMessage* commandMessage) { - storedRawData = DeviceHandlerMessage::getStoreAddress(commandMessage); - ReturnValue_t result = getStorageData(storedRawData, &rawPacket, - &rawPacketLen); - if (result != RETURN_OK) { - replyReturnvalueToCommand(result, RAW_COMMAND_ID); - storedRawData.raw = StorageManagerIF::INVALID_ADDRESS; - } else { - cookieInfo.pendingCommand = deviceCommandMap.find( - (DeviceCommandId_t) RAW_COMMAND_ID); - cookieInfo.pendingCommand->second.isExecuting = true; - cookieInfo.state = COOKIE_WRITE_READY; - } + storedRawData = DeviceHandlerMessage::getStoreAddress(commandMessage); + ReturnValue_t result = getStorageData(storedRawData, &rawPacket, &rawPacketLen); + if (result != RETURN_OK) { + replyReturnvalueToCommand(result, RAW_COMMAND_ID); + storedRawData.raw = StorageManagerIF::INVALID_ADDRESS; + } else { + cookieInfo.pendingCommand = deviceCommandMap.find((DeviceCommandId_t)RAW_COMMAND_ID); + cookieInfo.pendingCommand->second.isExecuting = true; + cookieInfo.state = COOKIE_WRITE_READY; + } } void DeviceHandlerBase::commandSwitch(ReturnValue_t onOff) { - if(powerSwitcher == nullptr) { - return; - } - const uint8_t *switches; - uint8_t numberOfSwitches = 0; - ReturnValue_t result = getSwitches(&switches, &numberOfSwitches); - if (result == RETURN_OK) { - while (numberOfSwitches > 0) { - powerSwitcher->sendSwitchCommand(switches[numberOfSwitches - 1], - onOff); - numberOfSwitches--; - } + if (powerSwitcher == nullptr) { + return; + } + const uint8_t* switches; + uint8_t numberOfSwitches = 0; + ReturnValue_t result = getSwitches(&switches, &numberOfSwitches); + if (result == RETURN_OK) { + while (numberOfSwitches > 0) { + powerSwitcher->sendSwitchCommand(switches[numberOfSwitches - 1], onOff); + numberOfSwitches--; } + } } -ReturnValue_t DeviceHandlerBase::getSwitches(const uint8_t **switches, - uint8_t *numberOfSwitches) { - return DeviceHandlerBase::NO_SWITCH; +ReturnValue_t DeviceHandlerBase::getSwitches(const uint8_t** switches, uint8_t* numberOfSwitches) { + return DeviceHandlerBase::NO_SWITCH; } -void DeviceHandlerBase::modeChanged(void) { -} +void DeviceHandlerBase::modeChanged(void) {} -ReturnValue_t DeviceHandlerBase::enableReplyInReplyMap( - DeviceCommandMap::iterator command, uint8_t expectedReplies, - bool useAlternativeId, DeviceCommandId_t alternativeReply) { - DeviceReplyMap::iterator iter; - if (useAlternativeId) { - iter = deviceReplyMap.find(alternativeReply); - } else { - iter = deviceReplyMap.find(command->first); - } - if (iter != deviceReplyMap.end()) { - DeviceReplyInfo *info = &(iter->second); - info->delayCycles = info->maxDelayCycles; - info->command = command; - command->second.expectedReplies = expectedReplies; - return RETURN_OK; - } else { - return NO_REPLY_EXPECTED; - } +ReturnValue_t DeviceHandlerBase::enableReplyInReplyMap(DeviceCommandMap::iterator command, + uint8_t expectedReplies, + bool useAlternativeId, + DeviceCommandId_t alternativeReply) { + DeviceReplyMap::iterator iter; + if (useAlternativeId) { + iter = deviceReplyMap.find(alternativeReply); + } else { + iter = deviceReplyMap.find(command->first); + } + if (iter != deviceReplyMap.end()) { + DeviceReplyInfo* info = &(iter->second); + info->delayCycles = info->maxDelayCycles; + info->command = command; + command->second.expectedReplies = expectedReplies; + return RETURN_OK; + } else { + return NO_REPLY_EXPECTED; + } } void DeviceHandlerBase::doTransition(Mode_t modeFrom, Submode_t subModeFrom) { - setMode(getBaseMode(mode)); + setMode(getBaseMode(mode)); } ReturnValue_t DeviceHandlerBase::getStateOfSwitches(void) { - if(powerSwitcher == nullptr) { - return NO_SWITCH; - } - uint8_t numberOfSwitches = 0; - const uint8_t *switches; - - ReturnValue_t result = getSwitches(&switches, &numberOfSwitches); - if ((result == RETURN_OK) && (numberOfSwitches != 0)) { - while (numberOfSwitches > 0) { - if (powerSwitcher->getSwitchState(switches[numberOfSwitches - 1]) - == PowerSwitchIF::SWITCH_OFF) { - return PowerSwitchIF::SWITCH_OFF; - } - numberOfSwitches--; - } - return PowerSwitchIF::SWITCH_ON; - } - + if (powerSwitcher == nullptr) { return NO_SWITCH; + } + uint8_t numberOfSwitches = 0; + const uint8_t* switches; + + ReturnValue_t result = getSwitches(&switches, &numberOfSwitches); + if ((result == RETURN_OK) && (numberOfSwitches != 0)) { + while (numberOfSwitches > 0) { + if (powerSwitcher->getSwitchState(switches[numberOfSwitches - 1]) == + PowerSwitchIF::SWITCH_OFF) { + return PowerSwitchIF::SWITCH_OFF; + } + numberOfSwitches--; + } + return PowerSwitchIF::SWITCH_ON; + } + + return NO_SWITCH; } Mode_t DeviceHandlerBase::getBaseMode(Mode_t transitionMode) { - // only child action special modes are handled, as a child should - // never see any base action modes - if (transitionMode == _MODE_START_UP) { - return _MODE_TO_ON; - } - if (transitionMode == _MODE_SHUT_DOWN) { - return _MODE_POWER_DOWN; - } - return transitionMode - & ~(TRANSITION_MODE_BASE_ACTION_MASK - | TRANSITION_MODE_CHILD_ACTION_MASK); + // only child action special modes are handled, as a child should + // never see any base action modes + if (transitionMode == _MODE_START_UP) { + return _MODE_TO_ON; + } + if (transitionMode == _MODE_SHUT_DOWN) { + return _MODE_POWER_DOWN; + } + 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 way, throw away DHB and write a new one: -// - Include power and thermal completely, but more modular :-) -// - Don't use modes for state transitions, reduce FSM (Finte State Machine) complexity. -// - Modularization? -ReturnValue_t DeviceHandlerBase::checkModeCommand(Mode_t commandedMode, - Submode_t commandedSubmode, uint32_t* msToReachTheMode) { - if (isTransitionalMode()) { - return IN_TRANSITION; - } - if ((mode == MODE_ERROR_ON) && (commandedMode != MODE_OFF)) { - return TRANS_NOT_ALLOWED; - } - if ((commandedMode == MODE_NORMAL) && (mode == MODE_OFF)) { - return TRANS_NOT_ALLOWED; - } +// SHOULDDO: Allow transition from OFF to NORMAL to reduce complexity in assemblies. And, by the +// way, throw away DHB and write a new one: +// - Include power and thermal completely, but more modular :-) +// - Don't use modes for state transitions, reduce FSM (Finte State Machine) complexity. +// - Modularization? +ReturnValue_t DeviceHandlerBase::checkModeCommand(Mode_t commandedMode, Submode_t commandedSubmode, + uint32_t* msToReachTheMode) { + if (isTransitionalMode()) { + return IN_TRANSITION; + } + if ((mode == MODE_ERROR_ON) && (commandedMode != MODE_OFF)) { + 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)) { - ReturnValue_t result = thermalSet->read(); - if(result == HasReturnvaluesIF::RETURN_OK) { - if((thermalSet->heaterRequest.value != - ThermalComponentIF::STATE_REQUEST_IGNORE) and (not - ThermalComponentIF::isOperational( - thermalSet->thermalState.value))) { - triggerEvent(ThermalComponentIF::TEMP_NOT_IN_OP_RANGE, - thermalSet->thermalState.value); - return NON_OP_TEMPERATURE; - } - } + if ((commandedMode == MODE_ON) && (mode == MODE_OFF) and (thermalSet != nullptr)) { + ReturnValue_t result = thermalSet->read(); + if (result == HasReturnvaluesIF::RETURN_OK) { + if ((thermalSet->heaterRequest.value != ThermalComponentIF::STATE_REQUEST_IGNORE) and + (not ThermalComponentIF::isOperational(thermalSet->thermalState.value))) { + triggerEvent(ThermalComponentIF::TEMP_NOT_IN_OP_RANGE, thermalSet->thermalState.value); + return NON_OP_TEMPERATURE; + } } + } - return isModeCombinationValid(commandedMode, commandedSubmode); + return isModeCombinationValid(commandedMode, commandedSubmode); } -void DeviceHandlerBase::startTransition(Mode_t commandedMode, - Submode_t commandedSubmode) { - switch (commandedMode) { +void DeviceHandlerBase::startTransition(Mode_t commandedMode, Submode_t commandedSubmode) { + switch (commandedMode) { case MODE_ON: - handleTransitionToOnMode(commandedMode, commandedSubmode); - break; + handleTransitionToOnMode(commandedMode, commandedSubmode); + break; case MODE_OFF: - if (mode == MODE_OFF) { - triggerEvent(CHANGING_MODE, commandedMode, commandedSubmode); - setMode(_MODE_POWER_DOWN, commandedSubmode); - } else { - // already set the delay for the child transition - // so we don't need to call it twice - childTransitionDelay = getTransitionDelayMs(mode, _MODE_POWER_DOWN); - transitionSourceMode = _MODE_POWER_DOWN; - transitionSourceSubMode = commandedSubmode; - childTransitionFailure = CHILD_TIMEOUT; - setMode(_MODE_SHUT_DOWN, commandedSubmode); - triggerEvent(CHANGING_MODE, commandedMode, commandedSubmode); - } - break; + if (mode == MODE_OFF) { + triggerEvent(CHANGING_MODE, commandedMode, commandedSubmode); + setMode(_MODE_POWER_DOWN, commandedSubmode); + } else { + // already set the delay for the child transition + // so we don't need to call it twice + childTransitionDelay = getTransitionDelayMs(mode, _MODE_POWER_DOWN); + transitionSourceMode = _MODE_POWER_DOWN; + transitionSourceSubMode = commandedSubmode; + childTransitionFailure = CHILD_TIMEOUT; + setMode(_MODE_SHUT_DOWN, commandedSubmode); + triggerEvent(CHANGING_MODE, commandedMode, commandedSubmode); + } + break; case MODE_RAW: - if (mode != MODE_OFF) { - setTransition(MODE_RAW, commandedSubmode); - } else { - setMode(MODE_RAW, commandedSubmode); - } - break; + if (mode != MODE_OFF) { + setTransition(MODE_RAW, commandedSubmode); + } else { + setMode(MODE_RAW, commandedSubmode); + } + break; case MODE_NORMAL: - if (mode != MODE_OFF) { - setTransition(MODE_NORMAL, commandedSubmode); - } else { - replyReturnvalueToCommand(HasModesIF::TRANS_NOT_ALLOWED); - } - break; - } + if (mode != MODE_OFF) { + setTransition(MODE_NORMAL, commandedSubmode); + } else { + replyReturnvalueToCommand(HasModesIF::TRANS_NOT_ALLOWED); + } + break; + } } -void DeviceHandlerBase::handleTransitionToOnMode(Mode_t commandedMode, - Submode_t commandedSubmode) { - if (mode == MODE_OFF) { - transitionSourceMode = _MODE_POWER_DOWN; - transitionSourceSubMode = SUBMODE_NONE; - setMode(_MODE_POWER_ON, commandedSubmode); - // already set the delay for the child transition so we don't - // need to call it twice - childTransitionDelay = getTransitionDelayMs(_MODE_START_UP, - MODE_ON); - triggerEvent(CHANGING_MODE, commandedMode, commandedSubmode); - if(thermalSet != nullptr) { - ReturnValue_t result = thermalSet->read(); - if(result == HasReturnvaluesIF::RETURN_OK) { - if(thermalSet->heaterRequest != - ThermalComponentIF::STATE_REQUEST_IGNORE) { - thermalSet->heaterRequest = - ThermalComponentIF::STATE_REQUEST_OPERATIONAL; - thermalSet->commit(); - } - } +void DeviceHandlerBase::handleTransitionToOnMode(Mode_t commandedMode, Submode_t commandedSubmode) { + if (mode == MODE_OFF) { + transitionSourceMode = _MODE_POWER_DOWN; + transitionSourceSubMode = SUBMODE_NONE; + setMode(_MODE_POWER_ON, commandedSubmode); + // already set the delay for the child transition so we don't + // need to call it twice + childTransitionDelay = getTransitionDelayMs(_MODE_START_UP, MODE_ON); + triggerEvent(CHANGING_MODE, commandedMode, commandedSubmode); + if (thermalSet != nullptr) { + ReturnValue_t result = thermalSet->read(); + if (result == HasReturnvaluesIF::RETURN_OK) { + if (thermalSet->heaterRequest != ThermalComponentIF::STATE_REQUEST_IGNORE) { + thermalSet->heaterRequest = ThermalComponentIF::STATE_REQUEST_OPERATIONAL; + thermalSet->commit(); } - } else { - setTransition(MODE_ON, commandedSubmode); + } } + } else { + setTransition(MODE_ON, commandedSubmode); + } } void DeviceHandlerBase::getMode(Mode_t* mode, Submode_t* submode) { - *mode = this->mode; - *submode = this->submode; + *mode = this->mode; + *submode = this->submode; } -void DeviceHandlerBase::setToExternalControl() { - healthHelper.setHealth(EXTERNAL_CONTROL); -} +void DeviceHandlerBase::setToExternalControl() { healthHelper.setHealth(EXTERNAL_CONTROL); } -void DeviceHandlerBase::announceMode(bool recursive) { - triggerEvent(MODE_INFO, mode, submode); -} +void DeviceHandlerBase::announceMode(bool recursive) { triggerEvent(MODE_INFO, mode, submode); } -bool DeviceHandlerBase::dontCheckQueue() { - return false; -} +bool DeviceHandlerBase::dontCheckQueue() { return false; } void DeviceHandlerBase::missedReply(DeviceCommandId_t id) { - if (ignoreMissedRepliesCount > 0) { - ignoreMissedRepliesCount--; - } else { - triggerEvent(DEVICE_MISSED_REPLY, id); - } + if (ignoreMissedRepliesCount > 0) { + ignoreMissedRepliesCount--; + } else { + triggerEvent(DEVICE_MISSED_REPLY, id); + } } -HasHealthIF::HealthState DeviceHandlerBase::getHealth() { - return healthHelper.getHealth(); -} +HasHealthIF::HealthState DeviceHandlerBase::getHealth() { return healthHelper.getHealth(); } ReturnValue_t DeviceHandlerBase::setHealth(HealthState health) { - healthHelper.setHealth(health); - return HasReturnvaluesIF::RETURN_OK; + healthHelper.setHealth(health); + return HasReturnvaluesIF::RETURN_OK; } void DeviceHandlerBase::checkSwitchState() { - if ((mode == MODE_ON || mode == MODE_NORMAL)) { - //We only check in ON and NORMAL, ignore RAW and ERROR_ON. - ReturnValue_t result = getStateOfSwitches(); - if (result == PowerSwitchIF::SWITCH_OFF && !switchOffWasReported) { - triggerEvent(PowerSwitchIF::SWITCH_WENT_OFF); - switchOffWasReported = true; - } - } else { - switchOffWasReported = false; + if ((mode == MODE_ON || mode == MODE_NORMAL)) { + // We only check in ON and NORMAL, ignore RAW and ERROR_ON. + ReturnValue_t result = getStateOfSwitches(); + if (result == PowerSwitchIF::SWITCH_OFF && !switchOffWasReported) { + triggerEvent(PowerSwitchIF::SWITCH_WENT_OFF); + switchOffWasReported = true; } + } else { + switchOffWasReported = false; + } } -void DeviceHandlerBase::doOnActivity() { -} +void DeviceHandlerBase::doOnActivity() {} ReturnValue_t DeviceHandlerBase::acceptExternalDeviceCommands() { - if ((mode != MODE_ON) && (mode != MODE_NORMAL)) { - return WRONG_MODE_FOR_COMMAND; - } - return RETURN_OK; + if ((mode != MODE_ON) && (mode != MODE_NORMAL)) { + return WRONG_MODE_FOR_COMMAND; + } + return RETURN_OK; } -void DeviceHandlerBase::replyRawReplyIfnotWiretapped(const uint8_t* data, - size_t len) { - if ((wiretappingMode == RAW) - && (defaultRawReceiver == requestedRawTraffic)) { - //The raw packet was already sent by the wiretapping service - } else { - replyRawData(data, len, defaultRawReceiver); - } +void DeviceHandlerBase::replyRawReplyIfnotWiretapped(const uint8_t* data, size_t len) { + if ((wiretappingMode == RAW) && (defaultRawReceiver == requestedRawTraffic)) { + // The raw packet was already sent by the wiretapping service + } else { + replyRawData(data, len, defaultRawReceiver); + } } -ReturnValue_t DeviceHandlerBase::handleDeviceHandlerMessage( - CommandMessage * message) { - switch (message->getCommand()) { +ReturnValue_t DeviceHandlerBase::handleDeviceHandlerMessage(CommandMessage* message) { + switch (message->getCommand()) { case DeviceHandlerMessage::CMD_WIRETAPPING: - switch (DeviceHandlerMessage::getWiretappingMode(message)) { + switch (DeviceHandlerMessage::getWiretappingMode(message)) { case RAW: - wiretappingMode = RAW; - requestedRawTraffic = commandQueue->getLastPartner(); - break; + wiretappingMode = RAW; + requestedRawTraffic = commandQueue->getLastPartner(); + break; case TM: - wiretappingMode = TM; - requestedRawTraffic = commandQueue->getLastPartner(); - break; + wiretappingMode = TM; + requestedRawTraffic = commandQueue->getLastPartner(); + break; case OFF: - wiretappingMode = OFF; - break; + wiretappingMode = OFF; + break; default: - replyReturnvalueToCommand(INVALID_COMMAND_PARAMETER); - wiretappingMode = OFF; - return RETURN_OK; - } - replyReturnvalueToCommand(RETURN_OK); - return RETURN_OK; - case DeviceHandlerMessage::CMD_RAW: - if ((mode != MODE_RAW)) { - DeviceHandlerMessage::clear(message); - replyReturnvalueToCommand(WRONG_MODE_FOR_COMMAND); - } else { - buildRawDeviceCommand(message); - } - return RETURN_OK; - default: - return RETURN_FAILED; - } + replyReturnvalueToCommand(INVALID_COMMAND_PARAMETER); + wiretappingMode = OFF; + return RETURN_OK; + } + replyReturnvalueToCommand(RETURN_OK); + return RETURN_OK; + case DeviceHandlerMessage::CMD_RAW: + if ((mode != MODE_RAW)) { + DeviceHandlerMessage::clear(message); + replyReturnvalueToCommand(WRONG_MODE_FOR_COMMAND); + } else { + buildRawDeviceCommand(message); + } + return RETURN_OK; + default: + return RETURN_FAILED; + } } void DeviceHandlerBase::setParentQueue(MessageQueueId_t parentQueueId) { - modeHelper.setParentQueue(parentQueueId); - healthHelper.setParentQueue(parentQueueId); + modeHelper.setParentQueue(parentQueueId); + healthHelper.setParentQueue(parentQueueId); } bool DeviceHandlerBase::isAwaitingReply() { - std::map::iterator iter; - for (iter = deviceReplyMap.begin(); iter != deviceReplyMap.end(); ++iter) { - if (iter->second.delayCycles != 0) { - return true; - } + std::map::iterator iter; + for (iter = deviceReplyMap.begin(); iter != deviceReplyMap.end(); ++iter) { + if (iter->second.delayCycles != 0) { + return true; } - return false; + } + return false; } -ReturnValue_t DeviceHandlerBase::letChildHandleMessage( - CommandMessage * message) { - return RETURN_FAILED; +ReturnValue_t DeviceHandlerBase::letChildHandleMessage(CommandMessage* message) { + return RETURN_FAILED; } -void DeviceHandlerBase::handleDeviceTM(SerializeIF *dataSet, DeviceCommandId_t replyId, - bool forceDirectTm) { - if(dataSet == nullptr) { - return; +void DeviceHandlerBase::handleDeviceTM(SerializeIF* dataSet, DeviceCommandId_t replyId, + bool forceDirectTm) { + if (dataSet == nullptr) { + return; + } + + DeviceReplyMap::iterator iter = deviceReplyMap.find(replyId); + if (iter == deviceReplyMap.end()) { + triggerEvent(DEVICE_UNKNOWN_REPLY, replyId); + return; + } + + /* Regular replies to a command */ + if (iter->second.command != deviceCommandMap.end()) { + MessageQueueId_t queueId = iter->second.command->second.sendReplyTo; + + if (queueId != NO_COMMANDER) { + /* This may fail, but we'll ignore the fault. */ + actionHelper.reportData(queueId, replyId, dataSet); } - DeviceReplyMap::iterator iter = deviceReplyMap.find(replyId); - if (iter == deviceReplyMap.end()) { - triggerEvent(DEVICE_UNKNOWN_REPLY, replyId); - return; + /* This check should make sure we get any TM but don't get anything doubled. */ + if (wiretappingMode == TM && (requestedRawTraffic != queueId)) { + DeviceTmReportingWrapper wrapper(getObjectId(), replyId, dataSet); + actionHelper.reportData(requestedRawTraffic, replyId, &wrapper); } - /* Regular replies to a command */ - if (iter->second.command != deviceCommandMap.end()) - { - MessageQueueId_t queueId = iter->second.command->second.sendReplyTo; - - if (queueId != NO_COMMANDER) { - /* This may fail, but we'll ignore the fault. */ - actionHelper.reportData(queueId, replyId, dataSet); - } - - /* This check should make sure we get any TM but don't get anything doubled. */ - if (wiretappingMode == TM && (requestedRawTraffic != queueId)) { - DeviceTmReportingWrapper wrapper(getObjectId(), replyId, dataSet); - actionHelper.reportData(requestedRawTraffic, replyId, &wrapper); - } - - else if (forceDirectTm and (defaultRawReceiver != queueId) and - (defaultRawReceiver != MessageQueueIF::NO_QUEUE)) - { - // hiding of sender needed so the service will handle it as - // unexpected Data, no matter what state (progress or completed) - // it is in - actionHelper.reportData(defaultRawReceiver, replyId, dataSet, true); - } + else if (forceDirectTm and (defaultRawReceiver != queueId) and + (defaultRawReceiver != MessageQueueIF::NO_QUEUE)) { + // hiding of sender needed so the service will handle it as + // unexpected Data, no matter what state (progress or completed) + // it is in + actionHelper.reportData(defaultRawReceiver, replyId, dataSet, true); } - /* Unrequested or aperiodic replies */ - else - { - DeviceTmReportingWrapper wrapper(getObjectId(), replyId, dataSet); - if (wiretappingMode == TM) { - actionHelper.reportData(requestedRawTraffic, replyId, &wrapper); - } - if (forceDirectTm and defaultRawReceiver != MessageQueueIF::NO_QUEUE) - { - // sid_t setSid = sid_t(this->getObjectId(), replyId); - // LocalPoolDataSetBase* dataset = getDataSetHandle(setSid); - // if(dataset != nullptr) { - // poolManager.generateHousekeepingPacket(setSid, dataset, true); - // } - - // hiding of sender needed so the service will handle it as - // unexpected Data, no matter what state (progress or completed) - // it is in - actionHelper.reportData(defaultRawReceiver, replyId, &wrapper, true); - } + } + /* Unrequested or aperiodic replies */ + else { + DeviceTmReportingWrapper wrapper(getObjectId(), replyId, dataSet); + if (wiretappingMode == TM) { + actionHelper.reportData(requestedRawTraffic, replyId, &wrapper); } + if (forceDirectTm and defaultRawReceiver != MessageQueueIF::NO_QUEUE) { + // sid_t setSid = sid_t(this->getObjectId(), replyId); + // LocalPoolDataSetBase* dataset = getDataSetHandle(setSid); + // if(dataset != nullptr) { + // poolManager.generateHousekeepingPacket(setSid, dataset, true); + // } + + // hiding of sender needed so the service will handle it as + // unexpected Data, no matter what state (progress or completed) + // it is in + actionHelper.reportData(defaultRawReceiver, replyId, &wrapper, true); + } + } } -ReturnValue_t DeviceHandlerBase::executeAction(ActionId_t actionId, - MessageQueueId_t commandedBy, const uint8_t* data, size_t size) { - ReturnValue_t result = acceptExternalDeviceCommands(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - DeviceCommandMap::iterator iter = deviceCommandMap.find(actionId); - if (iter == deviceCommandMap.end()) { - result = COMMAND_NOT_SUPPORTED; - } else if (iter->second.isExecuting) { - result = COMMAND_ALREADY_SENT; - } else { - result = buildCommandFromCommand(actionId, data, size); - } - if (result == RETURN_OK) { - iter->second.sendReplyTo = commandedBy; - iter->second.isExecuting = true; - cookieInfo.pendingCommand = iter; - cookieInfo.state = COOKIE_WRITE_READY; - } +ReturnValue_t DeviceHandlerBase::executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, + const uint8_t* data, size_t size) { + ReturnValue_t result = acceptExternalDeviceCommands(); + if (result != HasReturnvaluesIF::RETURN_OK) { return result; + } + DeviceCommandMap::iterator iter = deviceCommandMap.find(actionId); + if (iter == deviceCommandMap.end()) { + result = COMMAND_NOT_SUPPORTED; + } else if (iter->second.isExecuting) { + result = COMMAND_ALREADY_SENT; + } else { + result = buildCommandFromCommand(actionId, data, size); + } + if (result == RETURN_OK) { + iter->second.sendReplyTo = commandedBy; + iter->second.isExecuting = true; + cookieInfo.pendingCommand = iter; + cookieInfo.state = COOKIE_WRITE_READY; + } + return result; } void DeviceHandlerBase::buildInternalCommand(void) { - /* Neither raw nor direct could build a command */ - ReturnValue_t result = NOTHING_TO_SEND; - DeviceCommandId_t deviceCommandId = NO_COMMAND_ID; - if (mode == MODE_NORMAL) { - result = buildNormalDeviceCommand(&deviceCommandId); - if (result == BUSY) { - /* So we can track misconfigurations */ - printWarningOrError(sif::OutputTypes::OUT_WARNING, "buildInternalCommand", - HasReturnvaluesIF::RETURN_FAILED, "Busy."); - /* No need to report this */ - result = NOTHING_TO_SEND; - } - } - else if (mode == MODE_RAW) { - result = buildChildRawCommand(); - deviceCommandId = RAW_COMMAND_ID; - } - else if (mode & TRANSITION_MODE_CHILD_ACTION_MASK) { - result = buildTransitionDeviceCommand(&deviceCommandId); - } - else { - return; + /* Neither raw nor direct could build a command */ + ReturnValue_t result = NOTHING_TO_SEND; + DeviceCommandId_t deviceCommandId = NO_COMMAND_ID; + if (mode == MODE_NORMAL) { + result = buildNormalDeviceCommand(&deviceCommandId); + if (result == BUSY) { + /* So we can track misconfigurations */ + printWarningOrError(sif::OutputTypes::OUT_WARNING, "buildInternalCommand", + HasReturnvaluesIF::RETURN_FAILED, "Busy."); + /* No need to report this */ + result = NOTHING_TO_SEND; } + } else if (mode == MODE_RAW) { + result = buildChildRawCommand(); + deviceCommandId = RAW_COMMAND_ID; + } else if (mode & TRANSITION_MODE_CHILD_ACTION_MASK) { + result = buildTransitionDeviceCommand(&deviceCommandId); + } else { + return; + } - if (result == NOTHING_TO_SEND) { - return; - } - if (result == RETURN_OK) { - DeviceCommandMap::iterator iter = deviceCommandMap.find( - deviceCommandId); - if (iter == deviceCommandMap.end()) { + if (result == NOTHING_TO_SEND) { + return; + } + if (result == RETURN_OK) { + DeviceCommandMap::iterator iter = deviceCommandMap.find(deviceCommandId); + if (iter == deviceCommandMap.end()) { #if FSFW_VERBOSE_LEVEL >= 1 - char output[36]; - sprintf(output, "Command 0x%08x unknown", - static_cast(deviceCommandId)); - // so we can track misconfigurations - printWarningOrError(sif::OutputTypes::OUT_WARNING, - "buildInternalCommand", - COMMAND_NOT_SUPPORTED, - output); + char output[36]; + sprintf(output, "Command 0x%08x unknown", static_cast(deviceCommandId)); + // so we can track misconfigurations + printWarningOrError(sif::OutputTypes::OUT_WARNING, "buildInternalCommand", + COMMAND_NOT_SUPPORTED, output); #endif - result = COMMAND_NOT_SUPPORTED; - } - else if (iter->second.isExecuting) { + result = COMMAND_NOT_SUPPORTED; + } else if (iter->second.isExecuting) { #if FSFW_VERBOSE_LEVEL >= 1 - char output[36]; - sprintf(output, "Command 0x%08x is executing", - static_cast(deviceCommandId)); - // so we can track misconfigurations - printWarningOrError(sif::OutputTypes::OUT_WARNING, - "buildInternalCommand", - HasReturnvaluesIF::RETURN_FAILED, - output); + char output[36]; + sprintf(output, "Command 0x%08x is executing", static_cast(deviceCommandId)); + // so we can track misconfigurations + printWarningOrError(sif::OutputTypes::OUT_WARNING, "buildInternalCommand", + HasReturnvaluesIF::RETURN_FAILED, output); #endif - // this is an internal command, no need to report a failure here, - // missed reply will track if a reply is too late, otherwise, it's ok - return; - } else { - iter->second.sendReplyTo = NO_COMMANDER; - iter->second.isExecuting = true; - cookieInfo.pendingCommand = iter; - cookieInfo.state = COOKIE_WRITE_READY; - } - } - if (result != RETURN_OK) { - triggerEvent(DEVICE_BUILDING_COMMAND_FAILED, result, deviceCommandId); + // this is an internal command, no need to report a failure here, + // missed reply will track if a reply is too late, otherwise, it's ok + return; + } else { + iter->second.sendReplyTo = NO_COMMANDER; + iter->second.isExecuting = true; + cookieInfo.pendingCommand = iter; + cookieInfo.state = COOKIE_WRITE_READY; } + } + if (result != RETURN_OK) { + triggerEvent(DEVICE_BUILDING_COMMAND_FAILED, result, deviceCommandId); + } } -ReturnValue_t DeviceHandlerBase::buildChildRawCommand() { - return NOTHING_TO_SEND; +ReturnValue_t DeviceHandlerBase::buildChildRawCommand() { return NOTHING_TO_SEND; } + +uint8_t DeviceHandlerBase::getReplyDelayCycles(DeviceCommandId_t deviceCommand) { + DeviceReplyMap::iterator iter = deviceReplyMap.find(deviceCommand); + if (iter == deviceReplyMap.end()) { + return 0; + } + return iter->second.delayCycles; } -uint8_t DeviceHandlerBase::getReplyDelayCycles( - DeviceCommandId_t deviceCommand) { - DeviceReplyMap::iterator iter = deviceReplyMap.find(deviceCommand); - if (iter == deviceReplyMap.end()) { - return 0; - } - return iter->second.delayCycles; +Mode_t DeviceHandlerBase::getTransitionSourceMode() const { return transitionSourceMode; } + +Submode_t DeviceHandlerBase::getTransitionSourceSubMode() const { return transitionSourceSubMode; } + +void DeviceHandlerBase::triggerEvent(Event event, uint32_t parameter1, uint32_t parameter2) { + fdirInstance->triggerEvent(event, parameter1, parameter2); } -Mode_t DeviceHandlerBase::getTransitionSourceMode() const { - return transitionSourceMode; +void DeviceHandlerBase::forwardEvent(Event event, uint32_t parameter1, uint32_t parameter2) const { + fdirInstance->triggerEvent(event, parameter1, parameter2); } -Submode_t DeviceHandlerBase::getTransitionSourceSubMode() const { - return transitionSourceSubMode; -} - -void DeviceHandlerBase::triggerEvent(Event event, uint32_t parameter1, - uint32_t parameter2) { - fdirInstance->triggerEvent(event, parameter1, parameter2); -} - -void DeviceHandlerBase::forwardEvent(Event event, uint32_t parameter1, - uint32_t parameter2) const { - fdirInstance->triggerEvent(event, parameter1, parameter2); -} - -void DeviceHandlerBase::doOffActivity() { -} +void DeviceHandlerBase::doOffActivity() {} ReturnValue_t DeviceHandlerBase::getParameter(uint8_t domainId, uint8_t uniqueId, - ParameterWrapper* parameterWrapper, const ParameterWrapper* newValues, - uint16_t startAtIndex) { - ReturnValue_t result = fdirInstance->getParameter(domainId, uniqueId, parameterWrapper, - newValues, startAtIndex); - if (result != INVALID_DOMAIN_ID) { - return result; - } - return INVALID_DOMAIN_ID; - + ParameterWrapper* parameterWrapper, + const ParameterWrapper* newValues, + uint16_t startAtIndex) { + ReturnValue_t result = + fdirInstance->getParameter(domainId, uniqueId, parameterWrapper, newValues, startAtIndex); + if (result != INVALID_DOMAIN_ID) { + return result; + } + return INVALID_DOMAIN_ID; } bool DeviceHandlerBase::isTransitionalMode() { - return ((mode - & (TRANSITION_MODE_BASE_ACTION_MASK - | TRANSITION_MODE_CHILD_ACTION_MASK)) != 0); + return ((mode & (TRANSITION_MODE_BASE_ACTION_MASK | TRANSITION_MODE_CHILD_ACTION_MASK)) != 0); } bool DeviceHandlerBase::commandIsExecuting(DeviceCommandId_t commandId) { - auto iter = deviceCommandMap.find(commandId); - if (iter != deviceCommandMap.end()) { - return iter->second.isExecuting; - } else { - return false; - } - + auto iter = deviceCommandMap.find(commandId); + if (iter != deviceCommandMap.end()) { + return iter->second.isExecuting; + } else { + return false; + } } -void DeviceHandlerBase::setTaskIF(PeriodicTaskIF* task){ - executingTask = task; -} +void DeviceHandlerBase::setTaskIF(PeriodicTaskIF* task) { executingTask = task; } -void DeviceHandlerBase::debugInterface(uint8_t positionTracker, - object_id_t objectId, uint32_t parameter) {} +void DeviceHandlerBase::debugInterface(uint8_t positionTracker, object_id_t objectId, + uint32_t parameter) {} -void DeviceHandlerBase::performOperationHook() { -} +void DeviceHandlerBase::performOperationHook() {} -ReturnValue_t DeviceHandlerBase::initializeLocalDataPool( - localpool::DataPool &localDataPoolMap, - LocalDataPoolManager& poolManager) { - if(thermalSet != nullptr) { - localDataPoolMap.emplace(thermalSet->thermalStatePoolId, - new PoolEntry); - localDataPoolMap.emplace(thermalSet->heaterRequestPoolId, - new PoolEntry); - } - return RETURN_OK; +ReturnValue_t DeviceHandlerBase::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) { + if (thermalSet != nullptr) { + localDataPoolMap.emplace(thermalSet->thermalStatePoolId, + new PoolEntry); + localDataPoolMap.emplace(thermalSet->heaterRequestPoolId, + new PoolEntry); + } + return RETURN_OK; } ReturnValue_t DeviceHandlerBase::initializeAfterTaskCreation() { - // In this function, the task handle should be valid if the task - // was implemented correctly. We still check to be 1000 % sure :-) - if(executingTask != nullptr) { - pstIntervalMs = executingTask->getPeriodMs(); - } - this->poolManager.initializeAfterTaskCreation(); + // In this function, the task handle should be valid if the task + // was implemented correctly. We still check to be 1000 % sure :-) + if (executingTask != nullptr) { + pstIntervalMs = executingTask->getPeriodMs(); + } + this->poolManager.initializeAfterTaskCreation(); - if(setStartupImmediately) { - startTransition(MODE_ON, SUBMODE_NONE); - } - return HasReturnvaluesIF::RETURN_OK; + if (setStartupImmediately) { + startTransition(MODE_ON, SUBMODE_NONE); + } + return HasReturnvaluesIF::RETURN_OK; } LocalPoolDataSetBase* DeviceHandlerBase::getDataSetHandle(sid_t sid) { - auto iter = deviceReplyMap.find(sid.ownerSetId); - if(iter != deviceReplyMap.end()) { - return iter->second.dataSet; - } - else { - return nullptr; - } + auto iter = deviceReplyMap.find(sid.ownerSetId); + if (iter != deviceReplyMap.end()) { + return iter->second.dataSet; + } else { + return nullptr; + } } -object_id_t DeviceHandlerBase::getObjectId() const { - return SystemObject::getObjectId(); -} +object_id_t DeviceHandlerBase::getObjectId() const { return SystemObject::getObjectId(); } -void DeviceHandlerBase::setStartUpImmediately() { - this->setStartupImmediately = true; -} +void DeviceHandlerBase::setStartUpImmediately() { this->setStartupImmediately = true; } -dur_millis_t DeviceHandlerBase::getPeriodicOperationFrequency() const { - return pstIntervalMs; -} +dur_millis_t DeviceHandlerBase::getPeriodicOperationFrequency() const { return pstIntervalMs; } DeviceCommandId_t DeviceHandlerBase::getPendingCommand() const { - if(cookieInfo.pendingCommand != deviceCommandMap.end()) { - return cookieInfo.pendingCommand->first; - } - return DeviceHandlerIF::NO_COMMAND_ID; + if (cookieInfo.pendingCommand != deviceCommandMap.end()) { + return cookieInfo.pendingCommand->first; + } + return DeviceHandlerIF::NO_COMMAND_ID; } void DeviceHandlerBase::setNormalDatapoolEntriesInvalid() { - for(const auto& reply: deviceReplyMap) { - if(reply.second.dataSet != nullptr) { - reply.second.dataSet->setValidity(false, true); - } + for (const auto& reply : deviceReplyMap) { + if (reply.second.dataSet != nullptr) { + reply.second.dataSet->setValidity(false, true); } + } } -void DeviceHandlerBase::printWarningOrError(sif::OutputTypes errorType, - const char *functionName, ReturnValue_t errorCode, - const char *errorPrint) { - if(errorPrint == nullptr) { - if(errorCode == ObjectManagerIF::CHILD_INIT_FAILED) { - errorPrint = "Initialization error"; - } - else if(errorCode == HasReturnvaluesIF::RETURN_FAILED) { - if(errorType == sif::OutputTypes::OUT_WARNING) { - errorPrint = "Generic Warning"; - } - else { - errorPrint = "Generic Error"; - } - } - else { - errorPrint = "Unknown error"; - } - } - if(functionName == nullptr) { - functionName = "unknown function"; +void DeviceHandlerBase::printWarningOrError(sif::OutputTypes errorType, const char* functionName, + ReturnValue_t errorCode, const char* errorPrint) { + if (errorPrint == nullptr) { + if (errorCode == ObjectManagerIF::CHILD_INIT_FAILED) { + errorPrint = "Initialization error"; + } else if (errorCode == HasReturnvaluesIF::RETURN_FAILED) { + if (errorType == sif::OutputTypes::OUT_WARNING) { + errorPrint = "Generic Warning"; + } else { + errorPrint = "Generic Error"; + } + } else { + errorPrint = "Unknown error"; } + } + if (functionName == nullptr) { + functionName = "unknown function"; + } - if(errorType == sif::OutputTypes::OUT_WARNING) { + if (errorType == sif::OutputTypes::OUT_WARNING) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "DeviceHandlerBase::" << functionName << ": Object ID 0x" << std::hex << - std::setw(8) << std::setfill('0') << this->getObjectId() << " | " << errorPrint << - std::dec << std::setfill(' ') << std::endl; + sif::warning << "DeviceHandlerBase::" << functionName << ": Object ID 0x" << std::hex + << std::setw(8) << std::setfill('0') << this->getObjectId() << " | " << errorPrint + << std::dec << std::setfill(' ') << std::endl; #else - sif::printWarning("DeviceHandlerBase::%s: Object ID 0x%08x | %s\n", - functionName, this->getObjectId(), errorPrint); + sif::printWarning("DeviceHandlerBase::%s: Object ID 0x%08x | %s\n", functionName, + this->getObjectId(), errorPrint); #endif - } - else if(errorType == sif::OutputTypes::OUT_ERROR) { + } else if (errorType == sif::OutputTypes::OUT_ERROR) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "DeviceHandlerBase::" << functionName << ": Object ID 0x" - << std::hex << std::setw(8) << std::setfill('0') - << this->getObjectId() << " | " << errorPrint << std::dec - << std::setfill(' ') << std::endl; + sif::error << "DeviceHandlerBase::" << functionName << ": Object ID 0x" << std::hex + << std::setw(8) << std::setfill('0') << this->getObjectId() << " | " << errorPrint + << std::dec << std::setfill(' ') << std::endl; #else - sif::printError("DeviceHandlerBase::%s: Object ID 0x%08x | %s\n", - functionName, this->getObjectId(), errorPrint); + sif::printError("DeviceHandlerBase::%s: Object ID 0x%08x | %s\n", functionName, + this->getObjectId(), errorPrint); #endif - } - + } } -LocalDataPoolManager* DeviceHandlerBase::getHkManagerHandle() { - return &poolManager; -} +LocalDataPoolManager* DeviceHandlerBase::getHkManagerHandle() { return &poolManager; } MessageQueueId_t DeviceHandlerBase::getCommanderQueueId(DeviceCommandId_t replyId) const { - auto commandIter = deviceCommandMap.find(replyId); - if(commandIter == deviceCommandMap.end()) { - return MessageQueueIF::NO_QUEUE; - } - return commandIter->second.sendReplyTo; + auto commandIter = deviceCommandMap.find(replyId); + if (commandIter == deviceCommandMap.end()) { + return MessageQueueIF::NO_QUEUE; + } + return commandIter->second.sendReplyTo; } diff --git a/src/fsfw/devicehandlers/DeviceHandlerBase.h b/src/fsfw/devicehandlers/DeviceHandlerBase.h index da609eed..f3dda5c8 100644 --- a/src/fsfw/devicehandlers/DeviceHandlerBase.h +++ b/src/fsfw/devicehandlers/DeviceHandlerBase.h @@ -1,31 +1,30 @@ #ifndef FSFW_DEVICEHANDLERS_DEVICEHANDLERBASE_H_ #define FSFW_DEVICEHANDLERS_DEVICEHANDLERBASE_H_ -#include "DeviceHandlerIF.h" -#include "DeviceCommunicationIF.h" -#include "DeviceHandlerFailureIsolation.h" -#include "DeviceHandlerThermalSet.h" - -#include "fsfw/serviceinterface/ServiceInterface.h" -#include "fsfw/serviceinterface/serviceInterfaceDefintions.h" -#include "fsfw/objectmanager/SystemObject.h" -#include "fsfw/tasks/ExecutableObjectIF.h" -#include "fsfw/returnvalues/HasReturnvaluesIF.h" -#include "fsfw/action/HasActionsIF.h" -#include "fsfw/datapool/PoolVariableIF.h" -#include "fsfw/modes/HasModesIF.h" -#include "fsfw/power/PowerSwitchIF.h" -#include "fsfw/ipc/MessageQueueIF.h" -#include "fsfw/tasks/PeriodicTaskIF.h" -#include "fsfw/action/ActionHelper.h" -#include "fsfw/health/HealthHelper.h" -#include "fsfw/parameters/ParameterHelper.h" -#include "fsfw/datapoollocal/HasLocalDataPoolIF.h" -#include "fsfw/datapoollocal/LocalDataPoolManager.h" - #include -namespace Factory{ +#include "DeviceCommunicationIF.h" +#include "DeviceHandlerFailureIsolation.h" +#include "DeviceHandlerIF.h" +#include "DeviceHandlerThermalSet.h" +#include "fsfw/action/ActionHelper.h" +#include "fsfw/action/HasActionsIF.h" +#include "fsfw/datapool/PoolVariableIF.h" +#include "fsfw/datapoollocal/HasLocalDataPoolIF.h" +#include "fsfw/datapoollocal/LocalDataPoolManager.h" +#include "fsfw/health/HealthHelper.h" +#include "fsfw/ipc/MessageQueueIF.h" +#include "fsfw/modes/HasModesIF.h" +#include "fsfw/objectmanager/SystemObject.h" +#include "fsfw/parameters/ParameterHelper.h" +#include "fsfw/power/PowerSwitchIF.h" +#include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/serviceinterface/serviceInterfaceDefintions.h" +#include "fsfw/tasks/ExecutableObjectIF.h" +#include "fsfw/tasks/PeriodicTaskIF.h" + +namespace Factory { void setStaticFrameworkObjectIds(); } @@ -78,1220 +77,1203 @@ class StorageManagerIF; * * @ingroup devices */ -class DeviceHandlerBase: - public DeviceHandlerIF, - public HasReturnvaluesIF, - public ExecutableObjectIF, - public SystemObject, - public HasModesIF, - public HasHealthIF, - public HasActionsIF, - public ReceivesParameterMessagesIF, - public HasLocalDataPoolIF { - friend void (Factory::setStaticFrameworkObjectIds)(); -public: - /** - * The constructor passes the objectId to the SystemObject(). - * - * @param setObjectId the ObjectId to pass to the SystemObject() Constructor - * @param deviceCommuncation Communcation Interface object which is used - * to implement communication functions - * @param comCookie This object will be passed to the communication inter- - * face and can contain user-defined information about the communication. - * @param fdirInstance - * @param cmdQueueSize - */ - DeviceHandlerBase(object_id_t setObjectId, object_id_t deviceCommunication, - CookieIF * comCookie, FailureIsolationBase* fdirInstance = nullptr, - size_t cmdQueueSize = 20); - - void setHkDestination(object_id_t hkDestination); - - /** - * If the device handler is controlled by the FSFW thermal building blocks, - * this function should be called to initialize all required components. - * The device handler will then take care of creating local pool entries - * for the device thermal state and device heating request. - * Custom local pool IDs can be assigned as well. - * @param thermalStatePoolId - * @param thermalRequestPoolId - */ - void setThermalStateRequestPoolIds(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); - /** - * @brief Helper function to ease device handler development. - * This will instruct the transition to MODE_ON immediately - * (leading to doStartUp() being called for the transition to the ON mode), - * so external mode commanding is not necessary anymore. - * - * This has to be called before the task is started! - * (e.g. in the task factory). This is only a helper function for - * development. Regular mode commanding should be performed by commanding - * the AssemblyBase or Subsystem objects resposible for the device handler. - */ - void setStartUpImmediately(); - - /** - * @brief This function is the device handler base core component and is - * called periodically. - * @details - * General sequence, showing where abstract virtual functions are called: - * If the State is SEND_WRITE: - * 1. Set the cookie state to COOKIE_UNUSED and read the command queue - * 2. Handles Device State Modes by calling doStateMachine(). - * This function calls callChildStatemachine() which calls the - * abstract functions doStartUp() and doShutDown() - * 3. Check switch states by calling checkSwitchStates() - * 4. Decrements counter for timeout of replies by calling - * decrementDeviceReplyMap() - * 5. Performs FDIR check for failures - * 6. If the device mode is MODE_OFF, return RETURN_OK. - * Otherwise, perform the Action property and performs depending - * on value specified by input value counter (incremented in PST). - * The child class tells base class what to do by setting this value. - * - SEND_WRITE: Send data or commands to device by calling - * doSendWrite() which calls sendMessage function - * of #communicationInterface - * and calls buildInternalCommand if the cookie state is COOKIE_UNUSED - * - GET_WRITE: Get ackknowledgement for sending by calling doGetWrite() - * which calls getSendSuccess of #communicationInterface. - * Calls abstract functions scanForReply() and interpretDeviceReply(). - * - SEND_READ: Request reading data from device by calling doSendRead() - * which calls requestReceiveMessage of #communcationInterface - * - GET_READ: Access requested reading data by calling doGetRead() - * which calls readReceivedMessage of #communicationInterface - * @param counter Specifies which Action to perform - * @return RETURN_OK for successful execution - */ - virtual ReturnValue_t performOperation(uint8_t counter); - - /** - * @brief Initializes the device handler - * @details - * Initialize Device Handler as system object and - * initializes all important helper classes. - * Calls fillCommandAndReplyMap(). - * @return - */ - virtual ReturnValue_t initialize(); - - /** - * @brief Intialization steps performed after all tasks have been created. - * This function will be called by the executing task. - * @return - */ - virtual ReturnValue_t initializeAfterTaskCreation() override; - - /** Destructor. */ - virtual ~DeviceHandlerBase(); - - - /** - * Implementation of ExecutableObjectIF function - * Used to setup the reference of the task, that executes this component - * @param task_ Pointer to the taskIF of this task - */ - virtual void setTaskIF(PeriodicTaskIF* task_) override; - virtual MessageQueueId_t getCommandQueue(void) const override; - - /** Explicit interface implementation of getObjectId */ - virtual object_id_t getObjectId() const override; - - /** - * @param parentQueueId - */ - virtual void setParentQueue(MessageQueueId_t parentQueueId); - - /** @brief Implementation required for HasActionIF */ - ReturnValue_t executeAction(ActionId_t actionId, - MessageQueueId_t commandedBy, const uint8_t* data, - size_t size) override; - - Mode_t getTransitionSourceMode() const; - Submode_t getTransitionSourceSubMode() const; - virtual void getMode(Mode_t *mode, Submode_t *submode); - HealthState getHealth(); - ReturnValue_t setHealth(HealthState health); - virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, - ParameterWrapper *parameterWrapper, const ParameterWrapper *newValues, - uint16_t startAtIndex) override; - -protected: - /** - * @brief This is used to let the child class handle the transition from - * mode @c _MODE_START_UP to @c MODE_ON - * @details - * It is only called when the device handler is in mode @c _MODE_START_UP. - * That means, the device switch(es) are already set to on. - * Device handler commands are read and can be handled by the child class. - * If the child class handles a command, it should also send - * an reply accordingly. - * If an Command is not handled (ie #DeviceHandlerCommand is not @c CMD_NONE, - * the base class handles rejecting the command and sends a reply. - * The replies for mode transitions are handled by the base class. - * - * - If the device is started and ready for operation, the mode should be - * set to MODE_ON. It is possible to set the mode to _MODE_TO_ON to - * use the to on transition if available. - * - If the power-up fails, the mode should be set to _MODE_POWER_DOWN - * which will lead to the device being powered off. - * - If the device does not change the mode, the mode will be changed - * to _MODE_POWER_DOWN, after the timeout (from getTransitionDelay()) - * has passed. - * - * #transitionFailure can be set to a failure code indicating the reason - * for a failed transition - */ - virtual void doStartUp() = 0; - /** - * @brief This is used to let the child class handle the transition - * from mode @c _MODE_SHUT_DOWN to @c _MODE_POWER_DOWN - * @details - * It is only called when the device handler is in mode @c _MODE_SHUT_DOWN. - * Device handler commands are read and can be handled by the child class. - * If the child class handles a command, it should also send an reply - * accordingly. - * If an Command is not handled (ie #DeviceHandlerCommand is not - * @c CMD_NONE, the base class handles rejecting the command and sends a - * reply. The replies for mode transitions are handled by the base class. - * - * - If the device ready to be switched off, - * the mode should be set to _MODE_POWER_DOWN. - * - If the device should not be switched off, the mode can be changed to - * _MODE_TO_ON (or MODE_ON if no transition is needed). - * - If the device does not change the mode, the mode will be changed to - * _MODE_POWER_DOWN, when the timeout (from getTransitionDelay()) - * has passed. - * - * #transitionFailure can be set to a failure code indicating the reason - * for a failed transition - */ - virtual void doShutDown() = 0; - - /* Command handling */ - /** - * Build the device command to send for normal mode. - * - * This is only called in @c MODE_NORMAL. If multiple submodes for - * @c MODE_NORMAL are supported, different commands can built, - * depending on the submode. - * - * #rawPacket and #rawPacketLen must be set by this method to the - * packet to be sent. If variable command frequence is required, a counter - * can be used and the frequency in the reply map has to be set manually - * by calling updateReplyMap(). - * - * @param[out] id the device command id that has been built - * @return - * - @c RETURN_OK to send command after setting #rawPacket and - * #rawPacketLen. - * - @c NOTHING_TO_SEND when no command is to be sent. - * - Anything else triggers an even with the returnvalue as a parameter. - */ - virtual ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t * id) = 0; - /** - * Build the device command to send for a transitional mode. - * - * This is only called in @c _MODE_TO_NORMAL, @c _MODE_TO_ON, @c _MODE_TO_RAW, - * @c _MODE_START_UP and @c _MODE_SHUT_DOWN. So it is used by doStartUp() - * and doShutDown() as well as doTransition(), by setting those - * modes in the respective functions. - * - * A good idea is to implement a flag indicating a command has to be built - * and a variable containing the command number to be built - * and filling them in doStartUp(), doShutDown() and doTransition() so no - * modes have to be checked here. - * - * #rawPacket and #rawPacketLen must be set by this method to the - * packet to be sent. - * - * @param[out] id the device command id built - * @return - * - @c RETURN_OK when a command is to be sent - * - @c NOTHING_TO_SEND when no command is to be sent - * - Anything else triggers an even with the returnvalue as a parameter - */ - virtual ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t * id) = 0; - /** - * @brief Build a device command packet from data supplied by a direct - * command (PUS Service 8) - * @details - * This will be called if an functional command via PUS Service 8 is received and is - * the primary interface for functional command instead of #executeAction for users. The - * supplied ActionId_t action ID will be converted to a DeviceCommandId_t command ID after - * an internal check whether the action ID is a key in the device command map. - * - * #rawPacket and #rawPacketLen should be set by this method to the packet to be sent. - * The existence of the command in the command map and the command size check against 0 are - * done by the base class. - * - * @param deviceCommand The command to build, already checked against deviceCommandMap - * @param commandData Pointer to the data from the direct command - * @param commandDataLen Length of commandData - * @return - * - @c RETURN_OK to send command after #rawPacket and #rawPacketLen - * have been set. - * - @c HasActionsIF::EXECUTION_COMPLETE to generate a finish reply immediately. This can - * be used if no reply is expected - * - Anything else triggers an event with the return code as a parameter as well as a - * step reply failed with the return code - */ - virtual ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, - const uint8_t * commandData, size_t commandDataLen) = 0; - - /* Reply handling */ - /** - * @brief Scans a buffer for a valid reply. - * @details - * This is used by the base class to check the data received for valid packets. - * It only checks if a valid packet starts at @c start. - * It also only checks the structural validy of the packet, - * e.g. checksums lengths and protocol data. No information check is done, - * e.g. range checks etc. - * - * Errors should be reported directly, the base class does NOT report any - * errors based on the return value of this function. - * - * @param start start of remaining buffer to be scanned - * @param len length of remaining buffer to be scanned - * @param[out] foundId the id of the data found in the buffer. - * @param[out] foundLen length of the data found. Is to be set in function, - * buffer is scanned at previous position + foundLen. - * @return - * - @c RETURN_OK a valid packet was found at @c start, @c foundLen is valid - * - @c RETURN_FAILED no reply could be found starting at @c start, - * implies @c foundLen is not valid, base class will call scanForReply() - * again with ++start - * - @c DeviceHandlerIF::INVALID_DATA a packet was found but it is invalid, - * e.g. checksum error, implies @c foundLen is valid, can be used to - * skip some bytes - * - @c DeviceHandlerIF::LENGTH_MISSMATCH @c len is invalid - * - @c DeviceHandlerIF::IGNORE_REPLY_DATA Ignore this specific part of - * the packet - * - @c DeviceHandlerIF::IGNORE_FULL_PACKET Ignore the packet - * - @c APERIODIC_REPLY if a valid reply is received that has not been - * requested by a command, but should be handled anyway - * (@see also fillCommandAndCookieMap() ) - */ - virtual ReturnValue_t scanForReply(const uint8_t *start, size_t len, - DeviceCommandId_t *foundId, size_t *foundLen) = 0; - /** - * @brief Interpret a reply from the device. - * @details - * This is called after scanForReply() found a valid packet, it can be - * assumed that the length and structure is valid. - * This routine extracts the data from the packet into a DataSet and then - * calls handleDeviceTM(), which either sends a TM packet or stores the - * data in the DataPool depending on whether it was an external command. - * No packet length is given, as it should be defined implicitly by the id. - * - * @param id the id found by scanForReply() - * @param packet - * @return - * - @c RETURN_OK when the reply was interpreted. - * - @c IGNORE_REPLY_DATA Ignore the reply and don't reset reply cycle - * counter. - * - @c RETURN_FAILED when the reply could not be interpreted, - * e.g. logical errors or range violations occurred - */ - virtual ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, - const uint8_t *packet) = 0; - MessageQueueId_t getCommanderQueueId(DeviceCommandId_t replyId) const; - /** - * Helper function to get pending command. This is useful for devices - * like SPI sensors to identify the last sent command. - * This only returns the command sent in the last SEND_WRITE cycle. - * @return - */ - DeviceCommandId_t getPendingCommand() const; - - /* Specifying commands and replies */ - /** - * @brief Fill the #DeviceCommandMap and #DeviceReplyMap called by the #initialize - * of the base class - * @details - * This is used to let the base class know which replies are expected. - * There are different scenarios regarding this: - * - * - "Normal" commands. These are commands, that trigger a direct reply - * from the device. In this case, the id of the command should be added - * to the command map with a commandData_t where maxDelayCycles is set - * to the maximum expected number of PST cycles the reply will take. - * Then, scanForReply returns the id of the command and the base class - * can handle time-out and missing replies. - * - * - Periodic, unrequested replies. These are replies that, once enabled, - * are sent by the device on its own in a defined interval. - * In this case, the id of the reply or a placeholder id should be added - * to the deviceCommandMap with a commandData_t where maxDelayCycles is - * set to the maximum expected number of PST cycles between two replies - * (also a tolerance should be added, as an FDIR message will be - * generated if it is missed). - * From then on, the base class handles the reception. - * Then, scanForReply returns the id of the reply or the placeholder id - * and the base class will take care of checking that all replies are - * received and the interval is correct. - * - * - Aperiodic, unrequested replies. These are replies that are sent - * by the device without any preceding command and not in a defined - * interval. These are not entered in the deviceCommandMap but - * handled by returning @c APERIODIC_REPLY in scanForReply(). - */ - virtual void fillCommandAndReplyMap() = 0; - /** - * This is a helper method to facilitate inserting entries in the command map. - * @param deviceCommand Identifier of the command to add. - * @param maxDelayCycles The maximum number of delay cycles the command - * waits until it times out. - * @param replyLen Will be supplied to the requestReceiveMessage call of - * the communication interface. - * @param periodic Indicates if the command is periodic (i.e. it is sent - * by the device repeatedly without request) or not. Default is aperiodic (0). - * Please note that periodic replies are disabled by default. You can enable them with - * #updatePeriodicReply - * @return - @c RETURN_OK when the command was successfully inserted, - * - @c RETURN_FAILED else. - */ - ReturnValue_t insertInCommandAndReplyMap(DeviceCommandId_t deviceCommand, - uint16_t maxDelayCycles, - LocalPoolDataSetBase* replyDataSet = nullptr, - size_t replyLen = 0, bool periodic = false, - bool hasDifferentReplyId = false, DeviceCommandId_t replyId = 0); - /** - * @brief This is a helper method to insert replies in the reply map. - * @param deviceCommand Identifier of the reply to add. - * @param maxDelayCycles The maximum number of delay cycles the reply waits - * until it times out. - * @param periodic Indicates if the command is periodic (i.e. it is sent - * by the device repeatedly without request) or not. Default is aperiodic (0). - * Please note that periodic replies are disabled by default. You can enable them with - * #updatePeriodicReply - * @return - @c RETURN_OK when the command was successfully inserted, - * - @c RETURN_FAILED else. - */ - ReturnValue_t insertInReplyMap(DeviceCommandId_t deviceCommand, - uint16_t maxDelayCycles, LocalPoolDataSetBase* dataSet = nullptr, - size_t replyLen = 0, bool periodic = false); - - /** - * @brief A simple command to add a command to the commandList. - * @param deviceCommand The command to add - * @return - @c RETURN_OK when the command was successfully inserted, - * - @c RETURN_FAILED else. - */ - ReturnValue_t insertInCommandMap(DeviceCommandId_t deviceCommand); - - /** - * Enables a periodic reply for a given command. It sets to delay cycles to the specified - * maximum delay cycles for a given reply ID if enabled or to 0 if disabled. - * @param enable Specify whether to enable or disable a given periodic reply - * @return - */ - ReturnValue_t updatePeriodicReply(bool enable, DeviceCommandId_t deviceReply); - - /** - * @brief This function returns the reply length of the next reply to read. - * - * @param deviceCommand The command which triggered the device reply. - * - * @details The default implementation assumes only one reply is triggered by the command. In - * case the command triggers multiple replies (e.g. one acknowledgment, one data, - * and one execution status reply), this function can be overwritten to get the - * reply length of the next reply to read. - */ - virtual size_t getNextReplyLength(DeviceCommandId_t deviceCommand); - - /** - * @brief This is a helper method to facilitate updating entries in the reply map. - * @param deviceCommand Identifier of the reply to update. - * @param delayCycles The current number of delay cycles to wait. As stated in - * #fillCommandAndReplyMap, to disable periodic commands, this is set to zero. - * @param maxDelayCycles The maximum number of delay cycles the reply waits - * until it times out. By passing 0 the entry remains untouched. - * @param periodic Indicates if the command is periodic (i.e. it is sent - * by the device repeatedly without request) or not. Default is aperiodic (0). - * Warning: The setting always overrides the value that was entered in the map. - * @return - @c RETURN_OK when the command was successfully inserted, - * - @c RETURN_FAILED else. - */ - ReturnValue_t updateReplyMapEntry(DeviceCommandId_t deviceReply, - uint16_t delayCycles, uint16_t maxDelayCycles, - bool periodic = false); - /** - * @brief Can be used to set the dataset corresponding to a reply ID manually. - * @details - * Used by the local data pool manager. - */ - ReturnValue_t setReplyDataset(DeviceCommandId_t replyId, - LocalPoolDataSetBase* dataset); - - /** - * Get the time needed to transit from modeFrom to modeTo. - * - * Used for the following transitions: - * modeFrom -> modeTo: - * MODE_ON -> [MODE_ON, MODE_NORMAL, MODE_RAW, _MODE_POWER_DOWN] - * MODE_NORMAL -> [MODE_ON, MODE_NORMAL, MODE_RAW, _MODE_POWER_DOWN] - * MODE_RAW -> [MODE_ON, MODE_NORMAL, MODE_RAW, _MODE_POWER_DOWN] - * _MODE_START_UP -> MODE_ON (do not include time to set the switches, - * the base class got you covered) - * - * The default implementation returns 0 ! - * @param modeFrom - * @param modeTo - * @return time in ms - */ - virtual uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) = 0; - - /* Functions used by the local data pool manager */ - /** - * This function is used to initialize the local housekeeping pool - * entries. The default implementation leaves the pool empty. - * @param localDataPoolMap - * @return - */ - virtual ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, - LocalDataPoolManager& poolManager) override; - /** - * @brief Set all datapool variables that are update periodically in - * normal mode invalid - * @details - * The default implementation will set all datasets which have been added - * in #fillCommandAndReplyMap to invalid. It will also set all pool - * variables inside the dataset to invalid. The user can override this - * method optionally. - */ - virtual void setNormalDatapoolEntriesInvalid(); - /** - * @brief Get the dataset handle for a given SID. - * @details - * The default implementation will use the deviceCommandMap to look for the corresponding - * dataset handle. The user can override this function if this is not desired. - * @param sid - * @return - */ - virtual LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override; - - /* HasModesIF overrides */ - virtual void startTransition(Mode_t mode, Submode_t submode) override; - virtual void setToExternalControl() override; - virtual void announceMode(bool recursive) override; - /** - * @brief Set the device handler mode - * @details - * Sets #timeoutStart with every call Also sets #transitionTargetMode if necessary so - * transitional states can be entered from everywhere without breaking the state machine - * (which relies on a correct #transitionTargetMode). - * The submode is left unchanged. - * - * @param newMode - */ - void setMode(Mode_t newMode); - /** - * @overload - * @param submode - */ - void setMode(Mode_t newMode, Submode_t submode); - /** - * @brief Should be implemented properly by child class. - * @param mode - * @param submode - * @return - * - @c RETURN_OK if valid - * - @c RETURN_FAILED if invalid - */ - virtual ReturnValue_t isModeCombinationValid(Mode_t mode, - Submode_t submode); - /** - * @brief Notify child about mode change. - * @details - * Can be overriden to be used like a callback. - */ - virtual void modeChanged(); - - /* Power handling functions */ - /** - * Return the switches connected to the device. - * - * The default implementation returns one switch set in the ctor. - * - * @param[out] switches pointer to an array of switches - * @param[out] numberOfSwitches length of returned array - * @return - * - @c RETURN_OK if the parameters were set - * - @c RETURN_FAILED if no switches exist - */ - virtual ReturnValue_t getSwitches(const uint8_t **switches, - uint8_t *numberOfSwitches); - - /** - * @brief Helper function to report a missed reply - * @details Can be overwritten by children to act on missed replies or to fake reporting Id. - * @param id of the missed reply - */ - virtual void missedReply(DeviceCommandId_t id); - - /* Miscellaneous functions */ - /** - * @brief Hook function for child handlers which is called once per - * performOperation(). Default implementation is empty. - */ - virtual void performOperationHook(); - /** - * @brief Can be implemented by child handler to - * perform debugging - * @details Example: Calling this in performOperation - * to track values like mode. - * @param positionTracker Provide the child handler a way to know - * where the debugInterface was called - * @param objectId Provide the child handler object Id to - * specify actions for spefic devices - * @param parameter Supply a parameter of interest - * Please delete all debugInterface calls in DHB after debugging is finished ! - */ - virtual void debugInterface(uint8_t positionTracker = 0, - object_id_t objectId = 0, uint32_t parameter = 0); - -protected: - - static const uint8_t INTERFACE_ID = CLASS_ID::DEVICE_HANDLER_BASE; - - static const ReturnValue_t INVALID_CHANNEL = MAKE_RETURN_CODE(0xA0); - /* Return codes for scanForReply */ - //! This is used to specify for replies from a device which are not replies to requests - static const ReturnValue_t APERIODIC_REPLY = MAKE_RETURN_CODE(0xB0); - //! Ignore parts of the received packet - static const ReturnValue_t IGNORE_REPLY_DATA = MAKE_RETURN_CODE(0xB1); - //! Ignore full received packet - static const ReturnValue_t IGNORE_FULL_PACKET = MAKE_RETURN_CODE(0xB2); - /* Return codes for command building */ - //! Return this if no command sending in required - static const ReturnValue_t NOTHING_TO_SEND = MAKE_RETURN_CODE(0xC0); - static const ReturnValue_t COMMAND_MAP_ERROR = MAKE_RETURN_CODE(0xC2); - // Return codes for getSwitches */ - static const ReturnValue_t NO_SWITCH = MAKE_RETURN_CODE(0xD0); - /* Mode handling error Codes */ - static const ReturnValue_t CHILD_TIMEOUT = MAKE_RETURN_CODE(0xE0); - static const ReturnValue_t SWITCH_FAILED = MAKE_RETURN_CODE(0xE1); - - static const MessageQueueId_t NO_COMMANDER = MessageQueueIF::NO_QUEUE; - - //! Pointer to the raw packet that will be sent. - uint8_t *rawPacket = nullptr; - //! Size of the #rawPacket. - uint32_t rawPacketLen = 0; - - /** - * The mode the device handler is currently in. - * This should never be changed directly but only with setMode() - */ - Mode_t mode; - /** - * The submode the device handler is currently in. - * This should never be changed directly but only with setMode() - */ - Submode_t submode; - - /** This is the counter value from performOperation(). */ - uint8_t pstStep = 0; - uint8_t lastStep = 0; - uint32_t pstIntervalMs = 0; - - /** - * Wiretapping flag: - * - * indicates either that all raw messages to and from the device should be - * sent to #defaultRawReceiver - * or that all device TM should be downlinked to #defaultRawReceiver. - */ - enum WiretappingMode { - OFF = 0, RAW = 1, TM = 2 - } wiretappingMode; - /** - * @brief A message queue that accepts raw replies - * - * Statically initialized in initialize() to a configurable object. - * Used when there is no method of finding a recipient, ie raw mode and - * reporting erroneous replies - */ - MessageQueueId_t defaultRawReceiver = MessageQueueIF::NO_QUEUE; - store_address_t storedRawData; - - /** - * @brief The message queue which wants to read all raw traffic - * If #isWiretappingActive all raw communication from and to the device - * will be sent to this queue - */ - MessageQueueId_t requestedRawTraffic = 0; - - /** - * Pointer to the IPCStore. - * This caches the pointer received from the objectManager in the constructor. - */ - StorageManagerIF *IPCStore = nullptr; - /** The comIF object ID is cached for the intialize() function */ - object_id_t deviceCommunicationId; - /** Communication object used for device communication */ - DeviceCommunicationIF * communicationInterface = nullptr; - /** Cookie used for communication */ - CookieIF * comCookie; - - /* Health helper for HasHealthIF */ - HealthHelper healthHelper; - /* Mode helper for HasModesIF */ - ModeHelper modeHelper; - /* Parameter helper for ReceivesParameterMessagesIF */ - ParameterHelper parameterHelper; - /* Action helper for HasActionsIF */ - ActionHelper actionHelper; - /* Housekeeping Manager */ - LocalDataPoolManager poolManager; - - /** - * @brief Information about commands - */ - struct DeviceCommandInfo { - //! Indicates if the command is already executing. - bool isExecuting; - //! Dynamic value to indicate how many replies are expected. - //! Inititated with 0. - uint8_t expectedReplies; - //! if this is != NO_COMMANDER, DHB was commanded externally and shall - //! report everything to commander. - MessageQueueId_t sendReplyTo; - }; - using DeviceCommandMap = std::map ; - /** - * Information about commands - */ - DeviceCommandMap deviceCommandMap; - - /** - * @brief Information about expected replies - * This is used to keep track of pending replies. - */ - struct DeviceReplyInfo { - //! The maximum number of cycles the handler should wait for a reply - //! to this command. - uint16_t maxDelayCycles; - //! The currently remaining cycles the handler should wait for a reply, - //! 0 means there is no reply expected - uint16_t delayCycles; - size_t replyLen = 0; //!< Expected size of the reply. - //! if this is !=0, the delayCycles will not be reset to 0 but to - //! maxDelayCycles - bool periodic = false; - //! The dataset used to access housekeeping data related to the - //! respective device reply. Will point to a dataset held by - //! the child handler (if one is specified) - LocalPoolDataSetBase* dataSet = nullptr; - //! The command that expects this reply. - DeviceCommandMap::iterator command; - }; - - using DeviceReplyMap = std::map ; - using DeviceReplyIter = DeviceReplyMap::iterator; - /** - * This map is used to check and track correct reception of all replies. - * - * It has multiple use: - * - It stores the information on pending replies. If a command is sent, - * the DeviceCommandInfo.count is incremented. - * - It is used to time-out missing replies. If a command is sent, the - * DeviceCommandInfo.DelayCycles is set to MaxDelayCycles. - * - It is queried to check if a reply from the device can be interpreted. - * scanForReply() returns the id of the command a reply was found for. - * The reply is ignored in the following cases: - * - No entry for the returned id was found - * - The deviceReplyInfo.delayCycles is == 0 - */ - DeviceReplyMap deviceReplyMap; - - //! The MessageQueue used to receive device handler commands - //! and to send replies. - MessageQueueIF* commandQueue = nullptr; - - DeviceHandlerThermalSet* thermalSet = nullptr; - - /** - * Optional Error code. Can be set in doStartUp(), doShutDown() and - * doTransition() to signal cause for Transition failure. - */ - ReturnValue_t childTransitionFailure; - - /** Counts if communication channel lost a reply, so some missed - * replys can be ignored. */ - uint32_t ignoreMissedRepliesCount = 0; - - /** Pointer to the used FDIR instance. If not provided by child, - * default class is instantiated. */ - FailureIsolationBase* fdirInstance; - - //! To correctly delete the default instance. - bool defaultFDIRUsed; - - //! Indicates if SWITCH_WENT_OFF was already thrown. - bool switchOffWasReported; - - /** Pointer to the task which executes this component, - is invalid before setTaskIF was called. */ - PeriodicTaskIF* executingTask = nullptr; - - //! Object which switches power on and off. - static object_id_t powerSwitcherId; - - //! Object which receives RAW data by default. - static object_id_t rawDataReceiverId; - - //! Object which may be the root cause of an identified fault. - static object_id_t defaultFdirParentId; - - /** - * @brief Send a reply to a received device handler command. - * - * This also resets #DeviceHandlerCommand to 0. - * - * @param reply the reply type - * @param parameter parameter for the reply - */ - void replyReturnvalueToCommand(ReturnValue_t status, uint32_t parameter = 0); - /** - * TODO: Whats the difference between this and the upper command? - * @param status - * @param parameter - */ - void replyToCommand(ReturnValue_t status, uint32_t parameter = 0); - - /** - * 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, - * which can be deduced from the current mode which is - * [_MODE_TO_ON, _MODE_TO_NORMAL, _MODE_TO_RAW] - * - * The intended target submode is already set. - * The origin submode can be read in subModeFrom. - * - * If the transition can not be completed, the child class can try to reach - * an working mode by setting the mode either directly - * or setting the mode to an transitional mode (TO_ON, TO_NORMAL, TO_RAW) - * if the device needs to be reconfigured. - * - * If nothing works, the child class can wait for the timeout and the base - * class will reset the mode to the mode where the transition - * originated from (the child should report the reason for the failed transition). - * - * The intended way to send commands is to set a flag (enum) indicating - * which command is to be sent here and then to check in - * buildTransitionCommand() for the flag. This flag can also be used by - * doStartUp() and doShutDown() to get a nice and clean implementation of - * buildTransitionCommand() without switching through modes. - * - * When the the condition for the completion of the transition is met, the - * mode can be set, for example in the scanForReply() function. - * - * The default implementation goes into the target mode directly. - * - * #transitionFailure can be set to a failure code indicating the reason - * for a failed transition - * - * @param modeFrom - * The mode the transition originated from: - * [MODE_ON, MODE_NORMAL, MODE_RAW and _MODE_POWER_DOWN (if the mode changed - * from _MODE_START_UP to _MODE_TO_ON)] - * @param subModeFrom the subMode of modeFrom - */ - virtual void doTransition(Mode_t modeFrom, Submode_t subModeFrom); - - /** - * Get the communication action for the current step. - * The step number can be read from #pstStep. - * @return The communication action to execute in this step - */ - virtual CommunicationAction getComAction(); - - /** - * Checks state of switches in conjunction with mode and triggers an event - * if they don't fit. - */ - virtual void checkSwitchState(); - - /** - * Reserved for the rare case where a device needs to perform additional - * operation cyclically in OFF mode. - */ - virtual void doOffActivity(); - - /** - * Reserved for the rare case where a device needs to perform additional - * operation cyclically in ON mode. - */ - virtual void doOnActivity(); - - /** - * Required for HasLocalDataPoolIF, return a handle to the local pool manager. - * @return - */ - LocalDataPoolManager* getHkManagerHandle() override; - - /** - * Returns the delay cycle count of a reply. - * A count != 0 indicates that the command is already executed. - * @param deviceCommand The command to look for - * @return - * The current delay count. If the command does not exist (should never - * happen) it returns 0. - */ - uint8_t getReplyDelayCycles(DeviceCommandId_t deviceCommand); - - /** - * Calls replyRawData() with #defaultRawReceiver, but checks if wiretapping - * is active and if so, does not send the data as the wiretapping will have - * sent it already - */ - void replyRawReplyIfnotWiretapped(const uint8_t *data, size_t len); - - /** - * Enable the reply checking for a command - * - * Is only called, if the command was sent (i.e. the getWriteReply was - * successful). Must ensure that all replies are activated and correctly - * linked to the command that initiated it. - * The default implementation looks for a reply with the same id as the - * command id in the replyMap or uses the alternativeReplyId if flagged so. - * When found, copies maxDelayCycles to delayCycles in the reply information - * and sets the command to expect one reply. - * - * Can be overwritten by the child, if a command activates multiple replies - * or replyId differs from commandId. - * Notes for child implementations: - * - If the command was not found in the reply map, - * NO_REPLY_EXPECTED MUST be returned. - * - A failure code may be returned if something went fundamentally wrong. - * - * @param deviceCommand - * @return - RETURN_OK if a reply was activated. - * - NO_REPLY_EXPECTED if there was no reply found. This is not an - * error case as many commands do not expect a reply. - */ - virtual ReturnValue_t enableReplyInReplyMap(DeviceCommandMap::iterator command, - uint8_t expectedReplies = 1, bool useAlternateId = false, - DeviceCommandId_t alternateReplyID = 0); - - /** - * @brief Build the device command to send for raw mode. - * @details - * This is only called in @c MODE_RAW. It is for the rare case that in - * raw mode packets are to be sent by the handler itself. It is NOT needed - * for the raw commanding service. Its only current use is in the STR - * handler which gets its raw packets from a different source. - * Also it can be used for transitional commands, to get the device ready - * for @c MODE_RAW - * - * As it is almost never used, there is a default implementation - * returning @c NOTHING_TO_SEND. - * - * #rawPacket and #rawPacketLen must be set by this method to the packet - * to be sent. - * - * @param[out] id the device command id built - * @return - * - @c RETURN_OK when a command is to be sent - * - not @c NOTHING_TO_SEND when no command is to be sent - */ - virtual ReturnValue_t buildChildRawCommand(); - - /** - * @brief Construct a command reply containing a raw reply. - * @details - * It gets space in the #IPCStore, copies data there, then sends a raw reply - * containing the store address. This method is virtual, as devices can have different channels - * to send raw replies - * - * @param data data to send - * @param len length of @c data - * @param sendTo the messageQueueId of the one to send to - * @param isCommand marks the raw data as a command, the message then - * will be of type raw_command - */ - virtual void replyRawData(const uint8_t *data, size_t len, - MessageQueueId_t sendTo, bool isCommand = false); - - /** - * Get the state of the PCDU switches in the local datapool - * @return - * - @c PowerSwitchIF::SWITCH_ON if all switches specified - * by #switches are on - * - @c PowerSwitchIF::SWITCH_OFF one of the switches specified by - * #switches are off - * - @c PowerSwitchIF::RETURN_FAILED if an error occured - */ - ReturnValue_t getStateOfSwitches(); - - /** - * Children can overwrite this function to suppress checking of the - * command Queue - * - * This can be used when the child does not want to receive a command in - * a certain situation. Care must be taken that checking is not - * permanentely disabled as this would render the handler unusable. - * - * @return whether checking the queue should NOT be done - */ - virtual bool dontCheckQueue(); - - Mode_t getBaseMode(Mode_t transitionMode); - - bool isAwaitingReply(); - - void handleDeviceTM(SerializeIF *dataSet, DeviceCommandId_t replyId, - bool forceDirectTm = false); - // void handleDeviceTM(uint8_t* data, size_t dataSize, DeviceCommandId_t replyId, - // bool forceDirectTm); - - virtual ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, - uint32_t *msToReachTheMode); - - virtual ReturnValue_t letChildHandleMessage(CommandMessage *message); - - /** - * Overwrites SystemObject::triggerEvent in order to inform FDIR"Helper" - * faster about executed events. - * This is a bit sneaky, but improves responsiveness of the device FDIR. - * @param event The event to be thrown - * @param parameter1 Optional parameter 1 - * @param parameter2 Optional parameter 2 - */ - void triggerEvent(Event event, uint32_t parameter1 = 0, - uint32_t parameter2 = 0); - /** - * Same as triggerEvent, but for forwarding if object is used as proxy. - */ - virtual void forwardEvent(Event event, uint32_t parameter1 = 0, - uint32_t parameter2 = 0) const; - - /** - * Checks if current mode is transitional mode. - * @return true if mode is transitional, false else. - */ - bool isTransitionalMode(); - - /** - * Checks if current handler state allows reception of external device commands. - * Default implementation allows commands only in plain MODE_ON and MODE_NORMAL. - * @return RETURN_OK if commands are accepted, anything else otherwise. - */ - virtual ReturnValue_t acceptExternalDeviceCommands(); - - bool commandIsExecuting(DeviceCommandId_t commandId); - - /** - * set all switches returned by getSwitches() - * - * @param onOff on == @c SWITCH_ON; off != @c SWITCH_ON - */ - void commandSwitch(ReturnValue_t onOff); - -private: - - /** - * State a cookie is in. - * - * Used to keep track of the state of the RMAP communication. - */ - enum CookieState_t { - COOKIE_UNUSED, //!< The Cookie is unused - COOKIE_WRITE_READY, //!< There's data available to send. - COOKIE_READ_SENT, //!< A sendRead command was sent with this cookie - COOKIE_WRITE_SENT //!< A sendWrite command was sent with this cookie - }; - /** - * Information about a cookie. - * - * This is stored in a map for each cookie, to not only track the state, - * but also information about the sent command. Tracking this information - * is needed as the state of a commandId (waiting for reply) is done when a - * write reply is received. - */ - struct CookieInfo { - CookieState_t state; - DeviceCommandMap::iterator pendingCommand; - }; - - /** - * @brief Info about the #cookie - * Used to track the state of the communication - */ - CookieInfo cookieInfo; - - /** the object used to set power switches */ - PowerSwitchIF *powerSwitcher = nullptr; - - /** HK destination can also be set individually */ - object_id_t hkDestination = objects::NO_OBJECT; - - /** - * @brief Used for timing out mode transitions. - * Set when setMode() is called. - */ - uint32_t timeoutStart = 0; - - bool setStartupImmediately = false; - - /** - * Delay for the current mode transition, used for time out - */ - uint32_t childTransitionDelay; - - /** - * @brief The mode the current transition originated from - * - * This is private so the child can not change it and mess up the timeouts - * - * IMPORTANT: This is not valid during _MODE_SHUT_DOWN and _MODE_START_UP!! - * (it is _MODE_POWER_DOWN during this modes) - * - * is element of [MODE_ON, MODE_NORMAL, MODE_RAW] - */ - Mode_t transitionSourceMode; - - /** - * the submode of the source mode during a transition - */ - Submode_t transitionSourceSubMode; - - /** - * read the command queue - */ - void readCommandQueue(void); - - /** - * Handle the device handler mode. - * - * - checks whether commands are valid for the current mode, rejects - * them accordingly - * - checks whether commanded mode transitions are required and calls - * handleCommandedModeTransition() - * - does the necessary action for the current mode or calls - * doChildStateMachine in modes @c MODE_TO_ON and @c MODE_TO_OFF - * - actions that happen in transitions (e.g. setting a timeout) are - * handled in setMode() - */ - void doStateMachine(void); - - void buildRawDeviceCommand(CommandMessage* message); - void buildInternalCommand(void); - /** - * Decrement the counter for the timout of replies. - * - * This is called at the beginning of each cycle. It checks whether a - * reply has timed out (that means a reply was expected but not received). - */ - void decrementDeviceReplyMap(void); - /** - * Convenience function to handle a reply. - * - * Called after scanForReply() has found a packet. Checks if the found ID - * is in the #deviceCommandMap, if so, calls - * #interpretDeviceReply for further action. - * - * It also resets the timeout counter for the command id. - * - * @param data the found packet - * @param id the found id - * @foundLen the length of the packet - */ - void handleReply(const uint8_t *data, DeviceCommandId_t id, uint32_t foundLen); - void replyToReply(const DeviceCommandId_t command, DeviceReplyInfo& replyInfo, - ReturnValue_t status); - - /** - * Build and send a command to the device. - * - * This routine checks whether a raw or direct command has been received, - * checks the content of the received command and calls - * buildCommandFromCommand() for direct commands or sets #rawpacket - * to the received raw packet. - * If no external command is received or the received command is invalid and - * the current mode is @c MODE_NORMAL or a transitional mode, it asks the - * child class to build a command (via getNormalDeviceCommand() or - * getTransitionalDeviceCommand() and buildCommand()) and - * sends the command via RMAP. - */ - void doSendWrite(void); - /** - * Check if the RMAP sendWrite action was successful. - * - * Depending on the result, the following is done - * - if the device command was external commanded, a reply is sent - * indicating the result - * - if the action was successful, the reply timout counter is initialized - */ - 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); - - /** - * Retrive data from the #IPCStore. - * - * @param storageAddress - * @param[out] data - * @param[out] len - * @return - * - @c RETURN_OK @c data is valid - * - @c RETURN_FAILED IPCStore is nullptr - * - the return value from the IPCStore if it was not @c RETURN_OK - */ - ReturnValue_t getStorageData(store_address_t storageAddress, uint8_t **data, - uint32_t *len); - - /** - * @param modeTo either @c MODE_ON, MODE_NORMAL or MODE_RAW, nothing else! - */ - void setTransition(Mode_t modeTo, Submode_t submodeTo); - - /** - * Calls the right child function for the transitional submodes - */ - void callChildStatemachine(); - - ReturnValue_t handleDeviceHandlerMessage(CommandMessage *message); - - virtual dur_millis_t getPeriodicOperationFrequency() const override; - - void parseReply(const uint8_t* receivedData, - size_t receivedDataLen); - - void handleTransitionToOnMode(Mode_t commandedMode, - Submode_t commandedSubmode); - - /** - * Generic internal printer function which also handles printing the object ID. - * @param errorType - * @param functionName - * @param errorCode - * @param errorPrint - */ - void printWarningOrError(sif::OutputTypes errorType, - const char* functionName, - ReturnValue_t errorCode = HasReturnvaluesIF::RETURN_FAILED, - const char* errorPrint = nullptr); +class DeviceHandlerBase : public DeviceHandlerIF, + public HasReturnvaluesIF, + public ExecutableObjectIF, + public SystemObject, + public HasModesIF, + public HasHealthIF, + public HasActionsIF, + public ReceivesParameterMessagesIF, + public HasLocalDataPoolIF { + friend void(Factory::setStaticFrameworkObjectIds)(); + + public: + /** + * The constructor passes the objectId to the SystemObject(). + * + * @param setObjectId the ObjectId to pass to the SystemObject() Constructor + * @param deviceCommuncation Communcation Interface object which is used + * to implement communication functions + * @param comCookie This object will be passed to the communication inter- + * face and can contain user-defined information about the communication. + * @param fdirInstance + * @param cmdQueueSize + */ + DeviceHandlerBase(object_id_t setObjectId, object_id_t deviceCommunication, CookieIF *comCookie, + FailureIsolationBase *fdirInstance = nullptr, size_t cmdQueueSize = 20); + + void setHkDestination(object_id_t hkDestination); + + /** + * If the device handler is controlled by the FSFW thermal building blocks, + * this function should be called to initialize all required components. + * The device handler will then take care of creating local pool entries + * for the device thermal state and device heating request. + * Custom local pool IDs can be assigned as well. + * @param thermalStatePoolId + * @param thermalRequestPoolId + */ + void setThermalStateRequestPoolIds( + 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); + /** + * @brief Helper function to ease device handler development. + * This will instruct the transition to MODE_ON immediately + * (leading to doStartUp() being called for the transition to the ON mode), + * so external mode commanding is not necessary anymore. + * + * This has to be called before the task is started! + * (e.g. in the task factory). This is only a helper function for + * development. Regular mode commanding should be performed by commanding + * the AssemblyBase or Subsystem objects resposible for the device handler. + */ + void setStartUpImmediately(); + + /** + * @brief This function is the device handler base core component and is + * called periodically. + * @details + * General sequence, showing where abstract virtual functions are called: + * If the State is SEND_WRITE: + * 1. Set the cookie state to COOKIE_UNUSED and read the command queue + * 2. Handles Device State Modes by calling doStateMachine(). + * This function calls callChildStatemachine() which calls the + * abstract functions doStartUp() and doShutDown() + * 3. Check switch states by calling checkSwitchStates() + * 4. Decrements counter for timeout of replies by calling + * decrementDeviceReplyMap() + * 5. Performs FDIR check for failures + * 6. If the device mode is MODE_OFF, return RETURN_OK. + * Otherwise, perform the Action property and performs depending + * on value specified by input value counter (incremented in PST). + * The child class tells base class what to do by setting this value. + * - SEND_WRITE: Send data or commands to device by calling + * doSendWrite() which calls sendMessage function + * of #communicationInterface + * and calls buildInternalCommand if the cookie state is COOKIE_UNUSED + * - GET_WRITE: Get ackknowledgement for sending by calling doGetWrite() + * which calls getSendSuccess of #communicationInterface. + * Calls abstract functions scanForReply() and interpretDeviceReply(). + * - SEND_READ: Request reading data from device by calling doSendRead() + * which calls requestReceiveMessage of #communcationInterface + * - GET_READ: Access requested reading data by calling doGetRead() + * which calls readReceivedMessage of #communicationInterface + * @param counter Specifies which Action to perform + * @return RETURN_OK for successful execution + */ + virtual ReturnValue_t performOperation(uint8_t counter); + + /** + * @brief Initializes the device handler + * @details + * Initialize Device Handler as system object and + * initializes all important helper classes. + * Calls fillCommandAndReplyMap(). + * @return + */ + virtual ReturnValue_t initialize(); + + /** + * @brief Intialization steps performed after all tasks have been created. + * This function will be called by the executing task. + * @return + */ + virtual ReturnValue_t initializeAfterTaskCreation() override; + + /** Destructor. */ + virtual ~DeviceHandlerBase(); + + /** + * Implementation of ExecutableObjectIF function + * Used to setup the reference of the task, that executes this component + * @param task_ Pointer to the taskIF of this task + */ + virtual void setTaskIF(PeriodicTaskIF *task_) override; + virtual MessageQueueId_t getCommandQueue(void) const override; + + /** Explicit interface implementation of getObjectId */ + virtual object_id_t getObjectId() const override; + + /** + * @param parentQueueId + */ + virtual void setParentQueue(MessageQueueId_t parentQueueId); + + /** @brief Implementation required for HasActionIF */ + ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, + const uint8_t *data, size_t size) override; + + Mode_t getTransitionSourceMode() const; + Submode_t getTransitionSourceSubMode() const; + virtual void getMode(Mode_t *mode, Submode_t *submode); + HealthState getHealth(); + ReturnValue_t setHealth(HealthState health); + virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, + ParameterWrapper *parameterWrapper, + const ParameterWrapper *newValues, + uint16_t startAtIndex) override; + + protected: + /** + * @brief This is used to let the child class handle the transition from + * mode @c _MODE_START_UP to @c MODE_ON + * @details + * It is only called when the device handler is in mode @c _MODE_START_UP. + * That means, the device switch(es) are already set to on. + * Device handler commands are read and can be handled by the child class. + * If the child class handles a command, it should also send + * an reply accordingly. + * If an Command is not handled (ie #DeviceHandlerCommand is not @c CMD_NONE, + * the base class handles rejecting the command and sends a reply. + * The replies for mode transitions are handled by the base class. + * + * - If the device is started and ready for operation, the mode should be + * set to MODE_ON. It is possible to set the mode to _MODE_TO_ON to + * use the to on transition if available. + * - If the power-up fails, the mode should be set to _MODE_POWER_DOWN + * which will lead to the device being powered off. + * - If the device does not change the mode, the mode will be changed + * to _MODE_POWER_DOWN, after the timeout (from getTransitionDelay()) + * has passed. + * + * #transitionFailure can be set to a failure code indicating the reason + * for a failed transition + */ + virtual void doStartUp() = 0; + /** + * @brief This is used to let the child class handle the transition + * from mode @c _MODE_SHUT_DOWN to @c _MODE_POWER_DOWN + * @details + * It is only called when the device handler is in mode @c _MODE_SHUT_DOWN. + * Device handler commands are read and can be handled by the child class. + * If the child class handles a command, it should also send an reply + * accordingly. + * If an Command is not handled (ie #DeviceHandlerCommand is not + * @c CMD_NONE, the base class handles rejecting the command and sends a + * reply. The replies for mode transitions are handled by the base class. + * + * - If the device ready to be switched off, + * the mode should be set to _MODE_POWER_DOWN. + * - If the device should not be switched off, the mode can be changed to + * _MODE_TO_ON (or MODE_ON if no transition is needed). + * - If the device does not change the mode, the mode will be changed to + * _MODE_POWER_DOWN, when the timeout (from getTransitionDelay()) + * has passed. + * + * #transitionFailure can be set to a failure code indicating the reason + * for a failed transition + */ + virtual void doShutDown() = 0; + + /* Command handling */ + /** + * Build the device command to send for normal mode. + * + * This is only called in @c MODE_NORMAL. If multiple submodes for + * @c MODE_NORMAL are supported, different commands can built, + * depending on the submode. + * + * #rawPacket and #rawPacketLen must be set by this method to the + * packet to be sent. If variable command frequence is required, a counter + * can be used and the frequency in the reply map has to be set manually + * by calling updateReplyMap(). + * + * @param[out] id the device command id that has been built + * @return + * - @c RETURN_OK to send command after setting #rawPacket and + * #rawPacketLen. + * - @c NOTHING_TO_SEND when no command is to be sent. + * - Anything else triggers an even with the returnvalue as a parameter. + */ + virtual ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) = 0; + /** + * Build the device command to send for a transitional mode. + * + * This is only called in @c _MODE_TO_NORMAL, @c _MODE_TO_ON, @c _MODE_TO_RAW, + * @c _MODE_START_UP and @c _MODE_SHUT_DOWN. So it is used by doStartUp() + * and doShutDown() as well as doTransition(), by setting those + * modes in the respective functions. + * + * A good idea is to implement a flag indicating a command has to be built + * and a variable containing the command number to be built + * and filling them in doStartUp(), doShutDown() and doTransition() so no + * modes have to be checked here. + * + * #rawPacket and #rawPacketLen must be set by this method to the + * packet to be sent. + * + * @param[out] id the device command id built + * @return + * - @c RETURN_OK when a command is to be sent + * - @c NOTHING_TO_SEND when no command is to be sent + * - Anything else triggers an even with the returnvalue as a parameter + */ + virtual ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) = 0; + /** + * @brief Build a device command packet from data supplied by a direct + * command (PUS Service 8) + * @details + * This will be called if an functional command via PUS Service 8 is received and is + * the primary interface for functional command instead of #executeAction for users. The + * supplied ActionId_t action ID will be converted to a DeviceCommandId_t command ID after + * an internal check whether the action ID is a key in the device command map. + * + * #rawPacket and #rawPacketLen should be set by this method to the packet to be sent. + * The existence of the command in the command map and the command size check against 0 are + * done by the base class. + * + * @param deviceCommand The command to build, already checked against deviceCommandMap + * @param commandData Pointer to the data from the direct command + * @param commandDataLen Length of commandData + * @return + * - @c RETURN_OK to send command after #rawPacket and #rawPacketLen + * have been set. + * - @c HasActionsIF::EXECUTION_COMPLETE to generate a finish reply immediately. This can + * be used if no reply is expected + * - Anything else triggers an event with the return code as a parameter as well as a + * step reply failed with the return code + */ + virtual ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t *commandData, + size_t commandDataLen) = 0; + + /* Reply handling */ + /** + * @brief Scans a buffer for a valid reply. + * @details + * This is used by the base class to check the data received for valid packets. + * It only checks if a valid packet starts at @c start. + * It also only checks the structural validy of the packet, + * e.g. checksums lengths and protocol data. No information check is done, + * e.g. range checks etc. + * + * Errors should be reported directly, the base class does NOT report any + * errors based on the return value of this function. + * + * @param start start of remaining buffer to be scanned + * @param len length of remaining buffer to be scanned + * @param[out] foundId the id of the data found in the buffer. + * @param[out] foundLen length of the data found. Is to be set in function, + * buffer is scanned at previous position + foundLen. + * @return + * - @c RETURN_OK a valid packet was found at @c start, @c foundLen is valid + * - @c RETURN_FAILED no reply could be found starting at @c start, + * implies @c foundLen is not valid, base class will call scanForReply() + * again with ++start + * - @c DeviceHandlerIF::INVALID_DATA a packet was found but it is invalid, + * e.g. checksum error, implies @c foundLen is valid, can be used to + * skip some bytes + * - @c DeviceHandlerIF::LENGTH_MISSMATCH @c len is invalid + * - @c DeviceHandlerIF::IGNORE_REPLY_DATA Ignore this specific part of + * the packet + * - @c DeviceHandlerIF::IGNORE_FULL_PACKET Ignore the packet + * - @c APERIODIC_REPLY if a valid reply is received that has not been + * requested by a command, but should be handled anyway + * (@see also fillCommandAndCookieMap() ) + */ + virtual ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) = 0; + /** + * @brief Interpret a reply from the device. + * @details + * This is called after scanForReply() found a valid packet, it can be + * assumed that the length and structure is valid. + * This routine extracts the data from the packet into a DataSet and then + * calls handleDeviceTM(), which either sends a TM packet or stores the + * data in the DataPool depending on whether it was an external command. + * No packet length is given, as it should be defined implicitly by the id. + * + * @param id the id found by scanForReply() + * @param packet + * @return + * - @c RETURN_OK when the reply was interpreted. + * - @c IGNORE_REPLY_DATA Ignore the reply and don't reset reply cycle + * counter. + * - @c RETURN_FAILED when the reply could not be interpreted, + * e.g. logical errors or range violations occurred + */ + virtual ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) = 0; + MessageQueueId_t getCommanderQueueId(DeviceCommandId_t replyId) const; + /** + * Helper function to get pending command. This is useful for devices + * like SPI sensors to identify the last sent command. + * This only returns the command sent in the last SEND_WRITE cycle. + * @return + */ + DeviceCommandId_t getPendingCommand() const; + + /* Specifying commands and replies */ + /** + * @brief Fill the #DeviceCommandMap and #DeviceReplyMap called by the #initialize + * of the base class + * @details + * This is used to let the base class know which replies are expected. + * There are different scenarios regarding this: + * + * - "Normal" commands. These are commands, that trigger a direct reply + * from the device. In this case, the id of the command should be added + * to the command map with a commandData_t where maxDelayCycles is set + * to the maximum expected number of PST cycles the reply will take. + * Then, scanForReply returns the id of the command and the base class + * can handle time-out and missing replies. + * + * - Periodic, unrequested replies. These are replies that, once enabled, + * are sent by the device on its own in a defined interval. + * In this case, the id of the reply or a placeholder id should be added + * to the deviceCommandMap with a commandData_t where maxDelayCycles is + * set to the maximum expected number of PST cycles between two replies + * (also a tolerance should be added, as an FDIR message will be + * generated if it is missed). + * From then on, the base class handles the reception. + * Then, scanForReply returns the id of the reply or the placeholder id + * and the base class will take care of checking that all replies are + * received and the interval is correct. + * + * - Aperiodic, unrequested replies. These are replies that are sent + * by the device without any preceding command and not in a defined + * interval. These are not entered in the deviceCommandMap but + * handled by returning @c APERIODIC_REPLY in scanForReply(). + */ + virtual void fillCommandAndReplyMap() = 0; + /** + * This is a helper method to facilitate inserting entries in the command map. + * @param deviceCommand Identifier of the command to add. + * @param maxDelayCycles The maximum number of delay cycles the command + * waits until it times out. + * @param replyLen Will be supplied to the requestReceiveMessage call of + * the communication interface. + * @param periodic Indicates if the command is periodic (i.e. it is sent + * by the device repeatedly without request) or not. Default is aperiodic (0). + * Please note that periodic replies are disabled by default. You can enable them with + * #updatePeriodicReply + * @return - @c RETURN_OK when the command was successfully inserted, + * - @c RETURN_FAILED else. + */ + ReturnValue_t insertInCommandAndReplyMap(DeviceCommandId_t deviceCommand, uint16_t maxDelayCycles, + LocalPoolDataSetBase *replyDataSet = nullptr, + size_t replyLen = 0, bool periodic = false, + bool hasDifferentReplyId = false, + DeviceCommandId_t replyId = 0); + /** + * @brief This is a helper method to insert replies in the reply map. + * @param deviceCommand Identifier of the reply to add. + * @param maxDelayCycles The maximum number of delay cycles the reply waits + * until it times out. + * @param periodic Indicates if the command is periodic (i.e. it is sent + * by the device repeatedly without request) or not. Default is aperiodic (0). + * Please note that periodic replies are disabled by default. You can enable them with + * #updatePeriodicReply + * @return - @c RETURN_OK when the command was successfully inserted, + * - @c RETURN_FAILED else. + */ + ReturnValue_t insertInReplyMap(DeviceCommandId_t deviceCommand, uint16_t maxDelayCycles, + LocalPoolDataSetBase *dataSet = nullptr, size_t replyLen = 0, + bool periodic = false); + + /** + * @brief A simple command to add a command to the commandList. + * @param deviceCommand The command to add + * @return - @c RETURN_OK when the command was successfully inserted, + * - @c RETURN_FAILED else. + */ + ReturnValue_t insertInCommandMap(DeviceCommandId_t deviceCommand); + + /** + * Enables a periodic reply for a given command. It sets to delay cycles to the specified + * maximum delay cycles for a given reply ID if enabled or to 0 if disabled. + * @param enable Specify whether to enable or disable a given periodic reply + * @return + */ + ReturnValue_t updatePeriodicReply(bool enable, DeviceCommandId_t deviceReply); + + /** + * @brief This function returns the reply length of the next reply to read. + * + * @param deviceCommand The command which triggered the device reply. + * + * @details The default implementation assumes only one reply is triggered by the command. In + * case the command triggers multiple replies (e.g. one acknowledgment, one data, + * and one execution status reply), this function can be overwritten to get the + * reply length of the next reply to read. + */ + virtual size_t getNextReplyLength(DeviceCommandId_t deviceCommand); + + /** + * @brief This is a helper method to facilitate updating entries in the reply map. + * @param deviceCommand Identifier of the reply to update. + * @param delayCycles The current number of delay cycles to wait. As stated in + * #fillCommandAndReplyMap, to disable periodic commands, this is set to zero. + * @param maxDelayCycles The maximum number of delay cycles the reply waits + * until it times out. By passing 0 the entry remains untouched. + * @param periodic Indicates if the command is periodic (i.e. it is sent + * by the device repeatedly without request) or not. Default is aperiodic (0). + * Warning: The setting always overrides the value that was entered in the map. + * @return - @c RETURN_OK when the command was successfully inserted, + * - @c RETURN_FAILED else. + */ + ReturnValue_t updateReplyMapEntry(DeviceCommandId_t deviceReply, uint16_t delayCycles, + uint16_t maxDelayCycles, bool periodic = false); + /** + * @brief Can be used to set the dataset corresponding to a reply ID manually. + * @details + * Used by the local data pool manager. + */ + ReturnValue_t setReplyDataset(DeviceCommandId_t replyId, LocalPoolDataSetBase *dataset); + + /** + * Get the time needed to transit from modeFrom to modeTo. + * + * Used for the following transitions: + * modeFrom -> modeTo: + * MODE_ON -> [MODE_ON, MODE_NORMAL, MODE_RAW, _MODE_POWER_DOWN] + * MODE_NORMAL -> [MODE_ON, MODE_NORMAL, MODE_RAW, _MODE_POWER_DOWN] + * MODE_RAW -> [MODE_ON, MODE_NORMAL, MODE_RAW, _MODE_POWER_DOWN] + * _MODE_START_UP -> MODE_ON (do not include time to set the switches, + * the base class got you covered) + * + * The default implementation returns 0 ! + * @param modeFrom + * @param modeTo + * @return time in ms + */ + virtual uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) = 0; + + /* Functions used by the local data pool manager */ + /** + * This function is used to initialize the local housekeeping pool + * entries. The default implementation leaves the pool empty. + * @param localDataPoolMap + * @return + */ + virtual ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) override; + /** + * @brief Set all datapool variables that are update periodically in + * normal mode invalid + * @details + * The default implementation will set all datasets which have been added + * in #fillCommandAndReplyMap to invalid. It will also set all pool + * variables inside the dataset to invalid. The user can override this + * method optionally. + */ + virtual void setNormalDatapoolEntriesInvalid(); + /** + * @brief Get the dataset handle for a given SID. + * @details + * The default implementation will use the deviceCommandMap to look for the corresponding + * dataset handle. The user can override this function if this is not desired. + * @param sid + * @return + */ + virtual LocalPoolDataSetBase *getDataSetHandle(sid_t sid) override; + + /* HasModesIF overrides */ + virtual void startTransition(Mode_t mode, Submode_t submode) override; + virtual void setToExternalControl() override; + virtual void announceMode(bool recursive) override; + /** + * @brief Set the device handler mode + * @details + * Sets #timeoutStart with every call Also sets #transitionTargetMode if necessary so + * transitional states can be entered from everywhere without breaking the state machine + * (which relies on a correct #transitionTargetMode). + * The submode is left unchanged. + * + * @param newMode + */ + void setMode(Mode_t newMode); + /** + * @overload + * @param submode + */ + void setMode(Mode_t newMode, Submode_t submode); + /** + * @brief Should be implemented properly by child class. + * @param mode + * @param submode + * @return + * - @c RETURN_OK if valid + * - @c RETURN_FAILED if invalid + */ + virtual ReturnValue_t isModeCombinationValid(Mode_t mode, Submode_t submode); + /** + * @brief Notify child about mode change. + * @details + * Can be overriden to be used like a callback. + */ + virtual void modeChanged(); + + /* Power handling functions */ + /** + * Return the switches connected to the device. + * + * The default implementation returns one switch set in the ctor. + * + * @param[out] switches pointer to an array of switches + * @param[out] numberOfSwitches length of returned array + * @return + * - @c RETURN_OK if the parameters were set + * - @c RETURN_FAILED if no switches exist + */ + virtual ReturnValue_t getSwitches(const uint8_t **switches, uint8_t *numberOfSwitches); + + /** + * @brief Helper function to report a missed reply + * @details Can be overwritten by children to act on missed replies or to fake reporting Id. + * @param id of the missed reply + */ + virtual void missedReply(DeviceCommandId_t id); + + /* Miscellaneous functions */ + /** + * @brief Hook function for child handlers which is called once per + * performOperation(). Default implementation is empty. + */ + virtual void performOperationHook(); + /** + * @brief Can be implemented by child handler to + * perform debugging + * @details Example: Calling this in performOperation + * to track values like mode. + * @param positionTracker Provide the child handler a way to know + * where the debugInterface was called + * @param objectId Provide the child handler object Id to + * specify actions for spefic devices + * @param parameter Supply a parameter of interest + * Please delete all debugInterface calls in DHB after debugging is finished ! + */ + virtual void debugInterface(uint8_t positionTracker = 0, object_id_t objectId = 0, + uint32_t parameter = 0); + + protected: + static const uint8_t INTERFACE_ID = CLASS_ID::DEVICE_HANDLER_BASE; + + static const ReturnValue_t INVALID_CHANNEL = MAKE_RETURN_CODE(0xA0); + /* Return codes for scanForReply */ + //! This is used to specify for replies from a device which are not replies to requests + static const ReturnValue_t APERIODIC_REPLY = MAKE_RETURN_CODE(0xB0); + //! Ignore parts of the received packet + static const ReturnValue_t IGNORE_REPLY_DATA = MAKE_RETURN_CODE(0xB1); + //! Ignore full received packet + static const ReturnValue_t IGNORE_FULL_PACKET = MAKE_RETURN_CODE(0xB2); + /* Return codes for command building */ + //! Return this if no command sending in required + static const ReturnValue_t NOTHING_TO_SEND = MAKE_RETURN_CODE(0xC0); + static const ReturnValue_t COMMAND_MAP_ERROR = MAKE_RETURN_CODE(0xC2); + // Return codes for getSwitches */ + static const ReturnValue_t NO_SWITCH = MAKE_RETURN_CODE(0xD0); + /* Mode handling error Codes */ + static const ReturnValue_t CHILD_TIMEOUT = MAKE_RETURN_CODE(0xE0); + static const ReturnValue_t SWITCH_FAILED = MAKE_RETURN_CODE(0xE1); + + static const MessageQueueId_t NO_COMMANDER = MessageQueueIF::NO_QUEUE; + + //! Pointer to the raw packet that will be sent. + uint8_t *rawPacket = nullptr; + //! Size of the #rawPacket. + uint32_t rawPacketLen = 0; + + /** + * The mode the device handler is currently in. + * This should never be changed directly but only with setMode() + */ + Mode_t mode; + /** + * The submode the device handler is currently in. + * This should never be changed directly but only with setMode() + */ + Submode_t submode; + + /** This is the counter value from performOperation(). */ + uint8_t pstStep = 0; + uint8_t lastStep = 0; + uint32_t pstIntervalMs = 0; + + /** + * Wiretapping flag: + * + * indicates either that all raw messages to and from the device should be + * sent to #defaultRawReceiver + * or that all device TM should be downlinked to #defaultRawReceiver. + */ + enum WiretappingMode { OFF = 0, RAW = 1, TM = 2 } wiretappingMode; + /** + * @brief A message queue that accepts raw replies + * + * Statically initialized in initialize() to a configurable object. + * Used when there is no method of finding a recipient, ie raw mode and + * reporting erroneous replies + */ + MessageQueueId_t defaultRawReceiver = MessageQueueIF::NO_QUEUE; + store_address_t storedRawData; + + /** + * @brief The message queue which wants to read all raw traffic + * If #isWiretappingActive all raw communication from and to the device + * will be sent to this queue + */ + MessageQueueId_t requestedRawTraffic = 0; + + /** + * Pointer to the IPCStore. + * This caches the pointer received from the objectManager in the constructor. + */ + StorageManagerIF *IPCStore = nullptr; + /** The comIF object ID is cached for the intialize() function */ + object_id_t deviceCommunicationId; + /** Communication object used for device communication */ + DeviceCommunicationIF *communicationInterface = nullptr; + /** Cookie used for communication */ + CookieIF *comCookie; + + /* Health helper for HasHealthIF */ + HealthHelper healthHelper; + /* Mode helper for HasModesIF */ + ModeHelper modeHelper; + /* Parameter helper for ReceivesParameterMessagesIF */ + ParameterHelper parameterHelper; + /* Action helper for HasActionsIF */ + ActionHelper actionHelper; + /* Housekeeping Manager */ + LocalDataPoolManager poolManager; + + /** + * @brief Information about commands + */ + struct DeviceCommandInfo { + //! Indicates if the command is already executing. + bool isExecuting; + //! Dynamic value to indicate how many replies are expected. + //! Inititated with 0. + uint8_t expectedReplies; + //! if this is != NO_COMMANDER, DHB was commanded externally and shall + //! report everything to commander. + MessageQueueId_t sendReplyTo; + }; + using DeviceCommandMap = std::map; + /** + * Information about commands + */ + DeviceCommandMap deviceCommandMap; + + /** + * @brief Information about expected replies + * This is used to keep track of pending replies. + */ + struct DeviceReplyInfo { + //! The maximum number of cycles the handler should wait for a reply + //! to this command. + uint16_t maxDelayCycles; + //! The currently remaining cycles the handler should wait for a reply, + //! 0 means there is no reply expected + uint16_t delayCycles; + size_t replyLen = 0; //!< Expected size of the reply. + //! if this is !=0, the delayCycles will not be reset to 0 but to + //! maxDelayCycles + bool periodic = false; + //! The dataset used to access housekeeping data related to the + //! respective device reply. Will point to a dataset held by + //! the child handler (if one is specified) + LocalPoolDataSetBase *dataSet = nullptr; + //! The command that expects this reply. + DeviceCommandMap::iterator command; + }; + + using DeviceReplyMap = std::map; + using DeviceReplyIter = DeviceReplyMap::iterator; + /** + * This map is used to check and track correct reception of all replies. + * + * It has multiple use: + * - It stores the information on pending replies. If a command is sent, + * the DeviceCommandInfo.count is incremented. + * - It is used to time-out missing replies. If a command is sent, the + * DeviceCommandInfo.DelayCycles is set to MaxDelayCycles. + * - It is queried to check if a reply from the device can be interpreted. + * scanForReply() returns the id of the command a reply was found for. + * The reply is ignored in the following cases: + * - No entry for the returned id was found + * - The deviceReplyInfo.delayCycles is == 0 + */ + DeviceReplyMap deviceReplyMap; + + //! The MessageQueue used to receive device handler commands + //! and to send replies. + MessageQueueIF *commandQueue = nullptr; + + DeviceHandlerThermalSet *thermalSet = nullptr; + + /** + * Optional Error code. Can be set in doStartUp(), doShutDown() and + * doTransition() to signal cause for Transition failure. + */ + ReturnValue_t childTransitionFailure; + + /** Counts if communication channel lost a reply, so some missed + * replys can be ignored. */ + uint32_t ignoreMissedRepliesCount = 0; + + /** Pointer to the used FDIR instance. If not provided by child, + * default class is instantiated. */ + FailureIsolationBase *fdirInstance; + + //! To correctly delete the default instance. + bool defaultFDIRUsed; + + //! Indicates if SWITCH_WENT_OFF was already thrown. + bool switchOffWasReported; + + /** Pointer to the task which executes this component, + is invalid before setTaskIF was called. */ + PeriodicTaskIF *executingTask = nullptr; + + //! Object which switches power on and off. + static object_id_t powerSwitcherId; + + //! Object which receives RAW data by default. + static object_id_t rawDataReceiverId; + + //! Object which may be the root cause of an identified fault. + static object_id_t defaultFdirParentId; + + /** + * @brief Send a reply to a received device handler command. + * + * This also resets #DeviceHandlerCommand to 0. + * + * @param reply the reply type + * @param parameter parameter for the reply + */ + void replyReturnvalueToCommand(ReturnValue_t status, uint32_t parameter = 0); + /** + * TODO: Whats the difference between this and the upper command? + * @param status + * @param parameter + */ + void replyToCommand(ReturnValue_t status, uint32_t parameter = 0); + + /** + * 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, + * which can be deduced from the current mode which is + * [_MODE_TO_ON, _MODE_TO_NORMAL, _MODE_TO_RAW] + * + * The intended target submode is already set. + * The origin submode can be read in subModeFrom. + * + * If the transition can not be completed, the child class can try to reach + * an working mode by setting the mode either directly + * or setting the mode to an transitional mode (TO_ON, TO_NORMAL, TO_RAW) + * if the device needs to be reconfigured. + * + * If nothing works, the child class can wait for the timeout and the base + * class will reset the mode to the mode where the transition + * originated from (the child should report the reason for the failed transition). + * + * The intended way to send commands is to set a flag (enum) indicating + * which command is to be sent here and then to check in + * buildTransitionCommand() for the flag. This flag can also be used by + * doStartUp() and doShutDown() to get a nice and clean implementation of + * buildTransitionCommand() without switching through modes. + * + * When the the condition for the completion of the transition is met, the + * mode can be set, for example in the scanForReply() function. + * + * The default implementation goes into the target mode directly. + * + * #transitionFailure can be set to a failure code indicating the reason + * for a failed transition + * + * @param modeFrom + * The mode the transition originated from: + * [MODE_ON, MODE_NORMAL, MODE_RAW and _MODE_POWER_DOWN (if the mode changed + * from _MODE_START_UP to _MODE_TO_ON)] + * @param subModeFrom the subMode of modeFrom + */ + virtual void doTransition(Mode_t modeFrom, Submode_t subModeFrom); + + /** + * Get the communication action for the current step. + * The step number can be read from #pstStep. + * @return The communication action to execute in this step + */ + virtual CommunicationAction getComAction(); + + /** + * Checks state of switches in conjunction with mode and triggers an event + * if they don't fit. + */ + virtual void checkSwitchState(); + + /** + * Reserved for the rare case where a device needs to perform additional + * operation cyclically in OFF mode. + */ + virtual void doOffActivity(); + + /** + * Reserved for the rare case where a device needs to perform additional + * operation cyclically in ON mode. + */ + virtual void doOnActivity(); + + /** + * Required for HasLocalDataPoolIF, return a handle to the local pool manager. + * @return + */ + LocalDataPoolManager *getHkManagerHandle() override; + + /** + * Returns the delay cycle count of a reply. + * A count != 0 indicates that the command is already executed. + * @param deviceCommand The command to look for + * @return + * The current delay count. If the command does not exist (should never + * happen) it returns 0. + */ + uint8_t getReplyDelayCycles(DeviceCommandId_t deviceCommand); + + /** + * Calls replyRawData() with #defaultRawReceiver, but checks if wiretapping + * is active and if so, does not send the data as the wiretapping will have + * sent it already + */ + void replyRawReplyIfnotWiretapped(const uint8_t *data, size_t len); + + /** + * Enable the reply checking for a command + * + * Is only called, if the command was sent (i.e. the getWriteReply was + * successful). Must ensure that all replies are activated and correctly + * linked to the command that initiated it. + * The default implementation looks for a reply with the same id as the + * command id in the replyMap or uses the alternativeReplyId if flagged so. + * When found, copies maxDelayCycles to delayCycles in the reply information + * and sets the command to expect one reply. + * + * Can be overwritten by the child, if a command activates multiple replies + * or replyId differs from commandId. + * Notes for child implementations: + * - If the command was not found in the reply map, + * NO_REPLY_EXPECTED MUST be returned. + * - A failure code may be returned if something went fundamentally wrong. + * + * @param deviceCommand + * @return - RETURN_OK if a reply was activated. + * - NO_REPLY_EXPECTED if there was no reply found. This is not an + * error case as many commands do not expect a reply. + */ + virtual ReturnValue_t enableReplyInReplyMap(DeviceCommandMap::iterator command, + uint8_t expectedReplies = 1, + bool useAlternateId = false, + DeviceCommandId_t alternateReplyID = 0); + + /** + * @brief Build the device command to send for raw mode. + * @details + * This is only called in @c MODE_RAW. It is for the rare case that in + * raw mode packets are to be sent by the handler itself. It is NOT needed + * for the raw commanding service. Its only current use is in the STR + * handler which gets its raw packets from a different source. + * Also it can be used for transitional commands, to get the device ready + * for @c MODE_RAW + * + * As it is almost never used, there is a default implementation + * returning @c NOTHING_TO_SEND. + * + * #rawPacket and #rawPacketLen must be set by this method to the packet + * to be sent. + * + * @param[out] id the device command id built + * @return + * - @c RETURN_OK when a command is to be sent + * - not @c NOTHING_TO_SEND when no command is to be sent + */ + virtual ReturnValue_t buildChildRawCommand(); + + /** + * @brief Construct a command reply containing a raw reply. + * @details + * It gets space in the #IPCStore, copies data there, then sends a raw reply + * containing the store address. This method is virtual, as devices can have different channels + * to send raw replies + * + * @param data data to send + * @param len length of @c data + * @param sendTo the messageQueueId of the one to send to + * @param isCommand marks the raw data as a command, the message then + * will be of type raw_command + */ + virtual void replyRawData(const uint8_t *data, size_t len, MessageQueueId_t sendTo, + bool isCommand = false); + + /** + * Get the state of the PCDU switches in the local datapool + * @return + * - @c PowerSwitchIF::SWITCH_ON if all switches specified + * by #switches are on + * - @c PowerSwitchIF::SWITCH_OFF one of the switches specified by + * #switches are off + * - @c PowerSwitchIF::RETURN_FAILED if an error occured + */ + ReturnValue_t getStateOfSwitches(); + + /** + * Children can overwrite this function to suppress checking of the + * command Queue + * + * This can be used when the child does not want to receive a command in + * a certain situation. Care must be taken that checking is not + * permanentely disabled as this would render the handler unusable. + * + * @return whether checking the queue should NOT be done + */ + virtual bool dontCheckQueue(); + + Mode_t getBaseMode(Mode_t transitionMode); + + bool isAwaitingReply(); + + void handleDeviceTM(SerializeIF *dataSet, DeviceCommandId_t replyId, bool forceDirectTm = false); + // void handleDeviceTM(uint8_t* data, size_t dataSize, DeviceCommandId_t replyId, + // bool forceDirectTm); + + virtual ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, + uint32_t *msToReachTheMode); + + virtual ReturnValue_t letChildHandleMessage(CommandMessage *message); + + /** + * Overwrites SystemObject::triggerEvent in order to inform FDIR"Helper" + * faster about executed events. + * This is a bit sneaky, but improves responsiveness of the device FDIR. + * @param event The event to be thrown + * @param parameter1 Optional parameter 1 + * @param parameter2 Optional parameter 2 + */ + void triggerEvent(Event event, uint32_t parameter1 = 0, uint32_t parameter2 = 0); + /** + * Same as triggerEvent, but for forwarding if object is used as proxy. + */ + virtual void forwardEvent(Event event, uint32_t parameter1 = 0, uint32_t parameter2 = 0) const; + + /** + * Checks if current mode is transitional mode. + * @return true if mode is transitional, false else. + */ + bool isTransitionalMode(); + + /** + * Checks if current handler state allows reception of external device commands. + * Default implementation allows commands only in plain MODE_ON and MODE_NORMAL. + * @return RETURN_OK if commands are accepted, anything else otherwise. + */ + virtual ReturnValue_t acceptExternalDeviceCommands(); + + bool commandIsExecuting(DeviceCommandId_t commandId); + + /** + * set all switches returned by getSwitches() + * + * @param onOff on == @c SWITCH_ON; off != @c SWITCH_ON + */ + void commandSwitch(ReturnValue_t onOff); + + private: + /** + * State a cookie is in. + * + * Used to keep track of the state of the RMAP communication. + */ + enum CookieState_t { + COOKIE_UNUSED, //!< The Cookie is unused + COOKIE_WRITE_READY, //!< There's data available to send. + COOKIE_READ_SENT, //!< A sendRead command was sent with this cookie + COOKIE_WRITE_SENT //!< A sendWrite command was sent with this cookie + }; + /** + * Information about a cookie. + * + * This is stored in a map for each cookie, to not only track the state, + * but also information about the sent command. Tracking this information + * is needed as the state of a commandId (waiting for reply) is done when a + * write reply is received. + */ + struct CookieInfo { + CookieState_t state; + DeviceCommandMap::iterator pendingCommand; + }; + + /** + * @brief Info about the #cookie + * Used to track the state of the communication + */ + CookieInfo cookieInfo; + + /** the object used to set power switches */ + PowerSwitchIF *powerSwitcher = nullptr; + + /** HK destination can also be set individually */ + object_id_t hkDestination = objects::NO_OBJECT; + + /** + * @brief Used for timing out mode transitions. + * Set when setMode() is called. + */ + uint32_t timeoutStart = 0; + + bool setStartupImmediately = false; + + /** + * Delay for the current mode transition, used for time out + */ + uint32_t childTransitionDelay; + + /** + * @brief The mode the current transition originated from + * + * This is private so the child can not change it and mess up the timeouts + * + * IMPORTANT: This is not valid during _MODE_SHUT_DOWN and _MODE_START_UP!! + * (it is _MODE_POWER_DOWN during this modes) + * + * is element of [MODE_ON, MODE_NORMAL, MODE_RAW] + */ + Mode_t transitionSourceMode; + + /** + * the submode of the source mode during a transition + */ + Submode_t transitionSourceSubMode; + + /** + * read the command queue + */ + void readCommandQueue(void); + + /** + * Handle the device handler mode. + * + * - checks whether commands are valid for the current mode, rejects + * them accordingly + * - checks whether commanded mode transitions are required and calls + * handleCommandedModeTransition() + * - does the necessary action for the current mode or calls + * doChildStateMachine in modes @c MODE_TO_ON and @c MODE_TO_OFF + * - actions that happen in transitions (e.g. setting a timeout) are + * handled in setMode() + */ + void doStateMachine(void); + + void buildRawDeviceCommand(CommandMessage *message); + void buildInternalCommand(void); + /** + * Decrement the counter for the timout of replies. + * + * This is called at the beginning of each cycle. It checks whether a + * reply has timed out (that means a reply was expected but not received). + */ + void decrementDeviceReplyMap(void); + /** + * Convenience function to handle a reply. + * + * Called after scanForReply() has found a packet. Checks if the found ID + * is in the #deviceCommandMap, if so, calls + * #interpretDeviceReply for further action. + * + * It also resets the timeout counter for the command id. + * + * @param data the found packet + * @param id the found id + * @foundLen the length of the packet + */ + void handleReply(const uint8_t *data, DeviceCommandId_t id, uint32_t foundLen); + void replyToReply(const DeviceCommandId_t command, DeviceReplyInfo &replyInfo, + ReturnValue_t status); + + /** + * Build and send a command to the device. + * + * This routine checks whether a raw or direct command has been received, + * checks the content of the received command and calls + * buildCommandFromCommand() for direct commands or sets #rawpacket + * to the received raw packet. + * If no external command is received or the received command is invalid and + * the current mode is @c MODE_NORMAL or a transitional mode, it asks the + * child class to build a command (via getNormalDeviceCommand() or + * getTransitionalDeviceCommand() and buildCommand()) and + * sends the command via RMAP. + */ + void doSendWrite(void); + /** + * Check if the RMAP sendWrite action was successful. + * + * Depending on the result, the following is done + * - if the device command was external commanded, a reply is sent + * indicating the result + * - if the action was successful, the reply timout counter is initialized + */ + 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); + + /** + * Retrive data from the #IPCStore. + * + * @param storageAddress + * @param[out] data + * @param[out] len + * @return + * - @c RETURN_OK @c data is valid + * - @c RETURN_FAILED IPCStore is nullptr + * - the return value from the IPCStore if it was not @c RETURN_OK + */ + ReturnValue_t getStorageData(store_address_t storageAddress, uint8_t **data, uint32_t *len); + + /** + * @param modeTo either @c MODE_ON, MODE_NORMAL or MODE_RAW, nothing else! + */ + void setTransition(Mode_t modeTo, Submode_t submodeTo); + + /** + * Calls the right child function for the transitional submodes + */ + void callChildStatemachine(); + + ReturnValue_t handleDeviceHandlerMessage(CommandMessage *message); + + virtual dur_millis_t getPeriodicOperationFrequency() const override; + + void parseReply(const uint8_t *receivedData, size_t receivedDataLen); + + void handleTransitionToOnMode(Mode_t commandedMode, Submode_t commandedSubmode); + + /** + * Generic internal printer function which also handles printing the object ID. + * @param errorType + * @param functionName + * @param errorCode + * @param errorPrint + */ + void printWarningOrError(sif::OutputTypes errorType, const char *functionName, + ReturnValue_t errorCode = HasReturnvaluesIF::RETURN_FAILED, + const char *errorPrint = nullptr); }; #endif /* FSFW_DEVICEHANDLERS_DEVICEHANDLERBASE_H_ */ diff --git a/src/fsfw/devicehandlers/DeviceHandlerFailureIsolation.cpp b/src/fsfw/devicehandlers/DeviceHandlerFailureIsolation.cpp index 8b1c1489..48783c20 100644 --- a/src/fsfw/devicehandlers/DeviceHandlerFailureIsolation.cpp +++ b/src/fsfw/devicehandlers/DeviceHandlerFailureIsolation.cpp @@ -1,269 +1,260 @@ #include "fsfw/devicehandlers/DeviceHandlerFailureIsolation.h" #include "fsfw/devicehandlers/DeviceHandlerIF.h" -#include "fsfw/objectmanager/ObjectManager.h" -#include "fsfw/modes/HasModesIF.h" #include "fsfw/health/HealthTableIF.h" +#include "fsfw/modes/HasModesIF.h" +#include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/power/Fuse.h" #include "fsfw/serviceinterface/ServiceInterfaceStream.h" #include "fsfw/thermal/ThermalComponentIF.h" -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) : - FailureIsolationBase(owner, parent), - strangeReplyCount(DEFAULT_MAX_STRANGE_REPLIES, - DEFAULT_STRANGE_REPLIES_TIME_MS, - parameterDomainBase++), - missedReplyCount( DEFAULT_MAX_MISSED_REPLY_COUNT, - DEFAULT_MISSED_REPLY_TIME_MS, - parameterDomainBase++), - recoveryCounter(DEFAULT_MAX_REBOOT, DEFAULT_REBOOT_TIME_MS, - parameterDomainBase++), - fdirState(NONE) { -} +DeviceHandlerFailureIsolation::DeviceHandlerFailureIsolation(object_id_t owner, object_id_t parent) + : FailureIsolationBase(owner, parent), + strangeReplyCount(DEFAULT_MAX_STRANGE_REPLIES, DEFAULT_STRANGE_REPLIES_TIME_MS, + parameterDomainBase++), + missedReplyCount(DEFAULT_MAX_MISSED_REPLY_COUNT, DEFAULT_MISSED_REPLY_TIME_MS, + parameterDomainBase++), + recoveryCounter(DEFAULT_MAX_REBOOT, DEFAULT_REBOOT_TIME_MS, parameterDomainBase++), + fdirState(NONE) {} -DeviceHandlerFailureIsolation::~DeviceHandlerFailureIsolation() { -} +DeviceHandlerFailureIsolation::~DeviceHandlerFailureIsolation() {} ReturnValue_t DeviceHandlerFailureIsolation::eventReceived(EventMessage* event) { - if(isFdirInActionOrAreWeFaulty(event)) { - return RETURN_OK; - } - ReturnValue_t result = RETURN_FAILED; - switch (event->getEvent()) { - case HasModesIF::MODE_TRANSITION_FAILED: - case HasModesIF::OBJECT_IN_INVALID_MODE: - //We'll try a recovery as long as defined in MAX_REBOOT. - //Might cause some AssemblyBase cycles, so keep number low. - handleRecovery(event->getEvent()); - break; - case DeviceHandlerIF::DEVICE_INTERPRETING_REPLY_FAILED: - case DeviceHandlerIF::DEVICE_READING_REPLY_FAILED: - case DeviceHandlerIF::DEVICE_UNREQUESTED_REPLY: - case DeviceHandlerIF::DEVICE_UNKNOWN_REPLY: //Some DH's generate generic reply-ids. - case DeviceHandlerIF::DEVICE_BUILDING_COMMAND_FAILED: - //These faults all mean that there were stupid replies from a device. - if (strangeReplyCount.incrementAndCheck()) { - handleRecovery(event->getEvent()); - } - break; - case DeviceHandlerIF::DEVICE_SENDING_COMMAND_FAILED: - case DeviceHandlerIF::DEVICE_REQUESTING_REPLY_FAILED: - //The two above should never be confirmed. - case DeviceHandlerIF::DEVICE_MISSED_REPLY: - result = sendConfirmationRequest(event); - if (result == HasReturnvaluesIF::RETURN_OK) { - break; - } - //else - if (missedReplyCount.incrementAndCheck()) { - handleRecovery(event->getEvent()); - } - break; - case StorageManagerIF::GET_DATA_FAILED: - case StorageManagerIF::STORE_DATA_FAILED: - //Rather strange bugs, occur in RAW mode only. Ignore. - break; - case DeviceHandlerIF::INVALID_DEVICE_COMMAND: - //Ignore, is bad configuration. We can't do anything in flight. - break; - case HasHealthIF::HEALTH_INFO: - case HasModesIF::MODE_INFO: - case HasModesIF::CHANGING_MODE: - //Do nothing, but mark as handled. - break; - //****Power***** - case PowerSwitchIF::SWITCH_WENT_OFF: - if(powerConfirmation != MessageQueueIF::NO_QUEUE) { - result = sendConfirmationRequest(event, powerConfirmation); - if (result == RETURN_OK) { - setFdirState(DEVICE_MIGHT_BE_OFF); - } - } - break; - case Fuse::FUSE_WENT_OFF: - //Not so good, because PCDU reacted. - case Fuse::POWER_ABOVE_HIGH_LIMIT: - //Better, because software detected over-current. - setFaulty(event->getEvent()); - break; - case Fuse::POWER_BELOW_LOW_LIMIT: - //Device might got stuck during boot, retry. - handleRecovery(event->getEvent()); - break; - //****Thermal***** - case ThermalComponentIF::COMPONENT_TEMP_LOW: - case ThermalComponentIF::COMPONENT_TEMP_HIGH: - case ThermalComponentIF::COMPONENT_TEMP_OOL_LOW: - case ThermalComponentIF::COMPONENT_TEMP_OOL_HIGH: - //Well, the device is not really faulty, but it is required to stay off as long as possible. - setFaulty(event->getEvent()); - break; - case ThermalComponentIF::TEMP_NOT_IN_OP_RANGE: - //Ignore, is information only. - break; - //*******Default monitoring variables. Are currently not used.***** -// case DeviceHandlerIF::MONITORING_LIMIT_EXCEEDED: -// setFaulty(event->getEvent()); -// break; -// case DeviceHandlerIF::MONITORING_AMBIGUOUS: -// break; - default: - //We don't know the event, someone else should handle it. - return RETURN_FAILED; - } - return RETURN_OK; + if (isFdirInActionOrAreWeFaulty(event)) { + return RETURN_OK; + } + ReturnValue_t result = RETURN_FAILED; + switch (event->getEvent()) { + case HasModesIF::MODE_TRANSITION_FAILED: + case HasModesIF::OBJECT_IN_INVALID_MODE: + // We'll try a recovery as long as defined in MAX_REBOOT. + // Might cause some AssemblyBase cycles, so keep number low. + handleRecovery(event->getEvent()); + break; + case DeviceHandlerIF::DEVICE_INTERPRETING_REPLY_FAILED: + case DeviceHandlerIF::DEVICE_READING_REPLY_FAILED: + case DeviceHandlerIF::DEVICE_UNREQUESTED_REPLY: + case DeviceHandlerIF::DEVICE_UNKNOWN_REPLY: // Some DH's generate generic reply-ids. + case DeviceHandlerIF::DEVICE_BUILDING_COMMAND_FAILED: + // These faults all mean that there were stupid replies from a device. + if (strangeReplyCount.incrementAndCheck()) { + handleRecovery(event->getEvent()); + } + break; + case DeviceHandlerIF::DEVICE_SENDING_COMMAND_FAILED: + case DeviceHandlerIF::DEVICE_REQUESTING_REPLY_FAILED: + // The two above should never be confirmed. + case DeviceHandlerIF::DEVICE_MISSED_REPLY: + result = sendConfirmationRequest(event); + if (result == HasReturnvaluesIF::RETURN_OK) { + break; + } + // else + if (missedReplyCount.incrementAndCheck()) { + handleRecovery(event->getEvent()); + } + break; + case StorageManagerIF::GET_DATA_FAILED: + case StorageManagerIF::STORE_DATA_FAILED: + // Rather strange bugs, occur in RAW mode only. Ignore. + break; + case DeviceHandlerIF::INVALID_DEVICE_COMMAND: + // Ignore, is bad configuration. We can't do anything in flight. + break; + case HasHealthIF::HEALTH_INFO: + case HasModesIF::MODE_INFO: + case HasModesIF::CHANGING_MODE: + // Do nothing, but mark as handled. + break; + //****Power***** + case PowerSwitchIF::SWITCH_WENT_OFF: + if (powerConfirmation != MessageQueueIF::NO_QUEUE) { + result = sendConfirmationRequest(event, powerConfirmation); + if (result == RETURN_OK) { + setFdirState(DEVICE_MIGHT_BE_OFF); + } + } + break; + case Fuse::FUSE_WENT_OFF: + // Not so good, because PCDU reacted. + case Fuse::POWER_ABOVE_HIGH_LIMIT: + // Better, because software detected over-current. + setFaulty(event->getEvent()); + break; + case Fuse::POWER_BELOW_LOW_LIMIT: + // Device might got stuck during boot, retry. + handleRecovery(event->getEvent()); + break; + //****Thermal***** + case ThermalComponentIF::COMPONENT_TEMP_LOW: + case ThermalComponentIF::COMPONENT_TEMP_HIGH: + case ThermalComponentIF::COMPONENT_TEMP_OOL_LOW: + case ThermalComponentIF::COMPONENT_TEMP_OOL_HIGH: + // Well, the device is not really faulty, but it is required to stay off as long as possible. + setFaulty(event->getEvent()); + break; + case ThermalComponentIF::TEMP_NOT_IN_OP_RANGE: + // Ignore, is information only. + break; + //*******Default monitoring variables. Are currently not used.***** + // case DeviceHandlerIF::MONITORING_LIMIT_EXCEEDED: + // setFaulty(event->getEvent()); + // break; + // case DeviceHandlerIF::MONITORING_AMBIGUOUS: + // break; + default: + // We don't know the event, someone else should handle it. + return RETURN_FAILED; + } + return RETURN_OK; } void DeviceHandlerFailureIsolation::eventConfirmed(EventMessage* event) { - switch (event->getEvent()) { - case DeviceHandlerIF::DEVICE_SENDING_COMMAND_FAILED: - case DeviceHandlerIF::DEVICE_REQUESTING_REPLY_FAILED: - case DeviceHandlerIF::DEVICE_MISSED_REPLY: - if (missedReplyCount.incrementAndCheck()) { - handleRecovery(event->getEvent()); - } - break; - case PowerSwitchIF::SWITCH_WENT_OFF: - //This means the switch went off only for one device. - handleRecovery(event->getEvent()); - break; - default: - break; - } + switch (event->getEvent()) { + case DeviceHandlerIF::DEVICE_SENDING_COMMAND_FAILED: + case DeviceHandlerIF::DEVICE_REQUESTING_REPLY_FAILED: + case DeviceHandlerIF::DEVICE_MISSED_REPLY: + if (missedReplyCount.incrementAndCheck()) { + handleRecovery(event->getEvent()); + } + break; + case PowerSwitchIF::SWITCH_WENT_OFF: + // This means the switch went off only for one device. + handleRecovery(event->getEvent()); + break; + default: + break; + } } void DeviceHandlerFailureIsolation::decrementFaultCounters() { - strangeReplyCount.checkForDecrement(); - missedReplyCount.checkForDecrement(); - recoveryCounter.checkForDecrement(); + strangeReplyCount.checkForDecrement(); + missedReplyCount.checkForDecrement(); + recoveryCounter.checkForDecrement(); } void DeviceHandlerFailureIsolation::handleRecovery(Event reason) { - clearFaultCounters(); - if (not recoveryCounter.incrementAndCheck()) { - startRecovery(reason); - } else { - setFaulty(reason); - } + clearFaultCounters(); + if (not recoveryCounter.incrementAndCheck()) { + startRecovery(reason); + } else { + setFaulty(reason); + } } void DeviceHandlerFailureIsolation::wasParentsFault(EventMessage* event) { - //We'll better ignore the SWITCH_WENT_OFF event and await a system-wide reset. - //This means, no fault message will come through until a MODE_ or - //HEALTH_INFO message comes through -> Is that ok? - //Same issue in TxFailureIsolation! -// if ((event->getEvent() == PowerSwitchIF::SWITCH_WENT_OFF) -// && (fdirState != RECOVERY_ONGOING)) { -// setFdirState(NONE); -// } + // We'll better ignore the SWITCH_WENT_OFF event and await a system-wide reset. + // This means, no fault message will come through until a MODE_ or + // HEALTH_INFO message comes through -> Is that ok? + // Same issue in TxFailureIsolation! + // if ((event->getEvent() == PowerSwitchIF::SWITCH_WENT_OFF) + // && (fdirState != RECOVERY_ONGOING)) { + // setFdirState(NONE); + // } } void DeviceHandlerFailureIsolation::clearFaultCounters() { - strangeReplyCount.clear(); - missedReplyCount.clear(); + strangeReplyCount.clear(); + missedReplyCount.clear(); } ReturnValue_t DeviceHandlerFailureIsolation::initialize() { - ReturnValue_t result = FailureIsolationBase::initialize(); - if (result != HasReturnvaluesIF::RETURN_OK) { + ReturnValue_t result = FailureIsolationBase::initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "DeviceHandlerFailureIsolation::initialize: Could not" - " initialize FailureIsolationBase." << std::endl; + sif::error << "DeviceHandlerFailureIsolation::initialize: Could not" + " initialize FailureIsolationBase." + << std::endl; #endif - return result; - } - ConfirmsFailuresIF* power = ObjectManager::instance()->get( - powerConfirmationId); - if (power != nullptr) { - powerConfirmation = power->getEventReceptionQueue(); - } + return result; + } + ConfirmsFailuresIF* power = + ObjectManager::instance()->get(powerConfirmationId); + if (power != nullptr) { + powerConfirmation = power->getEventReceptionQueue(); + } - return RETURN_OK; + return RETURN_OK; } void DeviceHandlerFailureIsolation::setFdirState(FDIRState state) { - FailureIsolationBase::throwFdirEvent(FDIR_CHANGED_STATE, state, fdirState); - fdirState = state; + FailureIsolationBase::throwFdirEvent(FDIR_CHANGED_STATE, state, fdirState); + fdirState = state; } void DeviceHandlerFailureIsolation::triggerEvent(Event event, uint32_t parameter1, - uint32_t parameter2) { - //Do not throw error events if fdirState != none. - //This will still forward MODE and HEALTH INFO events in any case. - if (fdirState == NONE || event::getSeverity(event) == severity::INFO) { - FailureIsolationBase::triggerEvent(event, parameter1, parameter2); - } + uint32_t parameter2) { + // Do not throw error events if fdirState != none. + // This will still forward MODE and HEALTH INFO events in any case. + if (fdirState == NONE || event::getSeverity(event) == severity::INFO) { + FailureIsolationBase::triggerEvent(event, parameter1, parameter2); + } } -bool DeviceHandlerFailureIsolation::isFdirActionInProgress() { - return (fdirState != NONE); -} +bool DeviceHandlerFailureIsolation::isFdirActionInProgress() { return (fdirState != NONE); } void DeviceHandlerFailureIsolation::startRecovery(Event reason) { - throwFdirEvent(FDIR_STARTS_RECOVERY, event::getEventId(reason)); - setOwnerHealth(HasHealthIF::NEEDS_RECOVERY); - setFdirState(RECOVERY_ONGOING); + throwFdirEvent(FDIR_STARTS_RECOVERY, event::getEventId(reason)); + setOwnerHealth(HasHealthIF::NEEDS_RECOVERY); + setFdirState(RECOVERY_ONGOING); } -ReturnValue_t DeviceHandlerFailureIsolation::getParameter(uint8_t domainId, - uint8_t uniqueId, ParameterWrapper* parameterWrapper, - const ParameterWrapper* newValues, uint16_t startAtIndex) { - ReturnValue_t result = strangeReplyCount.getParameter(domainId, uniqueId, - parameterWrapper, newValues, startAtIndex); - if (result != INVALID_DOMAIN_ID) { - return result; - } - result = missedReplyCount.getParameter(domainId, uniqueId, parameterWrapper, newValues, - startAtIndex); - if (result != INVALID_DOMAIN_ID) { - return result; - } - result = recoveryCounter.getParameter(domainId, uniqueId, parameterWrapper, newValues, - startAtIndex); - if (result != INVALID_DOMAIN_ID) { - return result; - } - return INVALID_DOMAIN_ID; +ReturnValue_t DeviceHandlerFailureIsolation::getParameter(uint8_t domainId, uint8_t uniqueId, + ParameterWrapper* parameterWrapper, + const ParameterWrapper* newValues, + uint16_t startAtIndex) { + ReturnValue_t result = + strangeReplyCount.getParameter(domainId, uniqueId, parameterWrapper, newValues, startAtIndex); + if (result != INVALID_DOMAIN_ID) { + return result; + } + result = + missedReplyCount.getParameter(domainId, uniqueId, parameterWrapper, newValues, startAtIndex); + if (result != INVALID_DOMAIN_ID) { + return result; + } + result = + recoveryCounter.getParameter(domainId, uniqueId, parameterWrapper, newValues, startAtIndex); + if (result != INVALID_DOMAIN_ID) { + return result; + } + return INVALID_DOMAIN_ID; } void DeviceHandlerFailureIsolation::setFaulty(Event reason) { - throwFdirEvent(FDIR_TURNS_OFF_DEVICE, event::getEventId(reason)); - setOwnerHealth(HasHealthIF::FAULTY); - setFdirState(AWAIT_SHUTDOWN); + throwFdirEvent(FDIR_TURNS_OFF_DEVICE, event::getEventId(reason)); + setOwnerHealth(HasHealthIF::FAULTY); + setFdirState(AWAIT_SHUTDOWN); } -bool DeviceHandlerFailureIsolation::isFdirInActionOrAreWeFaulty( - EventMessage* event) { - if (fdirState != NONE) { - //Only wait for those events, ignore all others. - if (event->getParameter1() == HasHealthIF::HEALTHY - && event->getEvent() == HasHealthIF::HEALTH_INFO) { - setFdirState(NONE); - } - if (event->getEvent() == HasModesIF::MODE_INFO - && fdirState != RECOVERY_ONGOING) { - setFdirState(NONE); - } - return true; - } +bool DeviceHandlerFailureIsolation::isFdirInActionOrAreWeFaulty(EventMessage* event) { + if (fdirState != NONE) { + // Only wait for those events, ignore all others. + if (event->getParameter1() == HasHealthIF::HEALTHY && + event->getEvent() == HasHealthIF::HEALTH_INFO) { + setFdirState(NONE); + } + if (event->getEvent() == HasModesIF::MODE_INFO && fdirState != RECOVERY_ONGOING) { + setFdirState(NONE); + } + return true; + } - if (owner == nullptr) { - // Configuration error. + if (owner == nullptr) { + // Configuration error. #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "DeviceHandlerFailureIsolation::" - << "isFdirInActionOrAreWeFaulty: Owner not set!" << std::endl; + sif::error << "DeviceHandlerFailureIsolation::" + << "isFdirInActionOrAreWeFaulty: Owner not set!" << std::endl; #endif - return false; - } + return false; + } - if (owner->getHealth() == HasHealthIF::FAULTY - || owner->getHealth() == HasHealthIF::PERMANENT_FAULTY) { - //Ignore all events in case device is already faulty. - return true; - } - return false; + if (owner->getHealth() == HasHealthIF::FAULTY || + owner->getHealth() == HasHealthIF::PERMANENT_FAULTY) { + // Ignore all events in case device is already faulty. + return true; + } + return false; } diff --git a/src/fsfw/devicehandlers/DeviceHandlerFailureIsolation.h b/src/fsfw/devicehandlers/DeviceHandlerFailureIsolation.h index 016b18b3..6007ceb8 100644 --- a/src/fsfw/devicehandlers/DeviceHandlerFailureIsolation.h +++ b/src/fsfw/devicehandlers/DeviceHandlerFailureIsolation.h @@ -1,57 +1,56 @@ #ifndef FSFW_DEVICEHANDLERS_DEVICEHANDLERFAILUREISOLATION_H_ #define FSFW_DEVICEHANDLERS_DEVICEHANDLERFAILUREISOLATION_H_ -#include "../fdir/FaultCounter.h" #include "../fdir/FailureIsolationBase.h" +#include "../fdir/FaultCounter.h" -namespace Factory{ +namespace Factory { void setStaticFrameworkObjectIds(); } -class DeviceHandlerFailureIsolation: public FailureIsolationBase { - friend void (Factory::setStaticFrameworkObjectIds)(); - friend class Heater; -public: - DeviceHandlerFailureIsolation(object_id_t owner, object_id_t parent); - ~DeviceHandlerFailureIsolation(); - ReturnValue_t initialize(); - void triggerEvent(Event event, uint32_t parameter1 = 0, - uint32_t parameter2 = 0);bool isFdirActionInProgress(); - virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, - ParameterWrapper *parameterWrapper, const ParameterWrapper *newValues, - uint16_t startAtIndex); +class DeviceHandlerFailureIsolation : public FailureIsolationBase { + friend void(Factory::setStaticFrameworkObjectIds)(); + friend class Heater; -protected: - FaultCounter strangeReplyCount; - FaultCounter missedReplyCount; - FaultCounter recoveryCounter; + public: + DeviceHandlerFailureIsolation(object_id_t owner, object_id_t parent); + ~DeviceHandlerFailureIsolation(); + ReturnValue_t initialize(); + void triggerEvent(Event event, uint32_t parameter1 = 0, uint32_t parameter2 = 0); + bool isFdirActionInProgress(); + virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, + ParameterWrapper* parameterWrapper, + const ParameterWrapper* newValues, uint16_t startAtIndex); - enum FDIRState { - NONE, RECOVERY_ONGOING, DEVICE_MIGHT_BE_OFF, AWAIT_SHUTDOWN - }; - FDIRState fdirState; + protected: + FaultCounter strangeReplyCount; + FaultCounter missedReplyCount; + FaultCounter recoveryCounter; - MessageQueueId_t powerConfirmation = MessageQueueIF::NO_QUEUE; - static object_id_t powerConfirmationId; + enum FDIRState { NONE, RECOVERY_ONGOING, DEVICE_MIGHT_BE_OFF, AWAIT_SHUTDOWN }; + FDIRState fdirState; - static const uint32_t DEFAULT_MAX_REBOOT = 1; - static const uint32_t DEFAULT_REBOOT_TIME_MS = 180000; - static const uint32_t DEFAULT_MAX_STRANGE_REPLIES = 10; - static const uint32_t DEFAULT_STRANGE_REPLIES_TIME_MS = 10000; - static const uint32_t DEFAULT_MAX_MISSED_REPLY_COUNT = 5; - static const uint32_t DEFAULT_MISSED_REPLY_TIME_MS = 10000; + MessageQueueId_t powerConfirmation = MessageQueueIF::NO_QUEUE; + static object_id_t powerConfirmationId; - virtual ReturnValue_t eventReceived(EventMessage* event); - virtual void eventConfirmed(EventMessage* event); - void wasParentsFault(EventMessage* event); - void decrementFaultCounters(); - void handleRecovery(Event reason); - virtual void clearFaultCounters(); - void setFdirState(FDIRState state); - void startRecovery(Event reason); - void setFaulty(Event reason); + static const uint32_t DEFAULT_MAX_REBOOT = 1; + static const uint32_t DEFAULT_REBOOT_TIME_MS = 180000; + static const uint32_t DEFAULT_MAX_STRANGE_REPLIES = 10; + static const uint32_t DEFAULT_STRANGE_REPLIES_TIME_MS = 10000; + static const uint32_t DEFAULT_MAX_MISSED_REPLY_COUNT = 5; + static const uint32_t DEFAULT_MISSED_REPLY_TIME_MS = 10000; - bool isFdirInActionOrAreWeFaulty(EventMessage* event); + virtual ReturnValue_t eventReceived(EventMessage* event); + virtual void eventConfirmed(EventMessage* event); + void wasParentsFault(EventMessage* event); + void decrementFaultCounters(); + void handleRecovery(Event reason); + virtual void clearFaultCounters(); + void setFdirState(FDIRState state); + void startRecovery(Event reason); + void setFaulty(Event reason); + + bool isFdirInActionOrAreWeFaulty(EventMessage* event); }; #endif /* FSFW_DEVICEHANDLERS_DEVICEHANDLERFAILUREISOLATION_H_ */ diff --git a/src/fsfw/devicehandlers/DeviceHandlerIF.h b/src/fsfw/devicehandlers/DeviceHandlerIF.h index 1fc57c42..1fc63d3b 100644 --- a/src/fsfw/devicehandlers/DeviceHandlerIF.h +++ b/src/fsfw/devicehandlers/DeviceHandlerIF.h @@ -1,13 +1,12 @@ #ifndef FSFW_DEVICEHANDLERS_DEVICEHANDLERIF_H_ #define FSFW_DEVICEHANDLERS_DEVICEHANDLERIF_H_ -#include "DeviceHandlerMessage.h" - -#include "../datapoollocal/localPoolDefinitions.h" #include "../action/HasActionsIF.h" +#include "../datapoollocal/localPoolDefinitions.h" #include "../events/Event.h" -#include "../modes/HasModesIF.h" #include "../ipc/MessageQueueSenderIF.h" +#include "../modes/HasModesIF.h" +#include "DeviceHandlerMessage.h" /** * This is used to uniquely identify commands that are sent to a device @@ -21,159 +20,163 @@ using DeviceCommandId_t = uint32_t; * */ class DeviceHandlerIF { -public: - static const DeviceCommandId_t RAW_COMMAND_ID = -1; - static const DeviceCommandId_t NO_COMMAND_ID = -2; + public: + static const DeviceCommandId_t RAW_COMMAND_ID = -1; + 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; + 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_thermal_state_t = int8_t; + using dh_heater_request_t = uint8_t; + using dh_thermal_state_t = int8_t; - /** - * @brief This is the mode the device handler is in. - * - * @details The mode of the device handler must not be confused with the mode the device is in. - * The mode of the device itself is transparent to the user but related to the mode of the handler. - * MODE_ON and MODE_OFF are included in hasModesIF.h - */ + /** + * @brief This is the mode the device handler is in. + * + * @details The mode of the device handler must not be confused with the mode the device is in. + * The mode of the device itself is transparent to the user but related to the mode of the + * handler. MODE_ON and MODE_OFF are included in hasModesIF.h + */ - // MODE_ON = 0, //!< 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 interpreted - // MODE_OFF = 1, //!< The device is powered off. The only command accepted in this mode is a mode change to on. - //! The device is powered on and the device handler periodically sends - //! commands. The commands to be sent are selected by the handler - //! according to the submode. - static const Mode_t MODE_NORMAL = 2; - //! The device is powered on and ready to perform operations. In this mode, - //! raw commands can be sent. The device handler will send all replies - //! received from the command back to the commanding object. - static const Mode_t MODE_RAW = 3; - //! The device is shut down but the switch could not be turned off, so the - //! 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. - 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; + // MODE_ON = 0, //!< 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 interpreted MODE_OFF = 1, //!< The device is powered off. The only command accepted in this + // mode is a mode change to on. + //! The device is powered on and the device handler periodically sends + //! commands. The commands to be sent are selected by the handler + //! according to the submode. + static const Mode_t MODE_NORMAL = 2; + //! The device is powered on and ready to perform operations. In this mode, + //! raw commands can be sent. The device handler will send all replies + //! received from the command back to the commanding object. + static const Mode_t MODE_RAW = 3; + //! The device is shut down but the switch could not be turned off, so the + //! 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. + 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 Event DEVICE_BUILDING_COMMAND_FAILED = MAKE_EVENT(0, severity::LOW); - static const Event DEVICE_SENDING_COMMAND_FAILED = MAKE_EVENT(1, severity::LOW); - static const Event DEVICE_REQUESTING_REPLY_FAILED = MAKE_EVENT(2, severity::LOW); - static const Event DEVICE_READING_REPLY_FAILED = MAKE_EVENT(3, severity::LOW); - static const Event DEVICE_INTERPRETING_REPLY_FAILED = MAKE_EVENT(4, severity::LOW); - static const Event DEVICE_MISSED_REPLY = MAKE_EVENT(5, severity::LOW); - static const Event DEVICE_UNKNOWN_REPLY = MAKE_EVENT(6, severity::LOW); - static const Event DEVICE_UNREQUESTED_REPLY = MAKE_EVENT(7, severity::LOW); - //! [EXPORT] : [COMMENT] Indicates a SW bug in child class. - 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_AMBIGUOUS = MAKE_EVENT(10, severity::HIGH); + 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_SENDING_COMMAND_FAILED = MAKE_EVENT(1, severity::LOW); + static const Event DEVICE_REQUESTING_REPLY_FAILED = MAKE_EVENT(2, severity::LOW); + static const Event DEVICE_READING_REPLY_FAILED = MAKE_EVENT(3, severity::LOW); + static const Event DEVICE_INTERPRETING_REPLY_FAILED = MAKE_EVENT(4, severity::LOW); + static const Event DEVICE_MISSED_REPLY = MAKE_EVENT(5, severity::LOW); + static const Event DEVICE_UNKNOWN_REPLY = MAKE_EVENT(6, severity::LOW); + static const Event DEVICE_UNREQUESTED_REPLY = MAKE_EVENT(7, severity::LOW); + //! [EXPORT] : [COMMENT] Indicates a SW bug in child class. + 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_AMBIGUOUS = MAKE_EVENT(10, severity::HIGH); - static const uint8_t INTERFACE_ID = CLASS_ID::DEVICE_HANDLER_IF; + static const uint8_t INTERFACE_ID = CLASS_ID::DEVICE_HANDLER_IF; - // Standard codes used when building commands. - static const ReturnValue_t NO_COMMAND_DATA = MAKE_RETURN_CODE(0xA0); //!< If no command data was given when expected. - static const ReturnValue_t COMMAND_NOT_SUPPORTED = MAKE_RETURN_CODE(0xA1); //!< Command ID not in commandMap. Checked in DHB - static const ReturnValue_t COMMAND_ALREADY_SENT = MAKE_RETURN_CODE(0xA2); //!< Command was already executed. Checked in DHB - static const ReturnValue_t COMMAND_WAS_NOT_SENT = MAKE_RETURN_CODE(0xA3); - static const ReturnValue_t CANT_SWITCH_ADDRESS = MAKE_RETURN_CODE(0xA4); - static const ReturnValue_t WRONG_MODE_FOR_COMMAND = MAKE_RETURN_CODE(0xA5); - static const ReturnValue_t TIMEOUT = MAKE_RETURN_CODE(0xA6); - static const ReturnValue_t BUSY = MAKE_RETURN_CODE(0xA7); - //!< Used to indicate that this is a command-only command. - static const ReturnValue_t NO_REPLY_EXPECTED = MAKE_RETURN_CODE(0xA8); - static const ReturnValue_t NON_OP_TEMPERATURE = MAKE_RETURN_CODE(0xA9); - static const ReturnValue_t COMMAND_NOT_IMPLEMENTED = MAKE_RETURN_CODE(0xAA); + // Standard codes used when building commands. + static const ReturnValue_t NO_COMMAND_DATA = + MAKE_RETURN_CODE(0xA0); //!< If no command data was given when expected. + static const ReturnValue_t COMMAND_NOT_SUPPORTED = + MAKE_RETURN_CODE(0xA1); //!< Command ID not in commandMap. Checked in DHB + static const ReturnValue_t COMMAND_ALREADY_SENT = + MAKE_RETURN_CODE(0xA2); //!< Command was already executed. Checked in DHB + static const ReturnValue_t COMMAND_WAS_NOT_SENT = MAKE_RETURN_CODE(0xA3); + static const ReturnValue_t CANT_SWITCH_ADDRESS = MAKE_RETURN_CODE(0xA4); + static const ReturnValue_t WRONG_MODE_FOR_COMMAND = MAKE_RETURN_CODE(0xA5); + static const ReturnValue_t TIMEOUT = MAKE_RETURN_CODE(0xA6); + static const ReturnValue_t BUSY = MAKE_RETURN_CODE(0xA7); + //!< Used to indicate that this is a command-only command. + static const ReturnValue_t NO_REPLY_EXPECTED = MAKE_RETURN_CODE(0xA8); + static const ReturnValue_t NON_OP_TEMPERATURE = MAKE_RETURN_CODE(0xA9); + static const ReturnValue_t COMMAND_NOT_IMPLEMENTED = MAKE_RETURN_CODE(0xAA); - // Standard codes used in scanForReply - static const ReturnValue_t CHECKSUM_ERROR = MAKE_RETURN_CODE(0xB0); - static const ReturnValue_t LENGTH_MISSMATCH = MAKE_RETURN_CODE(0xB1); - static const ReturnValue_t INVALID_DATA = MAKE_RETURN_CODE(0xB2); - static const ReturnValue_t PROTOCOL_ERROR = MAKE_RETURN_CODE(0xB3); + // Standard codes used in scanForReply + static const ReturnValue_t CHECKSUM_ERROR = MAKE_RETURN_CODE(0xB0); + static const ReturnValue_t LENGTH_MISSMATCH = MAKE_RETURN_CODE(0xB1); + static const ReturnValue_t INVALID_DATA = MAKE_RETURN_CODE(0xB2); + static const ReturnValue_t PROTOCOL_ERROR = MAKE_RETURN_CODE(0xB3); - // Standard codes used in interpretDeviceReply - static const ReturnValue_t DEVICE_DID_NOT_EXECUTE = MAKE_RETURN_CODE(0xC0); //the device reported, that it did not execute the command - static const ReturnValue_t DEVICE_REPORTED_ERROR = MAKE_RETURN_CODE(0xC1); - static const ReturnValue_t UNKNOWN_DEVICE_REPLY = MAKE_RETURN_CODE(0xC2); //the deviceCommandId reported by scanforReply is unknown - static const ReturnValue_t DEVICE_REPLY_INVALID = MAKE_RETURN_CODE(0xC3); //syntax etc is correct but still not ok, eg parameters where none are expected + // Standard codes used in interpretDeviceReply + static const ReturnValue_t DEVICE_DID_NOT_EXECUTE = + MAKE_RETURN_CODE(0xC0); // the device reported, that it did not execute the command + static const ReturnValue_t DEVICE_REPORTED_ERROR = MAKE_RETURN_CODE(0xC1); + static const ReturnValue_t UNKNOWN_DEVICE_REPLY = + MAKE_RETURN_CODE(0xC2); // the deviceCommandId reported by scanforReply is unknown + static const ReturnValue_t DEVICE_REPLY_INVALID = MAKE_RETURN_CODE( + 0xC3); // syntax etc is correct but still not ok, eg parameters where none are expected - // Standard codes used in buildCommandFromCommand - static const ReturnValue_t INVALID_COMMAND_PARAMETER = MAKE_RETURN_CODE(0xD0); - static const ReturnValue_t INVALID_NUMBER_OR_LENGTH_OF_PARAMETERS = MAKE_RETURN_CODE(0xD1); + // Standard codes used in buildCommandFromCommand + static const ReturnValue_t INVALID_COMMAND_PARAMETER = MAKE_RETURN_CODE(0xD0); + static const ReturnValue_t INVALID_NUMBER_OR_LENGTH_OF_PARAMETERS = MAKE_RETURN_CODE(0xD1); - /** - * Communication action that will be executed. - * - * This is used by the child class to tell the base class what to do. - */ - enum CommunicationAction: uint8_t { - PERFORM_OPERATION, - SEND_WRITE,//!< Send write - GET_WRITE, //!< Get write - SEND_READ, //!< Send read - GET_READ, //!< Get read - NOTHING //!< Do nothing. - }; + /** + * Communication action that will be executed. + * + * This is used by the child class to tell the base class what to do. + */ + enum CommunicationAction : uint8_t { + PERFORM_OPERATION, + SEND_WRITE, //!< Send write + GET_WRITE, //!< Get write + SEND_READ, //!< Send read + GET_READ, //!< Get read + NOTHING //!< Do nothing. + }; - static constexpr uint32_t DEFAULT_THERMAL_SET_ID = sid_t::INVALID_SET_ID - 1; + static constexpr uint32_t DEFAULT_THERMAL_SET_ID = sid_t::INVALID_SET_ID - 1; - static constexpr lp_id_t DEFAULT_THERMAL_STATE_POOL_ID = - localpool::INVALID_LPID - 2; - static constexpr lp_id_t DEFAULT_THERMAL_HEATING_REQUEST_POOL_ID = - localpool::INVALID_LPID - 1; + static constexpr lp_id_t DEFAULT_THERMAL_STATE_POOL_ID = localpool::INVALID_LPID - 2; + static constexpr lp_id_t DEFAULT_THERMAL_HEATING_REQUEST_POOL_ID = localpool::INVALID_LPID - 1; + /** + * Default Destructor + */ + virtual ~DeviceHandlerIF() {} - /** - * Default Destructor - */ - virtual ~DeviceHandlerIF() {} - - /** - * This MessageQueue is used to command the device handler. - * @return the id of the MessageQueue - */ - virtual MessageQueueId_t getCommandQueue() const = 0; - + /** + * This MessageQueue is used to command the device handler. + * @return the id of the MessageQueue + */ + virtual MessageQueueId_t getCommandQueue() const = 0; }; #endif /* FSFW_DEVICEHANDLERS_DEVICEHANDLERIF_H_ */ diff --git a/src/fsfw/devicehandlers/DeviceHandlerMessage.cpp b/src/fsfw/devicehandlers/DeviceHandlerMessage.cpp index 48277c9a..6b38b2ff 100644 --- a/src/fsfw/devicehandlers/DeviceHandlerMessage.cpp +++ b/src/fsfw/devicehandlers/DeviceHandlerMessage.cpp @@ -1,88 +1,83 @@ #include "fsfw/devicehandlers/DeviceHandlerMessage.h" + #include "fsfw/objectmanager/ObjectManager.h" -store_address_t DeviceHandlerMessage::getStoreAddress( - const CommandMessage* message) { - return store_address_t(message->getParameter2()); +store_address_t DeviceHandlerMessage::getStoreAddress(const CommandMessage* message) { + return store_address_t(message->getParameter2()); } -uint32_t DeviceHandlerMessage::getDeviceCommandId( - const CommandMessage* message) { - return message->getParameter(); +uint32_t DeviceHandlerMessage::getDeviceCommandId(const CommandMessage* message) { + return message->getParameter(); } -object_id_t DeviceHandlerMessage::getIoBoardObjectId( - const CommandMessage* message) { - return message->getParameter(); +object_id_t DeviceHandlerMessage::getIoBoardObjectId(const CommandMessage* message) { + return message->getParameter(); } -uint8_t DeviceHandlerMessage::getWiretappingMode( - const CommandMessage* message) { - return message->getParameter(); +uint8_t DeviceHandlerMessage::getWiretappingMode(const CommandMessage* message) { + return message->getParameter(); } -void DeviceHandlerMessage::setDeviceHandlerRawCommandMessage( - CommandMessage* message, store_address_t rawPacketStoreId) { - message->setCommand(CMD_RAW); - message->setParameter2(rawPacketStoreId.raw); +void DeviceHandlerMessage::setDeviceHandlerRawCommandMessage(CommandMessage* message, + store_address_t rawPacketStoreId) { + message->setCommand(CMD_RAW); + message->setParameter2(rawPacketStoreId.raw); } -void DeviceHandlerMessage::setDeviceHandlerWiretappingMessage( - CommandMessage* message, uint8_t wiretappingMode) { - message->setCommand(CMD_WIRETAPPING); - message->setParameter(wiretappingMode); +void DeviceHandlerMessage::setDeviceHandlerWiretappingMessage(CommandMessage* message, + uint8_t wiretappingMode) { + message->setCommand(CMD_WIRETAPPING); + message->setParameter(wiretappingMode); } -void DeviceHandlerMessage::setDeviceHandlerSwitchIoBoardMessage( - CommandMessage* message, uint32_t ioBoardIdentifier) { - message->setCommand(CMD_SWITCH_ADDRESS); - message->setParameter(ioBoardIdentifier); +void DeviceHandlerMessage::setDeviceHandlerSwitchIoBoardMessage(CommandMessage* message, + uint32_t ioBoardIdentifier) { + message->setCommand(CMD_SWITCH_ADDRESS); + message->setParameter(ioBoardIdentifier); } -object_id_t DeviceHandlerMessage::getDeviceObjectId( - const CommandMessage* message) { - return message->getParameter(); +object_id_t DeviceHandlerMessage::getDeviceObjectId(const CommandMessage* message) { + return message->getParameter(); } -void DeviceHandlerMessage::setDeviceHandlerRawReplyMessage( - CommandMessage* message, object_id_t deviceObjectid, - store_address_t rawPacketStoreId, bool isCommand) { - if (isCommand) { - message->setCommand(REPLY_RAW_COMMAND); - } else { - message->setCommand(REPLY_RAW_REPLY); - } - message->setParameter(deviceObjectid); - message->setParameter2(rawPacketStoreId.raw); +void DeviceHandlerMessage::setDeviceHandlerRawReplyMessage(CommandMessage* message, + object_id_t deviceObjectid, + store_address_t rawPacketStoreId, + bool isCommand) { + if (isCommand) { + message->setCommand(REPLY_RAW_COMMAND); + } else { + message->setCommand(REPLY_RAW_REPLY); + } + message->setParameter(deviceObjectid); + message->setParameter2(rawPacketStoreId.raw); } void DeviceHandlerMessage::setDeviceHandlerDirectCommandReply( - CommandMessage* message, object_id_t deviceObjectid, - store_address_t commandParametersStoreId) { - message->setCommand(REPLY_DIRECT_COMMAND_DATA); - message->setParameter(deviceObjectid); - message->setParameter2(commandParametersStoreId.raw); + CommandMessage* message, object_id_t deviceObjectid, store_address_t commandParametersStoreId) { + message->setCommand(REPLY_DIRECT_COMMAND_DATA); + message->setParameter(deviceObjectid); + message->setParameter2(commandParametersStoreId.raw); } void DeviceHandlerMessage::clear(CommandMessage* message) { - switch (message->getCommand()) { - case CMD_RAW: - case REPLY_RAW_COMMAND: - case REPLY_RAW_REPLY: - case REPLY_DIRECT_COMMAND_DATA: { - StorageManagerIF *ipcStore = ObjectManager::instance()->get( - objects::IPC_STORE); - if (ipcStore != nullptr) { - ipcStore->deleteData(getStoreAddress(message)); - } - } - /* NO BREAK falls through*/ - case CMD_SWITCH_ADDRESS: - case CMD_WIRETAPPING: - message->setCommand(CommandMessage::CMD_NONE); - message->setParameter(0); - message->setParameter2(0); - break; - } - + switch (message->getCommand()) { + case CMD_RAW: + case REPLY_RAW_COMMAND: + case REPLY_RAW_REPLY: + case REPLY_DIRECT_COMMAND_DATA: { + StorageManagerIF* ipcStore = + ObjectManager::instance()->get(objects::IPC_STORE); + if (ipcStore != nullptr) { + ipcStore->deleteData(getStoreAddress(message)); + } + } + /* NO BREAK falls through*/ + case CMD_SWITCH_ADDRESS: + case CMD_WIRETAPPING: + message->setCommand(CommandMessage::CMD_NONE); + message->setParameter(0); + message->setParameter2(0); + break; + } } diff --git a/src/fsfw/devicehandlers/DeviceHandlerMessage.h b/src/fsfw/devicehandlers/DeviceHandlerMessage.h index e5da01c8..84130654 100644 --- a/src/fsfw/devicehandlers/DeviceHandlerMessage.h +++ b/src/fsfw/devicehandlers/DeviceHandlerMessage.h @@ -8,66 +8,63 @@ // SHOULDDO: rework the static constructors to name the type of command // they are building, maybe even hide setting the commandID. - /** * @brief The DeviceHandlerMessage is used to send commands to classes * implementing DeviceHandlerIF */ class DeviceHandlerMessage { -public: - /** - * Instantiation forbidden. Instead, use static functions to operate - * on messages. - */ - DeviceHandlerMessage() = delete; - virtual ~DeviceHandlerMessage() {} + public: + /** + * Instantiation forbidden. Instead, use static functions to operate + * on messages. + */ + DeviceHandlerMessage() = delete; + virtual ~DeviceHandlerMessage() {} - /** - * These are the commands that can be sent to a DeviceHandlerBase - */ - static const uint8_t MESSAGE_ID = messagetypes::DEVICE_HANDLER_COMMAND; - //! Sends a raw command, setParameter is a storeId containing the - //! raw packet to send - static const Command_t CMD_RAW = MAKE_COMMAND_ID(1); - //! Requests a IO-Board switch, setParameter() is the IO-Board identifier - static const Command_t CMD_SWITCH_ADDRESS = MAKE_COMMAND_ID(3); - //! (De)Activates the monitoring of all raw traffic in DeviceHandlers, - //! setParameter is 0 to deactivate, 1 to activate - static const Command_t CMD_WIRETAPPING = MAKE_COMMAND_ID(4); + /** + * These are the commands that can be sent to a DeviceHandlerBase + */ + static const uint8_t MESSAGE_ID = messagetypes::DEVICE_HANDLER_COMMAND; + //! Sends a raw command, setParameter is a storeId containing the + //! raw packet to send + static const Command_t CMD_RAW = MAKE_COMMAND_ID(1); + //! Requests a IO-Board switch, setParameter() is the IO-Board identifier + static const Command_t CMD_SWITCH_ADDRESS = MAKE_COMMAND_ID(3); + //! (De)Activates the monitoring of all raw traffic in DeviceHandlers, + //! setParameter is 0 to deactivate, 1 to activate + static const Command_t CMD_WIRETAPPING = MAKE_COMMAND_ID(4); - //! Signals that a direct command was sent - static const Command_t REPLY_DIRECT_COMMAND_SENT = ActionMessage::STEP_SUCCESS; - //! Contains a raw command sent to the Device - static const Command_t REPLY_RAW_COMMAND = MAKE_COMMAND_ID(0x11); - //! Contains a raw reply from the Device, getParameter() is the ObjcetId - //! of the sender, getParameter2() is a ::store_id_t containing the - //! raw packet received - static const Command_t REPLY_RAW_REPLY = MAKE_COMMAND_ID(0x12); - static const Command_t REPLY_DIRECT_COMMAND_DATA = ActionMessage::DATA_REPLY; + //! Signals that a direct command was sent + static const Command_t REPLY_DIRECT_COMMAND_SENT = ActionMessage::STEP_SUCCESS; + //! Contains a raw command sent to the Device + static const Command_t REPLY_RAW_COMMAND = MAKE_COMMAND_ID(0x11); + //! Contains a raw reply from the Device, getParameter() is the ObjcetId + //! of the sender, getParameter2() is a ::store_id_t containing the + //! raw packet received + static const Command_t REPLY_RAW_REPLY = MAKE_COMMAND_ID(0x12); + static const Command_t REPLY_DIRECT_COMMAND_DATA = ActionMessage::DATA_REPLY; - static store_address_t getStoreAddress(const CommandMessage* message); - static uint32_t getDeviceCommandId(const CommandMessage* message); - static object_id_t getDeviceObjectId(const CommandMessage *message); - static object_id_t getIoBoardObjectId(const CommandMessage* message); - static uint8_t getWiretappingMode(const CommandMessage* message); + static store_address_t getStoreAddress(const CommandMessage* message); + static uint32_t getDeviceCommandId(const CommandMessage* message); + static object_id_t getDeviceObjectId(const CommandMessage* message); + static object_id_t getIoBoardObjectId(const CommandMessage* message); + static uint8_t getWiretappingMode(const CommandMessage* message); - static void setDeviceHandlerDirectCommandReply(CommandMessage* message, - object_id_t deviceObjectid, - store_address_t commandParametersStoreId); + static void setDeviceHandlerDirectCommandReply(CommandMessage* message, + object_id_t deviceObjectid, + store_address_t commandParametersStoreId); - static void setDeviceHandlerRawCommandMessage(CommandMessage* message, - store_address_t rawPacketStoreId); + static void setDeviceHandlerRawCommandMessage(CommandMessage* message, + store_address_t rawPacketStoreId); - static void setDeviceHandlerRawReplyMessage(CommandMessage* message, - object_id_t deviceObjectid, store_address_t rawPacketStoreId, - bool isCommand); + static void setDeviceHandlerRawReplyMessage(CommandMessage* message, object_id_t deviceObjectid, + store_address_t rawPacketStoreId, bool isCommand); - static void setDeviceHandlerWiretappingMessage(CommandMessage* message, - uint8_t wiretappingMode); - static void setDeviceHandlerSwitchIoBoardMessage(CommandMessage* message, - object_id_t ioBoardIdentifier); + static void setDeviceHandlerWiretappingMessage(CommandMessage* message, uint8_t wiretappingMode); + static void setDeviceHandlerSwitchIoBoardMessage(CommandMessage* message, + object_id_t ioBoardIdentifier); - static void clear(CommandMessage* message); + static void clear(CommandMessage* message); }; #endif /* FSFW_DEVICEHANDLERS_DEVICEHANDLERMESSAGE_H_ */ diff --git a/src/fsfw/devicehandlers/DeviceHandlerThermalSet.h b/src/fsfw/devicehandlers/DeviceHandlerThermalSet.h index 239012e2..944d7c0f 100644 --- a/src/fsfw/devicehandlers/DeviceHandlerThermalSet.h +++ b/src/fsfw/devicehandlers/DeviceHandlerThermalSet.h @@ -1,44 +1,33 @@ #ifndef FSFW_DEVICEHANDLERS_DEVICEHANDLERTHERMALSET_H_ #define FSFW_DEVICEHANDLERS_DEVICEHANDLERTHERMALSET_H_ -#include "DeviceHandlerIF.h" -#include "../datapoollocal/StaticLocalDataSet.h" #include "../datapoollocal/LocalPoolVariable.h" +#include "../datapoollocal/StaticLocalDataSet.h" +#include "DeviceHandlerIF.h" +class DeviceHandlerThermalSet : public StaticLocalDataSet<2> { + public: + DeviceHandlerThermalSet( + HasLocalDataPoolIF* hkOwner, uint32_t setId = DeviceHandlerIF::DEFAULT_THERMAL_SET_ID, + 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) {} -class DeviceHandlerThermalSet: public StaticLocalDataSet<2> { -public: + DeviceHandlerThermalSet( + object_id_t deviceHandler, uint32_t setId = DeviceHandlerIF::DEFAULT_THERMAL_SET_ID, + lp_id_t thermalStateId = DeviceHandlerIF::DEFAULT_THERMAL_STATE_POOL_ID, + lp_id_t thermalStateRequestId = DeviceHandlerIF::DEFAULT_THERMAL_HEATING_REQUEST_POOL_ID) + : StaticLocalDataSet(sid_t(deviceHandler, setId)), + thermalStatePoolId(thermalStateId), + heaterRequestPoolId(thermalStateRequestId) {} - DeviceHandlerThermalSet(HasLocalDataPoolIF* hkOwner, uint32_t setId = - DeviceHandlerIF::DEFAULT_THERMAL_SET_ID, - 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) {} + const lp_id_t thermalStatePoolId; + const lp_id_t heaterRequestPoolId; - DeviceHandlerThermalSet(object_id_t deviceHandler, uint32_t setId = - DeviceHandlerIF::DEFAULT_THERMAL_SET_ID, - lp_id_t thermalStateId = - DeviceHandlerIF::DEFAULT_THERMAL_STATE_POOL_ID, - lp_id_t thermalStateRequestId = - DeviceHandlerIF::DEFAULT_THERMAL_HEATING_REQUEST_POOL_ID): - StaticLocalDataSet(sid_t(deviceHandler, setId)), - thermalStatePoolId(thermalStateId), - heaterRequestPoolId(thermalStateRequestId) {} - - const lp_id_t thermalStatePoolId; - const lp_id_t heaterRequestPoolId; - - lp_var_t thermalState = - lp_var_t( - thermalStatePoolId, sid.objectId, this); - lp_var_t heaterRequest = - lp_var_t( - heaterRequestPoolId, sid.objectId, this); + lp_var_t thermalState = + lp_var_t(thermalStatePoolId, sid.objectId, this); + lp_var_t heaterRequest = + lp_var_t(heaterRequestPoolId, sid.objectId, this); }; - - #endif /* FSFW_DEVICEHANDLERS_DEVICEHANDLERTHERMALSET_H_ */ diff --git a/src/fsfw/devicehandlers/DeviceTmReportingWrapper.cpp b/src/fsfw/devicehandlers/DeviceTmReportingWrapper.cpp index 0300a24a..3da431dc 100644 --- a/src/fsfw/devicehandlers/DeviceTmReportingWrapper.cpp +++ b/src/fsfw/devicehandlers/DeviceTmReportingWrapper.cpp @@ -1,45 +1,40 @@ #include "fsfw/devicehandlers/DeviceTmReportingWrapper.h" + #include "fsfw/serialize/SerializeAdapter.h" -DeviceTmReportingWrapper::DeviceTmReportingWrapper(object_id_t objectId, - ActionId_t actionId, SerializeIF* data) : - objectId(objectId), actionId(actionId), data(data) { -} +DeviceTmReportingWrapper::DeviceTmReportingWrapper(object_id_t objectId, ActionId_t actionId, + SerializeIF* data) + : objectId(objectId), actionId(actionId), data(data) {} -DeviceTmReportingWrapper::~DeviceTmReportingWrapper() { +DeviceTmReportingWrapper::~DeviceTmReportingWrapper() {} -} - -ReturnValue_t DeviceTmReportingWrapper::serialize(uint8_t** buffer, - size_t* size, size_t maxSize, Endianness streamEndianness) const { - ReturnValue_t result = SerializeAdapter::serialize(&objectId, - buffer, size, maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::serialize(&actionId, buffer, - size, maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return data->serialize(buffer, size, maxSize, streamEndianness); +ReturnValue_t DeviceTmReportingWrapper::serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const { + ReturnValue_t result = + SerializeAdapter::serialize(&objectId, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::serialize(&actionId, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return data->serialize(buffer, size, maxSize, streamEndianness); } size_t DeviceTmReportingWrapper::getSerializedSize() const { - return sizeof(objectId) + sizeof(ActionId_t) + data->getSerializedSize(); + return sizeof(objectId) + sizeof(ActionId_t) + data->getSerializedSize(); } -ReturnValue_t DeviceTmReportingWrapper::deSerialize(const uint8_t** buffer, - size_t* size, Endianness streamEndianness) { - ReturnValue_t result = SerializeAdapter::deSerialize(&objectId, - buffer, size, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::deSerialize(&actionId, buffer, - size, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return data->deSerialize(buffer, size, streamEndianness); +ReturnValue_t DeviceTmReportingWrapper::deSerialize(const uint8_t** buffer, size_t* size, + Endianness streamEndianness) { + ReturnValue_t result = SerializeAdapter::deSerialize(&objectId, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::deSerialize(&actionId, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return data->deSerialize(buffer, size, streamEndianness); } diff --git a/src/fsfw/devicehandlers/DeviceTmReportingWrapper.h b/src/fsfw/devicehandlers/DeviceTmReportingWrapper.h index 447e95f2..71c64453 100644 --- a/src/fsfw/devicehandlers/DeviceTmReportingWrapper.h +++ b/src/fsfw/devicehandlers/DeviceTmReportingWrapper.h @@ -5,23 +5,23 @@ #include "../objectmanager/SystemObjectIF.h" #include "../serialize/SerializeIF.h" -class DeviceTmReportingWrapper: public SerializeIF { -public: - DeviceTmReportingWrapper(object_id_t objectId, ActionId_t actionId, - SerializeIF *data); - virtual ~DeviceTmReportingWrapper(); +class DeviceTmReportingWrapper : public SerializeIF { + public: + DeviceTmReportingWrapper(object_id_t objectId, ActionId_t actionId, SerializeIF* data); + virtual ~DeviceTmReportingWrapper(); - virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const override; + virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; - virtual size_t getSerializedSize() const override; + virtual size_t getSerializedSize() const override; - virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) override; -private: - object_id_t objectId; - ActionId_t actionId; - SerializeIF *data; + virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + Endianness streamEndianness) override; + + private: + object_id_t objectId; + ActionId_t actionId; + SerializeIF* data; }; #endif /* FSFW_DEVICEHANDLERS_DEVICETMREPORTINGWRAPPER_H_ */ diff --git a/src/fsfw/devicehandlers/HealthDevice.cpp b/src/fsfw/devicehandlers/HealthDevice.cpp index 2f6e1dfb..a626fa6c 100644 --- a/src/fsfw/devicehandlers/HealthDevice.cpp +++ b/src/fsfw/devicehandlers/HealthDevice.cpp @@ -1,59 +1,56 @@ #include "fsfw/devicehandlers/HealthDevice.h" + #include "fsfw/ipc/QueueFactory.h" -HealthDevice::HealthDevice(object_id_t setObjectId, - MessageQueueId_t parentQueue) : - SystemObject(setObjectId), lastHealth(HEALTHY), parentQueue( - parentQueue), commandQueue(), healthHelper(this, setObjectId) { - commandQueue = QueueFactory::instance()->createMessageQueue(3); +HealthDevice::HealthDevice(object_id_t setObjectId, MessageQueueId_t parentQueue) + : SystemObject(setObjectId), + lastHealth(HEALTHY), + parentQueue(parentQueue), + commandQueue(), + healthHelper(this, setObjectId) { + commandQueue = QueueFactory::instance()->createMessageQueue(3); } -HealthDevice::~HealthDevice() { - QueueFactory::instance()->deleteMessageQueue(commandQueue); -} +HealthDevice::~HealthDevice() { QueueFactory::instance()->deleteMessageQueue(commandQueue); } ReturnValue_t HealthDevice::performOperation(uint8_t opCode) { - CommandMessage command; - ReturnValue_t result = commandQueue->receiveMessage(&command); - if (result == HasReturnvaluesIF::RETURN_OK) { - result = healthHelper.handleHealthCommand(&command); - } - return result; + CommandMessage command; + ReturnValue_t result = commandQueue->receiveMessage(&command); + if (result == HasReturnvaluesIF::RETURN_OK) { + result = healthHelper.handleHealthCommand(&command); + } + return result; } ReturnValue_t HealthDevice::initialize() { - ReturnValue_t result = SystemObject::initialize(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if (parentQueue != 0) { - return healthHelper.initialize(parentQueue); - } else { - return healthHelper.initialize(); - } + ReturnValue_t result = SystemObject::initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (parentQueue != 0) { + return healthHelper.initialize(parentQueue); + } else { + return healthHelper.initialize(); + } } -MessageQueueId_t HealthDevice::getCommandQueue() const { - return commandQueue->getId(); -} +MessageQueueId_t HealthDevice::getCommandQueue() const { return commandQueue->getId(); } void HealthDevice::setParentQueue(MessageQueueId_t parentQueue) { - healthHelper.setParentQueue(parentQueue); + healthHelper.setParentQueue(parentQueue); } bool HealthDevice::hasHealthChanged() { - bool changed; - HealthState currentHealth = healthHelper.getHealth(); - changed = currentHealth != lastHealth; - lastHealth = currentHealth; - return changed; + bool changed; + HealthState currentHealth = healthHelper.getHealth(); + changed = currentHealth != lastHealth; + lastHealth = currentHealth; + return changed; } ReturnValue_t HealthDevice::setHealth(HealthState health) { - healthHelper.setHealth(health); - return HasReturnvaluesIF::RETURN_OK; + healthHelper.setHealth(health); + return HasReturnvaluesIF::RETURN_OK; } -HasHealthIF::HealthState HealthDevice::getHealth() { - return healthHelper.getHealth(); -} +HasHealthIF::HealthState HealthDevice::getHealth() { return healthHelper.getHealth(); } diff --git a/src/fsfw/devicehandlers/HealthDevice.h b/src/fsfw/devicehandlers/HealthDevice.h index bf9cdb82..f4c3520f 100644 --- a/src/fsfw/devicehandlers/HealthDevice.h +++ b/src/fsfw/devicehandlers/HealthDevice.h @@ -3,38 +3,37 @@ #include "fsfw/health/HasHealthIF.h" #include "fsfw/health/HealthHelper.h" +#include "fsfw/ipc/MessageQueueIF.h" #include "fsfw/objectmanager/SystemObject.h" #include "fsfw/tasks/ExecutableObjectIF.h" -#include "fsfw/ipc/MessageQueueIF.h" -class HealthDevice: public SystemObject, - public ExecutableObjectIF, - public HasHealthIF { -public: - HealthDevice(object_id_t setObjectId, MessageQueueId_t parentQueue); - virtual ~HealthDevice(); +class HealthDevice : public SystemObject, public ExecutableObjectIF, public HasHealthIF { + public: + HealthDevice(object_id_t setObjectId, MessageQueueId_t parentQueue); + virtual ~HealthDevice(); - ReturnValue_t performOperation(uint8_t opCode); + ReturnValue_t performOperation(uint8_t opCode); - ReturnValue_t initialize(); + ReturnValue_t initialize(); - virtual MessageQueueId_t getCommandQueue() const; + virtual MessageQueueId_t getCommandQueue() const; - void setParentQueue(MessageQueueId_t parentQueue); + void setParentQueue(MessageQueueId_t parentQueue); - bool hasHealthChanged(); + bool hasHealthChanged(); - virtual ReturnValue_t setHealth(HealthState health); + virtual ReturnValue_t setHealth(HealthState health); - virtual HealthState getHealth(); + virtual HealthState getHealth(); -protected: - HealthState lastHealth; + protected: + HealthState lastHealth; - MessageQueueId_t parentQueue; - MessageQueueIF* commandQueue; -public: - HealthHelper healthHelper; + MessageQueueId_t parentQueue; + MessageQueueIF* commandQueue; + + public: + HealthHelper healthHelper; }; #endif /* FSFW_DEVICEHANDLERS_HEALTHDEVICE_H_ */ diff --git a/src/fsfw/events/Event.h b/src/fsfw/events/Event.h index aebc4bc5..20b66679 100644 --- a/src/fsfw/events/Event.h +++ b/src/fsfw/events/Event.h @@ -2,6 +2,7 @@ #define EVENTOBJECT_EVENT_H_ #include + #include "fwSubsystemIdRanges.h" // could be moved to more suitable location #include @@ -9,32 +10,28 @@ typedef uint16_t EventId_t; typedef uint8_t EventSeverity_t; -#define MAKE_EVENT(id, severity) (((severity)<<16)+(SUBSYSTEM_ID*100)+(id)) +#define MAKE_EVENT(id, severity) (((severity) << 16) + (SUBSYSTEM_ID * 100) + (id)) typedef uint32_t Event; namespace event { -constexpr EventId_t getEventId(Event event) { - return (event & 0xFFFF); -} +constexpr EventId_t getEventId(Event event) { return (event & 0xFFFF); } -constexpr EventSeverity_t getSeverity(Event event) { - return ((event >> 16) & 0xFF); -} +constexpr EventSeverity_t getSeverity(Event event) { return ((event >> 16) & 0xFF); } constexpr Event makeEvent(uint8_t subsystemId, uint8_t uniqueEventId, - EventSeverity_t eventSeverity) { - return (eventSeverity << 16) + (subsystemId * 100) + uniqueEventId; + EventSeverity_t eventSeverity) { + return (eventSeverity << 16) + (subsystemId * 100) + uniqueEventId; } -} +} // namespace event namespace severity { - static constexpr EventSeverity_t INFO = 1; - static constexpr EventSeverity_t LOW = 2; - static constexpr EventSeverity_t MEDIUM = 3; - static constexpr EventSeverity_t HIGH = 4; -} +static constexpr EventSeverity_t INFO = 1; +static constexpr EventSeverity_t LOW = 2; +static constexpr EventSeverity_t MEDIUM = 3; +static constexpr EventSeverity_t HIGH = 4; +} // namespace severity #endif /* EVENTOBJECT_EVENT_H_ */ diff --git a/src/fsfw/events/EventManager.cpp b/src/fsfw/events/EventManager.cpp index 958076a9..aaa7d6c5 100644 --- a/src/fsfw/events/EventManager.cpp +++ b/src/fsfw/events/EventManager.cpp @@ -1,8 +1,8 @@ #include "fsfw/events/EventManager.h" -#include "fsfw/events/EventMessage.h" -#include "fsfw/ipc/QueueFactory.h" +#include "fsfw/events/EventMessage.h" #include "fsfw/ipc/MutexFactory.h" +#include "fsfw/ipc/QueueFactory.h" MessageQueueId_t EventManagerIF::eventmanagerQueue = MessageQueueIF::NO_QUEUE; @@ -11,201 +11,182 @@ MessageQueueId_t EventManagerIF::eventmanagerQueue = MessageQueueIF::NO_QUEUE; // Each listener requires 1 or 2 EventIdMatcher and 1 or 2 ReportRangeMatcher. // So a good guess is 75 to a max of 100 pools required for each, which fits well. const LocalPool::LocalPoolConfig EventManager::poolConfig = { - {fsfwconfig::FSFW_EVENTMGMR_MATCHTREE_NODES, - sizeof(EventMatchTree::Node)}, - {fsfwconfig::FSFW_EVENTMGMT_EVENTIDMATCHERS, - sizeof(EventIdRangeMatcher)}, - {fsfwconfig::FSFW_EVENTMGMR_RANGEMATCHERS, - sizeof(ReporterRangeMatcher)} -}; + {fsfwconfig::FSFW_EVENTMGMR_MATCHTREE_NODES, sizeof(EventMatchTree::Node)}, + {fsfwconfig::FSFW_EVENTMGMT_EVENTIDMATCHERS, sizeof(EventIdRangeMatcher)}, + {fsfwconfig::FSFW_EVENTMGMR_RANGEMATCHERS, sizeof(ReporterRangeMatcher)}}; -EventManager::EventManager(object_id_t setObjectId) : - SystemObject(setObjectId), - factoryBackend(0, poolConfig, false, true) { - mutex = MutexFactory::instance()->createMutex(); - eventReportQueue = QueueFactory::instance()->createMessageQueue( - MAX_EVENTS_PER_CYCLE, EventMessage::EVENT_MESSAGE_SIZE); +EventManager::EventManager(object_id_t setObjectId) + : SystemObject(setObjectId), factoryBackend(0, poolConfig, false, true) { + mutex = MutexFactory::instance()->createMutex(); + eventReportQueue = QueueFactory::instance()->createMessageQueue(MAX_EVENTS_PER_CYCLE, + EventMessage::EVENT_MESSAGE_SIZE); } EventManager::~EventManager() { - QueueFactory::instance()->deleteMessageQueue(eventReportQueue); - MutexFactory::instance()->deleteMutex(mutex); + QueueFactory::instance()->deleteMessageQueue(eventReportQueue); + MutexFactory::instance()->deleteMutex(mutex); } -MessageQueueId_t EventManager::getEventReportQueue() { - return eventReportQueue->getId(); -} +MessageQueueId_t EventManager::getEventReportQueue() { return eventReportQueue->getId(); } ReturnValue_t EventManager::performOperation(uint8_t opCode) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - while (result == HasReturnvaluesIF::RETURN_OK) { - EventMessage message; - result = eventReportQueue->receiveMessage(&message); - if (result == HasReturnvaluesIF::RETURN_OK) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + while (result == HasReturnvaluesIF::RETURN_OK) { + EventMessage message; + result = eventReportQueue->receiveMessage(&message); + if (result == HasReturnvaluesIF::RETURN_OK) { #if FSFW_OBJ_EVENT_TRANSLATION == 1 - printEvent(&message); + printEvent(&message); #endif - notifyListeners(&message); - } + notifyListeners(&message); } - return HasReturnvaluesIF::RETURN_OK; + } + return HasReturnvaluesIF::RETURN_OK; } void EventManager::notifyListeners(EventMessage* message) { - lockMutex(); - for (auto iter = listenerList.begin(); iter != listenerList.end(); ++iter) { - if (iter->second.match(message)) { - MessageQueueSenderIF::sendMessage(iter->first, message, - message->getSender()); - } + lockMutex(); + for (auto iter = listenerList.begin(); iter != listenerList.end(); ++iter) { + if (iter->second.match(message)) { + MessageQueueSenderIF::sendMessage(iter->first, message, message->getSender()); } - unlockMutex(); + } + unlockMutex(); } ReturnValue_t EventManager::registerListener(MessageQueueId_t listener, -bool forwardAllButSelected) { - auto result = listenerList.insert( - std::pair(listener, - EventMatchTree(&factoryBackend, forwardAllButSelected))); - if (!result.second) { - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + bool forwardAllButSelected) { + auto result = listenerList.insert(std::pair( + listener, EventMatchTree(&factoryBackend, forwardAllButSelected))); + if (!result.second) { + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t EventManager::subscribeToEvent(MessageQueueId_t listener, - EventId_t event) { - return subscribeToEventRange(listener, event); +ReturnValue_t EventManager::subscribeToEvent(MessageQueueId_t listener, EventId_t event) { + return subscribeToEventRange(listener, event); } ReturnValue_t EventManager::subscribeToAllEventsFrom(MessageQueueId_t listener, - object_id_t object) { - return subscribeToEventRange(listener, 0, 0, true, object); + object_id_t object) { + return subscribeToEventRange(listener, 0, 0, true, object); } -ReturnValue_t EventManager::subscribeToEventRange(MessageQueueId_t listener, - EventId_t idFrom, EventId_t idTo, bool idInverted, - object_id_t reporterFrom, object_id_t reporterTo, - bool reporterInverted) { - auto iter = listenerList.find(listener); - if (iter == listenerList.end()) { - return LISTENER_NOT_FOUND; - } - lockMutex(); - ReturnValue_t result = iter->second.addMatch(idFrom, idTo, idInverted, - reporterFrom, reporterTo, reporterInverted); - unlockMutex(); - return result; +ReturnValue_t EventManager::subscribeToEventRange(MessageQueueId_t listener, EventId_t idFrom, + EventId_t idTo, bool idInverted, + object_id_t reporterFrom, object_id_t reporterTo, + bool reporterInverted) { + auto iter = listenerList.find(listener); + if (iter == listenerList.end()) { + return LISTENER_NOT_FOUND; + } + lockMutex(); + ReturnValue_t result = + iter->second.addMatch(idFrom, idTo, idInverted, reporterFrom, reporterTo, reporterInverted); + unlockMutex(); + return result; } -ReturnValue_t EventManager::unsubscribeFromEventRange(MessageQueueId_t listener, - EventId_t idFrom, EventId_t idTo, bool idInverted, - object_id_t reporterFrom, object_id_t reporterTo, - bool reporterInverted) { - auto iter = listenerList.find(listener); - if (iter == listenerList.end()) { - return LISTENER_NOT_FOUND; - } - lockMutex(); - ReturnValue_t result = iter->second.removeMatch(idFrom, idTo, idInverted, - reporterFrom, reporterTo, reporterInverted); - unlockMutex(); - return result; +ReturnValue_t EventManager::unsubscribeFromEventRange(MessageQueueId_t listener, EventId_t idFrom, + EventId_t idTo, bool idInverted, + object_id_t reporterFrom, + object_id_t reporterTo, + bool reporterInverted) { + auto iter = listenerList.find(listener); + if (iter == listenerList.end()) { + return LISTENER_NOT_FOUND; + } + lockMutex(); + ReturnValue_t result = iter->second.removeMatch(idFrom, idTo, idInverted, reporterFrom, + reporterTo, reporterInverted); + unlockMutex(); + return result; } -void EventManager::lockMutex() { - mutex->lockMutex(timeoutType, timeoutMs); -} +void EventManager::lockMutex() { mutex->lockMutex(timeoutType, timeoutMs); } -void EventManager::unlockMutex() { - mutex->unlockMutex(); -} +void EventManager::unlockMutex() { mutex->unlockMutex(); } -void EventManager::setMutexTimeout(MutexIF::TimeoutType timeoutType, - uint32_t timeoutMs) { - this->timeoutType = timeoutType; - this->timeoutMs = timeoutMs; +void EventManager::setMutexTimeout(MutexIF::TimeoutType timeoutType, uint32_t timeoutMs) { + this->timeoutType = timeoutType; + this->timeoutMs = timeoutMs; } #if FSFW_OBJ_EVENT_TRANSLATION == 1 void EventManager::printEvent(EventMessage* message) { - switch (message->getSeverity()) { + switch (message->getSeverity()) { case severity::INFO: { #if FSFW_DEBUG_INFO == 1 - printUtility(sif::OutputTypes::OUT_INFO, message); + printUtility(sif::OutputTypes::OUT_INFO, message); #endif /* DEBUG_INFO_EVENT == 1 */ - break; + break; } default: - printUtility(sif::OutputTypes::OUT_DEBUG, message); - break; - } + printUtility(sif::OutputTypes::OUT_DEBUG, message); + break; + } } -void EventManager::printUtility(sif::OutputTypes printType, EventMessage *message) { - const char *string = 0; - if(printType == sif::OutputTypes::OUT_INFO) { - string = translateObject(message->getReporter()); +void EventManager::printUtility(sif::OutputTypes printType, EventMessage* message) { + const char* string = 0; + if (printType == sif::OutputTypes::OUT_INFO) { + string = translateObject(message->getReporter()); #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "EventManager: "; - if (string != 0) { - sif::info << string; - } - else { - sif::info << "0x" << std::hex << std::setw(8) << std::setfill('0') << - message->getReporter() << std::setfill(' ') << std::dec; - } - sif::info << " reported event with ID " << message->getEventId() << std::endl; - sif::info << translateEvents(message->getEvent()) << " | " <getParameter1() << " | P1 Dec: " << std::dec << message->getParameter1() << - std::hex << " | P2 Hex: 0x" << message->getParameter2() << " | P2 Dec: " << - std::dec << message->getParameter2() << std::endl; + sif::info << "EventManager: "; + if (string != 0) { + sif::info << string; + } else { + sif::info << "0x" << std::hex << std::setw(8) << std::setfill('0') << message->getReporter() + << std::setfill(' ') << std::dec; + } + sif::info << " reported event with ID " << message->getEventId() << std::endl; + sif::info << translateEvents(message->getEvent()) << " | " << std::hex << "P1 Hex: 0x" + << message->getParameter1() << " | P1 Dec: " << std::dec << message->getParameter1() + << std::hex << " | P2 Hex: 0x" << message->getParameter2() + << " | P2 Dec: " << std::dec << message->getParameter2() << std::endl; #else - if (string != 0) { - sif::printInfo("Event Manager: %s reported event with ID %d\n", string, - message->getEventId()); - } - else { - sif::printInfo("Event Manager: Reporter ID 0x%08x reported event with ID %d\n", - message->getReporter(), message->getEventId()); - } + if (string != 0) { + sif::printInfo("Event Manager: %s reported event with ID %d\n", string, + message->getEventId()); + } else { + sif::printInfo("Event Manager: Reporter ID 0x%08x reported event with ID %d\n", + message->getReporter(), message->getEventId()); + } - sif::printInfo("%s | P1 Hex: 0x%x | P1 Dec: %d | P2 Hex: 0x%x | P2 Dec: %d\n", - translateEvents(message->getEvent()), message->getParameter1(), - message->getParameter1(), message->getParameter2(), message->getParameter2()); + sif::printInfo("%s | P1 Hex: 0x%x | P1 Dec: %d | P2 Hex: 0x%x | P2 Dec: %d\n", + translateEvents(message->getEvent()), message->getParameter1(), + message->getParameter1(), message->getParameter2(), message->getParameter2()); #endif /* FSFW_CPP_OSTREAM_ENABLED == 0 */ - } - else { - string = translateObject(message->getReporter()); + } else { + string = translateObject(message->getReporter()); #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "EventManager: "; - if (string != 0) { - sif::debug << string; - } - else { - sif::debug << "0x" << std::hex << std::setw(8) << std::setfill('0') << - message->getReporter() << std::setfill(' ') << std::dec; - } - sif::debug << " reported event with ID " << message->getEventId() << std::endl; - sif::debug << translateEvents(message->getEvent()) << " | " <getParameter1() << " | P1 Dec: " << std::dec << message->getParameter1() << - std::hex << " | P2 Hex: 0x" << message->getParameter2() << " | P2 Dec: " << - std::dec << message->getParameter2() << std::endl; -#else - if (string != 0) { - sif::printDebug("Event Manager: %s reported event with ID %d\n", string, - message->getEventId()); - } - else { - sif::printDebug("Event Manager: Reporter ID 0x%08x reported event with ID %d\n", - message->getReporter(), message->getEventId()); - } - sif::printDebug("P1 Hex: 0x%x | P1 Dec: %d | P2 Hex: 0x%x | P2 Dec: %d\n", - message->getParameter1(), message->getParameter1(), - message->getParameter2(), message->getParameter2()); -#endif /* FSFW_CPP_OSTREAM_ENABLED == 0 */ + sif::debug << "EventManager: "; + if (string != 0) { + sif::debug << string; + } else { + sif::debug << "0x" << std::hex << std::setw(8) << std::setfill('0') << message->getReporter() + << std::setfill(' ') << std::dec; } + sif::debug << " reported event with ID " << message->getEventId() << std::endl; + sif::debug << translateEvents(message->getEvent()) << " | " << std::hex << "P1 Hex: 0x" + << message->getParameter1() << " | P1 Dec: " << std::dec << message->getParameter1() + << std::hex << " | P2 Hex: 0x" << message->getParameter2() + << " | P2 Dec: " << std::dec << message->getParameter2() << std::endl; +#else + if (string != 0) { + sif::printDebug("Event Manager: %s reported event with ID %d\n", string, + message->getEventId()); + } else { + sif::printDebug("Event Manager: Reporter ID 0x%08x reported event with ID %d\n", + message->getReporter(), message->getEventId()); + } + sif::printDebug("P1 Hex: 0x%x | P1 Dec: %d | P2 Hex: 0x%x | P2 Dec: %d\n", + message->getParameter1(), message->getParameter1(), message->getParameter2(), + message->getParameter2()); +#endif /* FSFW_CPP_OSTREAM_ENABLED == 0 */ + } } #endif /* FSFW_OBJ_EVENT_TRANSLATION == 1 */ diff --git a/src/fsfw/events/EventManager.h b/src/fsfw/events/EventManager.h index 012247db..f2d642ff 100644 --- a/src/fsfw/events/EventManager.h +++ b/src/fsfw/events/EventManager.h @@ -1,18 +1,17 @@ #ifndef FSFW_EVENT_EVENTMANAGER_H_ #define FSFW_EVENT_EVENTMANAGER_H_ -#include "EventManagerIF.h" -#include "eventmatching/EventMatchTree.h" -#include "FSFWConfig.h" +#include -#include "../serviceinterface/ServiceInterface.h" -#include "../objectmanager/SystemObject.h" -#include "../storagemanager/LocalPool.h" -#include "../tasks/ExecutableObjectIF.h" #include "../ipc/MessageQueueIF.h" #include "../ipc/MutexIF.h" - -#include +#include "../objectmanager/SystemObject.h" +#include "../serviceinterface/ServiceInterface.h" +#include "../storagemanager/LocalPool.h" +#include "../tasks/ExecutableObjectIF.h" +#include "EventManagerIF.h" +#include "FSFWConfig.h" +#include "eventmatching/EventMatchTree.h" #if FSFW_OBJ_EVENT_TRANSLATION == 1 // forward declaration, should be implemented by mission @@ -20,59 +19,56 @@ extern const char* translateObject(object_id_t object); extern const char* translateEvents(Event event); #endif -class EventManager: public EventManagerIF, - public ExecutableObjectIF, - public SystemObject { -public: - static const uint16_t MAX_EVENTS_PER_CYCLE = 80; +class EventManager : public EventManagerIF, public ExecutableObjectIF, public SystemObject { + public: + static const uint16_t MAX_EVENTS_PER_CYCLE = 80; - EventManager(object_id_t setObjectId); - virtual ~EventManager(); + EventManager(object_id_t setObjectId); + virtual ~EventManager(); - void setMutexTimeout(MutexIF::TimeoutType timeoutType, uint32_t timeoutMs); + void setMutexTimeout(MutexIF::TimeoutType timeoutType, uint32_t timeoutMs); - MessageQueueId_t getEventReportQueue(); + MessageQueueId_t getEventReportQueue(); - ReturnValue_t registerListener(MessageQueueId_t listener, bool forwardAllButSelected = false); - ReturnValue_t subscribeToEvent(MessageQueueId_t listener, EventId_t event); - ReturnValue_t subscribeToAllEventsFrom(MessageQueueId_t listener, - object_id_t object); - ReturnValue_t subscribeToEventRange(MessageQueueId_t listener, - EventId_t idFrom = 0, EventId_t idTo = 0, bool idInverted = false, - object_id_t reporterFrom = 0, object_id_t reporterTo = 0, - bool reporterInverted = false); - ReturnValue_t unsubscribeFromEventRange(MessageQueueId_t listener, - EventId_t idFrom = 0, EventId_t idTo = 0, bool idInverted = false, - object_id_t reporterFrom = 0, object_id_t reporterTo = 0, - bool reporterInverted = false); - ReturnValue_t performOperation(uint8_t opCode); -protected: + ReturnValue_t registerListener(MessageQueueId_t listener, bool forwardAllButSelected = false); + ReturnValue_t subscribeToEvent(MessageQueueId_t listener, EventId_t event); + ReturnValue_t subscribeToAllEventsFrom(MessageQueueId_t listener, object_id_t object); + ReturnValue_t subscribeToEventRange(MessageQueueId_t listener, EventId_t idFrom = 0, + EventId_t idTo = 0, bool idInverted = false, + object_id_t reporterFrom = 0, object_id_t reporterTo = 0, + bool reporterInverted = false); + ReturnValue_t unsubscribeFromEventRange(MessageQueueId_t listener, EventId_t idFrom = 0, + EventId_t idTo = 0, bool idInverted = false, + object_id_t reporterFrom = 0, object_id_t reporterTo = 0, + bool reporterInverted = false); + ReturnValue_t performOperation(uint8_t opCode); - MessageQueueIF* eventReportQueue = nullptr; + protected: + MessageQueueIF* eventReportQueue = nullptr; - std::map listenerList; + std::map listenerList; - MutexIF* mutex = nullptr; - MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING; - uint32_t timeoutMs = 20; + MutexIF* mutex = nullptr; + MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING; + uint32_t timeoutMs = 20; - static const uint8_t N_POOLS = 3; - LocalPool factoryBackend; - static const LocalPool::LocalPoolConfig poolConfig; + static const uint8_t N_POOLS = 3; + LocalPool factoryBackend; + static const LocalPool::LocalPoolConfig poolConfig; - static const uint16_t POOL_SIZES[N_POOLS]; - static const uint16_t N_ELEMENTS[N_POOLS]; + static const uint16_t POOL_SIZES[N_POOLS]; + static const uint16_t N_ELEMENTS[N_POOLS]; - void notifyListeners(EventMessage *message); + void notifyListeners(EventMessage* message); #if FSFW_OBJ_EVENT_TRANSLATION == 1 - void printEvent(EventMessage *message); - void printUtility(sif::OutputTypes printType, EventMessage* message); + void printEvent(EventMessage* message); + void printUtility(sif::OutputTypes printType, EventMessage* message); #endif - void lockMutex(); + void lockMutex(); - void unlockMutex(); + void unlockMutex(); }; #endif /* FSFW_EVENT_EVENTMANAGER_H_ */ diff --git a/src/fsfw/events/EventManagerIF.h b/src/fsfw/events/EventManagerIF.h index 0ba126a2..98051ba0 100644 --- a/src/fsfw/events/EventManagerIF.h +++ b/src/fsfw/events/EventManagerIF.h @@ -1,71 +1,67 @@ #ifndef FSFW_EVENTS_EVENTMANAGERIF_H_ #define FSFW_EVENTS_EVENTMANAGERIF_H_ +#include "../ipc/MessageQueueIF.h" +#include "../ipc/MessageQueueSenderIF.h" +#include "../objectmanager/ObjectManager.h" +#include "../serviceinterface/ServiceInterface.h" #include "EventMessage.h" #include "eventmatching/eventmatching.h" -#include "../objectmanager/ObjectManager.h" -#include "../ipc/MessageQueueSenderIF.h" -#include "../ipc/MessageQueueIF.h" -#include "../serviceinterface/ServiceInterface.h" class EventManagerIF { -public: + public: + static const uint8_t INTERFACE_ID = CLASS_ID::EVENT_MANAGER_IF; + static const ReturnValue_t LISTENER_NOT_FOUND = MAKE_RETURN_CODE(1); + virtual ~EventManagerIF() {} - static const uint8_t INTERFACE_ID = CLASS_ID::EVENT_MANAGER_IF; - static const ReturnValue_t LISTENER_NOT_FOUND = MAKE_RETURN_CODE(1); - virtual ~EventManagerIF() { - } + virtual MessageQueueId_t getEventReportQueue() = 0; - virtual MessageQueueId_t getEventReportQueue() = 0; + virtual ReturnValue_t registerListener(MessageQueueId_t listener, + bool forwardAllButSelected = false) = 0; + virtual ReturnValue_t subscribeToEvent(MessageQueueId_t listener, EventId_t event) = 0; + virtual ReturnValue_t subscribeToAllEventsFrom(MessageQueueId_t listener, object_id_t object) = 0; + virtual ReturnValue_t subscribeToEventRange(MessageQueueId_t listener, EventId_t idFrom = 0, + EventId_t idTo = 0, bool idInverted = false, + object_id_t reporterFrom = 0, + object_id_t reporterTo = 0, + bool reporterInverted = false) = 0; + virtual ReturnValue_t unsubscribeFromEventRange(MessageQueueId_t listener, EventId_t idFrom = 0, + EventId_t idTo = 0, bool idInverted = false, + object_id_t reporterFrom = 0, + object_id_t reporterTo = 0, + bool reporterInverted = false) = 0; - virtual ReturnValue_t registerListener(MessageQueueId_t listener, - bool forwardAllButSelected = false) = 0; - virtual ReturnValue_t subscribeToEvent(MessageQueueId_t listener, - EventId_t event) = 0; - virtual ReturnValue_t subscribeToAllEventsFrom(MessageQueueId_t listener, - object_id_t object) = 0; - virtual ReturnValue_t subscribeToEventRange(MessageQueueId_t listener, - EventId_t idFrom = 0, EventId_t idTo = 0, bool idInverted = false, - object_id_t reporterFrom = 0, object_id_t reporterTo = 0, - bool reporterInverted = false) = 0; - virtual ReturnValue_t unsubscribeFromEventRange(MessageQueueId_t listener, - EventId_t idFrom = 0, EventId_t idTo = 0, bool idInverted = false, - object_id_t reporterFrom = 0, object_id_t reporterTo = 0, - bool reporterInverted = false) = 0; + static void triggerEvent(object_id_t reportingObject, Event event, uint32_t parameter1 = 0, + uint32_t parameter2 = 0, MessageQueueId_t sentFrom = 0) { + EventMessage message(event, reportingObject, parameter1, parameter2); + triggerEvent(&message, sentFrom); + } - static void triggerEvent(object_id_t reportingObject, Event event, - uint32_t parameter1 = 0, uint32_t parameter2 = 0, - MessageQueueId_t sentFrom = 0) { - EventMessage message(event, reportingObject, parameter1, parameter2); - triggerEvent(&message, sentFrom); - } - - static void triggerEvent(EventMessage* message, - MessageQueueId_t sentFrom = 0) { - if (eventmanagerQueue == MessageQueueIF::NO_QUEUE) { - EventManagerIF *eventmanager = ObjectManager::instance()->get( - objects::EVENT_MANAGER); - if (eventmanager == nullptr) { + static void triggerEvent(EventMessage* message, MessageQueueId_t sentFrom = 0) { + if (eventmanagerQueue == MessageQueueIF::NO_QUEUE) { + EventManagerIF* eventmanager = + ObjectManager::instance()->get(objects::EVENT_MANAGER); + if (eventmanager == nullptr) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "EventManagerIF::triggerEvent: EventManager invalid or not found!" - << std::endl; + sif::warning << "EventManagerIF::triggerEvent: EventManager invalid or not found!" + << std::endl; #else - sif::printWarning("EventManagerIF::triggerEvent: " - "EventManager invalid or not found!"); + sif::printWarning( + "EventManagerIF::triggerEvent: " + "EventManager invalid or not found!"); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - return; - } - eventmanagerQueue = eventmanager->getEventReportQueue(); - } - MessageQueueSenderIF::sendMessage(eventmanagerQueue, message, sentFrom); - } - -private: - //! Initialized by EventManager (C++11 does not allow header-only static member initialization). - static MessageQueueId_t eventmanagerQueue; + return; + } + eventmanagerQueue = eventmanager->getEventReportQueue(); + } + MessageQueueSenderIF::sendMessage(eventmanagerQueue, message, sentFrom); + } + private: + //! Initialized by EventManager (C++11 does not allow header-only static member initialization). + static MessageQueueId_t eventmanagerQueue; }; #endif /* FSFW_EVENTS_EVENTMANAGERIF_H_ */ diff --git a/src/fsfw/events/EventMessage.cpp b/src/fsfw/events/EventMessage.cpp index 74f42b06..ebe1f2fe 100644 --- a/src/fsfw/events/EventMessage.cpp +++ b/src/fsfw/events/EventMessage.cpp @@ -1,114 +1,108 @@ #include "fsfw/events/EventMessage.h" + #include EventMessage::EventMessage() { - messageSize = EVENT_MESSAGE_SIZE; - clearEventMessage(); + messageSize = EVENT_MESSAGE_SIZE; + clearEventMessage(); } -EventMessage::EventMessage(Event event, object_id_t reporter, - uint32_t parameter1, uint32_t parameter2) { - messageSize = EVENT_MESSAGE_SIZE; - setMessageId(EVENT_MESSAGE); - setEvent(event); - setReporter(reporter); - setParameter1(parameter1); - setParameter2(parameter2); +EventMessage::EventMessage(Event event, object_id_t reporter, uint32_t parameter1, + uint32_t parameter2) { + messageSize = EVENT_MESSAGE_SIZE; + setMessageId(EVENT_MESSAGE); + setEvent(event); + setReporter(reporter); + setParameter1(parameter1); + setParameter2(parameter2); } -EventMessage::~EventMessage() { -} +EventMessage::~EventMessage() {} Event EventMessage::getEvent() { - Event event; - memcpy(&event, getData(), sizeof(Event)); - return (event & 0xFFFFFF); + Event event; + memcpy(&event, getData(), sizeof(Event)); + return (event & 0xFFFFFF); } void EventMessage::setEvent(Event event) { - Event tempEvent; - memcpy(&tempEvent, getData(), sizeof(Event)); - tempEvent = (tempEvent & 0xFF000000) + (event & 0xFFFFFF); - memcpy(getData(), &tempEvent, sizeof(Event)); + Event tempEvent; + memcpy(&tempEvent, getData(), sizeof(Event)); + tempEvent = (tempEvent & 0xFF000000) + (event & 0xFFFFFF); + memcpy(getData(), &tempEvent, sizeof(Event)); } uint8_t EventMessage::getMessageId() { - Event event; - memcpy(&event, getData(), sizeof(Event)); - return (event & 0xFF000000) >> 24; + Event event; + memcpy(&event, getData(), sizeof(Event)); + return (event & 0xFF000000) >> 24; } void EventMessage::setMessageId(uint8_t id) { - Event event; - memcpy(&event, getData(), sizeof(Event)); - event = (event & 0x00FFFFFF) + (id << 24); - memcpy(getData(), &event, sizeof(Event)); + Event event; + memcpy(&event, getData(), sizeof(Event)); + event = (event & 0x00FFFFFF) + (id << 24); + memcpy(getData(), &event, sizeof(Event)); } EventSeverity_t EventMessage::getSeverity() { - Event event; - memcpy(&event, getData(), sizeof(Event)); - return event::getSeverity(event); + Event event; + memcpy(&event, getData(), sizeof(Event)); + return event::getSeverity(event); } void EventMessage::setSeverity(EventSeverity_t severity) { - Event event; - memcpy(&event, getData(), sizeof(Event)); - event = (event & 0xFF00FFFF) + (severity << 16); - memcpy(getData(), &event, sizeof(Event)); + Event event; + memcpy(&event, getData(), sizeof(Event)); + event = (event & 0xFF00FFFF) + (severity << 16); + memcpy(getData(), &event, sizeof(Event)); } EventId_t EventMessage::getEventId() { - Event event; - memcpy(&event, getData(), sizeof(Event)); - return event::getEventId(event); + Event event; + memcpy(&event, getData(), sizeof(Event)); + return event::getEventId(event); } void EventMessage::setEventId(EventId_t eventId) { - Event event; - memcpy(&event, getData(), sizeof(Event)); - event = (event & 0xFFFF0000) + eventId; - memcpy(getData(), &event, sizeof(Event)); + Event event; + memcpy(&event, getData(), sizeof(Event)); + event = (event & 0xFFFF0000) + eventId; + memcpy(getData(), &event, sizeof(Event)); } object_id_t EventMessage::getReporter() { - object_id_t parameter; - memcpy(¶meter, getData() + sizeof(Event), sizeof(object_id_t)); - return parameter; + object_id_t parameter; + memcpy(¶meter, getData() + sizeof(Event), sizeof(object_id_t)); + return parameter; } void EventMessage::setReporter(object_id_t reporter) { - memcpy(getData() + sizeof(Event), &reporter, sizeof(object_id_t)); + memcpy(getData() + sizeof(Event), &reporter, sizeof(object_id_t)); } uint32_t EventMessage::getParameter1() { - uint32_t parameter; - memcpy(¶meter, getData() + sizeof(Event) + sizeof(object_id_t), 4); - return parameter; + uint32_t parameter; + memcpy(¶meter, getData() + sizeof(Event) + sizeof(object_id_t), 4); + return parameter; } void EventMessage::setParameter1(uint32_t parameter) { - memcpy(getData() + sizeof(Event) + sizeof(object_id_t), ¶meter, 4); + memcpy(getData() + sizeof(Event) + sizeof(object_id_t), ¶meter, 4); } uint32_t EventMessage::getParameter2() { - uint32_t parameter; - memcpy(¶meter, getData() + sizeof(Event) + sizeof(object_id_t) + 4, 4); - return parameter; + uint32_t parameter; + memcpy(¶meter, getData() + sizeof(Event) + sizeof(object_id_t) + 4, 4); + return parameter; } void EventMessage::setParameter2(uint32_t parameter) { - memcpy(getData() + sizeof(Event) + sizeof(object_id_t) + 4, ¶meter, 4); + memcpy(getData() + sizeof(Event) + sizeof(object_id_t) + 4, ¶meter, 4); } -void EventMessage::clearEventMessage() { - setEvent(INVALID_EVENT); -} +void EventMessage::clearEventMessage() { setEvent(INVALID_EVENT); } -bool EventMessage::isClearedEventMessage() { - return getEvent() == INVALID_EVENT; -} +bool EventMessage::isClearedEventMessage() { return getEvent() == INVALID_EVENT; } -size_t EventMessage::getMinimumMessageSize() const { - return EVENT_MESSAGE_SIZE; -} +size_t EventMessage::getMinimumMessageSize() const { return EVENT_MESSAGE_SIZE; } diff --git a/src/fsfw/events/EventMessage.h b/src/fsfw/events/EventMessage.h index 36e261bd..1624e6d6 100644 --- a/src/fsfw/events/EventMessage.h +++ b/src/fsfw/events/EventMessage.h @@ -9,44 +9,42 @@ * Passing on events through IPC. * Event Id, severity and message type retrieval is a bit difficult. */ -class EventMessage: public MessageQueueMessage { -public: - static const uint8_t EVENT_MESSAGE = 0; //!< Normal event - static const uint8_t CONFIRMATION_REQUEST = 1; //!< Request to parent if event is caused by child or not. - static const uint8_t YOUR_FAULT = 2; //!< The fault was caused by child, parent believes it's ok. - static const uint8_t MY_FAULT = 3; //!< The fault was caused by the parent, child is ok. - //Add other messageIDs here if necessary. - static const uint8_t EVENT_MESSAGE_SIZE = HEADER_SIZE + sizeof(Event) - + 3 * sizeof(uint32_t); +class EventMessage : public MessageQueueMessage { + public: + static const uint8_t EVENT_MESSAGE = 0; //!< Normal event + static const uint8_t CONFIRMATION_REQUEST = + 1; //!< Request to parent if event is caused by child or not. + static const uint8_t YOUR_FAULT = 2; //!< The fault was caused by child, parent believes it's ok. + static const uint8_t MY_FAULT = 3; //!< The fault was caused by the parent, child is ok. + // Add other messageIDs here if necessary. + static const uint8_t EVENT_MESSAGE_SIZE = HEADER_SIZE + sizeof(Event) + 3 * sizeof(uint32_t); - EventMessage(); -// EventMessage(EventId_t event, EventSeverity_t severity, -// object_id_t reporter, uint32_t parameter1, uint32_t parameter2 = 0); - EventMessage(Event event, object_id_t reporter, uint32_t parameter1, - uint32_t parameter2 = 0); - virtual ~EventMessage(); - Event getEvent(); - void setEvent(Event event); - uint8_t getMessageId(); - void setMessageId(uint8_t id); - EventSeverity_t getSeverity(); - void setSeverity(EventSeverity_t severity); - EventId_t getEventId(); - void setEventId(EventId_t event); - object_id_t getReporter(); - void setReporter(object_id_t reporter); - uint32_t getParameter1(); - void setParameter1(uint32_t parameter); - uint32_t getParameter2(); - void setParameter2(uint32_t parameter); + EventMessage(); + // EventMessage(EventId_t event, EventSeverity_t severity, + // object_id_t reporter, uint32_t parameter1, uint32_t parameter2 = 0); + EventMessage(Event event, object_id_t reporter, uint32_t parameter1, uint32_t parameter2 = 0); + virtual ~EventMessage(); + Event getEvent(); + void setEvent(Event event); + uint8_t getMessageId(); + void setMessageId(uint8_t id); + EventSeverity_t getSeverity(); + void setSeverity(EventSeverity_t severity); + EventId_t getEventId(); + void setEventId(EventId_t event); + object_id_t getReporter(); + void setReporter(object_id_t reporter); + uint32_t getParameter1(); + void setParameter1(uint32_t parameter); + uint32_t getParameter2(); + void setParameter2(uint32_t parameter); - void clearEventMessage(); - bool isClearedEventMessage(); - -protected: - static const Event INVALID_EVENT = 0; - virtual size_t getMinimumMessageSize() const override; + void clearEventMessage(); + bool isClearedEventMessage(); + protected: + static const Event INVALID_EVENT = 0; + virtual size_t getMinimumMessageSize() const override; }; #endif /* FSFW_EVENTS_EVENTMESSAGE_H_ */ diff --git a/src/fsfw/events/EventReportingProxyIF.h b/src/fsfw/events/EventReportingProxyIF.h index 7a96e3d1..c6034c9f 100644 --- a/src/fsfw/events/EventReportingProxyIF.h +++ b/src/fsfw/events/EventReportingProxyIF.h @@ -3,17 +3,12 @@ #include "Event.h" - class EventReportingProxyIF { -public: - virtual ~EventReportingProxyIF() { - } - - virtual void forwardEvent(Event event, uint32_t parameter1 = 0, uint32_t parameter2 = 0) const = 0; + public: + virtual ~EventReportingProxyIF() {} + virtual void forwardEvent(Event event, uint32_t parameter1 = 0, + uint32_t parameter2 = 0) const = 0; }; - - - #endif /* FRAMEWORK_EVENTS_EVENTREPORTINGPROXYIF_H_ */ diff --git a/src/fsfw/events/eventmatching/EventIdRangeMatcher.cpp b/src/fsfw/events/eventmatching/EventIdRangeMatcher.cpp index 92089f7c..02cf3432 100644 --- a/src/fsfw/events/eventmatching/EventIdRangeMatcher.cpp +++ b/src/fsfw/events/eventmatching/EventIdRangeMatcher.cpp @@ -1,12 +1,10 @@ #include "fsfw/events/eventmatching/EventIdRangeMatcher.h" -EventIdRangeMatcher::EventIdRangeMatcher(EventId_t lower, EventId_t upper, - bool inverted) : EventRangeMatcherBase(lower, upper, inverted) { -} +EventIdRangeMatcher::EventIdRangeMatcher(EventId_t lower, EventId_t upper, bool inverted) + : EventRangeMatcherBase(lower, upper, inverted) {} -EventIdRangeMatcher::~EventIdRangeMatcher() { -} +EventIdRangeMatcher::~EventIdRangeMatcher() {} bool EventIdRangeMatcher::match(EventMessage* message) { - return rangeMatcher.match(message->getEventId()); + return rangeMatcher.match(message->getEventId()); } diff --git a/src/fsfw/events/eventmatching/EventIdRangeMatcher.h b/src/fsfw/events/eventmatching/EventIdRangeMatcher.h index 540d372f..6fce4824 100644 --- a/src/fsfw/events/eventmatching/EventIdRangeMatcher.h +++ b/src/fsfw/events/eventmatching/EventIdRangeMatcher.h @@ -3,11 +3,11 @@ #include "EventRangeMatcherBase.h" -class EventIdRangeMatcher: public EventRangeMatcherBase { -public: - EventIdRangeMatcher(EventId_t lower, EventId_t upper, bool inverted); - ~EventIdRangeMatcher(); - bool match(EventMessage* message); +class EventIdRangeMatcher : public EventRangeMatcherBase { + public: + EventIdRangeMatcher(EventId_t lower, EventId_t upper, bool inverted); + ~EventIdRangeMatcher(); + bool match(EventMessage* message); }; #endif /* FRAMEWORK_EVENTS_EVENTMATCHING_EVENTIDRANGEMATCHER_H_ */ diff --git a/src/fsfw/events/eventmatching/EventMatchTree.cpp b/src/fsfw/events/eventmatching/EventMatchTree.cpp index 66e9e91a..b564e305 100644 --- a/src/fsfw/events/eventmatching/EventMatchTree.cpp +++ b/src/fsfw/events/eventmatching/EventMatchTree.cpp @@ -1,149 +1,145 @@ -#include "fsfw/events/eventmatching/EventIdRangeMatcher.h" #include "fsfw/events/eventmatching/EventMatchTree.h" + +#include "fsfw/events/eventmatching/EventIdRangeMatcher.h" #include "fsfw/events/eventmatching/ReporterRangeMatcher.h" #include "fsfw/events/eventmatching/SeverityRangeMatcher.h" -EventMatchTree::EventMatchTree(StorageManagerIF* storageBackend, - bool invertedMatch) : - MatchTree(end(), 1), factory(storageBackend), invertedMatch( - invertedMatch) { -} +EventMatchTree::EventMatchTree(StorageManagerIF* storageBackend, bool invertedMatch) + : MatchTree(end(), 1), factory(storageBackend), invertedMatch(invertedMatch) {} -EventMatchTree::~EventMatchTree() { -} +EventMatchTree::~EventMatchTree() {} bool EventMatchTree::match(EventMessage* number) { - if (invertedMatch) { - return !MatchTree::match(number); - } else { - return MatchTree::match(number); - } + if (invertedMatch) { + return !MatchTree::match(number); + } else { + return MatchTree::match(number); + } } -ReturnValue_t EventMatchTree::addMatch(EventId_t idFrom, EventId_t idTo, - bool idInverted, object_id_t reporterFrom, object_id_t reporterTo, - bool reporterInverted) { - if (idFrom == 0) { - //Assuming all events shall be forwarded. - idTo = 0; - idInverted = true; - } - if (idTo == 0) { - idTo = idFrom; - } - iterator lastTest; - ReturnValue_t result = findOrInsertRangeMatcher(begin(), idFrom, idTo, idInverted, &lastTest); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if (reporterFrom == 0) { - //No need to add another AND branch - return RETURN_OK; - } - if (reporterTo == 0) { - reporterTo = reporterFrom; - } - return findOrInsertRangeMatcher( - lastTest.left(), reporterFrom, reporterTo, reporterInverted, - &lastTest); +ReturnValue_t EventMatchTree::addMatch(EventId_t idFrom, EventId_t idTo, bool idInverted, + object_id_t reporterFrom, object_id_t reporterTo, + bool reporterInverted) { + if (idFrom == 0) { + // Assuming all events shall be forwarded. + idTo = 0; + idInverted = true; + } + if (idTo == 0) { + idTo = idFrom; + } + iterator lastTest; + ReturnValue_t result = findOrInsertRangeMatcher( + begin(), idFrom, idTo, idInverted, &lastTest); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (reporterFrom == 0) { + // No need to add another AND branch + return RETURN_OK; + } + if (reporterTo == 0) { + reporterTo = reporterFrom; + } + return findOrInsertRangeMatcher( + lastTest.left(), reporterFrom, reporterTo, reporterInverted, &lastTest); } -ReturnValue_t EventMatchTree::removeMatch(EventId_t idFrom, EventId_t idTo, - bool idInverted, object_id_t reporterFrom, object_id_t reporterTo, - bool reporterInverted) { +ReturnValue_t EventMatchTree::removeMatch(EventId_t idFrom, EventId_t idTo, bool idInverted, + object_id_t reporterFrom, object_id_t reporterTo, + bool reporterInverted) { + iterator foundElement; - iterator foundElement; - - if (idFrom == 0) { - //Assuming a "forward all events" request. - idTo = 0; - idInverted = true; - } - if (idTo == 0) { - idTo = idFrom; - } - foundElement = findRangeMatcher(begin(), - idFrom, idTo, idInverted); - if (foundElement == end()) { - return NO_MATCH; //Can't tell if too detailed or just not found. - } - if (reporterFrom == 0) { - if (foundElement.left() == end()) { - return removeElementAndReconnectChildren(foundElement); - } else { - return TOO_GENERAL_REQUEST; - } - } - if (reporterTo == 0) { - reporterTo = reporterFrom; - } - foundElement = findRangeMatcher( - foundElement.left(), reporterFrom, reporterTo, reporterInverted); - if (foundElement == end()) { - return NO_MATCH; - } else { - return removeElementAndReconnectChildren(foundElement); - } + if (idFrom == 0) { + // Assuming a "forward all events" request. + idTo = 0; + idInverted = true; + } + if (idTo == 0) { + idTo = idFrom; + } + foundElement = + findRangeMatcher(begin(), idFrom, idTo, idInverted); + if (foundElement == end()) { + return NO_MATCH; // Can't tell if too detailed or just not found. + } + if (reporterFrom == 0) { + if (foundElement.left() == end()) { + return removeElementAndReconnectChildren(foundElement); + } else { + return TOO_GENERAL_REQUEST; + } + } + if (reporterTo == 0) { + reporterTo = reporterFrom; + } + foundElement = findRangeMatcher( + foundElement.left(), reporterFrom, reporterTo, reporterInverted); + if (foundElement == end()) { + return NO_MATCH; + } else { + return removeElementAndReconnectChildren(foundElement); + } } -template -inline ReturnValue_t EventMatchTree::findOrInsertRangeMatcher(iterator start, - VALUE_T idFrom, VALUE_T idTo, bool inverted, iterator* lastTest) { - bool attachToBranch = AND; - iterator iter = start; - while (iter != end()) { - INSERTION_T* matcher = static_cast(*iter); - attachToBranch = OR; - *lastTest = iter; - if ((matcher->rangeMatcher.lowerBound == idFrom) - && (matcher->rangeMatcher.upperBound == idTo) - && (matcher->rangeMatcher.inverted == inverted)) { - return RETURN_OK; - } else { - iter = iter.right(); - } - } - //Only reached if nothing was found. - SerializeableMatcherIF* newContent = factory.generate< - INSERTION_T>(idFrom, idTo, inverted); - if (newContent == NULL) { - return FULL; - } - Node* newNode = factory.generate(newContent); - if (newNode == NULL) { - //Need to make sure partially generated content is deleted, otherwise, that's a leak. - factory.destroy(static_cast(newContent)); - return FULL; - } - *lastTest = insert(attachToBranch, *lastTest, newNode); - if (*lastTest == end()) { - //This actaully never fails, so creating a dedicated returncode seems an overshoot. - return RETURN_FAILED; - } - return RETURN_OK; +template +inline ReturnValue_t EventMatchTree::findOrInsertRangeMatcher(iterator start, VALUE_T idFrom, + VALUE_T idTo, bool inverted, + iterator* lastTest) { + bool attachToBranch = AND; + iterator iter = start; + while (iter != end()) { + INSERTION_T* matcher = static_cast(*iter); + attachToBranch = OR; + *lastTest = iter; + if ((matcher->rangeMatcher.lowerBound == idFrom) && + (matcher->rangeMatcher.upperBound == idTo) && + (matcher->rangeMatcher.inverted == inverted)) { + return RETURN_OK; + } else { + iter = iter.right(); + } + } + // Only reached if nothing was found. + SerializeableMatcherIF* newContent = + factory.generate(idFrom, idTo, inverted); + if (newContent == NULL) { + return FULL; + } + Node* newNode = factory.generate(newContent); + if (newNode == NULL) { + // Need to make sure partially generated content is deleted, otherwise, that's a leak. + factory.destroy(static_cast(newContent)); + return FULL; + } + *lastTest = insert(attachToBranch, *lastTest, newNode); + if (*lastTest == end()) { + // This actaully never fails, so creating a dedicated returncode seems an overshoot. + return RETURN_FAILED; + } + return RETURN_OK; } -template -EventMatchTree::iterator EventMatchTree::findRangeMatcher(iterator start, - VALUE_T idFrom, VALUE_T idTo, bool inverted) { - iterator iter = start; - while (iter != end()) { - INSERTION_T* matcher = static_cast(*iter); - if ((matcher->rangeMatcher.lowerBound == idFrom) - && (matcher->rangeMatcher.upperBound == idTo) - && (matcher->rangeMatcher.inverted == inverted)) { - break; - } else { - iter = iter.right(); //next OR element - } - } - return iter; +template +EventMatchTree::iterator EventMatchTree::findRangeMatcher(iterator start, VALUE_T idFrom, + VALUE_T idTo, bool inverted) { + iterator iter = start; + while (iter != end()) { + INSERTION_T* matcher = static_cast(*iter); + if ((matcher->rangeMatcher.lowerBound == idFrom) && + (matcher->rangeMatcher.upperBound == idTo) && + (matcher->rangeMatcher.inverted == inverted)) { + break; + } else { + iter = iter.right(); // next OR element + } + } + return iter; } ReturnValue_t EventMatchTree::cleanUpElement(iterator position) { - factory.destroy(position.element->value); - //If deletion fails, delete element anyway, nothing we can do. - //SHOULDO: Throw event, or write debug output. - return factory.destroy(position.element); + factory.destroy(position.element->value); + // If deletion fails, delete element anyway, nothing we can do. + // SHOULDO: Throw event, or write debug output. + return factory.destroy(position.element); } diff --git a/src/fsfw/events/eventmatching/EventMatchTree.h b/src/fsfw/events/eventmatching/EventMatchTree.h index 82a6de81..010e0623 100644 --- a/src/fsfw/events/eventmatching/EventMatchTree.h +++ b/src/fsfw/events/eventmatching/EventMatchTree.h @@ -7,30 +7,30 @@ #include "../../returnvalues/HasReturnvaluesIF.h" class StorageManagerIF; -class EventMatchTree: public MatchTree, public HasReturnvaluesIF { -public: - EventMatchTree(StorageManagerIF* storageBackend, bool invertedMatch); - virtual ~EventMatchTree(); - ReturnValue_t addMatch(EventId_t idFrom = 0, EventId_t idTo = 0, bool idInverted = false, - object_id_t reporterFrom = 0, object_id_t reporterTo = 0, - bool reporterInverted = false); - ReturnValue_t removeMatch(EventId_t idFrom = 0, EventId_t idTo = 0, bool idInverted = false, - object_id_t reporterFrom = 0, object_id_t reporterTo = 0, - bool reporterInverted = false); - bool match(EventMessage* number); -protected: - ReturnValue_t cleanUpElement(iterator position); -private: - PlacementFactory factory; - bool invertedMatch; - template - ReturnValue_t findOrInsertRangeMatcher(iterator start, VALUE_T idFrom, - VALUE_T idTo, bool inverted, iterator* lastTest); +class EventMatchTree : public MatchTree, public HasReturnvaluesIF { + public: + EventMatchTree(StorageManagerIF* storageBackend, bool invertedMatch); + virtual ~EventMatchTree(); + ReturnValue_t addMatch(EventId_t idFrom = 0, EventId_t idTo = 0, bool idInverted = false, + object_id_t reporterFrom = 0, object_id_t reporterTo = 0, + bool reporterInverted = false); + ReturnValue_t removeMatch(EventId_t idFrom = 0, EventId_t idTo = 0, bool idInverted = false, + object_id_t reporterFrom = 0, object_id_t reporterTo = 0, + bool reporterInverted = false); + bool match(EventMessage* number); - template - iterator findRangeMatcher(iterator start, VALUE_T idFrom, VALUE_T idTo, - bool inverted); + protected: + ReturnValue_t cleanUpElement(iterator position); + private: + PlacementFactory factory; + bool invertedMatch; + template + ReturnValue_t findOrInsertRangeMatcher(iterator start, VALUE_T idFrom, VALUE_T idTo, + bool inverted, iterator* lastTest); + + template + iterator findRangeMatcher(iterator start, VALUE_T idFrom, VALUE_T idTo, bool inverted); }; #endif /* FRAMEWORK_EVENTS_EVENTMATCHING_EVENTMATCHTREE_H_ */ diff --git a/src/fsfw/events/eventmatching/EventRangeMatcherBase.h b/src/fsfw/events/eventmatching/EventRangeMatcherBase.h index e9d57f1c..dbdc589e 100644 --- a/src/fsfw/events/eventmatching/EventRangeMatcherBase.h +++ b/src/fsfw/events/eventmatching/EventRangeMatcherBase.h @@ -6,24 +6,23 @@ #include "../../globalfunctions/matching/SerializeableMatcherIF.h" template -class EventRangeMatcherBase: public SerializeableMatcherIF { - friend class EventMatchTree; -public: - EventRangeMatcherBase(T from, T till, bool inverted) : rangeMatcher(from, till, inverted) { } - virtual ~EventRangeMatcherBase() { } - ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const { - return rangeMatcher.serialize(buffer, size, maxSize, streamEndianness); - } - size_t getSerializedSize() const { - return rangeMatcher.getSerializedSize(); - } - ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) { - return rangeMatcher.deSerialize(buffer, size, streamEndianness); - } -protected: - RangeMatcher rangeMatcher; +class EventRangeMatcherBase : public SerializeableMatcherIF { + friend class EventMatchTree; + + public: + EventRangeMatcherBase(T from, T till, bool inverted) : rangeMatcher(from, till, inverted) {} + virtual ~EventRangeMatcherBase() {} + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const { + return rangeMatcher.serialize(buffer, size, maxSize, streamEndianness); + } + size_t getSerializedSize() const { return rangeMatcher.getSerializedSize(); } + ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, Endianness streamEndianness) { + return rangeMatcher.deSerialize(buffer, size, streamEndianness); + } + + protected: + RangeMatcher rangeMatcher; }; #endif /* FRAMEWORK_EVENTS_EVENTMATCHING_EVENTRANGEMATCHERBASE_H_ */ diff --git a/src/fsfw/events/eventmatching/ReporterRangeMatcher.cpp b/src/fsfw/events/eventmatching/ReporterRangeMatcher.cpp index fc3a2f9f..3c7719a2 100644 --- a/src/fsfw/events/eventmatching/ReporterRangeMatcher.cpp +++ b/src/fsfw/events/eventmatching/ReporterRangeMatcher.cpp @@ -1,13 +1,10 @@ #include "fsfw/events/eventmatching/ReporterRangeMatcher.h" -ReporterRangeMatcher::ReporterRangeMatcher(object_id_t lower, object_id_t upper, - bool inverted) : EventRangeMatcherBase(lower, upper, inverted) { -} +ReporterRangeMatcher::ReporterRangeMatcher(object_id_t lower, object_id_t upper, bool inverted) + : EventRangeMatcherBase(lower, upper, inverted) {} -ReporterRangeMatcher::~ReporterRangeMatcher() { - -} +ReporterRangeMatcher::~ReporterRangeMatcher() {} bool ReporterRangeMatcher::match(EventMessage* message) { - return rangeMatcher.match(message->getReporter()); + return rangeMatcher.match(message->getReporter()); } diff --git a/src/fsfw/events/eventmatching/ReporterRangeMatcher.h b/src/fsfw/events/eventmatching/ReporterRangeMatcher.h index 9a0a5fcf..8d4f2d97 100644 --- a/src/fsfw/events/eventmatching/ReporterRangeMatcher.h +++ b/src/fsfw/events/eventmatching/ReporterRangeMatcher.h @@ -3,11 +3,11 @@ #include "EventRangeMatcherBase.h" -class ReporterRangeMatcher: public EventRangeMatcherBase { -public: - ReporterRangeMatcher(object_id_t lower, object_id_t upper, bool inverted); - ~ReporterRangeMatcher(); - bool match(EventMessage* message); +class ReporterRangeMatcher : public EventRangeMatcherBase { + public: + ReporterRangeMatcher(object_id_t lower, object_id_t upper, bool inverted); + ~ReporterRangeMatcher(); + bool match(EventMessage* message); }; #endif /* FRAMEWORK_EVENTS_EVENTMATCHING_REPORTERRANGEMATCHER_H_ */ diff --git a/src/fsfw/events/eventmatching/SeverityRangeMatcher.cpp b/src/fsfw/events/eventmatching/SeverityRangeMatcher.cpp index 230e4e77..aa5dfe17 100644 --- a/src/fsfw/events/eventmatching/SeverityRangeMatcher.cpp +++ b/src/fsfw/events/eventmatching/SeverityRangeMatcher.cpp @@ -1,14 +1,14 @@ #include "fsfw/events/eventmatching/SeverityRangeMatcher.h" + #include "fsfw/events/EventMessage.h" #include "fsfw/serialize/SerializeAdapter.h" -SeverityRangeMatcher::SeverityRangeMatcher(EventSeverity_t from, - EventSeverity_t till, bool inverted) : EventRangeMatcherBase(from, till, inverted) { -} +SeverityRangeMatcher::SeverityRangeMatcher(EventSeverity_t from, EventSeverity_t till, + bool inverted) + : EventRangeMatcherBase(from, till, inverted) {} -SeverityRangeMatcher::~SeverityRangeMatcher() { -} +SeverityRangeMatcher::~SeverityRangeMatcher() {} bool SeverityRangeMatcher::match(EventMessage* message) { - return rangeMatcher.match(message->getSeverity()); + return rangeMatcher.match(message->getSeverity()); } diff --git a/src/fsfw/events/eventmatching/SeverityRangeMatcher.h b/src/fsfw/events/eventmatching/SeverityRangeMatcher.h index 3f7cc418..db10a449 100644 --- a/src/fsfw/events/eventmatching/SeverityRangeMatcher.h +++ b/src/fsfw/events/eventmatching/SeverityRangeMatcher.h @@ -3,11 +3,11 @@ #include "EventRangeMatcherBase.h" -class SeverityRangeMatcher: public EventRangeMatcherBase { -public: - SeverityRangeMatcher(EventSeverity_t from, EventSeverity_t till, bool inverted); - ~SeverityRangeMatcher(); - bool match(EventMessage* message); +class SeverityRangeMatcher : public EventRangeMatcherBase { + public: + SeverityRangeMatcher(EventSeverity_t from, EventSeverity_t till, bool inverted); + ~SeverityRangeMatcher(); + bool match(EventMessage* message); }; #endif /* FRAMEWORK_EVENTS_EVENTMATCHING_SEVERITYRANGEMATCHER_H_ */ diff --git a/src/fsfw/events/eventmatching/eventmatching.h b/src/fsfw/events/eventmatching/eventmatching.h index 7a87e177..819c8328 100644 --- a/src/fsfw/events/eventmatching/eventmatching.h +++ b/src/fsfw/events/eventmatching/eventmatching.h @@ -6,5 +6,4 @@ #include "ReporterRangeMatcher.h" #include "SeverityRangeMatcher.h" - #endif /* EVENTMATCHING_H_ */ diff --git a/src/fsfw/events/fwSubsystemIdRanges.h b/src/fsfw/events/fwSubsystemIdRanges.h index 08fb878d..21123600 100644 --- a/src/fsfw/events/fwSubsystemIdRanges.h +++ b/src/fsfw/events/fwSubsystemIdRanges.h @@ -4,35 +4,35 @@ #include namespace SUBSYSTEM_ID { -enum: uint8_t { - MEMORY = 22, - OBSW = 26, - CDH = 28, - TCS_1 = 59, - PCDU_1 = 42, - PCDU_2 = 43, - HEATER = 50, - T_SENSORS = 52, - FDIR = 70, - FDIR_1 = 71, - FDIR_2 = 72, - HK = 73, - SYSTEM_MANAGER = 74, - SYSTEM_MANAGER_1 = 75, - SYSTEM_1 = 79, - PUS_SERVICE_1 = 80, - PUS_SERVICE_2 = 82, - PUS_SERVICE_3 = 83, - PUS_SERVICE_5 = 85, - PUS_SERVICE_6 = 86, - PUS_SERVICE_8 = 88, - PUS_SERVICE_9 = 89, - PUS_SERVICE_17 = 97, - PUS_SERVICE_23 = 103, - MGM_LIS3MDL = 106, - MGM_RM3100 = 107, +enum : uint8_t { + MEMORY = 22, + OBSW = 26, + CDH = 28, + TCS_1 = 59, + PCDU_1 = 42, + PCDU_2 = 43, + HEATER = 50, + T_SENSORS = 52, + FDIR = 70, + FDIR_1 = 71, + FDIR_2 = 72, + HK = 73, + SYSTEM_MANAGER = 74, + SYSTEM_MANAGER_1 = 75, + SYSTEM_1 = 79, + PUS_SERVICE_1 = 80, + PUS_SERVICE_2 = 82, + PUS_SERVICE_3 = 83, + PUS_SERVICE_5 = 85, + PUS_SERVICE_6 = 86, + PUS_SERVICE_8 = 88, + PUS_SERVICE_9 = 89, + PUS_SERVICE_17 = 97, + PUS_SERVICE_23 = 103, + MGM_LIS3MDL = 106, + MGM_RM3100 = 107, - FW_SUBSYSTEM_ID_RANGE + FW_SUBSYSTEM_ID_RANGE }; } diff --git a/src/fsfw/fdir/ConfirmsFailuresIF.h b/src/fsfw/fdir/ConfirmsFailuresIF.h index 14411461..e4d26907 100644 --- a/src/fsfw/fdir/ConfirmsFailuresIF.h +++ b/src/fsfw/fdir/ConfirmsFailuresIF.h @@ -1,19 +1,17 @@ #ifndef FRAMEWORK_FDIR_CONFIRMSFAILURESIF_H_ #define FRAMEWORK_FDIR_CONFIRMSFAILURESIF_H_ -#include "../returnvalues/HasReturnvaluesIF.h" #include "../ipc/MessageQueueSenderIF.h" +#include "../returnvalues/HasReturnvaluesIF.h" class ConfirmsFailuresIF { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::HANDLES_FAILURES_IF; - static const ReturnValue_t YOUR_FAULT = MAKE_RETURN_CODE(0); - static const ReturnValue_t MY_FAULT = MAKE_RETURN_CODE(1); - static const ReturnValue_t CONFIRM_LATER = MAKE_RETURN_CODE(2); - virtual ~ConfirmsFailuresIF() {} - virtual MessageQueueId_t getEventReceptionQueue() = 0; + public: + static const uint8_t INTERFACE_ID = CLASS_ID::HANDLES_FAILURES_IF; + static const ReturnValue_t YOUR_FAULT = MAKE_RETURN_CODE(0); + static const ReturnValue_t MY_FAULT = MAKE_RETURN_CODE(1); + static const ReturnValue_t CONFIRM_LATER = MAKE_RETURN_CODE(2); + virtual ~ConfirmsFailuresIF() {} + virtual MessageQueueId_t getEventReceptionQueue() = 0; }; - - #endif /* FRAMEWORK_FDIR_CONFIRMSFAILURESIF_H_ */ diff --git a/src/fsfw/fdir/EventCorrelation.cpp b/src/fsfw/fdir/EventCorrelation.cpp index 5b023334..5eb384d6 100644 --- a/src/fsfw/fdir/EventCorrelation.cpp +++ b/src/fsfw/fdir/EventCorrelation.cpp @@ -1,44 +1,42 @@ #include "fsfw/fdir/EventCorrelation.h" -EventCorrelation::EventCorrelation(uint32_t timeout) : - eventPending(false) { - correlationTimer.setTimeout(timeout); +EventCorrelation::EventCorrelation(uint32_t timeout) : eventPending(false) { + correlationTimer.setTimeout(timeout); } -EventCorrelation::~EventCorrelation() { -} +EventCorrelation::~EventCorrelation() {} EventCorrelation::State EventCorrelation::doesEventCorrelate() { - if (correlationTimer.isBusy()) { - eventPending = false; - return CORRELATED; - } else { - if (eventPending) { - return ALREADY_STARTED; - } else { - eventPending = true; - correlationTimer.resetTimer(); - return CORRELATION_STARTED; - } - } + if (correlationTimer.isBusy()) { + eventPending = false; + return CORRELATED; + } else { + if (eventPending) { + return ALREADY_STARTED; + } else { + eventPending = true; + correlationTimer.resetTimer(); + return CORRELATION_STARTED; + } + } } bool EventCorrelation::isEventPending() { - if (eventPending) { - eventPending = false; - return true; - } else { - correlationTimer.resetTimer(); - return false; - } + if (eventPending) { + eventPending = false; + return true; + } else { + correlationTimer.resetTimer(); + return false; + } } bool EventCorrelation::hasPendingEventTimedOut() { - if (correlationTimer.hasTimedOut()) { - bool temp = eventPending; - eventPending = false; - return temp; - } else { - return false; - } + if (correlationTimer.hasTimedOut()) { + bool temp = eventPending; + eventPending = false; + return temp; + } else { + return false; + } } diff --git a/src/fsfw/fdir/EventCorrelation.h b/src/fsfw/fdir/EventCorrelation.h index b8793edf..e7949777 100644 --- a/src/fsfw/fdir/EventCorrelation.h +++ b/src/fsfw/fdir/EventCorrelation.h @@ -4,20 +4,17 @@ #include "../timemanager/Countdown.h" class EventCorrelation { -public: - enum State { - CORRELATION_STARTED, - CORRELATED, - ALREADY_STARTED - }; - EventCorrelation(uint32_t timeout); - ~EventCorrelation(); - EventCorrelation::State doesEventCorrelate(); - bool isEventPending(); - bool hasPendingEventTimedOut(); - Countdown correlationTimer; -private: - bool eventPending; + public: + enum State { CORRELATION_STARTED, CORRELATED, ALREADY_STARTED }; + EventCorrelation(uint32_t timeout); + ~EventCorrelation(); + EventCorrelation::State doesEventCorrelate(); + bool isEventPending(); + bool hasPendingEventTimedOut(); + Countdown correlationTimer; + + private: + bool eventPending; }; #endif /* FRAMEWORK_FDIR_EVENTCORRELATION_H_ */ diff --git a/src/fsfw/fdir/FailureIsolationBase.cpp b/src/fsfw/fdir/FailureIsolationBase.cpp index 717e5072..fedef869 100644 --- a/src/fsfw/fdir/FailureIsolationBase.cpp +++ b/src/fsfw/fdir/FailureIsolationBase.cpp @@ -1,172 +1,162 @@ -#include "fsfw/events/EventManagerIF.h" #include "fsfw/fdir/FailureIsolationBase.h" + +#include "fsfw/events/EventManagerIF.h" #include "fsfw/health/HasHealthIF.h" #include "fsfw/health/HealthMessage.h" #include "fsfw/ipc/QueueFactory.h" #include "fsfw/objectmanager/ObjectManager.h" -FailureIsolationBase::FailureIsolationBase(object_id_t owner, - object_id_t parent, uint8_t messageDepth, uint8_t parameterDomainBase) : - ownerId(owner), faultTreeParent(parent), - parameterDomainBase(parameterDomainBase) { - eventQueue = QueueFactory::instance()->createMessageQueue(messageDepth, - EventMessage::EVENT_MESSAGE_SIZE); +FailureIsolationBase::FailureIsolationBase(object_id_t owner, object_id_t parent, + uint8_t messageDepth, uint8_t parameterDomainBase) + : ownerId(owner), faultTreeParent(parent), parameterDomainBase(parameterDomainBase) { + eventQueue = + QueueFactory::instance()->createMessageQueue(messageDepth, EventMessage::EVENT_MESSAGE_SIZE); } FailureIsolationBase::~FailureIsolationBase() { - QueueFactory::instance()->deleteMessageQueue(eventQueue); + QueueFactory::instance()->deleteMessageQueue(eventQueue); } ReturnValue_t FailureIsolationBase::initialize() { - EventManagerIF* manager = ObjectManager::instance()->get( - objects::EVENT_MANAGER); - if (manager == nullptr) { + EventManagerIF* manager = ObjectManager::instance()->get(objects::EVENT_MANAGER); + if (manager == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "FailureIsolationBase::initialize: Event Manager has not" - " been initialized!" << std::endl; + sif::error << "FailureIsolationBase::initialize: Event Manager has not" + " been initialized!" + << std::endl; #endif - return RETURN_FAILED; - } - ReturnValue_t result = manager->registerListener(eventQueue->getId()); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if (ownerId != objects::NO_OBJECT) { - result = manager->subscribeToAllEventsFrom(eventQueue->getId(), ownerId); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - owner = ObjectManager::instance()->get(ownerId); - if (owner == nullptr) { + return RETURN_FAILED; + } + ReturnValue_t result = manager->registerListener(eventQueue->getId()); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (ownerId != objects::NO_OBJECT) { + result = manager->subscribeToAllEventsFrom(eventQueue->getId(), ownerId); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + owner = ObjectManager::instance()->get(ownerId); + if (owner == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "FailureIsolationBase::intialize: Owner object " - "invalid. Make sure it implements HasHealthIF" << std::endl; + sif::error << "FailureIsolationBase::intialize: Owner object " + "invalid. Make sure it implements HasHealthIF" + << std::endl; #endif - return ObjectManagerIF::CHILD_INIT_FAILED; - } - } - if (faultTreeParent != objects::NO_OBJECT) { - ConfirmsFailuresIF* parentIF = ObjectManager::instance()->get( - faultTreeParent); - if (parentIF == nullptr) { + return ObjectManagerIF::CHILD_INIT_FAILED; + } + } + if (faultTreeParent != objects::NO_OBJECT) { + ConfirmsFailuresIF* parentIF = + ObjectManager::instance()->get(faultTreeParent); + if (parentIF == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "FailureIsolationBase::intialize: Parent object" - << "invalid." << std::endl; + sif::error << "FailureIsolationBase::intialize: Parent object" + << "invalid." << std::endl; #endif #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Make sure it implements ConfirmsFailuresIF." - << std::endl; + sif::error << "Make sure it implements ConfirmsFailuresIF." << std::endl; #endif - return ObjectManagerIF::CHILD_INIT_FAILED; - return RETURN_FAILED; - } - eventQueue->setDefaultDestination(parentIF->getEventReceptionQueue()); - } - return RETURN_OK; + return ObjectManagerIF::CHILD_INIT_FAILED; + return RETURN_FAILED; + } + eventQueue->setDefaultDestination(parentIF->getEventReceptionQueue()); + } + return RETURN_OK; } void FailureIsolationBase::checkForFailures() { - EventMessage event; - for (ReturnValue_t result = eventQueue->receiveMessage(&event); - result == RETURN_OK; result = eventQueue->receiveMessage(&event)) { - if (event.getSender() == eventQueue->getId()) { - //We already got this event, because we sent it. - continue; - } - switch (event.getMessageId()) { - case EventMessage::EVENT_MESSAGE: - if (isFdirDisabledForSeverity(event.getSeverity())) { - //We do not handle events when disabled. - continue; - } - eventReceived(&event); - break; - case EventMessage::CONFIRMATION_REQUEST: - doConfirmFault(&event); - break; - case EventMessage::YOUR_FAULT: - eventConfirmed(&event); - break; - case EventMessage::MY_FAULT: - wasParentsFault(&event); - break; - default: - break; - } - } - decrementFaultCounters(); + EventMessage event; + for (ReturnValue_t result = eventQueue->receiveMessage(&event); result == RETURN_OK; + result = eventQueue->receiveMessage(&event)) { + if (event.getSender() == eventQueue->getId()) { + // We already got this event, because we sent it. + continue; + } + switch (event.getMessageId()) { + case EventMessage::EVENT_MESSAGE: + if (isFdirDisabledForSeverity(event.getSeverity())) { + // We do not handle events when disabled. + continue; + } + eventReceived(&event); + break; + case EventMessage::CONFIRMATION_REQUEST: + doConfirmFault(&event); + break; + case EventMessage::YOUR_FAULT: + eventConfirmed(&event); + break; + case EventMessage::MY_FAULT: + wasParentsFault(&event); + break; + default: + break; + } + } + decrementFaultCounters(); } void FailureIsolationBase::setOwnerHealth(HasHealthIF::HealthState health) { - if (owner != NULL) { - owner->setHealth(health); - } - //else: owner has no health. - + if (owner != NULL) { + owner->setHealth(health); + } + // else: owner has no health. } -MessageQueueId_t FailureIsolationBase::getEventReceptionQueue() { - return eventQueue->getId(); -} +MessageQueueId_t FailureIsolationBase::getEventReceptionQueue() { return eventQueue->getId(); } ReturnValue_t FailureIsolationBase::sendConfirmationRequest(EventMessage* event, - MessageQueueId_t destination) { - event->setMessageId(EventMessage::CONFIRMATION_REQUEST); - if (destination != MessageQueueIF::NO_QUEUE) { - return eventQueue->sendMessage(destination, event); - } else if (faultTreeParent != objects::NO_OBJECT) { - return eventQueue->sendToDefault(event); - } - return RETURN_FAILED; + MessageQueueId_t destination) { + event->setMessageId(EventMessage::CONFIRMATION_REQUEST); + if (destination != MessageQueueIF::NO_QUEUE) { + return eventQueue->sendMessage(destination, event); + } else if (faultTreeParent != objects::NO_OBJECT) { + return eventQueue->sendToDefault(event); + } + return RETURN_FAILED; } -void FailureIsolationBase::eventConfirmed(EventMessage* event) { -} +void FailureIsolationBase::eventConfirmed(EventMessage* event) {} -void FailureIsolationBase::wasParentsFault(EventMessage* event) { -} +void FailureIsolationBase::wasParentsFault(EventMessage* event) {} void FailureIsolationBase::doConfirmFault(EventMessage* event) { - ReturnValue_t result = confirmFault(event); - if (result == YOUR_FAULT) { - event->setMessageId(EventMessage::YOUR_FAULT); - eventQueue->reply(event); - } else if (result == MY_FAULT) { - event->setMessageId(EventMessage::MY_FAULT); - eventQueue->reply(event); - } else { - - } + ReturnValue_t result = confirmFault(event); + if (result == YOUR_FAULT) { + event->setMessageId(EventMessage::YOUR_FAULT); + eventQueue->reply(event); + } else if (result == MY_FAULT) { + event->setMessageId(EventMessage::MY_FAULT); + eventQueue->reply(event); + } else { + } } -ReturnValue_t FailureIsolationBase::confirmFault(EventMessage* event) { - return YOUR_FAULT; -} +ReturnValue_t FailureIsolationBase::confirmFault(EventMessage* event) { return YOUR_FAULT; } -void FailureIsolationBase::triggerEvent(Event event, uint32_t parameter1, - uint32_t parameter2) { - //With this mechanism, all events are disabled for a certain device. - //That's not so good for visibility. - if (isFdirDisabledForSeverity(event::getSeverity(event))) { - return; - } - EventMessage message(event, ownerId, parameter1, parameter2); - EventManagerIF::triggerEvent(&message, eventQueue->getId()); - eventReceived(&message); +void FailureIsolationBase::triggerEvent(Event event, uint32_t parameter1, uint32_t parameter2) { + // With this mechanism, all events are disabled for a certain device. + // That's not so good for visibility. + if (isFdirDisabledForSeverity(event::getSeverity(event))) { + return; + } + EventMessage message(event, ownerId, parameter1, parameter2); + EventManagerIF::triggerEvent(&message, eventQueue->getId()); + eventReceived(&message); } bool FailureIsolationBase::isFdirDisabledForSeverity(EventSeverity_t severity) { - if ((owner != NULL) && (severity != severity::INFO)) { - if (owner->getHealth() == HasHealthIF::EXTERNAL_CONTROL) { - //External control disables handling of fault messages. - return true; - } - } - return false; + if ((owner != NULL) && (severity != severity::INFO)) { + if (owner->getHealth() == HasHealthIF::EXTERNAL_CONTROL) { + // External control disables handling of fault messages. + return true; + } + } + return false; } -void FailureIsolationBase::throwFdirEvent(Event event, uint32_t parameter1, - uint32_t parameter2) { - EventMessage message(event, ownerId, parameter1, parameter2); - EventManagerIF::triggerEvent(&message, eventQueue->getId()); +void FailureIsolationBase::throwFdirEvent(Event event, uint32_t parameter1, uint32_t parameter2) { + EventMessage message(event, ownerId, parameter1, parameter2); + EventManagerIF::triggerEvent(&message, eventQueue->getId()); } diff --git a/src/fsfw/fdir/FailureIsolationBase.h b/src/fsfw/fdir/FailureIsolationBase.h index 4a3f5adf..85d18add 100644 --- a/src/fsfw/fdir/FailureIsolationBase.h +++ b/src/fsfw/fdir/FailureIsolationBase.h @@ -2,55 +2,58 @@ #define FRAMEWORK_FDIR_FAILUREISOLATIONBASE_H_ #include "../events/EventMessage.h" -#include "ConfirmsFailuresIF.h" -#include "FaultCounter.h" #include "../health/HealthMessage.h" +#include "../ipc/MessageQueueIF.h" #include "../parameters/HasParametersIF.h" #include "../returnvalues/HasReturnvaluesIF.h" -#include "../ipc/MessageQueueIF.h" +#include "ConfirmsFailuresIF.h" +#include "FaultCounter.h" -class FailureIsolationBase: public HasReturnvaluesIF, - public ConfirmsFailuresIF, - public HasParametersIF { -public: - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::FDIR_1; - static const Event FDIR_CHANGED_STATE = MAKE_EVENT(1, severity::INFO); //!< FDIR has an internal state, which changed from par2 (oldState) to par1 (newState). - static const Event FDIR_STARTS_RECOVERY = MAKE_EVENT(2, severity::MEDIUM); //!< FDIR tries to restart device. Par1: event that caused recovery. - static const Event FDIR_TURNS_OFF_DEVICE = MAKE_EVENT(3, severity::MEDIUM); //!< FDIR turns off device. Par1: event that caused recovery. +class FailureIsolationBase : public HasReturnvaluesIF, + public ConfirmsFailuresIF, + public HasParametersIF { + public: + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::FDIR_1; + static const Event FDIR_CHANGED_STATE = + MAKE_EVENT(1, severity::INFO); //!< FDIR has an internal state, which changed from par2 + //!< (oldState) to par1 (newState). + static const Event FDIR_STARTS_RECOVERY = MAKE_EVENT( + 2, severity::MEDIUM); //!< FDIR tries to restart device. Par1: event that caused recovery. + static const Event FDIR_TURNS_OFF_DEVICE = MAKE_EVENT( + 3, severity::MEDIUM); //!< FDIR turns off device. Par1: event that caused recovery. - FailureIsolationBase(object_id_t owner, - object_id_t parent = objects::NO_OBJECT, - uint8_t messageDepth = 10, uint8_t parameterDomainBase = 0xF0); + FailureIsolationBase(object_id_t owner, object_id_t parent = objects::NO_OBJECT, + uint8_t messageDepth = 10, uint8_t parameterDomainBase = 0xF0); - virtual ~FailureIsolationBase(); - virtual ReturnValue_t initialize(); + virtual ~FailureIsolationBase(); + virtual ReturnValue_t initialize(); - /** - * This is called by the DHB in performOperation() - */ - void checkForFailures(); - MessageQueueId_t getEventReceptionQueue() override; - virtual void triggerEvent(Event event, uint32_t parameter1 = 0, - uint32_t parameter2 = 0); -protected: - MessageQueueIF* eventQueue = nullptr; - object_id_t ownerId; - HasHealthIF* owner = nullptr; - object_id_t faultTreeParent; - uint8_t parameterDomainBase; - void setOwnerHealth(HasHealthIF::HealthState health); - virtual ReturnValue_t eventReceived(EventMessage* event) = 0; - virtual void eventConfirmed(EventMessage* event); - virtual void wasParentsFault(EventMessage* event); - virtual ReturnValue_t confirmFault(EventMessage* event); - virtual void decrementFaultCounters() = 0; - ReturnValue_t sendConfirmationRequest(EventMessage* event, - MessageQueueId_t destination = MessageQueueIF::NO_QUEUE); - void throwFdirEvent(Event event, uint32_t parameter1 = 0, - uint32_t parameter2 = 0); -private: - void doConfirmFault(EventMessage* event);bool isFdirDisabledForSeverity( - EventSeverity_t severity); + /** + * This is called by the DHB in performOperation() + */ + void checkForFailures(); + MessageQueueId_t getEventReceptionQueue() override; + virtual void triggerEvent(Event event, uint32_t parameter1 = 0, uint32_t parameter2 = 0); + + protected: + MessageQueueIF* eventQueue = nullptr; + object_id_t ownerId; + HasHealthIF* owner = nullptr; + object_id_t faultTreeParent; + uint8_t parameterDomainBase; + void setOwnerHealth(HasHealthIF::HealthState health); + virtual ReturnValue_t eventReceived(EventMessage* event) = 0; + virtual void eventConfirmed(EventMessage* event); + virtual void wasParentsFault(EventMessage* event); + virtual ReturnValue_t confirmFault(EventMessage* event); + virtual void decrementFaultCounters() = 0; + ReturnValue_t sendConfirmationRequest(EventMessage* event, + MessageQueueId_t destination = MessageQueueIF::NO_QUEUE); + void throwFdirEvent(Event event, uint32_t parameter1 = 0, uint32_t parameter2 = 0); + + private: + void doConfirmFault(EventMessage* event); + bool isFdirDisabledForSeverity(EventSeverity_t severity); }; #endif /* FRAMEWORK_FDIR_FAILUREISOLATIONBASE_H_ */ diff --git a/src/fsfw/fdir/FaultCounter.cpp b/src/fsfw/fdir/FaultCounter.cpp index 0b30a67d..e87cf613 100644 --- a/src/fsfw/fdir/FaultCounter.cpp +++ b/src/fsfw/fdir/FaultCounter.cpp @@ -1,86 +1,79 @@ #include "fsfw/fdir/FaultCounter.h" FaultCounter::FaultCounter(uint32_t failureThreshold, uint32_t decrementAfterMs, - uint8_t setParameterDomain) : - parameterDomain(setParameterDomain), timer(), faultCount(0), failureThreshold( - failureThreshold) { - timer.setTimeout(decrementAfterMs); + uint8_t setParameterDomain) + : parameterDomain(setParameterDomain), + timer(), + faultCount(0), + failureThreshold(failureThreshold) { + timer.setTimeout(decrementAfterMs); } -FaultCounter::~FaultCounter() { -} +FaultCounter::~FaultCounter() {} void FaultCounter::increment(uint32_t amount) { - if (faultCount == 0) { - timer.resetTimer(); - } - faultCount += amount; + if (faultCount == 0) { + timer.resetTimer(); + } + faultCount += amount; } bool FaultCounter::checkForDecrement() { - if (timer.hasTimedOut()) { - timer.resetTimer(); - if (faultCount > 0) { - faultCount--; - return true; - } - } - return false; + if (timer.hasTimedOut()) { + timer.resetTimer(); + if (faultCount > 0) { + faultCount--; + return true; + } + } + return false; } bool FaultCounter::incrementAndCheck(uint32_t amount) { - increment(amount); - return aboveThreshold(); + increment(amount); + return aboveThreshold(); } bool FaultCounter::aboveThreshold() { - if (faultCount > failureThreshold) { - faultCount = 0; - return true; - } else { - return false; - } + if (faultCount > failureThreshold) { + faultCount = 0; + return true; + } else { + return false; + } } -void FaultCounter::clear() { - faultCount = 0; -} +void FaultCounter::clear() { faultCount = 0; } void FaultCounter::setFailureThreshold(uint32_t failureThreshold) { - this->failureThreshold = failureThreshold; + this->failureThreshold = failureThreshold; } -void FaultCounter::setFaultDecrementTimeMs(uint32_t timeMs) { - timer.setTimeout(timeMs); -} +void FaultCounter::setFaultDecrementTimeMs(uint32_t timeMs) { timer.setTimeout(timeMs); } -FaultCounter::FaultCounter() : - parameterDomain(0), timer(), faultCount(0), failureThreshold(0) { -} +FaultCounter::FaultCounter() : parameterDomain(0), timer(), faultCount(0), failureThreshold(0) {} ReturnValue_t FaultCounter::getParameter(uint8_t domainId, uint8_t uniqueId, - ParameterWrapper* parameterWrapper, const ParameterWrapper* newValues, - uint16_t startAtIndex) { - if (domainId != parameterDomain) { - return INVALID_DOMAIN_ID; - } + ParameterWrapper* parameterWrapper, + const ParameterWrapper* newValues, uint16_t startAtIndex) { + if (domainId != parameterDomain) { + return INVALID_DOMAIN_ID; + } - switch (uniqueId) { - case 0: - parameterWrapper->set(failureThreshold); - break; - case 1: - parameterWrapper->set(faultCount); - break; - case 2: - parameterWrapper->set(timer.timeout); - break; - default: - return INVALID_IDENTIFIER_ID; - } - return HasReturnvaluesIF::RETURN_OK; + switch (uniqueId) { + case 0: + parameterWrapper->set(failureThreshold); + break; + case 1: + parameterWrapper->set(faultCount); + break; + case 2: + parameterWrapper->set(timer.timeout); + break; + default: + return INVALID_IDENTIFIER_ID; + } + return HasReturnvaluesIF::RETURN_OK; } -void FaultCounter::setParameterDomain(uint8_t domain) { - parameterDomain = domain; -} +void FaultCounter::setParameterDomain(uint8_t domain) { parameterDomain = domain; } diff --git a/src/fsfw/fdir/FaultCounter.h b/src/fsfw/fdir/FaultCounter.h index a85e8cf7..3b59885c 100644 --- a/src/fsfw/fdir/FaultCounter.h +++ b/src/fsfw/fdir/FaultCounter.h @@ -4,35 +4,36 @@ #include "fsfw/parameters/HasParametersIF.h" #include "fsfw/timemanager/Countdown.h" -class FaultCounter: public HasParametersIF { -public: - FaultCounter(); - FaultCounter(uint32_t failureThreshold, uint32_t decrementAfterMs, - uint8_t setParameterDomain = 0); - virtual ~FaultCounter(); +class FaultCounter : public HasParametersIF { + public: + FaultCounter(); + FaultCounter(uint32_t failureThreshold, uint32_t decrementAfterMs, + uint8_t setParameterDomain = 0); + virtual ~FaultCounter(); - bool incrementAndCheck(uint32_t amount = 1); + bool incrementAndCheck(uint32_t amount = 1); - void increment(uint32_t amount = 1); + void increment(uint32_t amount = 1); - bool checkForDecrement(); + bool checkForDecrement(); - bool aboveThreshold(); + bool aboveThreshold(); - void clear(); - void setFailureThreshold(uint32_t failureThreshold); - void setFaultDecrementTimeMs(uint32_t timeMs); + void clear(); + void setFailureThreshold(uint32_t failureThreshold); + void setFaultDecrementTimeMs(uint32_t timeMs); - virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, - ParameterWrapper *parameterWrapper, - const ParameterWrapper *newValues, uint16_t startAtIndex); + virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, + ParameterWrapper *parameterWrapper, + const ParameterWrapper *newValues, uint16_t startAtIndex); - void setParameterDomain(uint8_t domain); -private: - uint8_t parameterDomain; - Countdown timer; - uint32_t faultCount; - uint32_t failureThreshold; + void setParameterDomain(uint8_t domain); + + private: + uint8_t parameterDomain; + Countdown timer; + uint32_t faultCount; + uint32_t failureThreshold; }; #endif /* FSFW_FDIR_FAULTCOUNTER_H_ */ diff --git a/src/fsfw/globalfunctions/AsciiConverter.cpp b/src/fsfw/globalfunctions/AsciiConverter.cpp index 09908815..6d49c777 100644 --- a/src/fsfw/globalfunctions/AsciiConverter.cpp +++ b/src/fsfw/globalfunctions/AsciiConverter.cpp @@ -1,231 +1,228 @@ #include "fsfw/globalfunctions/AsciiConverter.h" -#include #include +#include -template -ReturnValue_t AsciiConverter::scanAsciiDecimalNumber(const uint8_t** dataPtr, - uint8_t len, T* value) { - if (len > std::numeric_limits().digits10) { - return TOO_LONG_FOR_TARGET_TYPE; - } +template +ReturnValue_t AsciiConverter::scanAsciiDecimalNumber(const uint8_t** dataPtr, uint8_t len, + T* value) { + if (len > std::numeric_limits().digits10) { + return TOO_LONG_FOR_TARGET_TYPE; + } - double temp; + double temp; - ReturnValue_t result = scanAsciiDecimalNumber_(dataPtr, len, &temp); + ReturnValue_t result = scanAsciiDecimalNumber_(dataPtr, len, &temp); - *value = temp; + *value = temp; - return result; + return result; } -ReturnValue_t AsciiConverter::scanAsciiHexByte(const uint8_t** dataPtr, - uint8_t* value) { - int8_t tmp; +ReturnValue_t AsciiConverter::scanAsciiHexByte(const uint8_t** dataPtr, uint8_t* value) { + int8_t tmp; - tmp = convertHexChar(*dataPtr); - (*dataPtr)++; - if (tmp == -1) { - return INVALID_CHARACTERS; - } - if (tmp == -2) { - tmp = 0; - } + tmp = convertHexChar(*dataPtr); + (*dataPtr)++; + if (tmp == -1) { + return INVALID_CHARACTERS; + } + if (tmp == -2) { + tmp = 0; + } - *value = tmp << 4; + *value = tmp << 4; - tmp = convertHexChar(*dataPtr); - (*dataPtr)++; - if (tmp == -1) { - return INVALID_CHARACTERS; - } - if (tmp != -2) { - *value += tmp; - } else { - *value = *value >> 4; - } + tmp = convertHexChar(*dataPtr); + (*dataPtr)++; + if (tmp == -1) { + return INVALID_CHARACTERS; + } + if (tmp != -2) { + *value += tmp; + } else { + *value = *value >> 4; + } - return RETURN_OK; + return RETURN_OK; } -ReturnValue_t AsciiConverter::scanAsciiDecimalNumber_(uint8_t const ** dataPtr, - uint8_t len, double* value) { +ReturnValue_t AsciiConverter::scanAsciiDecimalNumber_(uint8_t const** dataPtr, uint8_t len, + double* value) { + uint8_t const* ptr = *dataPtr; + int8_t sign = 1; + float decimal = 0; + bool abort = false; - uint8_t const *ptr = *dataPtr; - int8_t sign = 1; - float decimal = 0; - bool abort = false; + *value = 0; - *value = 0; + // ignore leading space + ptr = clearSpace(ptr, len); - //ignore leading space - ptr = clearSpace(ptr, len); + while ((ptr - *dataPtr < len) && !abort) { + switch (*ptr) { + case '+': + sign = 1; + break; + case '-': + sign = -1; + break; + case '.': + decimal = 1; + break; + case ' ': + case 0x0d: + case 0x0a: + // ignore trailing space + ptr = clearSpace(ptr, len - (ptr - *dataPtr)) - + 1; // before aborting the loop, ptr will be incremented + abort = true; + break; + default: + if ((*ptr < 0x30) || (*ptr > 0x39)) { + return INVALID_CHARACTERS; + } + *value = *value * 10 + (*ptr - 0x30); + if (decimal > 0) { + decimal *= 10; + } + break; + } + ptr++; + } - while ((ptr - *dataPtr < len) && !abort) { - switch (*ptr) { - case '+': - sign = 1; - break; - case '-': - sign = -1; - break; - case '.': - decimal = 1; - break; - case ' ': - case 0x0d: - case 0x0a: - //ignore trailing space - ptr = clearSpace(ptr, len - (ptr - *dataPtr)) - 1; //before aborting the loop, ptr will be incremented - abort = true; - break; - default: - if ((*ptr < 0x30) || (*ptr > 0x39)) { - return INVALID_CHARACTERS; - } - *value = *value * 10 + (*ptr - 0x30); - if (decimal > 0) { - decimal *= 10; - } - break; - } - ptr++; - } + if (decimal == 0) { + decimal = 1; + } - if (decimal == 0) { - decimal = 1; - } + *value = *value / (decimal)*sign; - *value = *value / (decimal) * sign; + *dataPtr = ptr; - *dataPtr = ptr; - - return RETURN_OK; + return RETURN_OK; } -ReturnValue_t AsciiConverter::printFloat(uint8_t* buffer, uint32_t bufferLength, - float value, uint8_t decimalPlaces, uint32_t *printedSize) { - *printedSize = 0; - uint32_t streamposition = 0, integerSize; - bool negative = (value < 0); - int32_t digits = bufferLength - decimalPlaces - 1; - if (digits <= 0) { - return BUFFER_TOO_SMALL; - } - if (negative) { - digits -= 1; - buffer[streamposition++] = '-'; - value = -value; - } - float maximumNumber = pow(10, digits); - if (value >= maximumNumber) { - return BUFFER_TOO_SMALL; - } - //print the numbers before the decimal point; - ReturnValue_t result = printInteger(buffer + streamposition, - bufferLength - streamposition - decimalPlaces - 1, value, - &integerSize); - if (result != RETURN_OK) { - return result; - } - streamposition += integerSize; - //The decimal Point - buffer[streamposition++] = '.'; +ReturnValue_t AsciiConverter::printFloat(uint8_t* buffer, uint32_t bufferLength, float value, + uint8_t decimalPlaces, uint32_t* printedSize) { + *printedSize = 0; + uint32_t streamposition = 0, integerSize; + bool negative = (value < 0); + int32_t digits = bufferLength - decimalPlaces - 1; + if (digits <= 0) { + return BUFFER_TOO_SMALL; + } + if (negative) { + digits -= 1; + buffer[streamposition++] = '-'; + value = -value; + } + float maximumNumber = pow(10, digits); + if (value >= maximumNumber) { + return BUFFER_TOO_SMALL; + } + // print the numbers before the decimal point; + ReturnValue_t result = + printInteger(buffer + streamposition, bufferLength - streamposition - decimalPlaces - 1, + value, &integerSize); + if (result != RETURN_OK) { + return result; + } + streamposition += integerSize; + // The decimal Point + buffer[streamposition++] = '.'; - //Print the decimals - uint32_t integerValue = value; - value -= integerValue; - value = value * pow(10, decimalPlaces); - result = printInteger(buffer + streamposition, decimalPlaces, round(value), - &integerSize, true); - *printedSize = integerSize + streamposition; - return result; + // Print the decimals + uint32_t integerValue = value; + value -= integerValue; + value = value * pow(10, decimalPlaces); + result = printInteger(buffer + streamposition, decimalPlaces, round(value), &integerSize, true); + *printedSize = integerSize + streamposition; + return result; } -ReturnValue_t AsciiConverter::printInteger(uint8_t* buffer, - uint32_t bufferLength, uint32_t value, uint32_t *printedSize, - bool leadingZeros) { - *printedSize = 0; - if (bufferLength == 0) { - return BUFFER_TOO_SMALL; - } - uint32_t maximumNumber = -1; - if (bufferLength < 10) { - maximumNumber = pow(10, bufferLength); - if (value >= maximumNumber) { - return BUFFER_TOO_SMALL; - } - maximumNumber /= 10; - } else { - if (!(value <= maximumNumber)) { - return BUFFER_TOO_SMALL; - } - maximumNumber = 1000000000; - } - if (!leadingZeros && (value == 0)) { - buffer[(*printedSize)++] = '0'; - return RETURN_OK; - } - while (maximumNumber >= 1) { - uint8_t number = value / maximumNumber; - value = value - (number * maximumNumber); - if (!leadingZeros && number == 0) { - maximumNumber /= 10; - } else { - leadingZeros = true; - buffer[(*printedSize)++] = '0' + number; - maximumNumber /= 10; - } - } - return RETURN_OK; +ReturnValue_t AsciiConverter::printInteger(uint8_t* buffer, uint32_t bufferLength, uint32_t value, + uint32_t* printedSize, bool leadingZeros) { + *printedSize = 0; + if (bufferLength == 0) { + return BUFFER_TOO_SMALL; + } + uint32_t maximumNumber = -1; + if (bufferLength < 10) { + maximumNumber = pow(10, bufferLength); + if (value >= maximumNumber) { + return BUFFER_TOO_SMALL; + } + maximumNumber /= 10; + } else { + if (!(value <= maximumNumber)) { + return BUFFER_TOO_SMALL; + } + maximumNumber = 1000000000; + } + if (!leadingZeros && (value == 0)) { + buffer[(*printedSize)++] = '0'; + return RETURN_OK; + } + while (maximumNumber >= 1) { + uint8_t number = value / maximumNumber; + value = value - (number * maximumNumber); + if (!leadingZeros && number == 0) { + maximumNumber /= 10; + } else { + leadingZeros = true; + buffer[(*printedSize)++] = '0' + number; + maximumNumber /= 10; + } + } + return RETURN_OK; } -ReturnValue_t AsciiConverter::printSignedInteger(uint8_t* buffer, - uint32_t bufferLength, int32_t value, uint32_t *printedSize) { - bool negative = false; - if ((bufferLength > 0) && (value < 0)) { - *buffer++ = '-'; - bufferLength--; - value = -value; - negative = true; - } - ReturnValue_t result = printInteger(buffer, bufferLength, value, - printedSize); - if (negative) { - (*printedSize)++; - } - return result; +ReturnValue_t AsciiConverter::printSignedInteger(uint8_t* buffer, uint32_t bufferLength, + int32_t value, uint32_t* printedSize) { + bool negative = false; + if ((bufferLength > 0) && (value < 0)) { + *buffer++ = '-'; + bufferLength--; + value = -value; + negative = true; + } + ReturnValue_t result = printInteger(buffer, bufferLength, value, printedSize); + if (negative) { + (*printedSize)++; + } + return result; } int8_t AsciiConverter::convertHexChar(const uint8_t* character) { - if ((*character > 0x60) && (*character < 0x67)) { - return *character - 0x61 + 10; - } else if ((*character > 0x40) && (*character < 0x47)) { - return *character - 0x41 + 10; - } else if ((*character > 0x2F) && (*character < 0x3A)) { - return *character - 0x30; - } else if (*character == ' ') { - return -2; - } - return -1; + if ((*character > 0x60) && (*character < 0x67)) { + return *character - 0x61 + 10; + } else if ((*character > 0x40) && (*character < 0x47)) { + return *character - 0x41 + 10; + } else if ((*character > 0x2F) && (*character < 0x3A)) { + return *character - 0x30; + } else if (*character == ' ') { + return -2; + } + return -1; } -template ReturnValue_t AsciiConverter::scanAsciiDecimalNumber( - const uint8_t** dataPtr, uint8_t len, float* value); -template ReturnValue_t AsciiConverter::scanAsciiDecimalNumber( - const uint8_t** dataPtr, uint8_t len, uint8_t* value); -template ReturnValue_t AsciiConverter::scanAsciiDecimalNumber( - const uint8_t** dataPtr, uint8_t len, uint16_t* value); -template ReturnValue_t AsciiConverter::scanAsciiDecimalNumber( - const uint8_t** dataPtr, uint8_t len, double* value); +template ReturnValue_t AsciiConverter::scanAsciiDecimalNumber(const uint8_t** dataPtr, + uint8_t len, float* value); +template ReturnValue_t AsciiConverter::scanAsciiDecimalNumber(const uint8_t** dataPtr, + uint8_t len, uint8_t* value); +template ReturnValue_t AsciiConverter::scanAsciiDecimalNumber(const uint8_t** dataPtr, + uint8_t len, + uint16_t* value); +template ReturnValue_t AsciiConverter::scanAsciiDecimalNumber(const uint8_t** dataPtr, + uint8_t len, double* value); const uint8_t* AsciiConverter::clearSpace(const uint8_t* data, uint8_t len) { - while (len > 0) { - if ((*data != ' ') && (*data != 0x0a) && (*data != 0x0d)) { - return data; - } - data++; - len--; - } - return data; + while (len > 0) { + if ((*data != ' ') && (*data != 0x0a) && (*data != 0x0d)) { + return data; + } + data++; + len--; + } + return data; } diff --git a/src/fsfw/globalfunctions/AsciiConverter.h b/src/fsfw/globalfunctions/AsciiConverter.h index 7af3cb3d..db382b61 100644 --- a/src/fsfw/globalfunctions/AsciiConverter.h +++ b/src/fsfw/globalfunctions/AsciiConverter.h @@ -3,37 +3,34 @@ #include "../returnvalues/HasReturnvaluesIF.h" -class AsciiConverter: public HasReturnvaluesIF { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::ASCII_CONVERTER; - static const ReturnValue_t TOO_LONG_FOR_TARGET_TYPE = MAKE_RETURN_CODE(1); - static const ReturnValue_t INVALID_CHARACTERS = MAKE_RETURN_CODE(2); - static const ReturnValue_t BUFFER_TOO_SMALL = MAKE_RETURN_CODE(0x3); +class AsciiConverter : public HasReturnvaluesIF { + public: + static const uint8_t INTERFACE_ID = CLASS_ID::ASCII_CONVERTER; + static const ReturnValue_t TOO_LONG_FOR_TARGET_TYPE = MAKE_RETURN_CODE(1); + static const ReturnValue_t INVALID_CHARACTERS = MAKE_RETURN_CODE(2); + static const ReturnValue_t BUFFER_TOO_SMALL = MAKE_RETURN_CODE(0x3); - template - static ReturnValue_t scanAsciiDecimalNumber(const uint8_t **dataPtr, - uint8_t len, T *value); + template + static ReturnValue_t scanAsciiDecimalNumber(const uint8_t **dataPtr, uint8_t len, T *value); - static ReturnValue_t scanAsciiHexByte(const uint8_t **dataPtr, - uint8_t *value); + static ReturnValue_t scanAsciiHexByte(const uint8_t **dataPtr, uint8_t *value); - static ReturnValue_t printFloat(uint8_t *buffer, uint32_t bufferLength, - float value, uint8_t decimalPlaces, uint32_t *printedSize); + static ReturnValue_t printFloat(uint8_t *buffer, uint32_t bufferLength, float value, + uint8_t decimalPlaces, uint32_t *printedSize); - static ReturnValue_t printInteger(uint8_t *buffer, uint32_t bufferLength, - uint32_t value, uint32_t *printedSize, bool leadingZeros = false); + static ReturnValue_t printInteger(uint8_t *buffer, uint32_t bufferLength, uint32_t value, + uint32_t *printedSize, bool leadingZeros = false); - static ReturnValue_t printSignedInteger(uint8_t *buffer, - uint32_t bufferLength, int32_t value, uint32_t *printedSize); + static ReturnValue_t printSignedInteger(uint8_t *buffer, uint32_t bufferLength, int32_t value, + uint32_t *printedSize); -private: - AsciiConverter(); - static ReturnValue_t scanAsciiDecimalNumber_(const uint8_t **dataPtr, - uint8_t len, double *value); + private: + AsciiConverter(); + static ReturnValue_t scanAsciiDecimalNumber_(const uint8_t **dataPtr, uint8_t len, double *value); - static int8_t convertHexChar(const uint8_t *character); + static int8_t convertHexChar(const uint8_t *character); - static const uint8_t *clearSpace(const uint8_t *data, uint8_t len); + static const uint8_t *clearSpace(const uint8_t *data, uint8_t len); }; #endif /* ASCIICONVERTER_H_ */ diff --git a/src/fsfw/globalfunctions/CRC.cpp b/src/fsfw/globalfunctions/CRC.cpp index 3df6018c..942e4a1a 100644 --- a/src/fsfw/globalfunctions/CRC.cpp +++ b/src/fsfw/globalfunctions/CRC.cpp @@ -1,139 +1,126 @@ #include "fsfw/globalfunctions/CRC.h" + #include const uint16_t CRC::crc16ccitt_table[256] = { - 0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50a5, 0x60c6, 0x70e7, - 0x8108, 0x9129, 0xa14a, 0xb16b, 0xc18c, 0xd1ad, 0xe1ce, 0xf1ef, - 0x1231, 0x0210, 0x3273, 0x2252, 0x52b5, 0x4294, 0x72f7, 0x62d6, - 0x9339, 0x8318, 0xb37b, 0xa35a, 0xd3bd, 0xc39c, 0xf3ff, 0xe3de, - 0x2462, 0x3443, 0x0420, 0x1401, 0x64e6, 0x74c7, 0x44a4, 0x5485, - 0xa56a, 0xb54b, 0x8528, 0x9509, 0xe5ee, 0xf5cf, 0xc5ac, 0xd58d, - 0x3653, 0x2672, 0x1611, 0x0630, 0x76d7, 0x66f6, 0x5695, 0x46b4, - 0xb75b, 0xa77a, 0x9719, 0x8738, 0xf7df, 0xe7fe, 0xd79d, 0xc7bc, - 0x48c4, 0x58e5, 0x6886, 0x78a7, 0x0840, 0x1861, 0x2802, 0x3823, - 0xc9cc, 0xd9ed, 0xe98e, 0xf9af, 0x8948, 0x9969, 0xa90a, 0xb92b, - 0x5af5, 0x4ad4, 0x7ab7, 0x6a96, 0x1a71, 0x0a50, 0x3a33, 0x2a12, - 0xdbfd, 0xcbdc, 0xfbbf, 0xeb9e, 0x9b79, 0x8b58, 0xbb3b, 0xab1a, - 0x6ca6, 0x7c87, 0x4ce4, 0x5cc5, 0x2c22, 0x3c03, 0x0c60, 0x1c41, - 0xedae, 0xfd8f, 0xcdec, 0xddcd, 0xad2a, 0xbd0b, 0x8d68, 0x9d49, - 0x7e97, 0x6eb6, 0x5ed5, 0x4ef4, 0x3e13, 0x2e32, 0x1e51, 0x0e70, - 0xff9f, 0xefbe, 0xdfdd, 0xcffc, 0xbf1b, 0xaf3a, 0x9f59, 0x8f78, - 0x9188, 0x81a9, 0xb1ca, 0xa1eb, 0xd10c, 0xc12d, 0xf14e, 0xe16f, - 0x1080, 0x00a1, 0x30c2, 0x20e3, 0x5004, 0x4025, 0x7046, 0x6067, - 0x83b9, 0x9398, 0xa3fb, 0xb3da, 0xc33d, 0xd31c, 0xe37f, 0xf35e, - 0x02b1, 0x1290, 0x22f3, 0x32d2, 0x4235, 0x5214, 0x6277, 0x7256, - 0xb5ea, 0xa5cb, 0x95a8, 0x8589, 0xf56e, 0xe54f, 0xd52c, 0xc50d, - 0x34e2, 0x24c3, 0x14a0, 0x0481, 0x7466, 0x6447, 0x5424, 0x4405, - 0xa7db, 0xb7fa, 0x8799, 0x97b8, 0xe75f, 0xf77e, 0xc71d, 0xd73c, - 0x26d3, 0x36f2, 0x0691, 0x16b0, 0x6657, 0x7676, 0x4615, 0x5634, - 0xd94c, 0xc96d, 0xf90e, 0xe92f, 0x99c8, 0x89e9, 0xb98a, 0xa9ab, - 0x5844, 0x4865, 0x7806, 0x6827, 0x18c0, 0x08e1, 0x3882, 0x28a3, - 0xcb7d, 0xdb5c, 0xeb3f, 0xfb1e, 0x8bf9, 0x9bd8, 0xabbb, 0xbb9a, - 0x4a75, 0x5a54, 0x6a37, 0x7a16, 0x0af1, 0x1ad0, 0x2ab3, 0x3a92, - 0xfd2e, 0xed0f, 0xdd6c, 0xcd4d, 0xbdaa, 0xad8b, 0x9de8, 0x8dc9, - 0x7c26, 0x6c07, 0x5c64, 0x4c45, 0x3ca2, 0x2c83, 0x1ce0, 0x0cc1, - 0xef1f, 0xff3e, 0xcf5d, 0xdf7c, 0xaf9b, 0xbfba, 0x8fd9, 0x9ff8, - 0x6e17, 0x7e36, 0x4e55, 0x5e74, 0x2e93, 0x3eb2, 0x0ed1, 0x1ef0 -}; - + 0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50a5, 0x60c6, 0x70e7, 0x8108, 0x9129, 0xa14a, 0xb16b, + 0xc18c, 0xd1ad, 0xe1ce, 0xf1ef, 0x1231, 0x0210, 0x3273, 0x2252, 0x52b5, 0x4294, 0x72f7, 0x62d6, + 0x9339, 0x8318, 0xb37b, 0xa35a, 0xd3bd, 0xc39c, 0xf3ff, 0xe3de, 0x2462, 0x3443, 0x0420, 0x1401, + 0x64e6, 0x74c7, 0x44a4, 0x5485, 0xa56a, 0xb54b, 0x8528, 0x9509, 0xe5ee, 0xf5cf, 0xc5ac, 0xd58d, + 0x3653, 0x2672, 0x1611, 0x0630, 0x76d7, 0x66f6, 0x5695, 0x46b4, 0xb75b, 0xa77a, 0x9719, 0x8738, + 0xf7df, 0xe7fe, 0xd79d, 0xc7bc, 0x48c4, 0x58e5, 0x6886, 0x78a7, 0x0840, 0x1861, 0x2802, 0x3823, + 0xc9cc, 0xd9ed, 0xe98e, 0xf9af, 0x8948, 0x9969, 0xa90a, 0xb92b, 0x5af5, 0x4ad4, 0x7ab7, 0x6a96, + 0x1a71, 0x0a50, 0x3a33, 0x2a12, 0xdbfd, 0xcbdc, 0xfbbf, 0xeb9e, 0x9b79, 0x8b58, 0xbb3b, 0xab1a, + 0x6ca6, 0x7c87, 0x4ce4, 0x5cc5, 0x2c22, 0x3c03, 0x0c60, 0x1c41, 0xedae, 0xfd8f, 0xcdec, 0xddcd, + 0xad2a, 0xbd0b, 0x8d68, 0x9d49, 0x7e97, 0x6eb6, 0x5ed5, 0x4ef4, 0x3e13, 0x2e32, 0x1e51, 0x0e70, + 0xff9f, 0xefbe, 0xdfdd, 0xcffc, 0xbf1b, 0xaf3a, 0x9f59, 0x8f78, 0x9188, 0x81a9, 0xb1ca, 0xa1eb, + 0xd10c, 0xc12d, 0xf14e, 0xe16f, 0x1080, 0x00a1, 0x30c2, 0x20e3, 0x5004, 0x4025, 0x7046, 0x6067, + 0x83b9, 0x9398, 0xa3fb, 0xb3da, 0xc33d, 0xd31c, 0xe37f, 0xf35e, 0x02b1, 0x1290, 0x22f3, 0x32d2, + 0x4235, 0x5214, 0x6277, 0x7256, 0xb5ea, 0xa5cb, 0x95a8, 0x8589, 0xf56e, 0xe54f, 0xd52c, 0xc50d, + 0x34e2, 0x24c3, 0x14a0, 0x0481, 0x7466, 0x6447, 0x5424, 0x4405, 0xa7db, 0xb7fa, 0x8799, 0x97b8, + 0xe75f, 0xf77e, 0xc71d, 0xd73c, 0x26d3, 0x36f2, 0x0691, 0x16b0, 0x6657, 0x7676, 0x4615, 0x5634, + 0xd94c, 0xc96d, 0xf90e, 0xe92f, 0x99c8, 0x89e9, 0xb98a, 0xa9ab, 0x5844, 0x4865, 0x7806, 0x6827, + 0x18c0, 0x08e1, 0x3882, 0x28a3, 0xcb7d, 0xdb5c, 0xeb3f, 0xfb1e, 0x8bf9, 0x9bd8, 0xabbb, 0xbb9a, + 0x4a75, 0x5a54, 0x6a37, 0x7a16, 0x0af1, 0x1ad0, 0x2ab3, 0x3a92, 0xfd2e, 0xed0f, 0xdd6c, 0xcd4d, + 0xbdaa, 0xad8b, 0x9de8, 0x8dc9, 0x7c26, 0x6c07, 0x5c64, 0x4c45, 0x3ca2, 0x2c83, 0x1ce0, 0x0cc1, + 0xef1f, 0xff3e, 0xcf5d, 0xdf7c, 0xaf9b, 0xbfba, 0x8fd9, 0x9ff8, 0x6e17, 0x7e36, 0x4e55, 0x5e74, + 0x2e93, 0x3eb2, 0x0ed1, 0x1ef0}; // CRC implementation -uint16_t CRC::crc16ccitt(uint8_t const input[], uint32_t length, uint16_t startingCrc) -{ - uint8_t *data = (uint8_t *)input; - unsigned int tbl_idx; +uint16_t CRC::crc16ccitt(uint8_t const input[], uint32_t length, uint16_t startingCrc) { + uint8_t *data = (uint8_t *)input; + unsigned int tbl_idx; - while (length--) { - tbl_idx = ((startingCrc >> 8) ^ *data) & 0xff; - startingCrc = (crc16ccitt_table[tbl_idx] ^ (startingCrc << 8)) & 0xffff; + while (length--) { + tbl_idx = ((startingCrc >> 8) ^ *data) & 0xff; + startingCrc = (crc16ccitt_table[tbl_idx] ^ (startingCrc << 8)) & 0xffff; - data++; - } - return startingCrc & 0xffff; - - //The part below is not used! -// bool temr[16]; -// bool xor_out[16]; -// bool r[16]; -// bool d[8]; -// uint16_t crc_value = 0; -// -// -// for (int i=0; i<16 ;i++) { -// temr[i] = false; -// xor_out[i] = false; -// } -// -// -// for (int i=0; i<16 ;i++) -// r[i] = true; // initialize with 0xFFFF -// -// -// -// for (int j=0; j class CRC { -public: - static uint16_t crc16ccitt(uint8_t const input[], uint32_t length, - uint16_t startingCrc = 0xffff); -private: - CRC(); + public: + static uint16_t crc16ccitt(uint8_t const input[], uint32_t length, uint16_t startingCrc = 0xffff); - static const uint16_t crc16ccitt_table[256]; + private: + CRC(); + + static const uint16_t crc16ccitt_table[256]; }; #endif /* CRC_H_ */ diff --git a/src/fsfw/globalfunctions/DleEncoder.cpp b/src/fsfw/globalfunctions/DleEncoder.cpp index 91db5445..23caf02a 100644 --- a/src/fsfw/globalfunctions/DleEncoder.cpp +++ b/src/fsfw/globalfunctions/DleEncoder.cpp @@ -1,298 +1,280 @@ #include "fsfw/globalfunctions/DleEncoder.h" -DleEncoder::DleEncoder(bool escapeStxEtx, bool escapeCr): - escapeStxEtx(escapeStxEtx), escapeCr(escapeCr) {} +DleEncoder::DleEncoder(bool escapeStxEtx, bool escapeCr) + : escapeStxEtx(escapeStxEtx), escapeCr(escapeCr) {} DleEncoder::~DleEncoder() {} -ReturnValue_t DleEncoder::encode(const uint8_t* sourceStream, - size_t sourceLen, uint8_t* destStream, size_t maxDestLen, - size_t* encodedLen, bool addStxEtx) { - if(escapeStxEtx) { - return encodeStreamEscaped(sourceStream, sourceLen, - destStream, maxDestLen, encodedLen, addStxEtx); - } - else { - return encodeStreamNonEscaped(sourceStream, sourceLen, - destStream, maxDestLen, encodedLen, addStxEtx); - } - +ReturnValue_t DleEncoder::encode(const uint8_t *sourceStream, size_t sourceLen, uint8_t *destStream, + size_t maxDestLen, size_t *encodedLen, bool addStxEtx) { + if (escapeStxEtx) { + return encodeStreamEscaped(sourceStream, sourceLen, destStream, maxDestLen, encodedLen, + addStxEtx); + } else { + return encodeStreamNonEscaped(sourceStream, sourceLen, destStream, maxDestLen, encodedLen, + addStxEtx); + } } ReturnValue_t DleEncoder::encodeStreamEscaped(const uint8_t *sourceStream, size_t sourceLen, - uint8_t *destStream, size_t maxDestLen, size_t *encodedLen, - bool addStxEtx) { - size_t encodedIndex = 0; - size_t sourceIndex = 0; - uint8_t nextByte = 0; - if(addStxEtx) { - if(maxDestLen < 1) { - return STREAM_TOO_SHORT; - } - destStream[encodedIndex++] = STX_CHAR; + uint8_t *destStream, size_t maxDestLen, + size_t *encodedLen, bool addStxEtx) { + size_t encodedIndex = 0; + size_t sourceIndex = 0; + uint8_t nextByte = 0; + if (addStxEtx) { + if (maxDestLen < 1) { + return STREAM_TOO_SHORT; } - while (encodedIndex < maxDestLen and sourceIndex < sourceLen) { - nextByte = sourceStream[sourceIndex]; - // STX, ETX and CR characters in the stream need to be escaped with DLE - if ((nextByte == STX_CHAR or nextByte == ETX_CHAR) or - (this->escapeCr and nextByte == CARRIAGE_RETURN)) { - if (encodedIndex + 1 >= maxDestLen) { - return STREAM_TOO_SHORT; - } - else { - destStream[encodedIndex] = DLE_CHAR; - ++encodedIndex; - /* Escaped byte will be actual byte + 0x40. This prevents - * STX, ETX, and carriage return characters from appearing - * in the encoded data stream at all, so when polling an - * encoded stream, the transmission can be stopped at ETX. - * 0x40 was chosen at random with special requirements: - * - Prevent going from one control char to another - * - Prevent overflow for common characters */ - destStream[encodedIndex] = nextByte + 0x40; - } - } - // DLE characters are simply escaped with DLE. - else if (nextByte == DLE_CHAR) { - if (encodedIndex + 1 >= maxDestLen) { - return STREAM_TOO_SHORT; - } - else { - destStream[encodedIndex] = DLE_CHAR; - ++encodedIndex; - destStream[encodedIndex] = DLE_CHAR; - } - } - else { - destStream[encodedIndex] = nextByte; - } - ++encodedIndex; - ++sourceIndex; - } - - if (sourceIndex == sourceLen) { - if (addStxEtx) { - if(encodedIndex + 1 >= maxDestLen) { - return STREAM_TOO_SHORT; - } - destStream[encodedIndex] = ETX_CHAR; - ++encodedIndex; - } - *encodedLen = encodedIndex; - return RETURN_OK; - } - else { + destStream[encodedIndex++] = STX_CHAR; + } + while (encodedIndex < maxDestLen and sourceIndex < sourceLen) { + nextByte = sourceStream[sourceIndex]; + // STX, ETX and CR characters in the stream need to be escaped with DLE + if ((nextByte == STX_CHAR or nextByte == ETX_CHAR) or + (this->escapeCr and nextByte == CARRIAGE_RETURN)) { + if (encodedIndex + 1 >= maxDestLen) { return STREAM_TOO_SHORT; + } else { + destStream[encodedIndex] = DLE_CHAR; + ++encodedIndex; + /* Escaped byte will be actual byte + 0x40. This prevents + * STX, ETX, and carriage return characters from appearing + * in the encoded data stream at all, so when polling an + * encoded stream, the transmission can be stopped at ETX. + * 0x40 was chosen at random with special requirements: + * - Prevent going from one control char to another + * - Prevent overflow for common characters */ + destStream[encodedIndex] = nextByte + 0x40; + } } + // DLE characters are simply escaped with DLE. + else if (nextByte == DLE_CHAR) { + if (encodedIndex + 1 >= maxDestLen) { + return STREAM_TOO_SHORT; + } else { + destStream[encodedIndex] = DLE_CHAR; + ++encodedIndex; + destStream[encodedIndex] = DLE_CHAR; + } + } else { + destStream[encodedIndex] = nextByte; + } + ++encodedIndex; + ++sourceIndex; + } + + if (sourceIndex == sourceLen) { + if (addStxEtx) { + if (encodedIndex + 1 >= maxDestLen) { + return STREAM_TOO_SHORT; + } + destStream[encodedIndex] = ETX_CHAR; + ++encodedIndex; + } + *encodedLen = encodedIndex; + return RETURN_OK; + } else { + return STREAM_TOO_SHORT; + } } ReturnValue_t DleEncoder::encodeStreamNonEscaped(const uint8_t *sourceStream, size_t sourceLen, - uint8_t *destStream, size_t maxDestLen, size_t *encodedLen, - bool addStxEtx) { - size_t encodedIndex = 0; - size_t sourceIndex = 0; - uint8_t nextByte = 0; - if(addStxEtx) { - if(maxDestLen < 2) { - return STREAM_TOO_SHORT; - } - destStream[encodedIndex++] = DLE_CHAR; - destStream[encodedIndex++] = STX_CHAR; + uint8_t *destStream, size_t maxDestLen, + size_t *encodedLen, bool addStxEtx) { + size_t encodedIndex = 0; + size_t sourceIndex = 0; + uint8_t nextByte = 0; + if (addStxEtx) { + if (maxDestLen < 2) { + return STREAM_TOO_SHORT; } - while (encodedIndex < maxDestLen and sourceIndex < sourceLen) { - nextByte = sourceStream[sourceIndex]; - // DLE characters are simply escaped with DLE. - if (nextByte == DLE_CHAR) { - if (encodedIndex + 1 >= maxDestLen) { - return STREAM_TOO_SHORT; - } - else { - destStream[encodedIndex] = DLE_CHAR; - ++encodedIndex; - destStream[encodedIndex] = DLE_CHAR; - } - } - else { - destStream[encodedIndex] = nextByte; - } - ++encodedIndex; - ++sourceIndex; - } - - if (sourceIndex == sourceLen) { - if (addStxEtx) { - if(encodedIndex + 2 >= maxDestLen) { - return STREAM_TOO_SHORT; - } - destStream[encodedIndex++] = DLE_CHAR; - destStream[encodedIndex++] = ETX_CHAR; - } - *encodedLen = encodedIndex; - return RETURN_OK; - } - else { + destStream[encodedIndex++] = DLE_CHAR; + destStream[encodedIndex++] = STX_CHAR; + } + while (encodedIndex < maxDestLen and sourceIndex < sourceLen) { + nextByte = sourceStream[sourceIndex]; + // DLE characters are simply escaped with DLE. + if (nextByte == DLE_CHAR) { + if (encodedIndex + 1 >= maxDestLen) { return STREAM_TOO_SHORT; + } else { + destStream[encodedIndex] = DLE_CHAR; + ++encodedIndex; + destStream[encodedIndex] = DLE_CHAR; + } + } else { + destStream[encodedIndex] = nextByte; } + ++encodedIndex; + ++sourceIndex; + } + + if (sourceIndex == sourceLen) { + if (addStxEtx) { + if (encodedIndex + 2 >= maxDestLen) { + return STREAM_TOO_SHORT; + } + destStream[encodedIndex++] = DLE_CHAR; + destStream[encodedIndex++] = ETX_CHAR; + } + *encodedLen = encodedIndex; + return RETURN_OK; + } else { + return STREAM_TOO_SHORT; + } } -ReturnValue_t DleEncoder::decode(const uint8_t *sourceStream, - size_t sourceStreamLen, size_t *readLen, uint8_t *destStream, - size_t maxDestStreamlen, size_t *decodedLen) { - if(escapeStxEtx) { - return decodeStreamEscaped(sourceStream, sourceStreamLen, - readLen, destStream, maxDestStreamlen, decodedLen); - } - else { - return decodeStreamNonEscaped(sourceStream, sourceStreamLen, - readLen, destStream, maxDestStreamlen, decodedLen); - } +ReturnValue_t DleEncoder::decode(const uint8_t *sourceStream, size_t sourceStreamLen, + size_t *readLen, uint8_t *destStream, size_t maxDestStreamlen, + size_t *decodedLen) { + if (escapeStxEtx) { + return decodeStreamEscaped(sourceStream, sourceStreamLen, readLen, destStream, maxDestStreamlen, + decodedLen); + } else { + return decodeStreamNonEscaped(sourceStream, sourceStreamLen, readLen, destStream, + maxDestStreamlen, decodedLen); + } } ReturnValue_t DleEncoder::decodeStreamEscaped(const uint8_t *sourceStream, size_t sourceStreamLen, - size_t *readLen, uint8_t *destStream, - size_t maxDestStreamlen, size_t *decodedLen) { - size_t encodedIndex = 0; - size_t decodedIndex = 0; - uint8_t nextByte; + size_t *readLen, uint8_t *destStream, + size_t maxDestStreamlen, size_t *decodedLen) { + size_t encodedIndex = 0; + size_t decodedIndex = 0; + uint8_t nextByte; - //init to 0 so that we can just return in the first checks (which do not consume anything from - //the source stream) - *readLen = 0; + // init to 0 so that we can just return in the first checks (which do not consume anything from + // the source stream) + *readLen = 0; - if(maxDestStreamlen < 1) { - return STREAM_TOO_SHORT; - } - if (sourceStream[encodedIndex++] != STX_CHAR) { - return DECODING_ERROR; - } - while ((encodedIndex < sourceStreamLen) and (decodedIndex < maxDestStreamlen)) { - switch(sourceStream[encodedIndex]) { - case(DLE_CHAR): { - if(encodedIndex + 1 >= sourceStreamLen) { - //reached the end of the sourceStream - *readLen = sourceStreamLen; - return DECODING_ERROR; - } - nextByte = sourceStream[encodedIndex + 1]; - // The next byte is a DLE character that was escaped by another - // DLE character, so we can write it to the destination stream. - if (nextByte == DLE_CHAR) { - destStream[decodedIndex] = nextByte; - } - else { - /* The next byte is a STX, DTX or 0x0D character which - * was escaped by a DLE character. The actual byte was - * also encoded by adding + 0x40 to prevent having control chars, - * in the stream at all, so we convert it back. */ - if ((nextByte == STX_CHAR + 0x40 or nextByte == ETX_CHAR + 0x40) or - (this->escapeCr and nextByte == CARRIAGE_RETURN + 0x40)) { - destStream[decodedIndex] = nextByte - 0x40; - } - else { - // Set readLen so user can resume parsing after incorrect data - *readLen = encodedIndex + 2; - return DECODING_ERROR; - } - } - ++encodedIndex; - break; + if (maxDestStreamlen < 1) { + return STREAM_TOO_SHORT; + } + if (sourceStream[encodedIndex++] != STX_CHAR) { + return DECODING_ERROR; + } + while ((encodedIndex < sourceStreamLen) and (decodedIndex < maxDestStreamlen)) { + switch (sourceStream[encodedIndex]) { + case (DLE_CHAR): { + if (encodedIndex + 1 >= sourceStreamLen) { + // reached the end of the sourceStream + *readLen = sourceStreamLen; + return DECODING_ERROR; } - case(STX_CHAR): { - *readLen = encodedIndex; + nextByte = sourceStream[encodedIndex + 1]; + // The next byte is a DLE character that was escaped by another + // DLE character, so we can write it to the destination stream. + if (nextByte == DLE_CHAR) { + destStream[decodedIndex] = nextByte; + } else { + /* The next byte is a STX, DTX or 0x0D character which + * was escaped by a DLE character. The actual byte was + * also encoded by adding + 0x40 to prevent having control chars, + * in the stream at all, so we convert it back. */ + if ((nextByte == STX_CHAR + 0x40 or nextByte == ETX_CHAR + 0x40) or + (this->escapeCr and nextByte == CARRIAGE_RETURN + 0x40)) { + destStream[decodedIndex] = nextByte - 0x40; + } else { + // Set readLen so user can resume parsing after incorrect data + *readLen = encodedIndex + 2; return DECODING_ERROR; - } - case(ETX_CHAR): { - *readLen = ++encodedIndex; - *decodedLen = decodedIndex; - return RETURN_OK; - } - default: { - destStream[decodedIndex] = sourceStream[encodedIndex]; - break; - } + } } ++encodedIndex; - ++decodedIndex; - } - - if(decodedIndex == maxDestStreamlen) { - //so far we did not find anything wrong here, so let user try again - *readLen = 0; - return STREAM_TOO_SHORT; - } else { + break; + } + case (STX_CHAR): { *readLen = encodedIndex; return DECODING_ERROR; + } + case (ETX_CHAR): { + *readLen = ++encodedIndex; + *decodedLen = decodedIndex; + return RETURN_OK; + } + default: { + destStream[decodedIndex] = sourceStream[encodedIndex]; + break; + } } + ++encodedIndex; + ++decodedIndex; + } + + if (decodedIndex == maxDestStreamlen) { + // so far we did not find anything wrong here, so let user try again + *readLen = 0; + return STREAM_TOO_SHORT; + } else { + *readLen = encodedIndex; + return DECODING_ERROR; + } } ReturnValue_t DleEncoder::decodeStreamNonEscaped(const uint8_t *sourceStream, - size_t sourceStreamLen, size_t *readLen, uint8_t *destStream, - size_t maxDestStreamlen, size_t *decodedLen) { - size_t encodedIndex = 0; - size_t decodedIndex = 0; - uint8_t nextByte; + size_t sourceStreamLen, size_t *readLen, + uint8_t *destStream, size_t maxDestStreamlen, + size_t *decodedLen) { + size_t encodedIndex = 0; + size_t decodedIndex = 0; + uint8_t nextByte; - //init to 0 so that we can just return in the first checks (which do not consume anything from - //the source stream) - *readLen = 0; - - if(maxDestStreamlen < 2) { - return STREAM_TOO_SHORT; - } - if (sourceStream[encodedIndex++] != DLE_CHAR) { - return DECODING_ERROR; - } - if (sourceStream[encodedIndex++] != STX_CHAR) { - *readLen = 1; - return DECODING_ERROR; - } - while ((encodedIndex < sourceStreamLen) && (decodedIndex < maxDestStreamlen)) { - if (sourceStream[encodedIndex] == DLE_CHAR) { - if(encodedIndex + 1 >= sourceStreamLen) { - *readLen = encodedIndex; - return DECODING_ERROR; - } - nextByte = sourceStream[encodedIndex + 1]; - if(nextByte == STX_CHAR) { - // Set readLen so the DLE/STX char combination is preserved. Could be start of - // another frame - *readLen = encodedIndex; - return DECODING_ERROR; - } - else if(nextByte == DLE_CHAR) { - // The next byte is a DLE character that was escaped by another - // DLE character, so we can write it to the destination stream. - destStream[decodedIndex] = nextByte; - ++encodedIndex; - } - else if(nextByte == ETX_CHAR) { - // End of stream reached - *readLen = encodedIndex + 2; - *decodedLen = decodedIndex; - return RETURN_OK; - } - else { - *readLen = encodedIndex; - return DECODING_ERROR; - } - } - else { - destStream[decodedIndex] = sourceStream[encodedIndex]; - } - ++encodedIndex; - ++decodedIndex; - } + // init to 0 so that we can just return in the first checks (which do not consume anything from + // the source stream) + *readLen = 0; - if(decodedIndex == maxDestStreamlen) { - //so far we did not find anything wrong here, so let user try again - *readLen = 0; - return STREAM_TOO_SHORT; - } else { + if (maxDestStreamlen < 2) { + return STREAM_TOO_SHORT; + } + if (sourceStream[encodedIndex++] != DLE_CHAR) { + return DECODING_ERROR; + } + if (sourceStream[encodedIndex++] != STX_CHAR) { + *readLen = 1; + return DECODING_ERROR; + } + while ((encodedIndex < sourceStreamLen) && (decodedIndex < maxDestStreamlen)) { + if (sourceStream[encodedIndex] == DLE_CHAR) { + if (encodedIndex + 1 >= sourceStreamLen) { *readLen = encodedIndex; return DECODING_ERROR; + } + nextByte = sourceStream[encodedIndex + 1]; + if (nextByte == STX_CHAR) { + // Set readLen so the DLE/STX char combination is preserved. Could be start of + // another frame + *readLen = encodedIndex; + return DECODING_ERROR; + } else if (nextByte == DLE_CHAR) { + // The next byte is a DLE character that was escaped by another + // DLE character, so we can write it to the destination stream. + destStream[decodedIndex] = nextByte; + ++encodedIndex; + } else if (nextByte == ETX_CHAR) { + // End of stream reached + *readLen = encodedIndex + 2; + *decodedLen = decodedIndex; + return RETURN_OK; + } else { + *readLen = encodedIndex; + return DECODING_ERROR; + } + } else { + destStream[decodedIndex] = sourceStream[encodedIndex]; } + ++encodedIndex; + ++decodedIndex; + } + + if (decodedIndex == maxDestStreamlen) { + // so far we did not find anything wrong here, so let user try again + *readLen = 0; + return STREAM_TOO_SHORT; + } else { + *readLen = encodedIndex; + return DECODING_ERROR; + } } -void DleEncoder::setEscapeMode(bool escapeStxEtx) { - this->escapeStxEtx = escapeStxEtx; -} +void DleEncoder::setEscapeMode(bool escapeStxEtx) { this->escapeStxEtx = escapeStxEtx; } diff --git a/src/fsfw/globalfunctions/DleEncoder.h b/src/fsfw/globalfunctions/DleEncoder.h index 09fa2726..009c8656 100644 --- a/src/fsfw/globalfunctions/DleEncoder.h +++ b/src/fsfw/globalfunctions/DleEncoder.h @@ -1,9 +1,10 @@ #ifndef FRAMEWORK_GLOBALFUNCTIONS_DLEENCODER_H_ #define FRAMEWORK_GLOBALFUNCTIONS_DLEENCODER_H_ -#include "fsfw/returnvalues/HasReturnvaluesIF.h" #include +#include "fsfw/returnvalues/HasReturnvaluesIF.h" + /** * @brief This DLE Encoder (Data Link Encoder) can be used to encode and * decode arbitrary data with ASCII control characters @@ -29,90 +30,89 @@ * are escaped with DLE. If the receiver detects a DLE char, it needs to read the next char * to determine whether a start (STX) or end (ETX) of a frame has been detected. */ -class DleEncoder: public HasReturnvaluesIF { -public: - /** - * Create an encoder instance with the given configuration. - * @param escapeStxEtx Determines whether the algorithm works in escaped or non-escaped mode - * @param escapeCr In escaped mode, escape all CR occurrences as well - */ - DleEncoder(bool escapeStxEtx = true, bool escapeCr = false); +class DleEncoder : public HasReturnvaluesIF { + public: + /** + * Create an encoder instance with the given configuration. + * @param escapeStxEtx Determines whether the algorithm works in escaped or non-escaped mode + * @param escapeCr In escaped mode, escape all CR occurrences as well + */ + DleEncoder(bool escapeStxEtx = true, bool escapeCr = false); - void setEscapeMode(bool escapeStxEtx); + void setEscapeMode(bool escapeStxEtx); - virtual ~DleEncoder(); + virtual ~DleEncoder(); - static constexpr uint8_t INTERFACE_ID = CLASS_ID::DLE_ENCODER; - static constexpr ReturnValue_t STREAM_TOO_SHORT = MAKE_RETURN_CODE(0x01); - static constexpr ReturnValue_t DECODING_ERROR = MAKE_RETURN_CODE(0x02); + static constexpr uint8_t INTERFACE_ID = CLASS_ID::DLE_ENCODER; + static constexpr ReturnValue_t STREAM_TOO_SHORT = MAKE_RETURN_CODE(0x01); + static constexpr ReturnValue_t DECODING_ERROR = MAKE_RETURN_CODE(0x02); - //! Start Of Text character. First character is encoded stream - static constexpr uint8_t STX_CHAR = 0x02; - //! End Of Text character. Last character in encoded stream - static constexpr uint8_t ETX_CHAR = 0x03; - //! Data Link Escape character. Used to escape STX, ETX and DLE occurrences - //! in the source stream. - static constexpr uint8_t DLE_CHAR = 0x10; - static constexpr uint8_t CARRIAGE_RETURN = 0x0D; + //! Start Of Text character. First character is encoded stream + static constexpr uint8_t STX_CHAR = 0x02; + //! End Of Text character. Last character in encoded stream + static constexpr uint8_t ETX_CHAR = 0x03; + //! Data Link Escape character. Used to escape STX, ETX and DLE occurrences + //! in the source stream. + static constexpr uint8_t DLE_CHAR = 0x10; + static constexpr uint8_t CARRIAGE_RETURN = 0x0D; - /** - * Encodes the give data stream by preceding it with the STX marker - * and ending it with an ETX marker. DLE characters inside - * the stream are escaped by DLE characters. STX, ETX and CR characters can be escaped with a - * DLE character as well. The escaped characters are also encoded by adding - * 0x40 (which is reverted in the decoding process). This is performed so the source stream - * does not have STX/ETX/CR occurrences anymore, so the receiving side can simply parse for - * start and end markers - * @param sourceStream - * @param sourceLen - * @param destStream - * @param maxDestLen - * @param encodedLen - * @param addStxEtx Adding STX start marker and ETX end marker can be omitted, - * if they are added manually - * @return - * - RETURN_OK for successful encoding operation - * - STREAM_TOO_SHORT if the destination stream is too short - */ - ReturnValue_t encode(const uint8_t *sourceStream, size_t sourceLen, - uint8_t *destStream, size_t maxDestLen, size_t *encodedLen, - bool addStxEtx = true); + /** + * Encodes the give data stream by preceding it with the STX marker + * and ending it with an ETX marker. DLE characters inside + * the stream are escaped by DLE characters. STX, ETX and CR characters can be escaped with a + * DLE character as well. The escaped characters are also encoded by adding + * 0x40 (which is reverted in the decoding process). This is performed so the source stream + * does not have STX/ETX/CR occurrences anymore, so the receiving side can simply parse for + * start and end markers + * @param sourceStream + * @param sourceLen + * @param destStream + * @param maxDestLen + * @param encodedLen + * @param addStxEtx Adding STX start marker and ETX end marker can be omitted, + * if they are added manually + * @return + * - RETURN_OK for successful encoding operation + * - STREAM_TOO_SHORT if the destination stream is too short + */ + ReturnValue_t encode(const uint8_t *sourceStream, size_t sourceLen, uint8_t *destStream, + size_t maxDestLen, size_t *encodedLen, bool addStxEtx = true); - /** - * Converts an encoded stream back. - * @param sourceStream - * @param sourceStreamLen - * @param readLen - * @param destStream - * @param maxDestStreamlen - * @param decodedLen - * @return - * - RETURN_OK for successful decode operation - * - DECODE_ERROR if the source stream is invalid - * - STREAM_TOO_SHORT if the destination stream is too short - */ - ReturnValue_t decode(const uint8_t *sourceStream, - size_t sourceStreamLen, size_t *readLen, uint8_t *destStream, - size_t maxDestStreamlen, size_t *decodedLen); + /** + * Converts an encoded stream back. + * @param sourceStream + * @param sourceStreamLen + * @param readLen + * @param destStream + * @param maxDestStreamlen + * @param decodedLen + * @return + * - RETURN_OK for successful decode operation + * - DECODE_ERROR if the source stream is invalid + * - STREAM_TOO_SHORT if the destination stream is too short + */ + ReturnValue_t decode(const uint8_t *sourceStream, size_t sourceStreamLen, size_t *readLen, + uint8_t *destStream, size_t maxDestStreamlen, size_t *decodedLen); -private: + private: + ReturnValue_t encodeStreamEscaped(const uint8_t *sourceStream, size_t sourceLen, + uint8_t *destStream, size_t maxDestLen, size_t *encodedLen, + bool addStxEtx = true); - ReturnValue_t encodeStreamEscaped(const uint8_t *sourceStream, size_t sourceLen, - uint8_t *destStream, size_t maxDestLen, size_t *encodedLen, - bool addStxEtx = true); + ReturnValue_t encodeStreamNonEscaped(const uint8_t *sourceStream, size_t sourceLen, + uint8_t *destStream, size_t maxDestLen, size_t *encodedLen, + bool addStxEtx = true); - ReturnValue_t encodeStreamNonEscaped(const uint8_t *sourceStream, size_t sourceLen, - uint8_t *destStream, size_t maxDestLen, size_t *encodedLen, - bool addStxEtx = true); + ReturnValue_t decodeStreamEscaped(const uint8_t *sourceStream, size_t sourceStreamLen, + size_t *readLen, uint8_t *destStream, size_t maxDestStreamlen, + size_t *decodedLen); - ReturnValue_t decodeStreamEscaped(const uint8_t *sourceStream, size_t sourceStreamLen, - size_t *readLen, uint8_t *destStream, size_t maxDestStreamlen, size_t *decodedLen); + ReturnValue_t decodeStreamNonEscaped(const uint8_t *sourceStream, size_t sourceStreamLen, + size_t *readLen, uint8_t *destStream, + size_t maxDestStreamlen, size_t *decodedLen); - ReturnValue_t decodeStreamNonEscaped(const uint8_t *sourceStream, size_t sourceStreamLen, - size_t *readLen, uint8_t *destStream, size_t maxDestStreamlen, size_t *decodedLen); - - bool escapeStxEtx; - bool escapeCr; + bool escapeStxEtx; + bool escapeCr; }; #endif /* FRAMEWORK_GLOBALFUNCTIONS_DLEENCODER_H_ */ diff --git a/src/fsfw/globalfunctions/PeriodicOperationDivider.cpp b/src/fsfw/globalfunctions/PeriodicOperationDivider.cpp index ac6a78e4..46408615 100644 --- a/src/fsfw/globalfunctions/PeriodicOperationDivider.cpp +++ b/src/fsfw/globalfunctions/PeriodicOperationDivider.cpp @@ -1,41 +1,29 @@ #include "fsfw/globalfunctions/PeriodicOperationDivider.h" - -PeriodicOperationDivider::PeriodicOperationDivider(uint32_t divider, - bool resetAutomatically): resetAutomatically(resetAutomatically), - divider(divider) { -} +PeriodicOperationDivider::PeriodicOperationDivider(uint32_t divider, bool resetAutomatically) + : resetAutomatically(resetAutomatically), divider(divider) {} bool PeriodicOperationDivider::checkAndIncrement() { - bool opNecessary = check(); - if(opNecessary and resetAutomatically) { - resetCounter(); - } - else { - counter++; - } - return opNecessary; + bool opNecessary = check(); + if (opNecessary and resetAutomatically) { + resetCounter(); + } else { + counter++; + } + return opNecessary; } bool PeriodicOperationDivider::check() { - if(counter >= divider) { - return true; - } - return false; + if (counter >= divider) { + return true; + } + return false; } -void PeriodicOperationDivider::resetCounter() { - counter = 1; -} +void PeriodicOperationDivider::resetCounter() { counter = 1; } -void PeriodicOperationDivider::setDivider(uint32_t newDivider) { - divider = newDivider; -} +void PeriodicOperationDivider::setDivider(uint32_t newDivider) { divider = newDivider; } -uint32_t PeriodicOperationDivider::getCounter() const { - return counter; -} +uint32_t PeriodicOperationDivider::getCounter() const { return counter; } -uint32_t PeriodicOperationDivider::getDivider() const { - return divider; -} +uint32_t PeriodicOperationDivider::getDivider() const { return divider; } diff --git a/src/fsfw/globalfunctions/PeriodicOperationDivider.h b/src/fsfw/globalfunctions/PeriodicOperationDivider.h index 636849c0..a7106cbb 100644 --- a/src/fsfw/globalfunctions/PeriodicOperationDivider.h +++ b/src/fsfw/globalfunctions/PeriodicOperationDivider.h @@ -12,53 +12,51 @@ * or low priority operations. */ class PeriodicOperationDivider { -public: - /** - * Initialize with the desired divider and specify whether the internal - * counter will be reset automatically. - * @param divider Value of 0 or 1 will cause #check and #checkAndIncrement to always return - * true - * @param resetAutomatically - */ - PeriodicOperationDivider(uint32_t divider, bool resetAutomatically = true); + public: + /** + * Initialize with the desired divider and specify whether the internal + * counter will be reset automatically. + * @param divider Value of 0 or 1 will cause #check and #checkAndIncrement to always return + * true + * @param resetAutomatically + */ + PeriodicOperationDivider(uint32_t divider, bool resetAutomatically = true); - /** - * Check whether operation is necessary. If an operation is necessary and the class has been - * configured to be reset automatically, the counter will be reset to 1 automatically - * - * @return - * -@c true if the counter is larger or equal to the divider - * -@c false otherwise - */ - bool checkAndIncrement(); + /** + * Check whether operation is necessary. If an operation is necessary and the class has been + * configured to be reset automatically, the counter will be reset to 1 automatically + * + * @return + * -@c true if the counter is larger or equal to the divider + * -@c false otherwise + */ + bool checkAndIncrement(); - /** - * Checks whether an operation is necessary. This function will not increment the counter. - * @return - * -@c true if the counter is larger or equal to the divider - * -@c false otherwise - */ - bool check(); + /** + * Checks whether an operation is necessary. This function will not increment the counter. + * @return + * -@c true if the counter is larger or equal to the divider + * -@c false otherwise + */ + bool check(); - /** - * Can be used to reset the counter to 1 manually - */ - void resetCounter(); - uint32_t getCounter() const; + /** + * Can be used to reset the counter to 1 manually + */ + void resetCounter(); + uint32_t getCounter() const; - /** - * Can be used to set a new divider value. - * @param newDivider - */ - void setDivider(uint32_t newDivider); - uint32_t getDivider() const; + /** + * Can be used to set a new divider value. + * @param newDivider + */ + void setDivider(uint32_t newDivider); + uint32_t getDivider() const; -private: - bool resetAutomatically = true; - uint32_t counter = 1; - uint32_t divider = 0; + private: + bool resetAutomatically = true; + uint32_t counter = 1; + uint32_t divider = 0; }; - - #endif /* FSFW_GLOBALFUNCTIONS_PERIODICOPERATIONDIVIDER_H_ */ diff --git a/src/fsfw/globalfunctions/Type.cpp b/src/fsfw/globalfunctions/Type.cpp index 5f1e05d1..71193673 100644 --- a/src/fsfw/globalfunctions/Type.cpp +++ b/src/fsfw/globalfunctions/Type.cpp @@ -1,181 +1,164 @@ #include "fsfw/globalfunctions/Type.h" + #include "fsfw/serialize/SerializeAdapter.h" -Type::Type() : - actualType(UNKNOWN_TYPE) { +Type::Type() : actualType(UNKNOWN_TYPE) {} + +Type::Type(ActualType_t actualType) : actualType(actualType) {} + +Type::Type(const Type& type) : actualType(type.actualType) {} + +Type& Type::operator=(Type rhs) { + this->actualType = rhs.actualType; + return *this; } -Type::Type(ActualType_t actualType) : - actualType(actualType) { +Type& Type::operator=(ActualType_t actualType) { + this->actualType = actualType; + return *this; } -Type::Type(const Type& type) : - actualType(type.actualType) { -} +Type::operator Type::ActualType_t() const { return actualType; } -Type& Type::operator =(Type rhs) { - this->actualType = rhs.actualType; - return *this; -} +bool Type::operator==(const Type& rhs) { return this->actualType == rhs.actualType; } -Type& Type::operator =(ActualType_t actualType) { - this->actualType = actualType; - return *this; -} - -Type::operator Type::ActualType_t() const { - return actualType; -} - -bool Type::operator ==(const Type& rhs) { - return this->actualType == rhs.actualType; -} - -bool Type::operator !=(const Type& rhs) { - return !operator==(rhs); -} +bool Type::operator!=(const Type& rhs) { return !operator==(rhs); } uint8_t Type::getSize() const { - switch (actualType) { - case UINT8_T: - return sizeof(uint8_t); - case INT8_T: - return sizeof(int8_t); - case UINT16_T: - return sizeof(uint16_t); - case INT16_T: - return sizeof(int16_t); - case UINT32_T: - return sizeof(uint32_t); - case INT32_T: - return sizeof(int32_t); - case FLOAT: - return sizeof(float); - case DOUBLE: - return sizeof(double); - default: - return 0; - } + switch (actualType) { + case UINT8_T: + return sizeof(uint8_t); + case INT8_T: + return sizeof(int8_t); + case UINT16_T: + return sizeof(uint16_t); + case INT16_T: + return sizeof(int16_t); + case UINT32_T: + return sizeof(uint32_t); + case INT32_T: + return sizeof(int32_t); + case FLOAT: + return sizeof(float); + case DOUBLE: + return sizeof(double); + default: + return 0; + } } -ReturnValue_t Type::serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const { - uint8_t ptc; - uint8_t pfc; - ReturnValue_t result = getPtcPfc(&ptc, &pfc); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } +ReturnValue_t Type::serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const { + uint8_t ptc; + uint8_t pfc; + ReturnValue_t result = getPtcPfc(&ptc, &pfc); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - result = SerializeAdapter::serialize(&ptc, buffer, size, maxSize, - streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + result = SerializeAdapter::serialize(&ptc, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - result = SerializeAdapter::serialize(&pfc, buffer, size, maxSize, - streamEndianness); - - return result; + result = SerializeAdapter::serialize(&pfc, buffer, size, maxSize, streamEndianness); + return result; } size_t Type::getSerializedSize() const { - uint8_t dontcare = 0; - return 2 * SerializeAdapter::getSerializedSize(&dontcare); + uint8_t dontcare = 0; + return 2 * SerializeAdapter::getSerializedSize(&dontcare); } -ReturnValue_t Type::deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) { - uint8_t ptc; - uint8_t pfc; - ReturnValue_t result = SerializeAdapter::deSerialize(&ptc, buffer, - size, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } +ReturnValue_t Type::deSerialize(const uint8_t** buffer, size_t* size, Endianness streamEndianness) { + uint8_t ptc; + uint8_t pfc; + ReturnValue_t result = SerializeAdapter::deSerialize(&ptc, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - result = SerializeAdapter::deSerialize(&pfc, buffer, size, - streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + result = SerializeAdapter::deSerialize(&pfc, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - actualType = getActualType(ptc, pfc); + actualType = getActualType(ptc, pfc); - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t Type::getPtcPfc(uint8_t* ptc, uint8_t* pfc) const { - switch (actualType) { - case UINT8_T: - *ptc = 3; - *pfc = 4; - break; - case INT8_T: - *ptc = 4; - *pfc = 4; - break; - case UINT16_T: - *ptc = 3; - *pfc = 12; - break; - case INT16_T: - *ptc = 4; - *pfc = 12; - break; - case UINT32_T: - *ptc = 3; - *pfc = 14; - break; - case INT32_T: - *ptc = 4; - *pfc = 14; - break; - case FLOAT: - *ptc = 5; - *pfc = 1; - break; - case DOUBLE: - *ptc = 5; - *pfc = 2; - break; - default: - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + switch (actualType) { + case UINT8_T: + *ptc = 3; + *pfc = 4; + break; + case INT8_T: + *ptc = 4; + *pfc = 4; + break; + case UINT16_T: + *ptc = 3; + *pfc = 12; + break; + case INT16_T: + *ptc = 4; + *pfc = 12; + break; + case UINT32_T: + *ptc = 3; + *pfc = 14; + break; + case INT32_T: + *ptc = 4; + *pfc = 14; + break; + case FLOAT: + *ptc = 5; + *pfc = 1; + break; + case DOUBLE: + *ptc = 5; + *pfc = 2; + break; + default: + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } Type::ActualType_t Type::getActualType(uint8_t ptc, uint8_t pfc) { - switch (ptc) { - case 3: - switch (pfc) { - case 4: - return UINT8_T; - case 12: - return UINT16_T; - case 14: - return UINT32_T; - } - break; - case 4: - switch (pfc) { - case 4: - return INT8_T; - case 12: - return INT16_T; - case 14: - return INT32_T; - } - break; - case 5: - switch (pfc) { - case 1: - return FLOAT; - case 2: - return DOUBLE; - } - break; - } - return UNKNOWN_TYPE; + switch (ptc) { + case 3: + switch (pfc) { + case 4: + return UINT8_T; + case 12: + return UINT16_T; + case 14: + return UINT32_T; + } + break; + case 4: + switch (pfc) { + case 4: + return INT8_T; + case 12: + return INT16_T; + case 14: + return INT32_T; + } + break; + case 5: + switch (pfc) { + case 1: + return FLOAT; + case 2: + return DOUBLE; + } + break; + } + return UNKNOWN_TYPE; } diff --git a/src/fsfw/globalfunctions/Type.h b/src/fsfw/globalfunctions/Type.h index cfbb3cfa..385d7219 100644 --- a/src/fsfw/globalfunctions/Type.h +++ b/src/fsfw/globalfunctions/Type.h @@ -1,101 +1,101 @@ #ifndef FSFW_GLOBALFUNCTIONS_TYPE_H_ #define FSFW_GLOBALFUNCTIONS_TYPE_H_ +#include + #include "fsfw/returnvalues/HasReturnvaluesIF.h" #include "fsfw/serialize/SerializeIF.h" -#include - /** * @brief Type definition for CCSDS or ECSS. */ -class Type: public SerializeIF { -public: - enum ActualType_t { - UINT8_T, - INT8_T, - UINT16_T, - INT16_T, - UINT32_T, - INT32_T, - FLOAT, - DOUBLE, - UNKNOWN_TYPE - }; +class Type : public SerializeIF { + public: + enum ActualType_t { + UINT8_T, + INT8_T, + UINT16_T, + INT16_T, + UINT32_T, + INT32_T, + FLOAT, + DOUBLE, + UNKNOWN_TYPE + }; - Type(); + Type(); - Type(ActualType_t actualType); + Type(ActualType_t actualType); - Type(const Type &type); + Type(const Type &type); - Type& operator=(Type rhs); + Type &operator=(Type rhs); - Type& operator=(ActualType_t actualType); + Type &operator=(ActualType_t actualType); - operator ActualType_t() const; + operator ActualType_t() const; - bool operator==(const Type &rhs); - bool operator!=(const Type &rhs); + bool operator==(const Type &rhs); + bool operator!=(const Type &rhs); - uint8_t getSize() const; + uint8_t getSize() const; - ReturnValue_t getPtcPfc(uint8_t *ptc, uint8_t *pfc) const; + ReturnValue_t getPtcPfc(uint8_t *ptc, uint8_t *pfc) const; - static ActualType_t getActualType(uint8_t ptc, uint8_t pfc); + static ActualType_t getActualType(uint8_t ptc, uint8_t pfc); - virtual ReturnValue_t serialize(uint8_t **buffer, size_t *size, - size_t maxSize, Endianness streamEndianness) const override; + virtual ReturnValue_t serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const override; - virtual size_t getSerializedSize() const override; + virtual size_t getSerializedSize() const override; - virtual ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) override; + virtual ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) override; -private: - ActualType_t actualType; + private: + ActualType_t actualType; }; -template +template struct PodTypeConversion { - static_assert(not std::is_same::value, - "Do not use boolean for the PoolEntry type, use uint8_t " - "instead! The ECSS standard defines a boolean as a one bit " - "field. Therefore it is preferred to store a boolean as an " - "uint8_t"); - static const Type::ActualType_t type = Type::UNKNOWN_TYPE; + static_assert(not std::is_same::value, + "Do not use boolean for the PoolEntry type, use uint8_t " + "instead! The ECSS standard defines a boolean as a one bit " + "field. Therefore it is preferred to store a boolean as an " + "uint8_t"); + static const Type::ActualType_t type = Type::UNKNOWN_TYPE; }; -template<> +template <> struct PodTypeConversion { - static const Type::ActualType_t type = Type::UINT8_T; + static const Type::ActualType_t type = Type::UINT8_T; }; -template<> +template <> struct PodTypeConversion { - static const Type::ActualType_t type = Type::UINT16_T; + static const Type::ActualType_t type = Type::UINT16_T; }; -template<> +template <> struct PodTypeConversion { - static const Type::ActualType_t type = Type::UINT32_T; + static const Type::ActualType_t type = Type::UINT32_T; }; -template<> +template <> struct PodTypeConversion { - static const Type::ActualType_t type = Type::INT8_T; + static const Type::ActualType_t type = Type::INT8_T; }; -template<> +template <> struct PodTypeConversion { - static const Type::ActualType_t type = Type::INT16_T; + static const Type::ActualType_t type = Type::INT16_T; }; -template<> +template <> struct PodTypeConversion { - static const Type::ActualType_t type = Type::INT32_T; + static const Type::ActualType_t type = Type::INT32_T; }; -template<> +template <> struct PodTypeConversion { - static const Type::ActualType_t type = Type::FLOAT; + static const Type::ActualType_t type = Type::FLOAT; }; -template<> +template <> struct PodTypeConversion { - static const Type::ActualType_t type = Type::DOUBLE; + static const Type::ActualType_t type = Type::DOUBLE; }; #endif /* FSFW_GLOBALFUNCTIONS_TYPE_H_ */ diff --git a/src/fsfw/globalfunctions/arrayprinter.cpp b/src/fsfw/globalfunctions/arrayprinter.cpp index 964b9d04..e0899d94 100644 --- a/src/fsfw/globalfunctions/arrayprinter.cpp +++ b/src/fsfw/globalfunctions/arrayprinter.cpp @@ -1,139 +1,134 @@ #include "fsfw/globalfunctions/arrayprinter.h" -#include "fsfw/serviceinterface/ServiceInterface.h" #include +#include "fsfw/serviceinterface/ServiceInterface.h" -void arrayprinter::print(const uint8_t *data, size_t size, OutputType type, - bool printInfo, size_t maxCharPerLine) { - if(size == 0) { +void arrayprinter::print(const uint8_t *data, size_t size, OutputType type, bool printInfo, + size_t maxCharPerLine) { + if (size == 0) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "Size is zero, nothing to print" << std::endl; + sif::info << "Size is zero, nothing to print" << std::endl; #else - sif::printInfo("Size is zero, nothing to print\n"); + sif::printInfo("Size is zero, nothing to print\n"); #endif - return; - } + return; + } #if FSFW_CPP_OSTREAM_ENABLED == 1 - if(printInfo) { - sif::info << "Printing data with size " << size << ": " << std::endl; - } + if (printInfo) { + sif::info << "Printing data with size " << size << ": " << std::endl; + } #else #if FSFW_NO_C99_IO == 1 - sif::printInfo("Printing data with size %lu: \n", static_cast(size)); + sif::printInfo("Printing data with size %lu: \n", static_cast(size)); #else - sif::printInfo("Printing data with size %zu: \n", size); + sif::printInfo("Printing data with size %zu: \n", size); #endif /* FSFW_NO_C99_IO == 1 */ #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ - if(type == OutputType::HEX) { - arrayprinter::printHex(data, size, maxCharPerLine); - } - else if (type == OutputType::DEC) { - arrayprinter::printDec(data, size, maxCharPerLine); - } - else if(type == OutputType::BIN) { - arrayprinter::printBin(data, size); - } + if (type == OutputType::HEX) { + arrayprinter::printHex(data, size, maxCharPerLine); + } else if (type == OutputType::DEC) { + arrayprinter::printDec(data, size, maxCharPerLine); + } else if (type == OutputType::BIN) { + arrayprinter::printBin(data, size); + } } -void arrayprinter::printHex(const uint8_t *data, size_t size, - size_t maxCharPerLine) { +void arrayprinter::printHex(const uint8_t *data, size_t size, size_t maxCharPerLine) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - if(sif::info.crAdditionEnabled()) { - std::cout << "\r" << std::endl; - } + if (sif::info.crAdditionEnabled()) { + std::cout << "\r" << std::endl; + } - std::cout << "hex [" << std::setfill('0') << std::hex; - for(size_t i = 0; i < size; i++) { - std::cout << std::setw(2) << static_cast(data[i]); - if(i < size - 1) { - std::cout << ","; - if(i > 0 and (i + 1) % maxCharPerLine == 0) { - std::cout << std::endl; - - } - } + std::cout << "hex [" << std::setfill('0') << std::hex; + for (size_t i = 0; i < size; i++) { + std::cout << std::setw(2) << static_cast(data[i]); + if (i < size - 1) { + std::cout << ","; + if (i > 0 and (i + 1) % maxCharPerLine == 0) { + std::cout << std::endl; + } } - std::cout << std::dec << std::setfill(' '); - std::cout << "]" << std::endl; + } + std::cout << std::dec << std::setfill(' '); + std::cout << "]" << std::endl; #else - // General format: 0x01, 0x02, 0x03 so it is number of chars times 6 - // plus line break plus small safety margin. - char printBuffer[(size + 1) * 7 + 1] = {}; - size_t currentPos = 0; - for(size_t i = 0; i < size; i++) { - // To avoid buffer overflows. - if(sizeof(printBuffer) - currentPos <= 7) { - break; - } - - currentPos += snprintf(printBuffer + currentPos, 6, "%02x", data[i]); - if(i < size - 1) { - currentPos += sprintf(printBuffer + currentPos, ","); - if(i > 0 and (i + 1) % maxCharPerLine == 0) { - currentPos += sprintf(printBuffer + currentPos, "\n"); - } - } + // General format: 0x01, 0x02, 0x03 so it is number of chars times 6 + // plus line break plus small safety margin. + char printBuffer[(size + 1) * 7 + 1] = {}; + size_t currentPos = 0; + for (size_t i = 0; i < size; i++) { + // To avoid buffer overflows. + if (sizeof(printBuffer) - currentPos <= 7) { + break; } + + currentPos += snprintf(printBuffer + currentPos, 6, "%02x", data[i]); + if (i < size - 1) { + currentPos += sprintf(printBuffer + currentPos, ","); + if (i > 0 and (i + 1) % maxCharPerLine == 0) { + currentPos += sprintf(printBuffer + currentPos, "\n"); + } + } + } #if FSFW_DISABLE_PRINTOUT == 0 - printf("hex [%s]\n", printBuffer); + printf("hex [%s]\n", printBuffer); #endif /* FSFW_DISABLE_PRINTOUT == 0 */ #endif } -void arrayprinter::printDec(const uint8_t *data, size_t size, - size_t maxCharPerLine) { +void arrayprinter::printDec(const uint8_t *data, size_t size, size_t maxCharPerLine) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - if(sif::info.crAdditionEnabled()) { - std::cout << "\r" << std::endl; - } + if (sif::info.crAdditionEnabled()) { + std::cout << "\r" << std::endl; + } - std::cout << "dec [" << std::dec; - for(size_t i = 0; i < size; i++) { - std::cout << static_cast(data[i]); - if(i < size - 1){ - std::cout << ","; - if(i > 0 and (i + 1) % maxCharPerLine == 0) { - std::cout << std::endl; - } - } + std::cout << "dec [" << std::dec; + for (size_t i = 0; i < size; i++) { + std::cout << static_cast(data[i]); + if (i < size - 1) { + std::cout << ","; + if (i > 0 and (i + 1) % maxCharPerLine == 0) { + std::cout << std::endl; + } } - std::cout << "]" << std::endl; + } + std::cout << "]" << std::endl; #else - // General format: 32, 243, -12 so it is number of chars times 5 - // plus line break plus small safety margin. - char printBuffer[(size + 1) * 5 + 1] = {}; - size_t currentPos = 0; - for(size_t i = 0; i < size; i++) { - // To avoid buffer overflows. - if(sizeof(printBuffer) - currentPos <= 5) { - break; - } - - currentPos += snprintf(printBuffer + currentPos, 3, "%d", data[i]); - if(i < size - 1) { - currentPos += sprintf(printBuffer + currentPos, ","); - if(i > 0 and (i + 1) % maxCharPerLine == 0) { - currentPos += sprintf(printBuffer + currentPos, "\n"); - } - } + // General format: 32, 243, -12 so it is number of chars times 5 + // plus line break plus small safety margin. + char printBuffer[(size + 1) * 5 + 1] = {}; + size_t currentPos = 0; + for (size_t i = 0; i < size; i++) { + // To avoid buffer overflows. + if (sizeof(printBuffer) - currentPos <= 5) { + break; } + + currentPos += snprintf(printBuffer + currentPos, 3, "%d", data[i]); + if (i < size - 1) { + currentPos += sprintf(printBuffer + currentPos, ","); + if (i > 0 and (i + 1) % maxCharPerLine == 0) { + currentPos += sprintf(printBuffer + currentPos, "\n"); + } + } + } #if FSFW_DISABLE_PRINTOUT == 0 - printf("dec [%s]\n", printBuffer); + printf("dec [%s]\n", printBuffer); #endif /* FSFW_DISABLE_PRINTOUT == 0 */ #endif } void arrayprinter::printBin(const uint8_t *data, size_t size) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - for(size_t i = 0; i < size; i++) { - sif::info << "Byte " << i + 1 << ": 0b" << std::bitset<8>(data[i]) << std::endl; - } + for (size_t i = 0; i < size; i++) { + sif::info << "Byte " << i + 1 << ": 0b" << std::bitset<8>(data[i]) << std::endl; + } #else - for(size_t i = 0; i < size; i++) { - sif::printInfo("Byte %d: 0b" BYTE_TO_BINARY_PATTERN "\n", i + 1, BYTE_TO_BINARY(data[i])); - } + for (size_t i = 0; i < size; i++) { + sif::printInfo("Byte %d: 0b" BYTE_TO_BINARY_PATTERN "\n", i + 1, BYTE_TO_BINARY(data[i])); + } #endif } diff --git a/src/fsfw/globalfunctions/arrayprinter.h b/src/fsfw/globalfunctions/arrayprinter.h index e6b3ea6b..d517d4e4 100644 --- a/src/fsfw/globalfunctions/arrayprinter.h +++ b/src/fsfw/globalfunctions/arrayprinter.h @@ -1,25 +1,19 @@ #ifndef FRAMEWORK_GLOBALFUNCTIONS_ARRAYPRINTER_H_ #define FRAMEWORK_GLOBALFUNCTIONS_ARRAYPRINTER_H_ -#include #include +#include -enum class OutputType { - DEC, - HEX, - BIN -}; +enum class OutputType { DEC, HEX, BIN }; namespace arrayprinter { - - void print(const uint8_t* data, size_t size, OutputType type = OutputType::HEX, - bool printInfo = true, size_t maxCharPerLine = 10); + bool printInfo = true, size_t maxCharPerLine = 10); void printHex(const uint8_t* data, size_t size, size_t maxCharPerLine = 10); void printDec(const uint8_t* data, size_t size, size_t maxCharPerLine = 10); void printBin(const uint8_t* data, size_t size); -} +} // namespace arrayprinter #endif /* FRAMEWORK_GLOBALFUNCTIONS_ARRAYPRINTER_H_ */ diff --git a/src/fsfw/globalfunctions/bitutility.cpp b/src/fsfw/globalfunctions/bitutility.cpp index 54e94a95..e03bf9fe 100644 --- a/src/fsfw/globalfunctions/bitutility.cpp +++ b/src/fsfw/globalfunctions/bitutility.cpp @@ -1,34 +1,34 @@ #include "fsfw/globalfunctions/bitutility.h" void bitutil::set(uint8_t *byte, uint8_t position) { - if(position > 7) { - return; - } - uint8_t shiftNumber = position + (7 - 2 * position); - *byte |= 1 << shiftNumber; + if (position > 7) { + return; + } + uint8_t shiftNumber = position + (7 - 2 * position); + *byte |= 1 << shiftNumber; } void bitutil::toggle(uint8_t *byte, uint8_t position) { - if(position > 7) { - return; - } - uint8_t shiftNumber = position + (7 - 2 * position); - *byte ^= 1 << shiftNumber; + if (position > 7) { + return; + } + uint8_t shiftNumber = position + (7 - 2 * position); + *byte ^= 1 << shiftNumber; } void bitutil::clear(uint8_t *byte, uint8_t position) { - if(position > 7) { - return; - } - uint8_t shiftNumber = position + (7 - 2 * position); - *byte &= ~(1 << shiftNumber); + if (position > 7) { + return; + } + uint8_t shiftNumber = position + (7 - 2 * position); + *byte &= ~(1 << shiftNumber); } -bool bitutil::get(const uint8_t *byte, uint8_t position, bool& bit) { - if(position > 7) { - return false; - } - uint8_t shiftNumber = position + (7 - 2 * position); - bit = *byte & (1 << shiftNumber); - return true; +bool bitutil::get(const uint8_t *byte, uint8_t position, bool &bit) { + if (position > 7) { + return false; + } + uint8_t shiftNumber = position + (7 - 2 * position); + bit = *byte & (1 << shiftNumber); + return true; } diff --git a/src/fsfw/globalfunctions/bitutility.h b/src/fsfw/globalfunctions/bitutility.h index 00f19310..48223f51 100644 --- a/src/fsfw/globalfunctions/bitutility.h +++ b/src/fsfw/globalfunctions/bitutility.h @@ -36,6 +36,6 @@ void clear(uint8_t* byte, uint8_t position); */ bool get(const uint8_t* byte, uint8_t position, bool& bit); -} +} // namespace bitutil #endif /* FSFW_GLOBALFUNCTIONS_BITUTIL_H_ */ diff --git a/src/fsfw/globalfunctions/constants.h b/src/fsfw/globalfunctions/constants.h index 2c3b66c1..58855073 100644 --- a/src/fsfw/globalfunctions/constants.h +++ b/src/fsfw/globalfunctions/constants.h @@ -10,6 +10,6 @@ static const double OMEGA = 7.2921158553E-5; static const double GRAVITATIONAL_CONSTANT = 3.987095392E14; static const double MEAN_RADIUS = 6371008.8; static const double STANDARD_GRAVITATIONAL_PARAMETER = 3.9860044189e14; -} +} // namespace Earth #endif /* CONSTANTS_H_ */ diff --git a/src/fsfw/globalfunctions/matching/BinaryMatcher.h b/src/fsfw/globalfunctions/matching/BinaryMatcher.h index 4f6db85d..6a8b0f35 100644 --- a/src/fsfw/globalfunctions/matching/BinaryMatcher.h +++ b/src/fsfw/globalfunctions/matching/BinaryMatcher.h @@ -3,39 +3,35 @@ #include "MatcherIF.h" -template -class BinaryMatcher: public MatcherIF { -public: - bool inverted; - T mask, matchField; +template +class BinaryMatcher : public MatcherIF { + public: + bool inverted; + T mask, matchField; - BinaryMatcher() : - inverted(false), mask(0), matchField(0) { - } + BinaryMatcher() : inverted(false), mask(0), matchField(0) {} - BinaryMatcher(T mask, T match, bool inverted = false) : - inverted(inverted), mask(mask), matchField(match) { - } + BinaryMatcher(T mask, T match, bool inverted = false) + : inverted(inverted), mask(mask), matchField(match) {} - bool match(T input) { - if (inverted) { - return ~doMatch(input, mask, matchField); - } else { - return doMatch(input, mask, matchField); - } - } + bool match(T input) { + if (inverted) { + return ~doMatch(input, mask, matchField); + } else { + return doMatch(input, mask, matchField); + } + } -protected: - - bool doMatch(T input, T mask, T match) { - match = match & mask; - input = input & mask; - if (input == match) { - return true; - } else { - return false; - } - } + protected: + bool doMatch(T input, T mask, T match) { + match = match & mask; + input = input & mask; + if (input == match) { + return true; + } else { + return false; + } + } }; #endif /* BINARYMATCHER_H_ */ diff --git a/src/fsfw/globalfunctions/matching/DecimalMatcher.h b/src/fsfw/globalfunctions/matching/DecimalMatcher.h index 53505020..c2d480aa 100644 --- a/src/fsfw/globalfunctions/matching/DecimalMatcher.h +++ b/src/fsfw/globalfunctions/matching/DecimalMatcher.h @@ -3,48 +3,45 @@ #include "MatcherIF.h" -template -class DecimalMatcher: public MatcherIF { -public: - bool inverted; - T mask, matchField; +template +class DecimalMatcher : public MatcherIF { + public: + bool inverted; + T mask, matchField; - DecimalMatcher() : - inverted(false), mask(0), matchField(0) { - } + DecimalMatcher() : inverted(false), mask(0), matchField(0) {} - DecimalMatcher(T mask, T match, bool inverted = false) : - inverted(inverted), mask(mask), matchField(match) { - } + DecimalMatcher(T mask, T match, bool inverted = false) + : inverted(inverted), mask(mask), matchField(match) {} - bool match(T input) { - if (inverted) { - return ~doMatch(input, mask, matchField); - } else { - return doMatch(input, mask, matchField); - } - } + bool match(T input) { + if (inverted) { + return ~doMatch(input, mask, matchField); + } else { + return doMatch(input, mask, matchField); + } + } -protected: - bool doMatch(T input, T mask, T match) { - T decimal = 1, remainderMask, remainderMatch, remainderInput; + protected: + bool doMatch(T input, T mask, T match) { + T decimal = 1, remainderMask, remainderMatch, remainderInput; - while (mask != 0) { - remainderMask = mask % (decimal * 10); - remainderMatch = match % (decimal * 10); - remainderInput = input % (decimal * 10); - if (remainderMask != 0) { - if (remainderMatch != remainderInput) { - return false; - } - } - mask -= remainderMask; - match -= remainderMatch; - input -= remainderInput; - decimal *= 10; - } - return true; - } + while (mask != 0) { + remainderMask = mask % (decimal * 10); + remainderMatch = match % (decimal * 10); + remainderInput = input % (decimal * 10); + if (remainderMask != 0) { + if (remainderMatch != remainderInput) { + return false; + } + } + mask -= remainderMask; + match -= remainderMatch; + input -= remainderInput; + decimal *= 10; + } + return true; + } }; #endif /* DECIMALMATCHER_H_ */ diff --git a/src/fsfw/globalfunctions/matching/MatchTree.h b/src/fsfw/globalfunctions/matching/MatchTree.h index 755687b2..f7775d45 100644 --- a/src/fsfw/globalfunctions/matching/MatchTree.h +++ b/src/fsfw/globalfunctions/matching/MatchTree.h @@ -2,215 +2,201 @@ #define FRAMEWORK_GLOBALFUNCTIONS_MATCHING_MATCHTREE_H_ #include "../../container/BinaryTree.h" -#include "SerializeableMatcherIF.h" #include "../../serialize/SerializeAdapter.h" +#include "SerializeableMatcherIF.h" -template -class MatchTree: public SerializeableMatcherIF, public BinaryTree< - SerializeableMatcherIF> { -public: +template +class MatchTree : public SerializeableMatcherIF, public BinaryTree> { + public: + static const uint8_t INTERFACE_ID = CLASS_ID::MATCH_TREE_CLASS; + static const ReturnValue_t TOO_DETAILED_REQUEST = MAKE_RETURN_CODE(1); + static const ReturnValue_t TOO_GENERAL_REQUEST = MAKE_RETURN_CODE(2); + static const ReturnValue_t NO_MATCH = MAKE_RETURN_CODE(3); + static const ReturnValue_t FULL = MAKE_RETURN_CODE(4); + static const ReturnValue_t NEW_NODE_CREATED = MAKE_RETURN_CODE(5); - static const uint8_t INTERFACE_ID = CLASS_ID::MATCH_TREE_CLASS; - static const ReturnValue_t TOO_DETAILED_REQUEST = MAKE_RETURN_CODE(1); - static const ReturnValue_t TOO_GENERAL_REQUEST = MAKE_RETURN_CODE(2); - static const ReturnValue_t NO_MATCH = MAKE_RETURN_CODE(3); - static const ReturnValue_t FULL = MAKE_RETURN_CODE(4); - static const ReturnValue_t NEW_NODE_CREATED = MAKE_RETURN_CODE(5); + typedef typename BinaryTree>::iterator iterator; + typedef BinaryNode> Node; + static const bool AND = true; // LEFT + static const bool OR = false; // RIGHT + MatchTree(BinaryNode>* root, uint8_t maxDepth = -1) + : BinaryTree>(root), maxDepth(maxDepth) {} + MatchTree(iterator root, uint8_t maxDepth = -1) + : BinaryTree>(root.element), maxDepth(maxDepth) {} + MatchTree() : BinaryTree>(), maxDepth(-1) {} + virtual ~MatchTree() {} + virtual bool match(T number) { return matchesTree(number); } + bool matchesTree(T number) { + iterator iter = this->begin(); + if (iter == this->end()) { + return false; + } + return matchSubtree(iter, number); + } - typedef typename BinaryTree>::iterator iterator; - typedef BinaryNode> Node; - static const bool AND = true; //LEFT - static const bool OR = false; //RIGHT - MatchTree(BinaryNode>* root, - uint8_t maxDepth = -1) : - BinaryTree>(root), maxDepth(maxDepth) { - } - MatchTree(iterator root, uint8_t maxDepth = -1) : - BinaryTree>(root.element), maxDepth( - maxDepth) { - } - MatchTree() : - BinaryTree>(), maxDepth(-1) { - } - virtual ~MatchTree() { - } - virtual bool match(T number) { - return matchesTree(number); - } - bool matchesTree(T number) { - iterator iter = this->begin(); - if (iter == this->end()) { - return false; - } - return matchSubtree(iter, number); - } + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + SerializeIF::Endianness streamEndianness) const override { + iterator iter = this->begin(); + uint8_t count = this->countRight(iter); + ReturnValue_t result = + SerializeAdapter::serialize(&count, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (iter == this->end()) { + return HasReturnvaluesIF::RETURN_OK; + } + result = iter->serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (maxDepth > 0) { + MatchTree temp(iter.left(), maxDepth - 1); + result = temp.serialize(buffer, size, maxSize, streamEndianness); + } + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + iter = iter.right(); + while (iter != this->end()) { + result = iter->serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (maxDepth > 0) { + MatchTree temp(iter.left(), maxDepth - 1); + result = temp.serialize(buffer, size, maxSize, streamEndianness); + } + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + iter = iter.right(); + } + return result; + } - ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, SerializeIF::Endianness streamEndianness) const override { - iterator iter = this->begin(); - uint8_t count = this->countRight(iter); - ReturnValue_t result = SerializeAdapter::serialize(&count, - buffer, size, maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if (iter == this->end()) { - return HasReturnvaluesIF::RETURN_OK; - } - result = iter->serialize(buffer, size, maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if (maxDepth > 0) { - MatchTree temp(iter.left(), maxDepth - 1); - result = temp.serialize(buffer, size, maxSize, streamEndianness); - } - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - iter = iter.right(); - while (iter != this->end()) { - result = iter->serialize(buffer, size, maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if (maxDepth > 0) { - MatchTree temp(iter.left(), maxDepth - 1); - result = temp.serialize(buffer, size, maxSize, streamEndianness); - } - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - iter = iter.right(); - } - return result; - } + size_t getSerializedSize() const override { + // Analogous to serialize! + uint32_t size = 1; // One for count + iterator iter = this->begin(); + if (iter == this->end()) { + return size; + } + // Count object itself + size += iter->getSerializedSize(); + // Handle everything below on AND side + if (maxDepth > 0) { + MatchTree temp(iter.left(), maxDepth - 1); + size += temp.getSerializedSize(); + } + // Handle everything on OR side + iter = iter.right(); + // Iterate over every object on the OR branch + while (iter != this->end()) { + size += iter->getSerializedSize(); + if (maxDepth > 0) { + // If we are allowed to go deeper, handle AND elements. + MatchTree temp(iter.left(), maxDepth - 1); + size += temp.getSerializedSize(); + } + iter = iter.right(); + } + return size; + } - size_t getSerializedSize() const override { - //Analogous to serialize! - uint32_t size = 1; //One for count - iterator iter = this->begin(); - if (iter == this->end()) { - return size; - } - //Count object itself - size += iter->getSerializedSize(); - //Handle everything below on AND side - if (maxDepth > 0) { - MatchTree temp(iter.left(), maxDepth - 1); - size += temp.getSerializedSize(); - } - //Handle everything on OR side - iter = iter.right(); - //Iterate over every object on the OR branch - while (iter != this->end()) { - size += iter->getSerializedSize(); - if (maxDepth > 0) { - //If we are allowed to go deeper, handle AND elements. - MatchTree temp(iter.left(), maxDepth - 1); - size += temp.getSerializedSize(); - } - iter = iter.right(); - } - return size; - } + ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + SerializeIF::Endianness streamEndianness) override { + return HasReturnvaluesIF::RETURN_OK; + } - ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - SerializeIF::Endianness streamEndianness) override { - return HasReturnvaluesIF::RETURN_OK; - } + protected: + bool isOnAndBranch(iterator position) { + if ((position == this->end()) || (position.up() == this->end())) { + return false; + } + if (position.up().left() == position) { + return true; + } else { + return false; + } + } -protected: + // SHOULDDO: What to do if insertion/deletion fails. Throw event? + ReturnValue_t removeElementAndAllChildren(iterator position) { + auto children = this->erase(position); + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + if (children.first != this->end()) { + result = removeElementAndAllChildren(children.first); + } + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (children.second != this->end()) { + result = removeElementAndAllChildren(children.second); + } + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + // Delete element itself. + return cleanUpElement(position); + } - bool isOnAndBranch(iterator position) { - if ((position == this->end()) || (position.up() == this->end())) { - return false; - } - if (position.up().left() == position) { - return true; - } else { - return false; - } - } + ReturnValue_t removeElementAndReconnectChildren(iterator position) { + if (position == this->end()) { + return HasReturnvaluesIF::RETURN_OK; + } + // Delete everything from the AND branch. + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + if (position.left() != this->end()) { + result = removeElementAndAllChildren(position.left()); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + } - //SHOULDDO: What to do if insertion/deletion fails. Throw event? - ReturnValue_t removeElementAndAllChildren(iterator position) { - auto children = this->erase(position); - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - if (children.first != this->end()) { - result = removeElementAndAllChildren(children.first); - } - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if (children.second != this->end()) { - result = removeElementAndAllChildren(children.second); - } - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - //Delete element itself. - return cleanUpElement(position); - } + if (position.right() != this->end()) { + // There's something at the OR branch, reconnect to parent. + if (isOnAndBranch(position)) { + // Either one hierarchy up AND branch... + this->insert(AND, position.up(), position.right().element); + } else { + // or on another OR'ed element (or install new root node). + this->insert(OR, position.up(), position.right().element); + } + } else { + if (isOnAndBranch(position)) { + // Recursively delete parent node as well, because it is not expected to be there anymore. + return removeElementAndReconnectChildren(position.up()); + } else { + // simply delete self. + this->erase(position); + } + } + // Delete element itself. + return cleanUpElement(position); + } - ReturnValue_t removeElementAndReconnectChildren(iterator position) { - if (position == this->end()) { - return HasReturnvaluesIF::RETURN_OK; - } - //Delete everything from the AND branch. - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - if (position.left() != this->end()) { - result = removeElementAndAllChildren(position.left()); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - } + virtual ReturnValue_t cleanUpElement(iterator position) { return HasReturnvaluesIF::RETURN_OK; } - if (position.right() != this->end()) { - //There's something at the OR branch, reconnect to parent. - if (isOnAndBranch(position)) { - //Either one hierarchy up AND branch... - this->insert(AND, position.up(), position.right().element); - } else { - //or on another OR'ed element (or install new root node). - this->insert(OR, position.up(), position.right().element); - } - } else { - if (isOnAndBranch(position)) { - //Recursively delete parent node as well, because it is not expected to be there anymore. - return removeElementAndReconnectChildren(position.up()); - } else { - //simply delete self. - this->erase(position); - } + bool matchSubtree(iterator iter, T number) { + bool isMatch = iter->match(number); + if (isMatch) { + if (iter.left() == this->end()) { + return true; + } + isMatch = matchSubtree(iter.left(), number); + if (isMatch) { + return true; + } + } + if (iter.right() == this->end()) { + return false; + } + return matchSubtree(iter.right(), number); + } - } - //Delete element itself. - return cleanUpElement(position); - } - - virtual ReturnValue_t cleanUpElement(iterator position) { - return HasReturnvaluesIF::RETURN_OK; - } - - bool matchSubtree(iterator iter, T number) { - bool isMatch = iter->match(number); - if (isMatch) { - if (iter.left() == this->end()) { - return true; - } - isMatch = matchSubtree(iter.left(), number); - if (isMatch) { - return true; - } - } - if (iter.right() == this->end()) { - return false; - } - return matchSubtree(iter.right(), number); - } -private: - uint8_t maxDepth; + private: + uint8_t maxDepth; }; #endif /* FRAMEWORK_GLOBALFUNCTIONS_MATCHING_MATCHTREE_H_ */ diff --git a/src/fsfw/globalfunctions/matching/MatcherIF.h b/src/fsfw/globalfunctions/matching/MatcherIF.h index 4a6a05af..a571f7f1 100644 --- a/src/fsfw/globalfunctions/matching/MatcherIF.h +++ b/src/fsfw/globalfunctions/matching/MatcherIF.h @@ -1,16 +1,12 @@ #ifndef MATCHERIF_H_ #define MATCHERIF_H_ -template +template class MatcherIF { -public: - virtual ~MatcherIF() { - } - - virtual bool match(T number) { - return false; - } + public: + virtual ~MatcherIF() {} + virtual bool match(T number) { return false; } }; #endif /* MATCHERIF_H_ */ diff --git a/src/fsfw/globalfunctions/matching/RangeMatcher.h b/src/fsfw/globalfunctions/matching/RangeMatcher.h index b64b9e30..4e1f3922 100644 --- a/src/fsfw/globalfunctions/matching/RangeMatcher.h +++ b/src/fsfw/globalfunctions/matching/RangeMatcher.h @@ -1,70 +1,62 @@ #ifndef RANGEMATCHER_H_ #define RANGEMATCHER_H_ -#include "SerializeableMatcherIF.h" #include "../../serialize/SerializeAdapter.h" +#include "SerializeableMatcherIF.h" -template -class RangeMatcher: public SerializeableMatcherIF { -public: - bool inverted; - T lowerBound; - T upperBound; +template +class RangeMatcher : public SerializeableMatcherIF { + public: + bool inverted; + T lowerBound; + T upperBound; - RangeMatcher() : - inverted(true), lowerBound(1), upperBound(0) { - } - RangeMatcher(T lowerBound, T upperBound, bool inverted = false) : - inverted(inverted), lowerBound(lowerBound), upperBound(upperBound) { - } + RangeMatcher() : inverted(true), lowerBound(1), upperBound(0) {} + RangeMatcher(T lowerBound, T upperBound, bool inverted = false) + : inverted(inverted), lowerBound(lowerBound), upperBound(upperBound) {} - bool match(T input) { - if (inverted) { - return !doMatch(input); - } else { - return doMatch(input); - } - } + bool match(T input) { + if (inverted) { + return !doMatch(input); + } else { + return doMatch(input); + } + } - ReturnValue_t serialize(uint8_t **buffer, size_t *size, size_t maxSize, - SerializeIF::Endianness streamEndianness) const override { - ReturnValue_t result = SerializeAdapter::serialize(&lowerBound, buffer, - size, maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::serialize(&upperBound, buffer, size, - maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return SerializeAdapter::serialize(&inverted, buffer, size, maxSize, - streamEndianness); - } + ReturnValue_t serialize(uint8_t **buffer, size_t *size, size_t maxSize, + SerializeIF::Endianness streamEndianness) const override { + ReturnValue_t result = + SerializeAdapter::serialize(&lowerBound, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::serialize(&upperBound, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return SerializeAdapter::serialize(&inverted, buffer, size, maxSize, streamEndianness); + } - size_t getSerializedSize() const override { - return sizeof(lowerBound) + sizeof(upperBound) + sizeof(bool); - } + size_t getSerializedSize() const override { + return sizeof(lowerBound) + sizeof(upperBound) + sizeof(bool); + } - ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, - SerializeIF::Endianness streamEndianness) override { - ReturnValue_t result = SerializeAdapter::deSerialize(&lowerBound, - buffer, size, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::deSerialize(&upperBound, buffer, size, - streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return SerializeAdapter::deSerialize(&inverted, buffer, size, - streamEndianness); - } -protected: - bool doMatch(T input) { - return (input >= lowerBound) && (input <= upperBound); - } + ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, + SerializeIF::Endianness streamEndianness) override { + ReturnValue_t result = + SerializeAdapter::deSerialize(&lowerBound, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::deSerialize(&upperBound, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return SerializeAdapter::deSerialize(&inverted, buffer, size, streamEndianness); + } + + protected: + bool doMatch(T input) { return (input >= lowerBound) && (input <= upperBound); } }; #endif /* RANGEMATCHER_H_ */ diff --git a/src/fsfw/globalfunctions/matching/SerializeableMatcherIF.h b/src/fsfw/globalfunctions/matching/SerializeableMatcherIF.h index 067b0251..a83286de 100644 --- a/src/fsfw/globalfunctions/matching/SerializeableMatcherIF.h +++ b/src/fsfw/globalfunctions/matching/SerializeableMatcherIF.h @@ -1,13 +1,13 @@ #ifndef FRAMEWORK_GLOBALFUNCTIONS_MATCHING_SERIALIZEABLEMATCHERIF_H_ #define FRAMEWORK_GLOBALFUNCTIONS_MATCHING_SERIALIZEABLEMATCHERIF_H_ -#include "MatcherIF.h" #include "../../serialize/SerializeIF.h" +#include "MatcherIF.h" -template +template class SerializeableMatcherIF : public MatcherIF, public SerializeIF { -public: - virtual ~SerializeableMatcherIF() {} + public: + virtual ~SerializeableMatcherIF() {} }; #endif /* FRAMEWORK_GLOBALFUNCTIONS_MATCHING_SERIALIZEABLEMATCHERIF_H_ */ diff --git a/src/fsfw/globalfunctions/math/MatrixOperations.h b/src/fsfw/globalfunctions/math/MatrixOperations.h index 66f89c53..31966f8f 100644 --- a/src/fsfw/globalfunctions/math/MatrixOperations.h +++ b/src/fsfw/globalfunctions/math/MatrixOperations.h @@ -1,115 +1,100 @@ #ifndef MATRIXOPERATIONS_H_ #define MATRIXOPERATIONS_H_ -#include #include -template +#include + +template class MatrixOperations { -public: - //do not use with result == matrix1 or matrix2 - static void multiply(const T1 *matrix1, const T2 *matrix2, T3 *result, - uint8_t rows1, uint8_t columns1, uint8_t columns2) { - if ((matrix1 == (T1*)result) || (matrix2 == (T2*)result)){ - //SHOULDDO find an implementation that is tolerant to this - return; - } - for (uint8_t resultColumn = 0; resultColumn < columns2; - resultColumn++) { - for (uint8_t resultRow = 0; resultRow < rows1; resultRow++) { - result[resultColumn + columns2 * resultRow] = 0; - for (uint8_t i = 0; i < columns1; i++) { - result[resultColumn + columns2 * resultRow] += matrix1[i - + resultRow * columns1] - * matrix2[resultColumn + i * columns2]; - } - } - } - } + public: + // do not use with result == matrix1 or matrix2 + static void multiply(const T1 *matrix1, const T2 *matrix2, T3 *result, uint8_t rows1, + uint8_t columns1, uint8_t columns2) { + if ((matrix1 == (T1 *)result) || (matrix2 == (T2 *)result)) { + // SHOULDDO find an implementation that is tolerant to this + return; + } + for (uint8_t resultColumn = 0; resultColumn < columns2; resultColumn++) { + for (uint8_t resultRow = 0; resultRow < rows1; resultRow++) { + result[resultColumn + columns2 * resultRow] = 0; + for (uint8_t i = 0; i < columns1; i++) { + result[resultColumn + columns2 * resultRow] += + matrix1[i + resultRow * columns1] * matrix2[resultColumn + i * columns2]; + } + } + } + } - static void transpose(const T1 *matrix, T2 *transposed, uint8_t size) { - uint8_t row, column; - transposed[0] = matrix[0]; - for (column = 1; column < size; column++) { - transposed[column + size * column] = matrix[column + size * column]; - for (row = 0; row < column; row++) { - T1 temp = matrix[column + size * row]; - transposed[column + size * row] = matrix[row + size * column]; - transposed[row + size * column] = temp; - } - } - } + static void transpose(const T1 *matrix, T2 *transposed, uint8_t size) { + uint8_t row, column; + transposed[0] = matrix[0]; + for (column = 1; column < size; column++) { + transposed[column + size * column] = matrix[column + size * column]; + for (row = 0; row < column; row++) { + T1 temp = matrix[column + size * row]; + transposed[column + size * row] = matrix[row + size * column]; + transposed[row + size * column] = temp; + } + } + } - // Overload transpose to support non symmetrical matrices - //do not use with transposed == matrix && columns != rows - static void transpose(const T1 *matrix, T2 *transposed, uint8_t rows, uint8_t columns) { - uint8_t row, column; - transposed[0] = matrix[0]; - if (matrix == transposed && columns == rows) - { - transpose(matrix, transposed, rows); - } - else if (matrix == transposed && columns != rows) - { - // not permitted - return; - } - for (column = 0; column < columns; column++) { - for (row = 0; row < rows; row++) { - transposed[row + column * rows] = matrix[column + row * columns]; - } - } - } + // Overload transpose to support non symmetrical matrices + // do not use with transposed == matrix && columns != rows + static void transpose(const T1 *matrix, T2 *transposed, uint8_t rows, uint8_t columns) { + uint8_t row, column; + transposed[0] = matrix[0]; + if (matrix == transposed && columns == rows) { + transpose(matrix, transposed, rows); + } else if (matrix == transposed && columns != rows) { + // not permitted + return; + } + for (column = 0; column < columns; column++) { + for (row = 0; row < rows; row++) { + transposed[row + column * rows] = matrix[column + row * columns]; + } + } + } - static void add(const T1 *matrix1, const T2 *matrix2, T3 *result, - uint8_t rows, uint8_t columns) - { - for (uint8_t resultColumn = 0; resultColumn < columns; resultColumn++) - { - for (uint8_t resultRow = 0; resultRow < rows; resultRow++) - { - result[resultColumn + columns * resultRow] = matrix1[resultColumn + columns * resultRow]+ - matrix2[resultColumn + columns * resultRow]; - } - } - } + static void add(const T1 *matrix1, const T2 *matrix2, T3 *result, uint8_t rows, uint8_t columns) { + for (uint8_t resultColumn = 0; resultColumn < columns; resultColumn++) { + for (uint8_t resultRow = 0; resultRow < rows; resultRow++) { + result[resultColumn + columns * resultRow] = matrix1[resultColumn + columns * resultRow] + + matrix2[resultColumn + columns * resultRow]; + } + } + } - static void subtract(const T1 *matrix1, const T2 *matrix2, T3 *result, - uint8_t rows, uint8_t columns) - { - for (uint8_t resultColumn = 0; resultColumn < columns; resultColumn++) - { - for (uint8_t resultRow = 0; resultRow < rows; resultRow++) - { - result[resultColumn + columns * resultRow] = matrix1[resultColumn + columns * resultRow]- - matrix2[resultColumn + columns * resultRow]; - } - } - } + static void subtract(const T1 *matrix1, const T2 *matrix2, T3 *result, uint8_t rows, + uint8_t columns) { + for (uint8_t resultColumn = 0; resultColumn < columns; resultColumn++) { + for (uint8_t resultRow = 0; resultRow < rows; resultRow++) { + result[resultColumn + columns * resultRow] = matrix1[resultColumn + columns * resultRow] - + matrix2[resultColumn + columns * resultRow]; + } + } + } - static void addScalar(const T1 *matrix1, const T2 scalar, T3 *result, - uint8_t rows, uint8_t columns) - { - for (uint8_t resultColumn = 0; resultColumn < columns; resultColumn++) - { - for (uint8_t resultRow = 0; resultRow < rows; resultRow++) - { - result[resultColumn + columns * resultRow] = matrix1[resultColumn + columns * resultRow]+scalar; - } - } - } + static void addScalar(const T1 *matrix1, const T2 scalar, T3 *result, uint8_t rows, + uint8_t columns) { + for (uint8_t resultColumn = 0; resultColumn < columns; resultColumn++) { + for (uint8_t resultRow = 0; resultRow < rows; resultRow++) { + result[resultColumn + columns * resultRow] = + matrix1[resultColumn + columns * resultRow] + scalar; + } + } + } - static void multiplyScalar(const T1 *matrix1, const T2 scalar, T3 *result, - uint8_t rows, uint8_t columns) - { - for (uint8_t resultColumn = 0; resultColumn < columns; resultColumn++) - { - for (uint8_t resultRow = 0; resultRow < rows; resultRow++) - { - result[resultColumn + columns * resultRow] = matrix1[resultColumn + columns * resultRow]*scalar; - } - } - } + static void multiplyScalar(const T1 *matrix1, const T2 scalar, T3 *result, uint8_t rows, + uint8_t columns) { + for (uint8_t resultColumn = 0; resultColumn < columns; resultColumn++) { + for (uint8_t resultRow = 0; resultRow < rows; resultRow++) { + result[resultColumn + columns * resultRow] = + matrix1[resultColumn + columns * resultRow] * scalar; + } + } + } }; #endif /* MATRIXOPERATIONS_H_ */ diff --git a/src/fsfw/globalfunctions/math/QuaternionOperations.cpp b/src/fsfw/globalfunctions/math/QuaternionOperations.cpp index 31ba2044..f65a1847 100644 --- a/src/fsfw/globalfunctions/math/QuaternionOperations.cpp +++ b/src/fsfw/globalfunctions/math/QuaternionOperations.cpp @@ -1,156 +1,122 @@ #include "fsfw/globalfunctions/math/QuaternionOperations.h" -#include "fsfw/globalfunctions/math/VectorOperations.h" + +#include #include #include -#include -QuaternionOperations::~QuaternionOperations() { -} +#include "fsfw/globalfunctions/math/VectorOperations.h" -void QuaternionOperations::multiply(const double* q1, const double* q2, - double* q) { - double out[4]; +QuaternionOperations::~QuaternionOperations() {} - out[0] = q1[3] * q2[0] + q1[2] * q2[1] - q1[1] * q2[2] + q1[0] * q2[3]; - out[1] = -q1[2] * q2[0] + q1[3] * q2[1] + q1[0] * q2[2] + q1[1] * q2[3]; - out[2] = q1[1] * q2[0] - q1[0] * q2[1] + q1[3] * q2[2] + q1[2] * q2[3]; - out[3] = -q1[0] * q2[0] - q1[1] * q2[1] - q1[2] * q2[2] + q1[3] * q2[3]; +void QuaternionOperations::multiply(const double* q1, const double* q2, double* q) { + double out[4]; - memcpy(q, out, 4 * sizeof(*q)); + out[0] = q1[3] * q2[0] + q1[2] * q2[1] - q1[1] * q2[2] + q1[0] * q2[3]; + out[1] = -q1[2] * q2[0] + q1[3] * q2[1] + q1[0] * q2[2] + q1[1] * q2[3]; + out[2] = q1[1] * q2[0] - q1[0] * q2[1] + q1[3] * q2[2] + q1[2] * q2[3]; + out[3] = -q1[0] * q2[0] - q1[1] * q2[1] - q1[2] * q2[2] + q1[3] * q2[3]; + + memcpy(q, out, 4 * sizeof(*q)); } void QuaternionOperations::toDcm(const double* quaternion, double dcm[][3]) { - dcm[0][0] = 2 - * (quaternion[0] * quaternion[0] + quaternion[3] * quaternion[3]) - - 1; - dcm[0][1] = 2 - * (quaternion[0] * quaternion[1] + quaternion[2] * quaternion[3]); - dcm[0][2] = 2 - * (quaternion[0] * quaternion[2] - quaternion[1] * quaternion[3]); + dcm[0][0] = 2 * (quaternion[0] * quaternion[0] + quaternion[3] * quaternion[3]) - 1; + dcm[0][1] = 2 * (quaternion[0] * quaternion[1] + quaternion[2] * quaternion[3]); + dcm[0][2] = 2 * (quaternion[0] * quaternion[2] - quaternion[1] * quaternion[3]); - dcm[1][0] = 2 - * (quaternion[0] * quaternion[1] - quaternion[2] * quaternion[3]); - dcm[1][1] = 2 - * (quaternion[1] * quaternion[1] + quaternion[3] * quaternion[3]) - - 1; - dcm[1][2] = 2 - * (quaternion[1] * quaternion[2] + quaternion[0] * quaternion[3]); + dcm[1][0] = 2 * (quaternion[0] * quaternion[1] - quaternion[2] * quaternion[3]); + dcm[1][1] = 2 * (quaternion[1] * quaternion[1] + quaternion[3] * quaternion[3]) - 1; + dcm[1][2] = 2 * (quaternion[1] * quaternion[2] + quaternion[0] * quaternion[3]); - dcm[2][0] = 2 - * (quaternion[0] * quaternion[2] + quaternion[1] * quaternion[3]); - dcm[2][1] = 2 - * (quaternion[1] * quaternion[2] - quaternion[0] * quaternion[3]); - dcm[2][2] = 2 - * (quaternion[2] * quaternion[2] + quaternion[3] * quaternion[3]) - - 1; + dcm[2][0] = 2 * (quaternion[0] * quaternion[2] + quaternion[1] * quaternion[3]); + dcm[2][1] = 2 * (quaternion[1] * quaternion[2] - quaternion[0] * quaternion[3]); + dcm[2][2] = 2 * (quaternion[2] * quaternion[2] + quaternion[3] * quaternion[3]) - 1; } -void QuaternionOperations::inverse(const double* quaternion, - double* inverseQuaternion) { - memcpy(inverseQuaternion, quaternion, 4 * sizeof(*quaternion)); - VectorOperations::mulScalar(inverseQuaternion, -1, - inverseQuaternion, 3); +void QuaternionOperations::inverse(const double* quaternion, double* inverseQuaternion) { + memcpy(inverseQuaternion, quaternion, 4 * sizeof(*quaternion)); + VectorOperations::mulScalar(inverseQuaternion, -1, inverseQuaternion, 3); } -QuaternionOperations::QuaternionOperations() { +QuaternionOperations::QuaternionOperations() {} -} - -void QuaternionOperations::normalize(const double* quaternion, - double* unitQuaternion) { - VectorOperations::normalize(quaternion, unitQuaternion, 4); +void QuaternionOperations::normalize(const double* quaternion, double* unitQuaternion) { + VectorOperations::normalize(quaternion, unitQuaternion, 4); } float QuaternionOperations::norm(const double* quaternion) { - return VectorOperations::norm(quaternion, 4); + return VectorOperations::norm(quaternion, 4); } -void QuaternionOperations::fromDcm(const double dcm[][3], double* quaternion, - uint8_t *index) { +void QuaternionOperations::fromDcm(const double dcm[][3], double* quaternion, uint8_t* index) { + double a[4]; - double a[4]; + a[0] = 1 + dcm[0][0] - dcm[1][1] - dcm[2][2]; + a[1] = 1 - dcm[0][0] + dcm[1][1] - dcm[2][2]; + a[2] = 1 - dcm[0][0] - dcm[1][1] + dcm[2][2]; + a[3] = 1 + dcm[0][0] + dcm[1][1] + dcm[2][2]; - a[0] = 1 + dcm[0][0] - dcm[1][1] - dcm[2][2]; - a[1] = 1 - dcm[0][0] + dcm[1][1] - dcm[2][2]; - a[2] = 1 - dcm[0][0] - dcm[1][1] + dcm[2][2]; - a[3] = 1 + dcm[0][0] + dcm[1][1] + dcm[2][2]; + uint8_t maxAIndex = 0; - uint8_t maxAIndex = 0; + VectorOperations::maxValue(a, 4, &maxAIndex); - VectorOperations::maxValue(a, 4, &maxAIndex); - - if (index != 0) { - *index = maxAIndex; - } - - switch (maxAIndex) { - case 0: - quaternion[0] = 0.5 * sqrt(a[0]); - quaternion[1] = (dcm[0][1] + dcm[1][0]) / (2 * sqrt(a[0])); - quaternion[2] = (dcm[0][2] + dcm[2][0]) / (2 * sqrt(a[0])); - quaternion[3] = (dcm[1][2] - dcm[2][1]) / (2 * sqrt(a[0])); - break; - case 1: - quaternion[0] = (dcm[0][1] + dcm[1][0]) / (2 * sqrt(a[1])); - quaternion[1] = 0.5 * sqrt(a[1]); - quaternion[2] = (dcm[1][2] + dcm[2][1]) / (2 * sqrt(a[1])); - quaternion[3] = (dcm[2][0] - dcm[0][2]) / (2 * sqrt(a[1])); - break; - case 2: - quaternion[0] = (dcm[0][2] + dcm[2][0]) / (2 * sqrt(a[2])); - quaternion[1] = (dcm[1][2] + dcm[2][1]) / (2 * sqrt(a[2])); - quaternion[2] = 0.5 * sqrt(a[2]); - quaternion[3] = (dcm[0][1] - dcm[1][0]) / (2 * sqrt(a[2])); - break; - case 3: - quaternion[0] = (dcm[1][2] - dcm[2][1]) / (2 * sqrt(a[3])); - quaternion[1] = (dcm[2][0] - dcm[0][2]) / (2 * sqrt(a[3])); - quaternion[2] = (dcm[0][1] - dcm[1][0]) / (2 * sqrt(a[3])); - quaternion[3] = 0.5 * sqrt(a[3]); - break; - } + if (index != 0) { + *index = maxAIndex; + } + switch (maxAIndex) { + case 0: + quaternion[0] = 0.5 * sqrt(a[0]); + quaternion[1] = (dcm[0][1] + dcm[1][0]) / (2 * sqrt(a[0])); + quaternion[2] = (dcm[0][2] + dcm[2][0]) / (2 * sqrt(a[0])); + quaternion[3] = (dcm[1][2] - dcm[2][1]) / (2 * sqrt(a[0])); + break; + case 1: + quaternion[0] = (dcm[0][1] + dcm[1][0]) / (2 * sqrt(a[1])); + quaternion[1] = 0.5 * sqrt(a[1]); + quaternion[2] = (dcm[1][2] + dcm[2][1]) / (2 * sqrt(a[1])); + quaternion[3] = (dcm[2][0] - dcm[0][2]) / (2 * sqrt(a[1])); + break; + case 2: + quaternion[0] = (dcm[0][2] + dcm[2][0]) / (2 * sqrt(a[2])); + quaternion[1] = (dcm[1][2] + dcm[2][1]) / (2 * sqrt(a[2])); + quaternion[2] = 0.5 * sqrt(a[2]); + quaternion[3] = (dcm[0][1] - dcm[1][0]) / (2 * sqrt(a[2])); + break; + case 3: + quaternion[0] = (dcm[1][2] - dcm[2][1]) / (2 * sqrt(a[3])); + quaternion[1] = (dcm[2][0] - dcm[0][2]) / (2 * sqrt(a[3])); + quaternion[2] = (dcm[0][1] - dcm[1][0]) / (2 * sqrt(a[3])); + quaternion[3] = 0.5 * sqrt(a[3]); + break; + } } void QuaternionOperations::toDcm(const double* quaternion, float dcm[][3]) { - dcm[0][0] = 2 - * (quaternion[0] * quaternion[0] + quaternion[3] * quaternion[3]) - - 1; - dcm[0][1] = 2 - * (quaternion[0] * quaternion[1] + quaternion[2] * quaternion[3]); - dcm[0][2] = 2 - * (quaternion[0] * quaternion[2] - quaternion[1] * quaternion[3]); + dcm[0][0] = 2 * (quaternion[0] * quaternion[0] + quaternion[3] * quaternion[3]) - 1; + dcm[0][1] = 2 * (quaternion[0] * quaternion[1] + quaternion[2] * quaternion[3]); + dcm[0][2] = 2 * (quaternion[0] * quaternion[2] - quaternion[1] * quaternion[3]); - dcm[1][0] = 2 - * (quaternion[0] * quaternion[1] - quaternion[2] * quaternion[3]); - dcm[1][1] = 2 - * (quaternion[1] * quaternion[1] + quaternion[3] * quaternion[3]) - - 1; - dcm[1][2] = 2 - * (quaternion[1] * quaternion[2] + quaternion[0] * quaternion[3]); + dcm[1][0] = 2 * (quaternion[0] * quaternion[1] - quaternion[2] * quaternion[3]); + dcm[1][1] = 2 * (quaternion[1] * quaternion[1] + quaternion[3] * quaternion[3]) - 1; + dcm[1][2] = 2 * (quaternion[1] * quaternion[2] + quaternion[0] * quaternion[3]); - dcm[2][0] = 2 - * (quaternion[0] * quaternion[2] + quaternion[1] * quaternion[3]); - dcm[2][1] = 2 - * (quaternion[1] * quaternion[2] - quaternion[0] * quaternion[3]); - dcm[2][2] = 2 - * (quaternion[2] * quaternion[2] + quaternion[3] * quaternion[3]) - - 1; + dcm[2][0] = 2 * (quaternion[0] * quaternion[2] + quaternion[1] * quaternion[3]); + dcm[2][1] = 2 * (quaternion[1] * quaternion[2] - quaternion[0] * quaternion[3]); + dcm[2][2] = 2 * (quaternion[2] * quaternion[2] + quaternion[3] * quaternion[3]) - 1; } -void QuaternionOperations::normalize(double* quaternion) { - normalize(quaternion, quaternion); -} +void QuaternionOperations::normalize(double* quaternion) { normalize(quaternion, quaternion); } double QuaternionOperations::getAngle(const double* quaternion, bool abs) { - if (quaternion[3] >= 0) { - return 2 * acos(quaternion[3]); - } else { - if (abs) { - return 2 * acos(-quaternion[3]); - } else { - return -2 * acos(-quaternion[3]); - } - } + if (quaternion[3] >= 0) { + return 2 * acos(quaternion[3]); + } else { + if (abs) { + return 2 * acos(-quaternion[3]); + } else { + return -2 * acos(-quaternion[3]); + } + } } diff --git a/src/fsfw/globalfunctions/math/QuaternionOperations.h b/src/fsfw/globalfunctions/math/QuaternionOperations.h index 0d6fe860..e8ca400a 100644 --- a/src/fsfw/globalfunctions/math/QuaternionOperations.h +++ b/src/fsfw/globalfunctions/math/QuaternionOperations.h @@ -4,78 +4,51 @@ #include class QuaternionOperations { -public: - virtual ~QuaternionOperations(); + public: + virtual ~QuaternionOperations(); - static void multiply(const double *q1, const double *q2, double *q); + static void multiply(const double *q1, const double *q2, double *q); - static void fromDcm(const double dcm[][3], double *quaternion, - uint8_t *index = 0); + static void fromDcm(const double dcm[][3], double *quaternion, uint8_t *index = 0); - static void toDcm(const double *quaternion, double dcm[][3]); + static void toDcm(const double *quaternion, double dcm[][3]); - static void toDcm(const double *quaternion, float dcm[][3]); + static void toDcm(const double *quaternion, float dcm[][3]); - static float norm(const double *quaternion); + static float norm(const double *quaternion); - static void normalize(double *quaternion); + static void normalize(double *quaternion); - static void normalize(const double *quaternion, double *unitQuaternion); + static void normalize(const double *quaternion, double *unitQuaternion); - static void inverse(const double *quaternion, double *inverseQuaternion); + static void inverse(const double *quaternion, double *inverseQuaternion); - /** - * returns angle in ]-Pi;Pi] or [0;Pi] if abs == true - */ - static double getAngle(const double *quaternion, bool abs = false); + /** + * returns angle in ]-Pi;Pi] or [0;Pi] if abs == true + */ + static double getAngle(const double *quaternion, bool abs = false); - //multiplies 3d vector with dcm derived from quaternion - template - static void multiplyVector(const double *quaternion, const T *vector, - T * result) { - result[0] = - (2. - * (quaternion[0] * quaternion[0] - + quaternion[3] * quaternion[3]) - 1.) - * vector[0] - + 2. - * (quaternion[0] * quaternion[1] - + quaternion[2] * quaternion[3]) - * vector[1] - + 2. - * (quaternion[0] * quaternion[2] - - quaternion[1] * quaternion[3]) - * vector[2]; + // multiplies 3d vector with dcm derived from quaternion + template + static void multiplyVector(const double *quaternion, const T *vector, T *result) { + result[0] = + (2. * (quaternion[0] * quaternion[0] + quaternion[3] * quaternion[3]) - 1.) * vector[0] + + 2. * (quaternion[0] * quaternion[1] + quaternion[2] * quaternion[3]) * vector[1] + + 2. * (quaternion[0] * quaternion[2] - quaternion[1] * quaternion[3]) * vector[2]; - result[1] = - 2. - * (quaternion[0] * quaternion[1] - - quaternion[2] * quaternion[3]) * vector[0] - + (2. - * (quaternion[1] * quaternion[1] - + quaternion[3] * quaternion[3]) - 1.) - * vector[1] - + 2. - * (quaternion[1] * quaternion[2] - + quaternion[0] * quaternion[3]) - * vector[2]; + result[1] = + 2. * (quaternion[0] * quaternion[1] - quaternion[2] * quaternion[3]) * vector[0] + + (2. * (quaternion[1] * quaternion[1] + quaternion[3] * quaternion[3]) - 1.) * vector[1] + + 2. * (quaternion[1] * quaternion[2] + quaternion[0] * quaternion[3]) * vector[2]; - result[2] = - 2. - * (quaternion[0] * quaternion[2] - + quaternion[1] * quaternion[3]) * vector[0] - + 2. - * (quaternion[1] * quaternion[2] - - quaternion[0] * quaternion[3]) - * vector[1] - + (2. - * (quaternion[2] * quaternion[2] - + quaternion[3] * quaternion[3]) - 1.) - * vector[2]; - } + result[2] = + 2. * (quaternion[0] * quaternion[2] + quaternion[1] * quaternion[3]) * vector[0] + + 2. * (quaternion[1] * quaternion[2] - quaternion[0] * quaternion[3]) * vector[1] + + (2. * (quaternion[2] * quaternion[2] + quaternion[3] * quaternion[3]) - 1.) * vector[2]; + } -private: - QuaternionOperations(); + private: + QuaternionOperations(); }; #endif /* QUATERNIONOPERATIONS_H_ */ diff --git a/src/fsfw/globalfunctions/math/VectorOperations.h b/src/fsfw/globalfunctions/math/VectorOperations.h index f65d2263..197cd46a 100644 --- a/src/fsfw/globalfunctions/math/VectorOperations.h +++ b/src/fsfw/globalfunctions/math/VectorOperations.h @@ -2,102 +2,93 @@ #define VECTOROPERATIONS_ #include + #include -template +template class VectorOperations { -public: - virtual ~VectorOperations() { - } + public: + virtual ~VectorOperations() {} - static void cross(const T left[], const T right[], T out[]) { - T temp[3] = { 0, 0, 0 }; - temp[0] = left[1] * right[2] - left[2] * right[1]; - temp[1] = left[2] * right[0] - left[0] * right[2]; - temp[2] = left[0] * right[1] - left[1] * right[0]; - out[0] = temp[0]; - out[1] = temp[1]; - out[2] = temp[2]; - } + static void cross(const T left[], const T right[], T out[]) { + T temp[3] = {0, 0, 0}; + temp[0] = left[1] * right[2] - left[2] * right[1]; + temp[1] = left[2] * right[0] - left[0] * right[2]; + temp[2] = left[0] * right[1] - left[1] * right[0]; + out[0] = temp[0]; + out[1] = temp[1]; + out[2] = temp[2]; + } - static T dot(const T a[], const T b[]) { - return a[0] * b[0] + a[1] * b[1] + a[2] * b[2]; - } + static T dot(const T a[], const T b[]) { return a[0] * b[0] + a[1] * b[1] + a[2] * b[2]; } - static void mulScalar(const T vector[], T scalar, T out[], uint8_t size) { - for (; size > 0; size--) { - out[size - 1] = vector[size - 1] * scalar; - } - } + static void mulScalar(const T vector[], T scalar, T out[], uint8_t size) { + for (; size > 0; size--) { + out[size - 1] = vector[size - 1] * scalar; + } + } - static void add(const T vector1[], const T vector2[], T sum[], - uint8_t size = 3) { - for (; size > 0; size--) { - sum[size - 1] = vector1[size - 1] + vector2[size - 1]; - } - } + static void add(const T vector1[], const T vector2[], T sum[], uint8_t size = 3) { + for (; size > 0; size--) { + sum[size - 1] = vector1[size - 1] + vector2[size - 1]; + } + } - static void subtract(const T vector1[], const T vector2[], T sum[], - uint8_t size = 3) { - for (; size > 0; size--) { - sum[size - 1] = vector1[size - 1] - vector2[size - 1]; - } - } + static void subtract(const T vector1[], const T vector2[], T sum[], uint8_t size = 3) { + for (; size > 0; size--) { + sum[size - 1] = vector1[size - 1] - vector2[size - 1]; + } + } - static T norm(const T *vector, uint8_t size) { - T result = 0; - for (; size > 0; size--) { - result += vector[size - 1] * vector[size - 1]; - } - result = sqrt(result); - return result; - } + static T norm(const T *vector, uint8_t size) { + T result = 0; + for (; size > 0; size--) { + result += vector[size - 1] * vector[size - 1]; + } + result = sqrt(result); + return result; + } - static void normalize(const T *vector, T *normalizedVector, uint8_t size) { - mulScalar(vector, 1 / norm(vector, size), normalizedVector, size); - } + static void normalize(const T *vector, T *normalizedVector, uint8_t 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 = 0) { + T max = -1; - T max = -1; + for (; size > 0; size--) { + T abs = vector[size - 1]; + if (abs < 0) { + abs = -abs; + } + if (abs > max) { + max = abs; + if (index != 0) { + *index = size - 1; + } + } + } + return max; + } - for (; size > 0; size--) { - T abs = vector[size - 1]; - if (abs < 0) { - abs = -abs; - } - if (abs > max) { - max = abs; - if (index != 0) { - *index = size - 1; - } - } - } - return max; - } + static T maxValue(const T *vector, uint8_t size, uint8_t *index = 0) { + T max = -1; - static T maxValue(const T *vector, uint8_t size, uint8_t *index = 0) { + for (; size > 0; size--) { + if (vector[size - 1] > max) { + max = vector[size - 1]; + if (index != 0) { + *index = size - 1; + } + } + } + return max; + } - T max = -1; + static void copy(const T *in, T *out, uint8_t size) { mulScalar(in, 1, out, size); } - for (; size > 0; size--) { - if (vector[size - 1] > max) { - max = vector[size - 1]; - if (index != 0) { - *index = size - 1; - } - } - } - return max; - } - - - static void copy(const T *in, T *out, uint8_t size) { - mulScalar(in, 1, out, size); - } - -private: - VectorOperations(); + private: + VectorOperations(); }; #endif /* VECTOROPERATIONS_ */ diff --git a/src/fsfw/globalfunctions/sign.h b/src/fsfw/globalfunctions/sign.h index 8828fca1..b838b2bf 100644 --- a/src/fsfw/globalfunctions/sign.h +++ b/src/fsfw/globalfunctions/sign.h @@ -1,8 +1,9 @@ #ifndef SIGN_H_ #define SIGN_H_ -template int sign(T val) { - return (T(0) < val) - (val < T(0)); +template +int sign(T val) { + return (T(0) < val) - (val < T(0)); } #endif /* SIGN_H_ */ diff --git a/src/fsfw/globalfunctions/timevalOperations.cpp b/src/fsfw/globalfunctions/timevalOperations.cpp index e91e7f57..e2b35512 100644 --- a/src/fsfw/globalfunctions/timevalOperations.cpp +++ b/src/fsfw/globalfunctions/timevalOperations.cpp @@ -1,99 +1,91 @@ #include "fsfw/globalfunctions/timevalOperations.h" timeval& operator+=(timeval& lhs, const timeval& rhs) { - int64_t sum = lhs.tv_sec * 1000000. + lhs.tv_usec; - sum += rhs.tv_sec * 1000000. + rhs.tv_usec; - lhs.tv_sec = sum / 1000000; - lhs.tv_usec = sum - lhs.tv_sec * 1000000; - return lhs; + int64_t sum = lhs.tv_sec * 1000000. + lhs.tv_usec; + sum += rhs.tv_sec * 1000000. + rhs.tv_usec; + lhs.tv_sec = sum / 1000000; + lhs.tv_usec = sum - lhs.tv_sec * 1000000; + return lhs; } timeval operator+(timeval lhs, const timeval& rhs) { - lhs += rhs; - return lhs; + lhs += rhs; + return lhs; } timeval& operator-=(timeval& lhs, const timeval& rhs) { - int64_t sum = lhs.tv_sec * 1000000. + lhs.tv_usec; - sum -= rhs.tv_sec * 1000000. + rhs.tv_usec; - lhs.tv_sec = sum / 1000000; - lhs.tv_usec = sum - lhs.tv_sec * 1000000; - return lhs; + int64_t sum = lhs.tv_sec * 1000000. + lhs.tv_usec; + sum -= rhs.tv_sec * 1000000. + rhs.tv_usec; + lhs.tv_sec = sum / 1000000; + lhs.tv_usec = sum - lhs.tv_sec * 1000000; + return lhs; } timeval operator-(timeval lhs, const timeval& rhs) { - lhs -= rhs; - return lhs; + lhs -= rhs; + return lhs; } double operator/(const timeval& lhs, const timeval& rhs) { - double lhs64 = lhs.tv_sec * 1000000. + lhs.tv_usec; - double rhs64 = rhs.tv_sec * 1000000. + rhs.tv_usec; - return lhs64 / rhs64; + double lhs64 = lhs.tv_sec * 1000000. + lhs.tv_usec; + double rhs64 = rhs.tv_sec * 1000000. + rhs.tv_usec; + return lhs64 / rhs64; } timeval& operator/=(timeval& lhs, double scalar) { - int64_t product = lhs.tv_sec * 1000000. + lhs.tv_usec; - product /= scalar; - lhs.tv_sec = product / 1000000; - lhs.tv_usec = product - lhs.tv_sec * 1000000; - return lhs; + int64_t product = lhs.tv_sec * 1000000. + lhs.tv_usec; + product /= scalar; + lhs.tv_sec = product / 1000000; + lhs.tv_usec = product - lhs.tv_sec * 1000000; + return lhs; } timeval operator/(timeval lhs, double scalar) { - lhs /= scalar; - return lhs; + lhs /= scalar; + return lhs; } timeval& operator*=(timeval& lhs, double scalar) { - int64_t product = lhs.tv_sec * 1000000. + lhs.tv_usec; - product *= scalar; - lhs.tv_sec = product / 1000000; - lhs.tv_usec = product - lhs.tv_sec * 1000000; - return lhs; + int64_t product = lhs.tv_sec * 1000000. + lhs.tv_usec; + product *= scalar; + lhs.tv_sec = product / 1000000; + lhs.tv_usec = product - lhs.tv_sec * 1000000; + return lhs; } timeval operator*(timeval lhs, double scalar) { - lhs *= scalar; - return lhs; + lhs *= scalar; + return lhs; } timeval operator*(double scalar, timeval rhs) { - rhs *= scalar; - return rhs; + rhs *= scalar; + return rhs; } bool operator==(const timeval& lhs, const timeval& rhs) { - int64_t lhs64 = lhs.tv_sec * 1000000. + lhs.tv_usec; - int64_t rhs64 = rhs.tv_sec * 1000000. + rhs.tv_usec; - return lhs64 == rhs64; -} -bool operator!=(const timeval& lhs, const timeval& rhs) { - return !operator==(lhs, rhs); + int64_t lhs64 = lhs.tv_sec * 1000000. + lhs.tv_usec; + int64_t rhs64 = rhs.tv_sec * 1000000. + rhs.tv_usec; + return lhs64 == rhs64; } +bool operator!=(const timeval& lhs, const timeval& rhs) { return !operator==(lhs, rhs); } bool operator<(const timeval& lhs, const timeval& rhs) { - int64_t lhs64 = lhs.tv_sec * 1000000. + lhs.tv_usec; - int64_t rhs64 = rhs.tv_sec * 1000000. + rhs.tv_usec; - return lhs64 < rhs64; -} -bool operator>(const timeval& lhs, const timeval& rhs) { - return operator<(rhs, lhs); -} -bool operator<=(const timeval& lhs, const timeval& rhs) { - return !operator>(lhs, rhs); -} -bool operator>=(const timeval& lhs, const timeval& rhs) { - return !operator<(lhs, rhs); + int64_t lhs64 = lhs.tv_sec * 1000000. + lhs.tv_usec; + int64_t rhs64 = rhs.tv_sec * 1000000. + rhs.tv_usec; + return lhs64 < rhs64; } +bool operator>(const timeval& lhs, const timeval& rhs) { return operator<(rhs, lhs); } +bool operator<=(const timeval& lhs, const timeval& rhs) { return !operator>(lhs, rhs); } +bool operator>=(const timeval& lhs, const timeval& rhs) { return !operator<(lhs, rhs); } double timevalOperations::toDouble(const timeval timeval) { - double result = timeval.tv_sec * 1000000. + timeval.tv_usec; - return result / 1000000.; + double result = timeval.tv_sec * 1000000. + timeval.tv_usec; + return result / 1000000.; } timeval timevalOperations::toTimeval(const double seconds) { - timeval tval; - tval.tv_sec = seconds; - tval.tv_usec = seconds *(double) 1e6 - (tval.tv_sec *1e6); - return tval; + timeval tval; + tval.tv_sec = seconds; + tval.tv_usec = seconds * (double)1e6 - (tval.tv_sec * 1e6); + return tval; } diff --git a/src/fsfw/globalfunctions/timevalOperations.h b/src/fsfw/globalfunctions/timevalOperations.h index 41f4e52f..b5f6b531 100644 --- a/src/fsfw/globalfunctions/timevalOperations.h +++ b/src/fsfw/globalfunctions/timevalOperations.h @@ -1,8 +1,8 @@ #ifndef TIMEVALOPERATIONS_H_ #define TIMEVALOPERATIONS_H_ -#include #include +#include #ifdef PLATFORM_WIN #include @@ -48,6 +48,6 @@ namespace timevalOperations { */ double toDouble(const timeval timeval); timeval toTimeval(const double seconds); -} +} // namespace timevalOperations #endif /* TIMEVALOPERATIONS_H_ */ diff --git a/src/fsfw/health/HasHealthIF.h b/src/fsfw/health/HasHealthIF.h index a6254e39..41abeef3 100644 --- a/src/fsfw/health/HasHealthIF.h +++ b/src/fsfw/health/HasHealthIF.h @@ -2,50 +2,56 @@ #define FSFW_HEALTH_HASHEALTHIF_H_ #include "../events/Event.h" -#include "../returnvalues/HasReturnvaluesIF.h" #include "../ipc/MessageQueueSenderIF.h" +#include "../returnvalues/HasReturnvaluesIF.h" class HasHealthIF { -public: + public: + enum HealthState : uint8_t { + HEALTHY = 1, + FAULTY = 0, + EXTERNAL_CONTROL = 2, + NEEDS_RECOVERY = 3, + PERMANENT_FAULTY = 4 + }; - enum HealthState: uint8_t { - HEALTHY = 1, - FAULTY = 0, - EXTERNAL_CONTROL = 2, - NEEDS_RECOVERY = 3, - PERMANENT_FAULTY = 4 - }; + static const uint8_t INTERFACE_ID = CLASS_ID::HAS_HEALTH_IF; + static const ReturnValue_t OBJECT_NOT_HEALTHY = MAKE_RETURN_CODE(1); + static const ReturnValue_t INVALID_HEALTH_STATE = MAKE_RETURN_CODE(2); - static const uint8_t INTERFACE_ID = CLASS_ID::HAS_HEALTH_IF; - static const ReturnValue_t OBJECT_NOT_HEALTHY = MAKE_RETURN_CODE(1); - static const ReturnValue_t INVALID_HEALTH_STATE = MAKE_RETURN_CODE(2); + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::SYSTEM_MANAGER_1; + static const Event HEALTH_INFO = MAKE_EVENT(6, severity::INFO); + static const Event CHILD_CHANGED_HEALTH = MAKE_EVENT(7, severity::INFO); + static const Event CHILD_PROBLEMS = MAKE_EVENT(8, severity::LOW); + static const Event OVERWRITING_HEALTH = + MAKE_EVENT(9, severity::LOW); //!< Assembly overwrites health information of children to keep + //!< satellite alive. + static const Event TRYING_RECOVERY = + MAKE_EVENT(10, severity::MEDIUM); //!< Someone starts a recovery of a component (typically + //!< power-cycle). No parameters. + static const Event RECOVERY_STEP = + MAKE_EVENT(11, severity::MEDIUM); //!< Recovery is ongoing. Comes twice during recovery. P1: + //!< 0 for the first, 1 for the second event. P2: 0 + static const Event RECOVERY_DONE = MAKE_EVENT( + 12, + severity::MEDIUM); //!< Recovery was completed. Not necessarily successful. No parameters. - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::SYSTEM_MANAGER_1; - static const Event HEALTH_INFO = MAKE_EVENT(6, severity::INFO); - static const Event CHILD_CHANGED_HEALTH = MAKE_EVENT(7, severity::INFO); - static const Event CHILD_PROBLEMS = MAKE_EVENT(8, severity::LOW); - static const Event OVERWRITING_HEALTH = MAKE_EVENT(9, severity::LOW); //!< Assembly overwrites health information of children to keep satellite alive. - static const Event TRYING_RECOVERY = MAKE_EVENT(10, severity::MEDIUM); //!< Someone starts a recovery of a component (typically power-cycle). No parameters. - static const Event RECOVERY_STEP = MAKE_EVENT(11, severity::MEDIUM); //!< Recovery is ongoing. Comes twice during recovery. P1: 0 for the first, 1 for the second event. P2: 0 - static const Event RECOVERY_DONE = MAKE_EVENT(12, severity::MEDIUM); //!< Recovery was completed. Not necessarily successful. No parameters. + virtual ~HasHealthIF() {} - virtual ~HasHealthIF() { - } + virtual MessageQueueId_t getCommandQueue() const = 0; - virtual MessageQueueId_t getCommandQueue() const = 0; + /** + * @brief Set the Health State + * The parent will be informed, if the Health changes + * @param health + */ + virtual ReturnValue_t setHealth(HealthState health) = 0; - /** - * @brief Set the Health State - * The parent will be informed, if the Health changes - * @param health - */ - virtual ReturnValue_t setHealth(HealthState health) = 0; - - /** - * @brief Get Health State - * @return Health State of the object - */ - virtual HasHealthIF::HealthState getHealth() = 0; + /** + * @brief Get Health State + * @return Health State of the object + */ + virtual HasHealthIF::HealthState getHealth() = 0; }; #endif /* FSFW_HEALTH_HASHEALTHIF_H_ */ diff --git a/src/fsfw/health/HealthHelper.cpp b/src/fsfw/health/HealthHelper.cpp index 6bbbe25b..4bef128c 100644 --- a/src/fsfw/health/HealthHelper.cpp +++ b/src/fsfw/health/HealthHelper.cpp @@ -2,113 +2,104 @@ #include "fsfw/serviceinterface/ServiceInterface.h" -HealthHelper::HealthHelper(HasHealthIF* owner, object_id_t objectId) : - objectId(objectId), owner(owner) { -} +HealthHelper::HealthHelper(HasHealthIF* owner, object_id_t objectId) + : objectId(objectId), owner(owner) {} -HealthHelper::~HealthHelper() { -} +HealthHelper::~HealthHelper() {} ReturnValue_t HealthHelper::handleHealthCommand(CommandMessage* message) { - switch (message->getCommand()) { - case HealthMessage::HEALTH_SET: - handleSetHealthCommand(message); - return HasReturnvaluesIF::RETURN_OK; - case HealthMessage::HEALTH_ANNOUNCE: { - eventSender->forwardEvent(HasHealthIF::HEALTH_INFO, getHealth(), - getHealth()); - } - return HasReturnvaluesIF::RETURN_OK; - default: - return HasReturnvaluesIF::RETURN_FAILED; - } + switch (message->getCommand()) { + case HealthMessage::HEALTH_SET: + handleSetHealthCommand(message); + return HasReturnvaluesIF::RETURN_OK; + case HealthMessage::HEALTH_ANNOUNCE: { + eventSender->forwardEvent(HasHealthIF::HEALTH_INFO, getHealth(), getHealth()); + } + return HasReturnvaluesIF::RETURN_OK; + default: + return HasReturnvaluesIF::RETURN_FAILED; + } } -HasHealthIF::HealthState HealthHelper::getHealth() { - return healthTable->getHealth(objectId); -} +HasHealthIF::HealthState HealthHelper::getHealth() { return healthTable->getHealth(objectId); } ReturnValue_t HealthHelper::initialize(MessageQueueId_t parentQueue) { - setParentQueue(parentQueue); - return initialize(); + setParentQueue(parentQueue); + return initialize(); } -void HealthHelper::setParentQueue(MessageQueueId_t parentQueue) { - this->parentQueue = parentQueue; -} +void HealthHelper::setParentQueue(MessageQueueId_t parentQueue) { this->parentQueue = parentQueue; } ReturnValue_t HealthHelper::initialize() { - healthTable = ObjectManager::instance()->get(objects::HEALTH_TABLE); - eventSender = ObjectManager::instance()->get(objectId); + healthTable = ObjectManager::instance()->get(objects::HEALTH_TABLE); + eventSender = ObjectManager::instance()->get(objectId); - if (healthTable == nullptr) { + if (healthTable == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "HealthHelper::initialize: Health table object needs" - "to be created in factory." << std::endl; + sif::error << "HealthHelper::initialize: Health table object needs" + "to be created in factory." + << std::endl; #endif - return ObjectManagerIF::CHILD_INIT_FAILED; - } + return ObjectManagerIF::CHILD_INIT_FAILED; + } - if(eventSender == nullptr) { + if (eventSender == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "HealthHelper::initialize: Owner has to implement " - "ReportingProxyIF." << std::endl; + sif::error << "HealthHelper::initialize: Owner has to implement " + "ReportingProxyIF." + << std::endl; #endif - return ObjectManagerIF::CHILD_INIT_FAILED; - } + return ObjectManagerIF::CHILD_INIT_FAILED; + } - ReturnValue_t result = healthTable->registerObject(objectId, - HasHealthIF::HEALTHY); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return HasReturnvaluesIF::RETURN_OK; + ReturnValue_t result = healthTable->registerObject(objectId, HasHealthIF::HEALTHY); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return HasReturnvaluesIF::RETURN_OK; } void HealthHelper::setHealth(HasHealthIF::HealthState health) { - HasHealthIF::HealthState oldHealth = getHealth(); - eventSender->forwardEvent(HasHealthIF::HEALTH_INFO, health, oldHealth); - if (health != oldHealth) { - healthTable->setHealth(objectId, health); - informParent(health, oldHealth); - } + HasHealthIF::HealthState oldHealth = getHealth(); + eventSender->forwardEvent(HasHealthIF::HEALTH_INFO, health, oldHealth); + if (health != oldHealth) { + healthTable->setHealth(objectId, health); + informParent(health, oldHealth); + } } void HealthHelper::informParent(HasHealthIF::HealthState health, - HasHealthIF::HealthState oldHealth) { - if (parentQueue == MessageQueueIF::NO_QUEUE) { - return; - } - CommandMessage information; - HealthMessage::setHealthMessage(&information, HealthMessage::HEALTH_INFO, - health, oldHealth); - if (MessageQueueSenderIF::sendMessage(parentQueue, &information, - owner->getCommandQueue()) != HasReturnvaluesIF::RETURN_OK) { + HasHealthIF::HealthState oldHealth) { + if (parentQueue == MessageQueueIF::NO_QUEUE) { + return; + } + CommandMessage information; + HealthMessage::setHealthMessage(&information, HealthMessage::HEALTH_INFO, health, oldHealth); + if (MessageQueueSenderIF::sendMessage(parentQueue, &information, owner->getCommandQueue()) != + HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "HealthHelper::informParent: sending health reply failed." - << std::endl; + sif::debug << "HealthHelper::informParent: sending health reply failed." << std::endl; #endif - } + } } void HealthHelper::handleSetHealthCommand(CommandMessage* command) { - ReturnValue_t result = owner->setHealth(HealthMessage::getHealth(command)); - if (command->getSender() == MessageQueueIF::NO_QUEUE) { - return; - } - CommandMessage reply; - if (result == HasReturnvaluesIF::RETURN_OK) { - HealthMessage::setHealthMessage(&reply, - HealthMessage::REPLY_HEALTH_SET); - } else { - reply.setReplyRejected(result, command->getCommand()); - } - if (MessageQueueSenderIF::sendMessage(command->getSender(), &reply, - owner->getCommandQueue()) != HasReturnvaluesIF::RETURN_OK) { + ReturnValue_t result = owner->setHealth(HealthMessage::getHealth(command)); + if (command->getSender() == MessageQueueIF::NO_QUEUE) { + return; + } + CommandMessage reply; + if (result == HasReturnvaluesIF::RETURN_OK) { + HealthMessage::setHealthMessage(&reply, HealthMessage::REPLY_HEALTH_SET); + } else { + reply.setReplyRejected(result, command->getCommand()); + } + if (MessageQueueSenderIF::sendMessage(command->getSender(), &reply, owner->getCommandQueue()) != + HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "HealthHelper::handleHealthCommand: sending health " - "reply failed." << std::endl; + sif::debug << "HealthHelper::handleHealthCommand: sending health " + "reply failed." + << std::endl; #endif - - } + } } diff --git a/src/fsfw/health/HealthHelper.h b/src/fsfw/health/HealthHelper.h index 08889fba..9b3b0e2b 100644 --- a/src/fsfw/health/HealthHelper.h +++ b/src/fsfw/health/HealthHelper.h @@ -1,15 +1,14 @@ #ifndef FSFW_HEALTH_HEALTHHELPER_H_ #define FSFW_HEALTH_HEALTHHELPER_H_ -#include "HasHealthIF.h" -#include "HealthMessage.h" -#include "HealthTableIF.h" - #include "../events/EventManagerIF.h" #include "../events/EventReportingProxyIF.h" #include "../ipc/MessageQueueIF.h" #include "../objectmanager/ObjectManagerIF.h" #include "../returnvalues/HasReturnvaluesIF.h" +#include "HasHealthIF.h" +#include "HealthMessage.h" +#include "HealthTableIF.h" /** * @brief Helper class for Objects that implement HasHealthIF @@ -26,106 +25,104 @@ * It does NOT handle @c HEALTH_INFO messages */ class HealthHelper { -public: + public: + /** + * @param owner + * @param objectId The object Id to use when communication with + * the HealthTable + */ + HealthHelper(HasHealthIF* owner, object_id_t objectId); - /** - * @param owner - * @param objectId The object Id to use when communication with - * the HealthTable - */ - HealthHelper(HasHealthIF* owner, object_id_t objectId); + virtual ~HealthHelper(); - virtual ~HealthHelper(); + /** + * Pointer to the Health Table + * + * only valid after initialize() has been called + */ + HealthTableIF* healthTable = nullptr; - /** - * Pointer to the Health Table - * - * only valid after initialize() has been called - */ - HealthTableIF *healthTable = nullptr; + /** + * Proxy to forward events. + */ + EventReportingProxyIF* eventSender = nullptr; - /** - * Proxy to forward events. - */ - EventReportingProxyIF* eventSender = nullptr; + /** + * Try to handle the message. + * + * This function handles @c HEALTH_SET and @c HEALTH_READ commands. + * it updates the Health Table and generates a reply to the sender. + * + * @param message + * @return + * -@c RETURN_OK if the message was handled + * -@c RETURN_FAILED if the message could not be handled + * (ie it was not a @c HEALTH_SET or @c HEALTH_READ message) + */ + ReturnValue_t handleHealthCommand(CommandMessage* message); - /** - * Try to handle the message. - * - * This function handles @c HEALTH_SET and @c HEALTH_READ commands. - * it updates the Health Table and generates a reply to the sender. - * - * @param message - * @return - * -@c RETURN_OK if the message was handled - * -@c RETURN_FAILED if the message could not be handled - * (ie it was not a @c HEALTH_SET or @c HEALTH_READ message) - */ - ReturnValue_t handleHealthCommand(CommandMessage *message); + /** + * set the Health State + * + * The parent will be informed, if the Health changes + * + * @param health + */ + void setHealth(HasHealthIF::HealthState health); - /** - * set the Health State - * - * The parent will be informed, if the Health changes - * - * @param health - */ - void setHealth(HasHealthIF::HealthState health); + /** + * get Health State + * + * @return Health State of the object + */ + HasHealthIF::HealthState getHealth(); - /** - * get Health State - * - * @return Health State of the object - */ - HasHealthIF::HealthState getHealth(); + /** + * @param parentQueue The queue ID of the parent object. + * Set to 0 if no parent present + */ + void setParentQueue(MessageQueueId_t parentQueue); - /** - * @param parentQueue The queue ID of the parent object. - * Set to 0 if no parent present - */ - void setParentQueue(MessageQueueId_t parentQueue); + /** + * + * @param parentQueue The queue ID of the parent object. + * Set to 0 if no parent present + * @return + * -@c RETURN_OK if the Health Table was found and the object + * could be registered + * -@c RETURN_FAILED else + */ + ReturnValue_t initialize(MessageQueueId_t parentQueue); - /** - * - * @param parentQueue The queue ID of the parent object. - * Set to 0 if no parent present - * @return - * -@c RETURN_OK if the Health Table was found and the object - * could be registered - * -@c RETURN_FAILED else - */ - ReturnValue_t initialize(MessageQueueId_t parentQueue ); + ReturnValue_t initialize(); - ReturnValue_t initialize(); + private: + /** + * the object id to use when communicating with the Health Table + */ + object_id_t objectId; -private: - /** - * the object id to use when communicating with the Health Table - */ - object_id_t objectId; + /** + * The Queue of the parent + */ + MessageQueueId_t parentQueue = MessageQueueIF::NO_QUEUE; - /** - * The Queue of the parent - */ - MessageQueueId_t parentQueue = MessageQueueIF::NO_QUEUE; + /** + * The one using the healthHelper. + */ + HasHealthIF* owner; - /** - * The one using the healthHelper. - */ - HasHealthIF* owner; + /** + * if the #parentQueue is not NULL, a @c HEALTH_INFO message + * will be sent to this queue + * @param health + * The health is passed as parameter so that the number of + * calls to the health table can be minimized + * @param oldHealth information of the previous health state. + */ + void informParent(HasHealthIF::HealthState health, HasHealthIF::HealthState oldHealth); - /** - * if the #parentQueue is not NULL, a @c HEALTH_INFO message - * will be sent to this queue - * @param health - * The health is passed as parameter so that the number of - * calls to the health table can be minimized - * @param oldHealth information of the previous health state. - */ - void informParent(HasHealthIF::HealthState health, - HasHealthIF::HealthState oldHealth); - - void handleSetHealthCommand(CommandMessage *message); + void handleSetHealthCommand(CommandMessage* message); }; #endif /* FSFW_HEALTH_HEALTHHELPER_H_ */ diff --git a/src/fsfw/health/HealthMessage.cpp b/src/fsfw/health/HealthMessage.cpp index 31b6273b..1bc25e90 100644 --- a/src/fsfw/health/HealthMessage.cpp +++ b/src/fsfw/health/HealthMessage.cpp @@ -1,30 +1,27 @@ #include "fsfw/health/HealthMessage.h" void HealthMessage::setHealthMessage(CommandMessage* message, Command_t command, - HasHealthIF::HealthState health, HasHealthIF::HealthState oldHealth) { - message->setCommand(command); - message->setParameter(health); - message->setParameter2(oldHealth); + HasHealthIF::HealthState health, + HasHealthIF::HealthState oldHealth) { + message->setCommand(command); + message->setParameter(health); + message->setParameter2(oldHealth); } -void HealthMessage::setHealthMessage(CommandMessage* message, - Command_t command) { - message->setCommand(command); +void HealthMessage::setHealthMessage(CommandMessage* message, Command_t command) { + message->setCommand(command); } -HasHealthIF::HealthState HealthMessage::getHealth( - const CommandMessage* message) { - return (HasHealthIF::HealthState) message->getParameter(); +HasHealthIF::HealthState HealthMessage::getHealth(const CommandMessage* message) { + return (HasHealthIF::HealthState)message->getParameter(); } void HealthMessage::clear(CommandMessage* message) { - message->setCommand(CommandMessage::CMD_NONE); + message->setCommand(CommandMessage::CMD_NONE); } -HealthMessage::HealthMessage() { -} +HealthMessage::HealthMessage() {} -HasHealthIF::HealthState HealthMessage::getOldHealth( - const CommandMessage* message) { - return (HasHealthIF::HealthState) message->getParameter2(); +HasHealthIF::HealthState HealthMessage::getOldHealth(const CommandMessage* message) { + return (HasHealthIF::HealthState)message->getParameter2(); } diff --git a/src/fsfw/health/HealthMessage.h b/src/fsfw/health/HealthMessage.h index 3dc58977..b1af0cb4 100644 --- a/src/fsfw/health/HealthMessage.h +++ b/src/fsfw/health/HealthMessage.h @@ -5,32 +5,32 @@ #include "fsfw/ipc/CommandMessage.h" class HealthMessage { -public: - static const uint8_t MESSAGE_ID = messagetypes::HEALTH_COMMAND; + public: + static const uint8_t MESSAGE_ID = messagetypes::HEALTH_COMMAND; - static const Command_t HEALTH_SET = MAKE_COMMAND_ID(1); - // No reply expected, health will be announced as event! - static const Command_t HEALTH_ANNOUNCE = MAKE_COMMAND_ID(2); - // Same as before, but all objects in health table will - // announce their health as events. - static const Command_t HEALTH_ANNOUNCE_ALL = MAKE_COMMAND_ID(3); + static const Command_t HEALTH_SET = MAKE_COMMAND_ID(1); + // No reply expected, health will be announced as event! + static const Command_t HEALTH_ANNOUNCE = MAKE_COMMAND_ID(2); + // Same as before, but all objects in health table will + // announce their health as events. + static const Command_t HEALTH_ANNOUNCE_ALL = MAKE_COMMAND_ID(3); - static const Command_t HEALTH_INFO = MAKE_COMMAND_ID(5); - static const Command_t REPLY_HEALTH_SET = MAKE_COMMAND_ID(6); + static const Command_t HEALTH_INFO = MAKE_COMMAND_ID(5); + static const Command_t REPLY_HEALTH_SET = MAKE_COMMAND_ID(6); - static void setHealthMessage(CommandMessage *message, Command_t command, - HasHealthIF::HealthState health, - HasHealthIF::HealthState oldHealth = HasHealthIF::FAULTY); - static void setHealthMessage(CommandMessage *message, Command_t command); + static void setHealthMessage(CommandMessage *message, Command_t command, + HasHealthIF::HealthState health, + HasHealthIF::HealthState oldHealth = HasHealthIF::FAULTY); + static void setHealthMessage(CommandMessage *message, Command_t command); - static HasHealthIF::HealthState getHealth(const CommandMessage *message); + static HasHealthIF::HealthState getHealth(const CommandMessage *message); - static HasHealthIF::HealthState getOldHealth(const CommandMessage *message); + static HasHealthIF::HealthState getOldHealth(const CommandMessage *message); - static void clear(CommandMessage *message); + static void clear(CommandMessage *message); -private: - HealthMessage(); + private: + HealthMessage(); }; #endif /* FSFW_HEALTH_HEALTHMESSAGE_H_ */ diff --git a/src/fsfw/health/HealthTable.cpp b/src/fsfw/health/HealthTable.cpp index a3300462..ab4881f4 100644 --- a/src/fsfw/health/HealthTable.cpp +++ b/src/fsfw/health/HealthTable.cpp @@ -1,111 +1,107 @@ #include "fsfw/health/HealthTable.h" -#include "fsfw/ipc/MutexGuard.h" #include "fsfw/ipc/MutexFactory.h" +#include "fsfw/ipc/MutexGuard.h" #include "fsfw/serialize/SerializeAdapter.h" -HealthTable::HealthTable(object_id_t objectid) : - SystemObject(objectid) { - mutex = MutexFactory::instance()->createMutex();; +HealthTable::HealthTable(object_id_t objectid) : SystemObject(objectid) { + mutex = MutexFactory::instance()->createMutex(); + ; - mapIterator = healthMap.begin(); + mapIterator = healthMap.begin(); } -void HealthTable::setMutexTimeout(MutexIF::TimeoutType timeoutType, - uint32_t timeoutMs) { - this->timeoutType = timeoutType; - this->mutexTimeoutMs = timeoutMs; +void HealthTable::setMutexTimeout(MutexIF::TimeoutType timeoutType, uint32_t timeoutMs) { + this->timeoutType = timeoutType; + this->mutexTimeoutMs = timeoutMs; } -HealthTable::~HealthTable() { - MutexFactory::instance()->deleteMutex(mutex); -} +HealthTable::~HealthTable() { MutexFactory::instance()->deleteMutex(mutex); } ReturnValue_t HealthTable::registerObject(object_id_t object, - HasHealthIF::HealthState initilialState) { - if (healthMap.count(object) != 0) { - return HasReturnvaluesIF::RETURN_FAILED; - } - healthMap.emplace(object, initilialState); - return HasReturnvaluesIF::RETURN_OK; + HasHealthIF::HealthState initilialState) { + if (healthMap.count(object) != 0) { + return HasReturnvaluesIF::RETURN_FAILED; + } + healthMap.emplace(object, initilialState); + return HasReturnvaluesIF::RETURN_OK; } -void HealthTable::setHealth(object_id_t object, - HasHealthIF::HealthState newState) { - MutexGuard(mutex, timeoutType, mutexTimeoutMs); - HealthMap::iterator iter = healthMap.find(object); - if (iter != healthMap.end()) { - iter->second = newState; - } +void HealthTable::setHealth(object_id_t object, HasHealthIF::HealthState newState) { + MutexGuard(mutex, timeoutType, mutexTimeoutMs); + HealthMap::iterator iter = healthMap.find(object); + if (iter != healthMap.end()) { + iter->second = newState; + } } HasHealthIF::HealthState HealthTable::getHealth(object_id_t object) { - HasHealthIF::HealthState state = HasHealthIF::HEALTHY; - MutexGuard(mutex, timeoutType, mutexTimeoutMs); - HealthMap::iterator iter = healthMap.find(object); - if (iter != healthMap.end()) { - state = iter->second; - } - return state; + HasHealthIF::HealthState state = HasHealthIF::HEALTHY; + MutexGuard(mutex, timeoutType, mutexTimeoutMs); + HealthMap::iterator iter = healthMap.find(object); + if (iter != healthMap.end()) { + state = iter->second; + } + return state; } bool HealthTable::hasHealth(object_id_t object) { - MutexGuard(mutex, timeoutType, mutexTimeoutMs); - HealthMap::iterator iter = healthMap.find(object); - if (iter != healthMap.end()) { - return true; - } - return false; + MutexGuard(mutex, timeoutType, mutexTimeoutMs); + HealthMap::iterator iter = healthMap.find(object); + if (iter != healthMap.end()) { + return true; + } + return false; } size_t HealthTable::getPrintSize() { - MutexGuard(mutex, timeoutType, mutexTimeoutMs); - uint32_t size = healthMap.size() * sizeof(object_id_t) + - sizeof(HasHealthIF::HealthState) + sizeof(uint16_t); - return size; + MutexGuard(mutex, timeoutType, mutexTimeoutMs); + uint32_t size = + healthMap.size() * sizeof(object_id_t) + sizeof(HasHealthIF::HealthState) + sizeof(uint16_t); + return size; } void HealthTable::printAll(uint8_t* pointer, size_t maxSize) { - MutexGuard(mutex, timeoutType, mutexTimeoutMs); - size_t size = 0; - uint16_t count = healthMap.size(); - ReturnValue_t result = SerializeAdapter::serialize(&count, - &pointer, &size, maxSize, SerializeIF::Endianness::BIG); - if(result != HasReturnvaluesIF::RETURN_OK) { + MutexGuard(mutex, timeoutType, mutexTimeoutMs); + size_t size = 0; + uint16_t count = healthMap.size(); + ReturnValue_t result = + SerializeAdapter::serialize(&count, &pointer, &size, maxSize, SerializeIF::Endianness::BIG); + if (result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "HealthTable::printAll: Serialization of health table failed" << std::endl; + sif::warning << "HealthTable::printAll: Serialization of health table failed" << std::endl; #else - sif::printWarning("HealthTable::printAll: Serialization of health table failed\n"); + sif::printWarning("HealthTable::printAll: Serialization of health table failed\n"); #endif #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - return; - } - for (const auto& health: healthMap) { - result = SerializeAdapter::serialize(&health.first, - &pointer, &size, maxSize, SerializeIF::Endianness::BIG); - if(result != HasReturnvaluesIF::RETURN_OK) { - return; - } - uint8_t healthValue = health.second; - result = SerializeAdapter::serialize(&healthValue, &pointer, &size, - maxSize, SerializeIF::Endianness::BIG); - if(result != HasReturnvaluesIF::RETURN_OK) { - return; - } - } + return; + } + for (const auto& health : healthMap) { + result = SerializeAdapter::serialize(&health.first, &pointer, &size, maxSize, + SerializeIF::Endianness::BIG); + if (result != HasReturnvaluesIF::RETURN_OK) { + return; + } + uint8_t healthValue = health.second; + result = SerializeAdapter::serialize(&healthValue, &pointer, &size, maxSize, + SerializeIF::Endianness::BIG); + if (result != HasReturnvaluesIF::RETURN_OK) { + return; + } + } } -ReturnValue_t HealthTable::iterate(HealthEntry *value, bool reset) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - MutexGuard(mutex, timeoutType, mutexTimeoutMs); - if (reset) { - mapIterator = healthMap.begin(); - } - if (mapIterator == healthMap.end()) { - return HasReturnvaluesIF::RETURN_FAILED; - } - *value = *mapIterator; - mapIterator++; - return result; +ReturnValue_t HealthTable::iterate(HealthEntry* value, bool reset) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + MutexGuard(mutex, timeoutType, mutexTimeoutMs); + if (reset) { + mapIterator = healthMap.begin(); + } + if (mapIterator == healthMap.end()) { + return HasReturnvaluesIF::RETURN_FAILED; + } + *value = *mapIterator; + mapIterator++; + return result; } diff --git a/src/fsfw/health/HealthTable.h b/src/fsfw/health/HealthTable.h index cea34f68..4718abc3 100644 --- a/src/fsfw/health/HealthTable.h +++ b/src/fsfw/health/HealthTable.h @@ -1,47 +1,43 @@ #ifndef FSFW_HEALTH_HEALTHTABLE_H_ #define FSFW_HEALTH_HEALTHTABLE_H_ -#include "HealthTableIF.h" -#include "../objectmanager/SystemObject.h" -#include "../ipc/MutexIF.h" #include +#include "../ipc/MutexIF.h" +#include "../objectmanager/SystemObject.h" +#include "HealthTableIF.h" -class HealthTable: public HealthTableIF, public SystemObject { -public: - HealthTable(object_id_t objectid); - virtual ~HealthTable(); +class HealthTable : public HealthTableIF, public SystemObject { + public: + HealthTable(object_id_t objectid); + virtual ~HealthTable(); - void setMutexTimeout(MutexIF::TimeoutType timeoutType, uint32_t timeoutMs); + void setMutexTimeout(MutexIF::TimeoutType timeoutType, uint32_t timeoutMs); - /** HealthTableIF overrides */ - virtual ReturnValue_t registerObject(object_id_t object, - HasHealthIF::HealthState initilialState = - HasHealthIF::HEALTHY) override; - virtual size_t getPrintSize() override; - virtual void printAll(uint8_t *pointer, size_t maxSize) override; + /** HealthTableIF overrides */ + virtual ReturnValue_t registerObject( + object_id_t object, HasHealthIF::HealthState initilialState = HasHealthIF::HEALTHY) override; + virtual size_t getPrintSize() override; + virtual void printAll(uint8_t* pointer, size_t maxSize) override; - /** ManagesHealthIF overrides */ - virtual bool hasHealth(object_id_t object) override; - virtual void setHealth(object_id_t object, - HasHealthIF::HealthState newState) override; - virtual HasHealthIF::HealthState getHealth(object_id_t) override; + /** ManagesHealthIF overrides */ + virtual bool hasHealth(object_id_t object) override; + virtual void setHealth(object_id_t object, HasHealthIF::HealthState newState) override; + virtual HasHealthIF::HealthState getHealth(object_id_t) override; -protected: - using HealthMap = std::map; - using HealthEntry = std::pair; + protected: + using HealthMap = std::map; + using HealthEntry = std::pair; - MutexIF* mutex; - MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING; - uint32_t mutexTimeoutMs = 20; + MutexIF* mutex; + MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING; + uint32_t mutexTimeoutMs = 20; - HealthMap healthMap; + HealthMap healthMap; - HealthMap::iterator mapIterator; + HealthMap::iterator mapIterator; - virtual ReturnValue_t iterate( - HealthEntry* value, - bool reset = false) override; + virtual ReturnValue_t iterate(HealthEntry* value, bool reset = false) override; }; #endif /* FSFW_HEALTH_HEALTHTABLE_H_ */ diff --git a/src/fsfw/health/HealthTableIF.h b/src/fsfw/health/HealthTableIF.h index 727c4496..50266ac2 100644 --- a/src/fsfw/health/HealthTableIF.h +++ b/src/fsfw/health/HealthTableIF.h @@ -1,26 +1,25 @@ #ifndef FSFW_HEALTH_HEALTHTABLEIF_H_ #define FSFW_HEALTH_HEALTHTABLEIF_H_ -#include "ManagesHealthIF.h" -#include "../objectmanager/ObjectManagerIF.h" -#include "../returnvalues/HasReturnvaluesIF.h" - #include -class HealthTableIF: public ManagesHealthIF { -public: - virtual ~HealthTableIF() {} +#include "../objectmanager/ObjectManagerIF.h" +#include "../returnvalues/HasReturnvaluesIF.h" +#include "ManagesHealthIF.h" - virtual ReturnValue_t registerObject(object_id_t object, - HasHealthIF::HealthState initilialState = HasHealthIF::HEALTHY) = 0; +class HealthTableIF : public ManagesHealthIF { + public: + virtual ~HealthTableIF() {} - virtual size_t getPrintSize() = 0; - virtual void printAll(uint8_t *pointer, size_t maxSize) = 0; + virtual ReturnValue_t registerObject( + object_id_t object, HasHealthIF::HealthState initilialState = HasHealthIF::HEALTHY) = 0; -protected: - virtual ReturnValue_t iterate( - std::pair *value, - bool reset = false) = 0; + virtual size_t getPrintSize() = 0; + virtual void printAll(uint8_t *pointer, size_t maxSize) = 0; + + protected: + virtual ReturnValue_t iterate(std::pair *value, + bool reset = false) = 0; }; #endif /* FRAMEWORK_HEALTH_HEALTHTABLEIF_H_ */ diff --git a/src/fsfw/health/ManagesHealthIF.h b/src/fsfw/health/ManagesHealthIF.h index 2edfceca..a4d0d45e 100644 --- a/src/fsfw/health/ManagesHealthIF.h +++ b/src/fsfw/health/ManagesHealthIF.h @@ -1,53 +1,48 @@ #ifndef FSFW_HEALTH_MANAGESHEALTHIF_H_ #define FSFW_HEALTH_MANAGESHEALTHIF_H_ -#include "HasHealthIF.h" #include "../objectmanager/ObjectManagerIF.h" +#include "HasHealthIF.h" class ManagesHealthIF { -public: - virtual ~ManagesHealthIF() { - } - virtual bool hasHealth(object_id_t object) = 0; - virtual void setHealth(object_id_t object, - HasHealthIF::HealthState newState) = 0; - virtual HasHealthIF::HealthState getHealth(object_id_t) = 0; + public: + virtual ~ManagesHealthIF() {} + virtual bool hasHealth(object_id_t object) = 0; + virtual void setHealth(object_id_t object, HasHealthIF::HealthState newState) = 0; + virtual HasHealthIF::HealthState getHealth(object_id_t) = 0; - virtual bool isHealthy(object_id_t object) { - return (getHealth(object) == HasHealthIF::HEALTHY); - } + virtual bool isHealthy(object_id_t object) { return (getHealth(object) == HasHealthIF::HEALTHY); } - virtual bool isHealthy(HasHealthIF::HealthState health) { - return (health == HasHealthIF::HEALTHY); - } + virtual bool isHealthy(HasHealthIF::HealthState health) { + return (health == HasHealthIF::HEALTHY); + } - virtual bool isFaulty(object_id_t object) { - HasHealthIF::HealthState health = getHealth(object); - return isFaulty(health); - } + virtual bool isFaulty(object_id_t object) { + HasHealthIF::HealthState health = getHealth(object); + return isFaulty(health); + } - virtual bool isPermanentFaulty(object_id_t object) { - HasHealthIF::HealthState health = getHealth(object); - return isPermanentFaulty(health); - } + virtual bool isPermanentFaulty(object_id_t object) { + HasHealthIF::HealthState health = getHealth(object); + return isPermanentFaulty(health); + } - virtual bool isPermanentFaulty(HasHealthIF::HealthState health) { - return (health == HasHealthIF::PERMANENT_FAULTY); - } + virtual bool isPermanentFaulty(HasHealthIF::HealthState health) { + return (health == HasHealthIF::PERMANENT_FAULTY); + } - static bool isFaulty(HasHealthIF::HealthState health) { - return ((health == HasHealthIF::FAULTY) - || (health == HasHealthIF::PERMANENT_FAULTY) - || (health == HasHealthIF::NEEDS_RECOVERY)); - } + static bool isFaulty(HasHealthIF::HealthState health) { + return ((health == HasHealthIF::FAULTY) || (health == HasHealthIF::PERMANENT_FAULTY) || + (health == HasHealthIF::NEEDS_RECOVERY)); + } - virtual bool isCommandable(object_id_t object) { - return (getHealth(object) != HasHealthIF::EXTERNAL_CONTROL); - } + virtual bool isCommandable(object_id_t object) { + return (getHealth(object) != HasHealthIF::EXTERNAL_CONTROL); + } - virtual bool isCommandable(HasHealthIF::HealthState health) { - return (health != HasHealthIF::EXTERNAL_CONTROL); - } + virtual bool isCommandable(HasHealthIF::HealthState health) { + return (health != HasHealthIF::EXTERNAL_CONTROL); + } }; #endif /* FSFW_HEALTH_MANAGESHEALTHIF_H_ */ diff --git a/src/fsfw/housekeeping/AcceptsHkPacketsIF.h b/src/fsfw/housekeeping/AcceptsHkPacketsIF.h index 6fa151b1..07882829 100644 --- a/src/fsfw/housekeeping/AcceptsHkPacketsIF.h +++ b/src/fsfw/housekeeping/AcceptsHkPacketsIF.h @@ -4,9 +4,9 @@ #include "../ipc/MessageQueueMessageIF.h" class AcceptsHkPacketsIF { -public: - virtual~ AcceptsHkPacketsIF() {}; - virtual MessageQueueId_t getHkQueue() const = 0; + public: + virtual ~AcceptsHkPacketsIF(){}; + virtual MessageQueueId_t getHkQueue() const = 0; }; #endif /* FRAMEWORK_HOUSEKEEPING_ACCEPTSHKPACKETSIF_H_ */ diff --git a/src/fsfw/housekeeping/HousekeepingMessage.cpp b/src/fsfw/housekeeping/HousekeepingMessage.cpp index 432a8620..ed4370f4 100644 --- a/src/fsfw/housekeeping/HousekeepingMessage.cpp +++ b/src/fsfw/housekeeping/HousekeepingMessage.cpp @@ -1,233 +1,224 @@ #include "fsfw/housekeeping/HousekeepingMessage.h" -#include "fsfw/objectmanager/ObjectManager.h" - #include +#include "fsfw/objectmanager/ObjectManager.h" + HousekeepingMessage::~HousekeepingMessage() {} -void HousekeepingMessage::setHkReportReply(CommandMessage* message, sid_t sid, - store_address_t storeId) { - message->setCommand(HK_REPORT); - message->setMessageSize(HK_MESSAGE_SIZE); - setSid(message, sid); - message->setParameter3(storeId.raw); +void HousekeepingMessage::setHkReportReply(CommandMessage *message, sid_t sid, + store_address_t storeId) { + message->setCommand(HK_REPORT); + message->setMessageSize(HK_MESSAGE_SIZE); + setSid(message, sid); + message->setParameter3(storeId.raw); } -void HousekeepingMessage::setHkDiagnosticsReply(CommandMessage* message, - sid_t sid, store_address_t storeId) { - message->setCommand(DIAGNOSTICS_REPORT); - message->setMessageSize(HK_MESSAGE_SIZE); - setSid(message, sid); - message->setParameter3(storeId.raw); +void HousekeepingMessage::setHkDiagnosticsReply(CommandMessage *message, sid_t sid, + store_address_t storeId) { + message->setCommand(DIAGNOSTICS_REPORT); + message->setMessageSize(HK_MESSAGE_SIZE); + setSid(message, sid); + message->setParameter3(storeId.raw); } sid_t HousekeepingMessage::getHkDataReply(const CommandMessage *message, - store_address_t *storeIdToSet) { - if(storeIdToSet != nullptr) { - *storeIdToSet = message->getParameter3(); - } - return getSid(message); + store_address_t *storeIdToSet) { + if (storeIdToSet != nullptr) { + *storeIdToSet = message->getParameter3(); + } + return getSid(message); } -void HousekeepingMessage::setToggleReportingCommand(CommandMessage *message, - sid_t sid, bool enableReporting, bool isDiagnostics) { - if(isDiagnostics) { - if(enableReporting) { - message->setCommand(ENABLE_PERIODIC_DIAGNOSTICS_GENERATION); - } - else { - message->setCommand(DISABLE_PERIODIC_DIAGNOSTICS_GENERATION); - } - } - else { - if(enableReporting) { - message->setCommand(ENABLE_PERIODIC_HK_REPORT_GENERATION); - } - else { - message->setCommand(DISABLE_PERIODIC_HK_REPORT_GENERATION); - } - } +void HousekeepingMessage::setToggleReportingCommand(CommandMessage *message, sid_t sid, + bool enableReporting, bool isDiagnostics) { + if (isDiagnostics) { + if (enableReporting) { + message->setCommand(ENABLE_PERIODIC_DIAGNOSTICS_GENERATION); + } else { + message->setCommand(DISABLE_PERIODIC_DIAGNOSTICS_GENERATION); + } + } else { + if (enableReporting) { + message->setCommand(ENABLE_PERIODIC_HK_REPORT_GENERATION); + } else { + message->setCommand(DISABLE_PERIODIC_HK_REPORT_GENERATION); + } + } - setSid(message, sid); + setSid(message, sid); } -void HousekeepingMessage::setStructureReportingCommand(CommandMessage *command, - sid_t sid, bool isDiagnostics) { - if(isDiagnostics) { - command->setCommand(REPORT_DIAGNOSTICS_REPORT_STRUCTURES); - } - else { - command->setCommand(REPORT_HK_REPORT_STRUCTURES); - } +void HousekeepingMessage::setStructureReportingCommand(CommandMessage *command, sid_t sid, + bool isDiagnostics) { + if (isDiagnostics) { + command->setCommand(REPORT_DIAGNOSTICS_REPORT_STRUCTURES); + } else { + command->setCommand(REPORT_HK_REPORT_STRUCTURES); + } - setSid(command, sid); + setSid(command, sid); } -void HousekeepingMessage::setOneShotReportCommand(CommandMessage *command, - sid_t sid, bool isDiagnostics) { - if(isDiagnostics) { - command->setCommand(GENERATE_ONE_DIAGNOSTICS_REPORT); - } - else { - command->setCommand(GENERATE_ONE_PARAMETER_REPORT); - } +void HousekeepingMessage::setOneShotReportCommand(CommandMessage *command, sid_t sid, + bool isDiagnostics) { + if (isDiagnostics) { + command->setCommand(GENERATE_ONE_DIAGNOSTICS_REPORT); + } else { + command->setCommand(GENERATE_ONE_PARAMETER_REPORT); + } - setSid(command, sid); + setSid(command, sid); } -void HousekeepingMessage::setCollectionIntervalModificationCommand( - CommandMessage *command, sid_t sid, float collectionInterval, - bool isDiagnostics) { - if(isDiagnostics) { - command->setCommand(MODIFY_DIAGNOSTICS_REPORT_COLLECTION_INTERVAL); - } - else { - command->setCommand(MODIFY_PARAMETER_REPORT_COLLECTION_INTERVAL); - } +void HousekeepingMessage::setCollectionIntervalModificationCommand(CommandMessage *command, + sid_t sid, + float collectionInterval, + bool isDiagnostics) { + if (isDiagnostics) { + command->setCommand(MODIFY_DIAGNOSTICS_REPORT_COLLECTION_INTERVAL); + } else { + command->setCommand(MODIFY_PARAMETER_REPORT_COLLECTION_INTERVAL); + } - /* Raw storage of the float in the message. Do not use setParameter3, does - implicit conversion to integer type! */ - std::memcpy(command->getData() + 2 * sizeof(uint32_t), &collectionInterval, - sizeof(collectionInterval)); + /* Raw storage of the float in the message. Do not use setParameter3, does + implicit conversion to integer type! */ + std::memcpy(command->getData() + 2 * sizeof(uint32_t), &collectionInterval, + sizeof(collectionInterval)); - setSid(command, sid); + setSid(command, sid); } -sid_t HousekeepingMessage::getCollectionIntervalModificationCommand( - const CommandMessage* command, float* newCollectionInterval) { +sid_t HousekeepingMessage::getCollectionIntervalModificationCommand(const CommandMessage *command, + float *newCollectionInterval) { + if (newCollectionInterval != nullptr) { + std::memcpy(newCollectionInterval, command->getData() + 2 * sizeof(uint32_t), + sizeof(*newCollectionInterval)); + } - if(newCollectionInterval != nullptr) { - std::memcpy(newCollectionInterval, command->getData() + 2 * sizeof(uint32_t), - sizeof(*newCollectionInterval)); - } - - return getSid(command); + return getSid(command); } -void HousekeepingMessage::setHkRequestSuccessReply(CommandMessage *reply, - sid_t sid) { - setSid(reply, sid); - reply->setCommand(HK_REQUEST_SUCCESS); +void HousekeepingMessage::setHkRequestSuccessReply(CommandMessage *reply, sid_t sid) { + setSid(reply, sid); + reply->setCommand(HK_REQUEST_SUCCESS); } -void HousekeepingMessage::setHkRequestFailureReply(CommandMessage *reply, - sid_t sid, ReturnValue_t error) { - setSid(reply, sid); - reply->setCommand(HK_REQUEST_FAILURE); - reply->setParameter3(error); +void HousekeepingMessage::setHkRequestFailureReply(CommandMessage *reply, sid_t sid, + ReturnValue_t error) { + setSid(reply, sid); + reply->setCommand(HK_REQUEST_FAILURE); + reply->setParameter3(error); } sid_t HousekeepingMessage::getHkRequestFailureReply(const CommandMessage *reply, - ReturnValue_t *error) { - if(error != nullptr) { - *error = reply->getParameter3(); - } - return getSid(reply); + ReturnValue_t *error) { + if (error != nullptr) { + *error = reply->getParameter3(); + } + return getSid(reply); } -sid_t HousekeepingMessage::getSid(const CommandMessage* message) { - sid_t sid; - std::memcpy(&sid.raw, message->getData(), sizeof(sid.raw)); - return sid; +sid_t HousekeepingMessage::getSid(const CommandMessage *message) { + sid_t sid; + std::memcpy(&sid.raw, message->getData(), sizeof(sid.raw)); + return sid; } -gp_id_t HousekeepingMessage::getGpid(const CommandMessage* message) { - gp_id_t globalPoolId; - std::memcpy(&globalPoolId.raw, message->getData(), sizeof(globalPoolId.raw)); - return globalPoolId; +gp_id_t HousekeepingMessage::getGpid(const CommandMessage *message) { + gp_id_t globalPoolId; + std::memcpy(&globalPoolId.raw, message->getData(), sizeof(globalPoolId.raw)); + return globalPoolId; } -void HousekeepingMessage::setHkStuctureReportReply(CommandMessage *reply, - sid_t sid, store_address_t storeId) { - reply->setCommand(HK_DEFINITIONS_REPORT); - setSid(reply, sid); - reply->setParameter3(storeId.raw); +void HousekeepingMessage::setHkStuctureReportReply(CommandMessage *reply, sid_t sid, + store_address_t storeId) { + reply->setCommand(HK_DEFINITIONS_REPORT); + setSid(reply, sid); + reply->setParameter3(storeId.raw); } -void HousekeepingMessage::setDiagnosticsStuctureReportReply( - CommandMessage *reply, sid_t sid, store_address_t storeId) { - reply->setCommand(DIAGNOSTICS_DEFINITION_REPORT); - setSid(reply, sid); - reply->setParameter3(storeId.raw); +void HousekeepingMessage::setDiagnosticsStuctureReportReply(CommandMessage *reply, sid_t sid, + store_address_t storeId) { + reply->setCommand(DIAGNOSTICS_DEFINITION_REPORT); + setSid(reply, sid); + reply->setParameter3(storeId.raw); } -void HousekeepingMessage::clear(CommandMessage* message) { - switch(message->getCommand()) { - case(HK_REPORT): - case(DIAGNOSTICS_REPORT): - case(HK_DEFINITIONS_REPORT): - case(DIAGNOSTICS_DEFINITION_REPORT): - case(UPDATE_SNAPSHOT_SET): - case(UPDATE_SNAPSHOT_VARIABLE): { - store_address_t storeId; - getHkDataReply(message, &storeId); - StorageManagerIF *ipcStore = ObjectManager::instance()->get( - objects::IPC_STORE); - if (ipcStore != nullptr) { - ipcStore->deleteData(storeId); - } +void HousekeepingMessage::clear(CommandMessage *message) { + switch (message->getCommand()) { + case (HK_REPORT): + case (DIAGNOSTICS_REPORT): + case (HK_DEFINITIONS_REPORT): + case (DIAGNOSTICS_DEFINITION_REPORT): + case (UPDATE_SNAPSHOT_SET): + case (UPDATE_SNAPSHOT_VARIABLE): { + store_address_t storeId; + getHkDataReply(message, &storeId); + StorageManagerIF *ipcStore = + ObjectManager::instance()->get(objects::IPC_STORE); + if (ipcStore != nullptr) { + ipcStore->deleteData(storeId); + } } - } - message->setCommand(CommandMessage::CMD_NONE); + } + message->setCommand(CommandMessage::CMD_NONE); } -void HousekeepingMessage::setUpdateNotificationSetCommand( - CommandMessage *command, sid_t sid) { - command->setCommand(UPDATE_NOTIFICATION_SET); - setSid(command, sid); +void HousekeepingMessage::setUpdateNotificationSetCommand(CommandMessage *command, sid_t sid) { + command->setCommand(UPDATE_NOTIFICATION_SET); + setSid(command, sid); } -void HousekeepingMessage::setUpdateNotificationVariableCommand( - CommandMessage *command, gp_id_t globalPoolId) { - command->setCommand(UPDATE_NOTIFICATION_VARIABLE); - setGpid(command, globalPoolId); +void HousekeepingMessage::setUpdateNotificationVariableCommand(CommandMessage *command, + gp_id_t globalPoolId) { + command->setCommand(UPDATE_NOTIFICATION_VARIABLE); + setGpid(command, globalPoolId); } -void HousekeepingMessage::setUpdateSnapshotSetCommand(CommandMessage *command, - sid_t sid, store_address_t storeId) { - command->setCommand(UPDATE_SNAPSHOT_SET); - setSid(command, sid); - command->setParameter3(storeId.raw); +void HousekeepingMessage::setUpdateSnapshotSetCommand(CommandMessage *command, sid_t sid, + store_address_t storeId) { + command->setCommand(UPDATE_SNAPSHOT_SET); + setSid(command, sid); + command->setParameter3(storeId.raw); } -void HousekeepingMessage::setUpdateSnapshotVariableCommand( - CommandMessage *command, gp_id_t globalPoolId, store_address_t storeId) { - command->setCommand(UPDATE_SNAPSHOT_VARIABLE); - setGpid(command, globalPoolId); - command->setParameter3(storeId.raw); +void HousekeepingMessage::setUpdateSnapshotVariableCommand(CommandMessage *command, + gp_id_t globalPoolId, + store_address_t storeId) { + command->setCommand(UPDATE_SNAPSHOT_VARIABLE); + setGpid(command, globalPoolId); + command->setParameter3(storeId.raw); } -sid_t HousekeepingMessage::getUpdateNotificationSetCommand( - const CommandMessage *command) { - return getSid(command); +sid_t HousekeepingMessage::getUpdateNotificationSetCommand(const CommandMessage *command) { + return getSid(command); } -gp_id_t HousekeepingMessage::getUpdateNotificationVariableCommand( - const CommandMessage *command) { - return getGpid(command); +gp_id_t HousekeepingMessage::getUpdateNotificationVariableCommand(const CommandMessage *command) { + return getGpid(command); } -sid_t HousekeepingMessage::getUpdateSnapshotSetCommand( - const CommandMessage *command, store_address_t *storeId) { - if(storeId != nullptr) { - *storeId = command->getParameter3(); - } - return getSid(command); +sid_t HousekeepingMessage::getUpdateSnapshotSetCommand(const CommandMessage *command, + store_address_t *storeId) { + if (storeId != nullptr) { + *storeId = command->getParameter3(); + } + return getSid(command); } -gp_id_t HousekeepingMessage::getUpdateSnapshotVariableCommand( - const CommandMessage *command, store_address_t *storeId) { - if(storeId != nullptr) { - *storeId = command->getParameter3(); - } - return getGpid(command); +gp_id_t HousekeepingMessage::getUpdateSnapshotVariableCommand(const CommandMessage *command, + store_address_t *storeId) { + if (storeId != nullptr) { + *storeId = command->getParameter3(); + } + return getGpid(command); } void HousekeepingMessage::setSid(CommandMessage *message, sid_t sid) { - std::memcpy(message->getData(), &sid.raw, sizeof(sid.raw)); + std::memcpy(message->getData(), &sid.raw, sizeof(sid.raw)); } void HousekeepingMessage::setGpid(CommandMessage *message, gp_id_t globalPoolId) { - std::memcpy(message->getData(), &globalPoolId.raw, sizeof(globalPoolId.raw)); + std::memcpy(message->getData(), &globalPoolId.raw, sizeof(globalPoolId.raw)); } diff --git a/src/fsfw/housekeeping/HousekeepingMessage.h b/src/fsfw/housekeeping/HousekeepingMessage.h index 509a68c9..f52b6173 100644 --- a/src/fsfw/housekeeping/HousekeepingMessage.h +++ b/src/fsfw/housekeeping/HousekeepingMessage.h @@ -7,7 +7,6 @@ #include "fsfw/objectmanager/frameworkObjects.h" #include "fsfw/storagemanager/StorageManagerIF.h" - /** * @brief Special command message type for housekeeping messages * @details @@ -15,137 +14,110 @@ * the uint64_t structure ID (SID). */ class HousekeepingMessage { -public: + public: + static constexpr size_t HK_MESSAGE_SIZE = + CommandMessageIF::HEADER_SIZE + sizeof(sid_t) + sizeof(uint32_t); - static constexpr size_t HK_MESSAGE_SIZE = CommandMessageIF::HEADER_SIZE + - sizeof(sid_t) + sizeof(uint32_t); + /** + * Concrete instance is not used, instead this class operates on + * command message instances. + */ + HousekeepingMessage() = delete; + virtual ~HousekeepingMessage(); - /** - * Concrete instance is not used, instead this class operates on - * command message instances. - */ - HousekeepingMessage() = delete; - virtual ~HousekeepingMessage(); + static constexpr uint8_t MESSAGE_ID = messagetypes::HOUSEKEEPING; - static constexpr uint8_t MESSAGE_ID = messagetypes::HOUSEKEEPING; + static constexpr Command_t ENABLE_PERIODIC_HK_REPORT_GENERATION = MAKE_COMMAND_ID(5); + static constexpr Command_t DISABLE_PERIODIC_HK_REPORT_GENERATION = MAKE_COMMAND_ID(6); - static constexpr Command_t ENABLE_PERIODIC_HK_REPORT_GENERATION = - MAKE_COMMAND_ID(5); - static constexpr Command_t DISABLE_PERIODIC_HK_REPORT_GENERATION = - MAKE_COMMAND_ID(6); + static constexpr Command_t ENABLE_PERIODIC_DIAGNOSTICS_GENERATION = MAKE_COMMAND_ID(7); + static constexpr Command_t DISABLE_PERIODIC_DIAGNOSTICS_GENERATION = MAKE_COMMAND_ID(8); - static constexpr Command_t ENABLE_PERIODIC_DIAGNOSTICS_GENERATION = - MAKE_COMMAND_ID(7); - static constexpr Command_t DISABLE_PERIODIC_DIAGNOSTICS_GENERATION = - MAKE_COMMAND_ID(8); + static constexpr Command_t REPORT_HK_REPORT_STRUCTURES = MAKE_COMMAND_ID(9); + static constexpr Command_t REPORT_DIAGNOSTICS_REPORT_STRUCTURES = MAKE_COMMAND_ID(11); - static constexpr Command_t REPORT_HK_REPORT_STRUCTURES = MAKE_COMMAND_ID(9); - static constexpr Command_t REPORT_DIAGNOSTICS_REPORT_STRUCTURES = - MAKE_COMMAND_ID(11); + static constexpr Command_t HK_DEFINITIONS_REPORT = MAKE_COMMAND_ID(10); + static constexpr Command_t DIAGNOSTICS_DEFINITION_REPORT = MAKE_COMMAND_ID(12); - static constexpr Command_t HK_DEFINITIONS_REPORT = MAKE_COMMAND_ID(10); - static constexpr Command_t DIAGNOSTICS_DEFINITION_REPORT = MAKE_COMMAND_ID(12); + static constexpr Command_t HK_REPORT = MAKE_COMMAND_ID(25); + static constexpr Command_t DIAGNOSTICS_REPORT = MAKE_COMMAND_ID(26); - static constexpr Command_t HK_REPORT = MAKE_COMMAND_ID(25); - static constexpr Command_t DIAGNOSTICS_REPORT = MAKE_COMMAND_ID(26); + static constexpr Command_t GENERATE_ONE_PARAMETER_REPORT = MAKE_COMMAND_ID(27); + static constexpr Command_t GENERATE_ONE_DIAGNOSTICS_REPORT = MAKE_COMMAND_ID(28); - static constexpr Command_t GENERATE_ONE_PARAMETER_REPORT = - MAKE_COMMAND_ID(27); - static constexpr Command_t GENERATE_ONE_DIAGNOSTICS_REPORT = - MAKE_COMMAND_ID(28); + static constexpr Command_t MODIFY_PARAMETER_REPORT_COLLECTION_INTERVAL = MAKE_COMMAND_ID(31); + static constexpr Command_t MODIFY_DIAGNOSTICS_REPORT_COLLECTION_INTERVAL = MAKE_COMMAND_ID(32); - static constexpr Command_t MODIFY_PARAMETER_REPORT_COLLECTION_INTERVAL = - MAKE_COMMAND_ID(31); - static constexpr Command_t MODIFY_DIAGNOSTICS_REPORT_COLLECTION_INTERVAL = - MAKE_COMMAND_ID(32); + static constexpr Command_t HK_REQUEST_SUCCESS = MAKE_COMMAND_ID(128); + static constexpr Command_t HK_REQUEST_FAILURE = MAKE_COMMAND_ID(129); - static constexpr Command_t HK_REQUEST_SUCCESS = - MAKE_COMMAND_ID(128); - static constexpr Command_t HK_REQUEST_FAILURE = - MAKE_COMMAND_ID(129); + static constexpr Command_t UPDATE_NOTIFICATION_SET = MAKE_COMMAND_ID(130); + static constexpr Command_t UPDATE_NOTIFICATION_VARIABLE = MAKE_COMMAND_ID(131); - static constexpr Command_t UPDATE_NOTIFICATION_SET = - MAKE_COMMAND_ID(130); - static constexpr Command_t UPDATE_NOTIFICATION_VARIABLE = - MAKE_COMMAND_ID(131); + static constexpr Command_t UPDATE_SNAPSHOT_SET = MAKE_COMMAND_ID(132); + static constexpr Command_t UPDATE_SNAPSHOT_VARIABLE = MAKE_COMMAND_ID(133); - static constexpr Command_t UPDATE_SNAPSHOT_SET = MAKE_COMMAND_ID(132); - static constexpr Command_t UPDATE_SNAPSHOT_VARIABLE = MAKE_COMMAND_ID(133); + // static constexpr Command_t UPDATE_HK_REPORT = MAKE_COMMAND_ID(134); - //static constexpr Command_t UPDATE_HK_REPORT = MAKE_COMMAND_ID(134); + static sid_t getSid(const CommandMessage* message); + static gp_id_t getGpid(const CommandMessage* message); - static sid_t getSid(const CommandMessage* message); - static gp_id_t getGpid(const CommandMessage* message); + /* Housekeeping Interface Messages */ - /* Housekeeping Interface Messages */ + static void setToggleReportingCommand(CommandMessage* command, sid_t sid, bool enableReporting, + bool isDiagnostics); + static void setStructureReportingCommand(CommandMessage* command, sid_t sid, bool isDiagnostics); + static void setOneShotReportCommand(CommandMessage* command, sid_t sid, bool isDiagnostics); + static void setCollectionIntervalModificationCommand(CommandMessage* command, sid_t sid, + float collectionInterval, + bool isDiagnostics); - static void setToggleReportingCommand(CommandMessage* command, sid_t sid, - bool enableReporting, bool isDiagnostics); - static void setStructureReportingCommand(CommandMessage* command, sid_t sid, - bool isDiagnostics); - static void setOneShotReportCommand(CommandMessage* command, sid_t sid, - bool isDiagnostics); - static void setCollectionIntervalModificationCommand( - CommandMessage* command, sid_t sid, float collectionInterval, - bool isDiagnostics); + static void setHkReportReply(CommandMessage* reply, sid_t sid, store_address_t storeId); + static void setHkDiagnosticsReply(CommandMessage* reply, sid_t sid, store_address_t storeId); - static void setHkReportReply(CommandMessage* reply, sid_t sid, - store_address_t storeId); - static void setHkDiagnosticsReply(CommandMessage* reply, sid_t sid, - store_address_t storeId); + static void setHkRequestSuccessReply(CommandMessage* reply, sid_t sid); + static void setHkRequestFailureReply(CommandMessage* reply, sid_t sid, ReturnValue_t error); - static void setHkRequestSuccessReply(CommandMessage* reply, sid_t sid); - static void setHkRequestFailureReply(CommandMessage* reply, sid_t sid, - ReturnValue_t error); + static void setHkStuctureReportReply(CommandMessage* reply, sid_t sid, store_address_t storeId); + static void setDiagnosticsStuctureReportReply(CommandMessage* reply, sid_t sid, + store_address_t storeId); - static void setHkStuctureReportReply(CommandMessage* reply, - sid_t sid, store_address_t storeId); - static void setDiagnosticsStuctureReportReply(CommandMessage* reply, - sid_t sid, store_address_t storeId); + static sid_t getHkRequestFailureReply(const CommandMessage* reply, ReturnValue_t* error); - static sid_t getHkRequestFailureReply(const CommandMessage* reply, - ReturnValue_t* error); + /** + * @brief Generic getter function for housekeeping data replies + * @details + * Command ID can be used beforehand to distinguish between diagnostics and + * regular HK packets. This getter function should be used for the + * command IDs 10, 12, 25 and 26. + */ + static sid_t getHkDataReply(const CommandMessage* message, store_address_t* storeIdToSet); + static sid_t getCollectionIntervalModificationCommand(const CommandMessage* command, + float* newCollectionInterval); - /** - * @brief Generic getter function for housekeeping data replies - * @details - * Command ID can be used beforehand to distinguish between diagnostics and - * regular HK packets. This getter function should be used for the - * command IDs 10, 12, 25 and 26. - */ - static sid_t getHkDataReply(const CommandMessage* message, - store_address_t * storeIdToSet); - static sid_t getCollectionIntervalModificationCommand( - const CommandMessage* command, float* newCollectionInterval); + /* Update Notification Messages */ + static void setUpdateNotificationSetCommand(CommandMessage* command, sid_t sid); + static void setUpdateNotificationVariableCommand(CommandMessage* command, gp_id_t globalPoolId); - /* Update Notification Messages */ + static void setUpdateSnapshotSetCommand(CommandMessage* command, sid_t sid, + store_address_t storeId); + static void setUpdateSnapshotVariableCommand(CommandMessage* command, gp_id_t globalPoolId, + store_address_t storeId); - static void setUpdateNotificationSetCommand(CommandMessage* command, - sid_t sid); - static void setUpdateNotificationVariableCommand(CommandMessage* command, - gp_id_t globalPoolId); + static sid_t getUpdateNotificationSetCommand(const CommandMessage* command); + static gp_id_t getUpdateNotificationVariableCommand(const CommandMessage* command); - static void setUpdateSnapshotSetCommand(CommandMessage* command, sid_t sid, - store_address_t storeId); - static void setUpdateSnapshotVariableCommand(CommandMessage* command, - gp_id_t globalPoolId, store_address_t storeId); + static sid_t getUpdateSnapshotSetCommand(const CommandMessage* command, store_address_t* storeId); + static gp_id_t getUpdateSnapshotVariableCommand(const CommandMessage* command, + store_address_t* storeId); - static sid_t getUpdateNotificationSetCommand(const CommandMessage* command); - static gp_id_t getUpdateNotificationVariableCommand( - const CommandMessage* command); + /** Utility */ + static void clear(CommandMessage* message); - static sid_t getUpdateSnapshotSetCommand(const CommandMessage* command, - store_address_t* storeId); - static gp_id_t getUpdateSnapshotVariableCommand(const CommandMessage* command, - store_address_t* storeId); - - /** Utility */ - static void clear(CommandMessage* message); -private: - static void setSid(CommandMessage* message, sid_t sid); - static void setGpid(CommandMessage* message, gp_id_t globalPoolId); + private: + static void setSid(CommandMessage* message, sid_t sid); + static void setGpid(CommandMessage* message, gp_id_t globalPoolId); }; - #endif /* FSFW_HOUSEKEEPING_HOUSEKEEPINGMESSAGE_H_ */ diff --git a/src/fsfw/housekeeping/HousekeepingPacketDownlink.h b/src/fsfw/housekeeping/HousekeepingPacketDownlink.h index aeea16c3..0683aa19 100644 --- a/src/fsfw/housekeeping/HousekeepingPacketDownlink.h +++ b/src/fsfw/housekeeping/HousekeepingPacketDownlink.h @@ -16,23 +16,23 @@ * - Housekeeping Data: The rest of the packet will be the serialized housekeeping data. A validity * buffer might be appended at the end, depending on the set configuration. */ -class HousekeepingPacketDownlink: public SerialLinkedListAdapter { -public: - HousekeepingPacketDownlink(sid_t sid, LocalPoolDataSetBase* dataSetPtr): - sourceId(sid.objectId), setId(sid.ownerSetId), hkData(dataSetPtr) { - setLinks(); - } +class HousekeepingPacketDownlink : public SerialLinkedListAdapter { + public: + HousekeepingPacketDownlink(sid_t sid, LocalPoolDataSetBase* dataSetPtr) + : sourceId(sid.objectId), setId(sid.ownerSetId), hkData(dataSetPtr) { + setLinks(); + } -private: - void setLinks() { - setStart(&sourceId); - sourceId.setNext(&setId); - setId.setNext(&hkData); - } + private: + void setLinks() { + setStart(&sourceId); + sourceId.setNext(&setId); + setId.setNext(&hkData); + } - SerializeElement sourceId; - SerializeElement setId; - LinkedElement hkData; + SerializeElement sourceId; + SerializeElement setId; + LinkedElement hkData; }; #endif /* FRAMEWORK_HOUSEKEEPING_HOUSEKEEPINGPACKETDOWNLINK_H_ */ diff --git a/src/fsfw/housekeeping/HousekeepingSetPacket.h b/src/fsfw/housekeeping/HousekeepingSetPacket.h index f94720d4..96eaaed9 100644 --- a/src/fsfw/housekeeping/HousekeepingSetPacket.h +++ b/src/fsfw/housekeeping/HousekeepingSetPacket.h @@ -1,59 +1,60 @@ #ifndef FSFW_HOUSEKEEPING_HOUSEKEEPINGSETPACKET_H_ #define FSFW_HOUSEKEEPING_HOUSEKEEPINGSETPACKET_H_ +#include "../datapoollocal/LocalPoolDataSetBase.h" #include "../housekeeping/HousekeepingMessage.h" #include "../serialize/SerialLinkedListAdapter.h" -#include "../datapoollocal/LocalPoolDataSetBase.h" -class HousekeepingSetPacket: public SerialLinkedListAdapter { -public: - HousekeepingSetPacket(sid_t sid, bool reportingEnabled, bool valid, - float collectionInterval, LocalPoolDataSetBase* dataSetPtr): - objectId(sid.objectId), setId(sid.ownerSetId), - reportingEnabled(reportingEnabled), valid(valid), - collectionIntervalSeconds(collectionInterval), dataSet(dataSetPtr) { - setLinks(); - } +class HousekeepingSetPacket : public SerialLinkedListAdapter { + public: + HousekeepingSetPacket(sid_t sid, bool reportingEnabled, bool valid, float collectionInterval, + LocalPoolDataSetBase* dataSetPtr) + : objectId(sid.objectId), + setId(sid.ownerSetId), + reportingEnabled(reportingEnabled), + valid(valid), + collectionIntervalSeconds(collectionInterval), + dataSet(dataSetPtr) { + setLinks(); + } - ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const override { - ReturnValue_t result = SerialLinkedListAdapter::serialize(buffer, size, - maxSize, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return dataSet->serializeLocalPoolIds(buffer, size ,maxSize, - streamEndianness); - } + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override { + ReturnValue_t result = + SerialLinkedListAdapter::serialize(buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return dataSet->serializeLocalPoolIds(buffer, size, maxSize, streamEndianness); + } - size_t getSerializedSize() const override { - size_t linkedSize = SerialLinkedListAdapter::getSerializedSize(); - linkedSize += dataSet->getLocalPoolIdsSerializedSize(); - return linkedSize; - } + size_t getSerializedSize() const override { + size_t linkedSize = SerialLinkedListAdapter::getSerializedSize(); + linkedSize += dataSet->getLocalPoolIdsSerializedSize(); + return linkedSize; + } - ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) override { - return HasReturnvaluesIF::RETURN_OK; - } + ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + Endianness streamEndianness) override { + return HasReturnvaluesIF::RETURN_OK; + } -private: + private: + void setLinks() { + setStart(&objectId); + objectId.setNext(&setId); + setId.setNext(&reportingEnabled); + reportingEnabled.setNext(&valid); + valid.setNext(&collectionIntervalSeconds); + collectionIntervalSeconds.setEnd(); + } - void setLinks() { - setStart(&objectId); - objectId.setNext(&setId); - setId.setNext(&reportingEnabled); - reportingEnabled.setNext(&valid); - valid.setNext(&collectionIntervalSeconds); - collectionIntervalSeconds.setEnd(); - } - - SerializeElement objectId; - SerializeElement setId; - SerializeElement reportingEnabled; - SerializeElement valid; - SerializeElement collectionIntervalSeconds; - LocalPoolDataSetBase* dataSet; + SerializeElement objectId; + SerializeElement setId; + SerializeElement reportingEnabled; + SerializeElement valid; + SerializeElement collectionIntervalSeconds; + LocalPoolDataSetBase* dataSet; }; #endif /* FSFW_HOUSEKEEPING_HOUSEKEEPINGSETPACKET_H_ */ diff --git a/src/fsfw/housekeeping/HousekeepingSnapshot.h b/src/fsfw/housekeeping/HousekeepingSnapshot.h index 45b40d37..c3eabe80 100644 --- a/src/fsfw/housekeeping/HousekeepingSnapshot.h +++ b/src/fsfw/housekeeping/HousekeepingSnapshot.h @@ -1,117 +1,111 @@ #ifndef FSFW_HOUSEKEEPING_HOUSEKEEPINGSNAPSHOT_H_ #define FSFW_HOUSEKEEPING_HOUSEKEEPINGSNAPSHOT_H_ -#include "../serialize/SerialBufferAdapter.h" -#include "../serialize/SerialLinkedListAdapter.h" #include "../datapoollocal/LocalPoolDataSetBase.h" #include "../datapoollocal/LocalPoolObjectBase.h" +#include "../serialize/SerialBufferAdapter.h" +#include "../serialize/SerialLinkedListAdapter.h" #include "../timemanager/CCSDSTime.h" /** * @brief This helper class will be used to serialize and deserialize update housekeeping packets * into the store. */ -class HousekeepingSnapshot: - public SerializeIF { -public: +class HousekeepingSnapshot : public SerializeIF { + public: + /** + * Update packet constructor for datasets. + * @param cdsShort If a CSD short timestamp is used, a reference should be + * supplied here + * @param dataSetPtr Pointer to the dataset instance to serialize or deserialize the + * data into + */ + HousekeepingSnapshot(CCSDSTime::CDS_short* cdsShort, LocalPoolDataSetBase* dataSetPtr) + : timeStamp(reinterpret_cast(cdsShort)), + timeStampSize(sizeof(CCSDSTime::CDS_short)), + updateData(dataSetPtr){}; - /** - * Update packet constructor for datasets. - * @param cdsShort If a CSD short timestamp is used, a reference should be - * supplied here - * @param dataSetPtr Pointer to the dataset instance to serialize or deserialize the - * data into - */ - HousekeepingSnapshot(CCSDSTime::CDS_short* cdsShort, LocalPoolDataSetBase* dataSetPtr): - timeStamp(reinterpret_cast(cdsShort)), - timeStampSize(sizeof(CCSDSTime::CDS_short)), updateData(dataSetPtr) {}; + /** + * Update packet constructor for datasets. + * @param timeStamp Pointer to the buffer where the timestamp will be stored. + * @param timeStampSize Size of the timestamp + * @param dataSetPtr Pointer to the dataset instance to deserialize the data into + */ + HousekeepingSnapshot(uint8_t* timeStamp, size_t timeStampSize, LocalPoolDataSetBase* dataSetPtr) + : timeStamp(timeStamp), timeStampSize(timeStampSize), updateData(dataSetPtr){}; - /** - * Update packet constructor for datasets. - * @param timeStamp Pointer to the buffer where the timestamp will be stored. - * @param timeStampSize Size of the timestamp - * @param dataSetPtr Pointer to the dataset instance to deserialize the data into - */ - HousekeepingSnapshot(uint8_t* timeStamp, size_t timeStampSize, - LocalPoolDataSetBase* dataSetPtr): - timeStamp(timeStamp), timeStampSize(timeStampSize), - updateData(dataSetPtr) {}; + /** + * Update packet constructor for pool variables. + * @param timeStamp + * @param timeStampSize + * @param dataSetPtr + */ + HousekeepingSnapshot(CCSDSTime::CDS_short* cdsShort, LocalPoolObjectBase* dataSetPtr) + : timeStamp(reinterpret_cast(cdsShort)), + timeStampSize(sizeof(CCSDSTime::CDS_short)), + updateData(dataSetPtr){}; - /** - * Update packet constructor for pool variables. - * @param timeStamp - * @param timeStampSize - * @param dataSetPtr - */ - HousekeepingSnapshot(CCSDSTime::CDS_short* cdsShort, LocalPoolObjectBase* dataSetPtr): - timeStamp(reinterpret_cast(cdsShort)), - timeStampSize(sizeof(CCSDSTime::CDS_short)), updateData(dataSetPtr) {}; + /** + * Update packet constructor for pool variables. + * @param timeStamp + * @param timeStampSize + * @param dataSetPtr + */ + HousekeepingSnapshot(uint8_t* timeStamp, size_t timeStampSize, LocalPoolObjectBase* dataSetPtr) + : timeStamp(timeStamp), timeStampSize(timeStampSize), updateData(dataSetPtr){}; - - /** - * Update packet constructor for pool variables. - * @param timeStamp - * @param timeStampSize - * @param dataSetPtr - */ - HousekeepingSnapshot(uint8_t* timeStamp, size_t timeStampSize, - LocalPoolObjectBase* dataSetPtr): - timeStamp(timeStamp), timeStampSize(timeStampSize), - updateData(dataSetPtr) {}; - - virtual ReturnValue_t serialize(uint8_t **buffer, size_t *size, size_t maxSize, - Endianness streamEndianness) const { - if(timeStamp != nullptr) { - /* Endianness will always be MACHINE, so we can simply use memcpy - here. */ - std::memcpy(*buffer, timeStamp, timeStampSize); - *size += timeStampSize; - *buffer += timeStampSize; - } - if(updateData == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - - return updateData->serialize(buffer, size, maxSize, streamEndianness); + virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const { + if (timeStamp != nullptr) { + /* Endianness will always be MACHINE, so we can simply use memcpy + here. */ + std::memcpy(*buffer, timeStamp, timeStampSize); + *size += timeStampSize; + *buffer += timeStampSize; + } + if (updateData == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; } - virtual size_t getSerializedSize() const { - if(updateData == nullptr) { - return 0; - } - return timeStampSize + updateData->getSerializedSize(); + return updateData->serialize(buffer, size, maxSize, streamEndianness); + } + + virtual size_t getSerializedSize() const { + if (updateData == nullptr) { + return 0; + } + return timeStampSize + updateData->getSerializedSize(); + } + + virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + SerializeIF::Endianness streamEndianness) override { + if (*size < timeStampSize) { + return SerializeIF::STREAM_TOO_SHORT; } - virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - SerializeIF::Endianness streamEndianness) override { - if(*size < timeStampSize) { - return SerializeIF::STREAM_TOO_SHORT; - } - - if(timeStamp != nullptr) { - /* Endianness will always be MACHINE, so we can simply use memcpy - here. */ - std::memcpy(timeStamp, *buffer, timeStampSize); - *size -= timeStampSize; - *buffer += timeStampSize; - } - - if(updateData == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - if(*size < updateData->getSerializedSize()) { - return SerializeIF::STREAM_TOO_SHORT; - } - - return updateData->deSerialize(buffer, size, streamEndianness); + if (timeStamp != nullptr) { + /* Endianness will always be MACHINE, so we can simply use memcpy + here. */ + std::memcpy(timeStamp, *buffer, timeStampSize); + *size -= timeStampSize; + *buffer += timeStampSize; } -private: - uint8_t* timeStamp = nullptr; - size_t timeStampSize = 0; + if (updateData == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if (*size < updateData->getSerializedSize()) { + return SerializeIF::STREAM_TOO_SHORT; + } - SerializeIF* updateData = nullptr; + return updateData->deSerialize(buffer, size, streamEndianness); + } + + private: + uint8_t* timeStamp = nullptr; + size_t timeStampSize = 0; + + SerializeIF* updateData = nullptr; }; - #endif /* FSFW_HOUSEKEEPING_HOUSEKEEPINGSNAPSHOT_H_ */ diff --git a/src/fsfw/housekeeping/PeriodicHousekeepingHelper.cpp b/src/fsfw/housekeeping/PeriodicHousekeepingHelper.cpp index 68740d33..0c2bef96 100644 --- a/src/fsfw/housekeeping/PeriodicHousekeepingHelper.cpp +++ b/src/fsfw/housekeeping/PeriodicHousekeepingHelper.cpp @@ -1,90 +1,87 @@ #include "fsfw/housekeeping/PeriodicHousekeepingHelper.h" -#include "fsfw/datapoollocal/LocalPoolDataSetBase.h" #include -PeriodicHousekeepingHelper::PeriodicHousekeepingHelper( - LocalPoolDataSetBase* owner): owner(owner) {} +#include "fsfw/datapoollocal/LocalPoolDataSetBase.h" + +PeriodicHousekeepingHelper::PeriodicHousekeepingHelper(LocalPoolDataSetBase* owner) + : owner(owner) {} void PeriodicHousekeepingHelper::initialize(float collectionInterval, - dur_millis_t minimumPeriodicInterval, uint8_t nonDiagIntervalFactor) { - this->minimumPeriodicInterval = minimumPeriodicInterval; - this->nonDiagIntervalFactor = nonDiagIntervalFactor; - collectionIntervalTicks = intervalSecondsToIntervalTicks(collectionInterval); - /* 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. */ - internalTickCounter = collectionIntervalTicks; + dur_millis_t minimumPeriodicInterval, + uint8_t nonDiagIntervalFactor) { + this->minimumPeriodicInterval = minimumPeriodicInterval; + this->nonDiagIntervalFactor = nonDiagIntervalFactor; + collectionIntervalTicks = intervalSecondsToIntervalTicks(collectionInterval); + /* 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. */ + internalTickCounter = collectionIntervalTicks; } float PeriodicHousekeepingHelper::getCollectionIntervalInSeconds() const { - return intervalTicksToSeconds(collectionIntervalTicks); + return intervalTicksToSeconds(collectionIntervalTicks); } bool PeriodicHousekeepingHelper::checkOpNecessary() { - if(internalTickCounter >= collectionIntervalTicks) { - internalTickCounter = 1; - return true; - } - internalTickCounter++; - return false; + if (internalTickCounter >= collectionIntervalTicks) { + internalTickCounter = 1; + return true; + } + internalTickCounter++; + return false; } uint32_t PeriodicHousekeepingHelper::intervalSecondsToIntervalTicks( - float collectionIntervalSeconds) { - if(owner == nullptr) { - return 0; + float collectionIntervalSeconds) { + if (owner == nullptr) { + return 0; + } + bool isDiagnostics = owner->isDiagnostics(); + + /* Avoid division by zero */ + if (minimumPeriodicInterval == 0) { + if (isDiagnostics) { + /* Perform operation each cycle */ + return 1; + } else { + return nonDiagIntervalFactor; } - bool isDiagnostics = owner->isDiagnostics(); - - /* Avoid division by zero */ - if(minimumPeriodicInterval == 0) { - if(isDiagnostics) { - /* Perform operation each cycle */ - return 1; - } - else { - return nonDiagIntervalFactor; - } + } else { + dur_millis_t intervalInMs = collectionIntervalSeconds * 1000; + 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; } - else { - dur_millis_t intervalInMs = collectionIntervalSeconds * 1000; - 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(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. + uint32_t ticks = std::ceil(static_cast(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. + 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. + 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; + 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; + } } -float PeriodicHousekeepingHelper::intervalTicksToSeconds( - uint32_t collectionInterval) const { - /* Number of ticks times the minimum interval is in milliseconds, so we divide by 1000 to get - the value in seconds */ - return static_cast(collectionInterval * minimumPeriodicInterval / 1000.0); +float PeriodicHousekeepingHelper::intervalTicksToSeconds(uint32_t collectionInterval) const { + /* Number of ticks times the minimum interval is in milliseconds, so we divide by 1000 to get + the value in seconds */ + return static_cast(collectionInterval * minimumPeriodicInterval / 1000.0); } -void PeriodicHousekeepingHelper::changeCollectionInterval( - float newIntervalSeconds) { - collectionIntervalTicks = intervalSecondsToIntervalTicks(newIntervalSeconds); +void PeriodicHousekeepingHelper::changeCollectionInterval(float newIntervalSeconds) { + collectionIntervalTicks = intervalSecondsToIntervalTicks(newIntervalSeconds); } - diff --git a/src/fsfw/housekeeping/PeriodicHousekeepingHelper.h b/src/fsfw/housekeeping/PeriodicHousekeepingHelper.h index 4e93308b..8b6245ba 100644 --- a/src/fsfw/housekeeping/PeriodicHousekeepingHelper.h +++ b/src/fsfw/housekeeping/PeriodicHousekeepingHelper.h @@ -1,33 +1,33 @@ #ifndef FSFW_HOUSEKEEPING_PERIODICHOUSEKEEPINGHELPER_H_ #define FSFW_HOUSEKEEPING_PERIODICHOUSEKEEPINGHELPER_H_ -#include "fsfw/timemanager/Clock.h" #include +#include "fsfw/timemanager/Clock.h" + class LocalPoolDataSetBase; class PeriodicHousekeepingHelper { -public: - PeriodicHousekeepingHelper(LocalPoolDataSetBase* owner); + public: + PeriodicHousekeepingHelper(LocalPoolDataSetBase* owner); - void initialize(float collectionInterval, dur_millis_t minimumPeriodicInterval, - uint8_t nonDiagIntervalFactor); + void initialize(float collectionInterval, dur_millis_t minimumPeriodicInterval, + uint8_t nonDiagIntervalFactor); - void changeCollectionInterval(float newInterval); - float getCollectionIntervalInSeconds() const; - bool checkOpNecessary(); + void changeCollectionInterval(float newInterval); + float getCollectionIntervalInSeconds() const; + bool checkOpNecessary(); -private: - LocalPoolDataSetBase* owner = nullptr; - uint8_t nonDiagIntervalFactor = 0; + private: + LocalPoolDataSetBase* owner = nullptr; + uint8_t nonDiagIntervalFactor = 0; - uint32_t intervalSecondsToIntervalTicks(float collectionIntervalSeconds); - float intervalTicksToSeconds(uint32_t collectionInterval) const; - - dur_millis_t minimumPeriodicInterval = 0; - uint32_t internalTickCounter = 1; - uint32_t collectionIntervalTicks = 0; + uint32_t intervalSecondsToIntervalTicks(float collectionIntervalSeconds); + float intervalTicksToSeconds(uint32_t collectionInterval) const; + dur_millis_t minimumPeriodicInterval = 0; + uint32_t internalTickCounter = 1; + uint32_t collectionIntervalTicks = 0; }; #endif /* FSFW_HOUSEKEEPING_PERIODICHOUSEKEEPINGHELPER_H_ */ diff --git a/src/fsfw/internalerror/InternalErrorDataset.h b/src/fsfw/internalerror/InternalErrorDataset.h index bd9062ed..022cdedb 100644 --- a/src/fsfw/internalerror/InternalErrorDataset.h +++ b/src/fsfw/internalerror/InternalErrorDataset.h @@ -1,34 +1,22 @@ #ifndef FSFW_INTERNALERROR_INTERNALERRORDATASET_H_ #define FSFW_INTERNALERROR_INTERNALERRORDATASET_H_ -#include #include +#include -enum errorPoolIds { - TM_HITS, - QUEUE_HITS, - STORE_HITS +enum errorPoolIds { TM_HITS, QUEUE_HITS, STORE_HITS }; + +class InternalErrorDataset : public StaticLocalDataSet<3 * sizeof(uint32_t)> { + public: + static constexpr uint8_t ERROR_SET_ID = 0; + + InternalErrorDataset(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, ERROR_SET_ID) {} + + InternalErrorDataset(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, ERROR_SET_ID)) {} + + lp_var_t tmHits = lp_var_t(sid.objectId, TM_HITS, this); + lp_var_t queueHits = lp_var_t(sid.objectId, QUEUE_HITS, this); + lp_var_t storeHits = lp_var_t(sid.objectId, STORE_HITS, this); }; - -class InternalErrorDataset: public StaticLocalDataSet<3 * sizeof(uint32_t)> { -public: - static constexpr uint8_t ERROR_SET_ID = 0; - - InternalErrorDataset(HasLocalDataPoolIF* owner): - StaticLocalDataSet(owner, ERROR_SET_ID) {} - - InternalErrorDataset(object_id_t objectId): - StaticLocalDataSet(sid_t(objectId , ERROR_SET_ID)) {} - - lp_var_t tmHits = lp_var_t(sid.objectId, - TM_HITS, this); - lp_var_t queueHits = lp_var_t(sid.objectId, - QUEUE_HITS, this); - lp_var_t storeHits = lp_var_t(sid.objectId, - STORE_HITS, this); -}; - - - #endif /* FSFW_INTERNALERROR_INTERNALERRORDATASET_H_ */ diff --git a/src/fsfw/internalerror/InternalErrorReporter.cpp b/src/fsfw/internalerror/InternalErrorReporter.cpp index 8689ab3e..e7088e2c 100644 --- a/src/fsfw/internalerror/InternalErrorReporter.cpp +++ b/src/fsfw/internalerror/InternalErrorReporter.cpp @@ -1,202 +1,186 @@ #include "fsfw/internalerror/InternalErrorReporter.h" -#include "fsfw/ipc/QueueFactory.h" -#include "fsfw/ipc/MutexFactory.h" -#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/datapool/PoolReadGuard.h" +#include "fsfw/ipc/MutexFactory.h" +#include "fsfw/ipc/QueueFactory.h" +#include "fsfw/serviceinterface/ServiceInterface.h" -InternalErrorReporter::InternalErrorReporter(object_id_t setObjectId, - uint32_t messageQueueDepth): SystemObject(setObjectId), - commandQueue(QueueFactory::instance()-> - createMessageQueue(messageQueueDepth)), - poolManager(this, commandQueue), - internalErrorSid(setObjectId, InternalErrorDataset::ERROR_SET_ID), - internalErrorDataset(this) { - mutex = MutexFactory::instance()->createMutex(); +InternalErrorReporter::InternalErrorReporter(object_id_t setObjectId, uint32_t messageQueueDepth) + : SystemObject(setObjectId), + commandQueue(QueueFactory::instance()->createMessageQueue(messageQueueDepth)), + poolManager(this, commandQueue), + internalErrorSid(setObjectId, InternalErrorDataset::ERROR_SET_ID), + internalErrorDataset(this) { + mutex = MutexFactory::instance()->createMutex(); } -InternalErrorReporter::~InternalErrorReporter() { - MutexFactory::instance()->deleteMutex(mutex); -} +InternalErrorReporter::~InternalErrorReporter() { MutexFactory::instance()->deleteMutex(mutex); } void InternalErrorReporter::setDiagnosticPrintout(bool enable) { - this->diagnosticPrintout = enable; + this->diagnosticPrintout = enable; } ReturnValue_t InternalErrorReporter::performOperation(uint8_t opCode) { - CommandMessage message; - ReturnValue_t result = commandQueue->receiveMessage(&message); - if(result != MessageQueueIF::EMPTY) { - poolManager.handleHousekeepingMessage(&message); - } + CommandMessage message; + ReturnValue_t result = commandQueue->receiveMessage(&message); + if (result != MessageQueueIF::EMPTY) { + poolManager.handleHousekeepingMessage(&message); + } - uint32_t newQueueHits = getAndResetQueueHits(); - uint32_t newTmHits = getAndResetTmHits(); - uint32_t newStoreHits = getAndResetStoreHits(); + uint32_t newQueueHits = getAndResetQueueHits(); + uint32_t newTmHits = getAndResetTmHits(); + uint32_t newStoreHits = getAndResetStoreHits(); #if FSFW_VERBOSE_LEVEL >= 1 - if(diagnosticPrintout) { - if((newQueueHits > 0) or (newTmHits > 0) or (newStoreHits > 0)) { + if (diagnosticPrintout) { + if ((newQueueHits > 0) or (newTmHits > 0) or (newStoreHits > 0)) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "InternalErrorReporter::performOperation: Errors " - << "occured!" << std::endl; - sif::debug << "Queue errors: " << newQueueHits << std::endl; - sif::debug << "TM errors: " << newTmHits << std::endl; - sif::debug << "Store errors: " << newStoreHits << std::endl; + sif::debug << "InternalErrorReporter::performOperation: Errors " + << "occured!" << std::endl; + sif::debug << "Queue errors: " << newQueueHits << std::endl; + sif::debug << "TM errors: " << newTmHits << std::endl; + sif::debug << "Store errors: " << newStoreHits << std::endl; #else - sif::printDebug("InternalErrorReporter::performOperation: Errors occured!\n"); - sif::printDebug("Queue errors: %lu\n", static_cast(newQueueHits)); - sif::printDebug("TM errors: %lu\n", static_cast(newTmHits)); - sif::printDebug("Store errors: %lu\n", static_cast(newStoreHits)); + sif::printDebug("InternalErrorReporter::performOperation: Errors occured!\n"); + sif::printDebug("Queue errors: %lu\n", static_cast(newQueueHits)); + sif::printDebug("TM errors: %lu\n", static_cast(newTmHits)); + sif::printDebug("Store errors: %lu\n", static_cast(newStoreHits)); #endif - } } + } #endif - { - PoolReadGuard readGuard(&internalErrorDataset); - if(readGuard.getReadResult() == HasReturnvaluesIF::RETURN_OK) { - internalErrorDataset.queueHits.value += newQueueHits; - internalErrorDataset.storeHits.value += newStoreHits; - internalErrorDataset.tmHits.value += newTmHits; - internalErrorDataset.setValidity(true, true); - } + { + PoolReadGuard readGuard(&internalErrorDataset); + if (readGuard.getReadResult() == HasReturnvaluesIF::RETURN_OK) { + internalErrorDataset.queueHits.value += newQueueHits; + internalErrorDataset.storeHits.value += newStoreHits; + internalErrorDataset.tmHits.value += newTmHits; + internalErrorDataset.setValidity(true, true); } + } - poolManager.performHkOperation(); - return HasReturnvaluesIF::RETURN_OK; + poolManager.performHkOperation(); + return HasReturnvaluesIF::RETURN_OK; } -void InternalErrorReporter::queueMessageNotSent() { - incrementQueueHits(); -} +void InternalErrorReporter::queueMessageNotSent() { incrementQueueHits(); } -void InternalErrorReporter::lostTm() { - incrementTmHits(); -} +void InternalErrorReporter::lostTm() { incrementTmHits(); } uint32_t InternalErrorReporter::getAndResetQueueHits() { - uint32_t value; - mutex->lockMutex(timeoutType, timeoutMs); - value = queueHits; - queueHits = 0; - mutex->unlockMutex(); - return value; + uint32_t value; + mutex->lockMutex(timeoutType, timeoutMs); + value = queueHits; + queueHits = 0; + mutex->unlockMutex(); + return value; } uint32_t InternalErrorReporter::getQueueHits() { - uint32_t value; - mutex->lockMutex(timeoutType, timeoutMs); - value = queueHits; - mutex->unlockMutex(); - return value; + uint32_t value; + mutex->lockMutex(timeoutType, timeoutMs); + value = queueHits; + mutex->unlockMutex(); + return value; } void InternalErrorReporter::incrementQueueHits() { - mutex->lockMutex(timeoutType, timeoutMs); - queueHits++; - mutex->unlockMutex(); + mutex->lockMutex(timeoutType, timeoutMs); + queueHits++; + mutex->unlockMutex(); } uint32_t InternalErrorReporter::getAndResetTmHits() { - uint32_t value; - mutex->lockMutex(timeoutType, timeoutMs); - value = tmHits; - tmHits = 0; - mutex->unlockMutex(); - return value; + uint32_t value; + mutex->lockMutex(timeoutType, timeoutMs); + value = tmHits; + tmHits = 0; + mutex->unlockMutex(); + return value; } uint32_t InternalErrorReporter::getTmHits() { - uint32_t value; - mutex->lockMutex(timeoutType, timeoutMs); - value = tmHits; - mutex->unlockMutex(); - return value; + uint32_t value; + mutex->lockMutex(timeoutType, timeoutMs); + value = tmHits; + mutex->unlockMutex(); + return value; } void InternalErrorReporter::incrementTmHits() { - mutex->lockMutex(timeoutType, timeoutMs); - tmHits++; - mutex->unlockMutex(); + mutex->lockMutex(timeoutType, timeoutMs); + tmHits++; + mutex->unlockMutex(); } -void InternalErrorReporter::storeFull() { - incrementStoreHits(); -} +void InternalErrorReporter::storeFull() { incrementStoreHits(); } uint32_t InternalErrorReporter::getAndResetStoreHits() { - uint32_t value; - mutex->lockMutex(timeoutType, timeoutMs); - value = storeHits; - storeHits = 0; - mutex->unlockMutex(); - return value; + uint32_t value; + mutex->lockMutex(timeoutType, timeoutMs); + value = storeHits; + storeHits = 0; + mutex->unlockMutex(); + return value; } uint32_t InternalErrorReporter::getStoreHits() { - uint32_t value; - mutex->lockMutex(timeoutType, timeoutMs); - value = storeHits; - mutex->unlockMutex(); - return value; + uint32_t value; + mutex->lockMutex(timeoutType, timeoutMs); + value = storeHits; + mutex->unlockMutex(); + return value; } void InternalErrorReporter::incrementStoreHits() { - mutex->lockMutex(timeoutType, timeoutMs); - storeHits++; - mutex->unlockMutex(); + mutex->lockMutex(timeoutType, timeoutMs); + storeHits++; + mutex->unlockMutex(); } -object_id_t InternalErrorReporter::getObjectId() const { - return SystemObject::getObjectId(); -} +object_id_t InternalErrorReporter::getObjectId() const { return SystemObject::getObjectId(); } MessageQueueId_t InternalErrorReporter::getCommandQueue() const { - return this->commandQueue->getId(); + return this->commandQueue->getId(); } -ReturnValue_t InternalErrorReporter::initializeLocalDataPool( - localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { - localDataPoolMap.emplace(errorPoolIds::TM_HITS, new PoolEntry()); - localDataPoolMap.emplace(errorPoolIds::QUEUE_HITS, new PoolEntry()); - localDataPoolMap.emplace(errorPoolIds::STORE_HITS, new PoolEntry()); - poolManager.subscribeForPeriodicPacket(internalErrorSid, false, getPeriodicOperationFrequency(), - true); - internalErrorDataset.setValidity(true, true); - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t InternalErrorReporter::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) { + localDataPoolMap.emplace(errorPoolIds::TM_HITS, new PoolEntry()); + localDataPoolMap.emplace(errorPoolIds::QUEUE_HITS, new PoolEntry()); + localDataPoolMap.emplace(errorPoolIds::STORE_HITS, new PoolEntry()); + poolManager.subscribeForPeriodicPacket(internalErrorSid, false, getPeriodicOperationFrequency(), + true); + internalErrorDataset.setValidity(true, true); + return HasReturnvaluesIF::RETURN_OK; } dur_millis_t InternalErrorReporter::getPeriodicOperationFrequency() const { - return this->executingTask->getPeriodMs(); + return this->executingTask->getPeriodMs(); } -LocalPoolDataSetBase* InternalErrorReporter::getDataSetHandle(sid_t sid) { - return &internalErrorDataset; +LocalPoolDataSetBase *InternalErrorReporter::getDataSetHandle(sid_t sid) { + return &internalErrorDataset; } -void InternalErrorReporter::setTaskIF(PeriodicTaskIF *task) { - this->executingTask = task; -} +void InternalErrorReporter::setTaskIF(PeriodicTaskIF *task) { this->executingTask = task; } ReturnValue_t InternalErrorReporter::initialize() { - ReturnValue_t result = poolManager.initialize(commandQueue); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return SystemObject::initialize(); + ReturnValue_t result = poolManager.initialize(commandQueue); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return SystemObject::initialize(); } ReturnValue_t InternalErrorReporter::initializeAfterTaskCreation() { - return poolManager.initializeAfterTaskCreation(); + return poolManager.initializeAfterTaskCreation(); } -void InternalErrorReporter::setMutexTimeout(MutexIF::TimeoutType timeoutType, - uint32_t timeoutMs) { - this->timeoutType = timeoutType; - this->timeoutMs = timeoutMs; +void InternalErrorReporter::setMutexTimeout(MutexIF::TimeoutType timeoutType, uint32_t timeoutMs) { + this->timeoutType = timeoutType; + this->timeoutMs = timeoutMs; } -LocalDataPoolManager* InternalErrorReporter::getHkManagerHandle() { - return &poolManager; -} +LocalDataPoolManager *InternalErrorReporter::getHkManagerHandle() { return &poolManager; } diff --git a/src/fsfw/internalerror/InternalErrorReporter.h b/src/fsfw/internalerror/InternalErrorReporter.h index 57a6a135..98711139 100644 --- a/src/fsfw/internalerror/InternalErrorReporter.h +++ b/src/fsfw/internalerror/InternalErrorReporter.h @@ -2,13 +2,12 @@ #define FSFW_INTERNALERROR_INTERNALERRORREPORTER_H_ #include "InternalErrorReporterIF.h" - -#include "fsfw/tasks/PeriodicTaskIF.h" -#include "fsfw/internalerror/InternalErrorDataset.h" #include "fsfw/datapoollocal/LocalDataPoolManager.h" -#include "fsfw/tasks/ExecutableObjectIF.h" -#include "fsfw/objectmanager/SystemObject.h" +#include "fsfw/internalerror/InternalErrorDataset.h" #include "fsfw/ipc/MutexIF.h" +#include "fsfw/objectmanager/SystemObject.h" +#include "fsfw/tasks/ExecutableObjectIF.h" +#include "fsfw/tasks/PeriodicTaskIF.h" /** * @brief This class is used to track internal errors like lost telemetry, @@ -17,79 +16,74 @@ * All functions were kept virtual so this class can be extended easily * to store custom internal errors (e.g. communication interface errors). */ -class InternalErrorReporter: - public SystemObject, - public ExecutableObjectIF, - public InternalErrorReporterIF, - public HasLocalDataPoolIF { -public: +class InternalErrorReporter : public SystemObject, + public ExecutableObjectIF, + public InternalErrorReporterIF, + public HasLocalDataPoolIF { + public: + InternalErrorReporter(object_id_t setObjectId, uint32_t messageQueueDepth = 5); - InternalErrorReporter(object_id_t setObjectId, - uint32_t messageQueueDepth = 5); + /** + * Enable diagnostic printout. Please note that this feature will + * only work if DEBUG has been supplied to the build defines. + * @param enable + */ + void setDiagnosticPrintout(bool enable); - /** - * Enable diagnostic printout. Please note that this feature will - * only work if DEBUG has been supplied to the build defines. - * @param enable - */ - void setDiagnosticPrintout(bool enable); + void setMutexTimeout(MutexIF::TimeoutType timeoutType, uint32_t timeoutMs); - void setMutexTimeout(MutexIF::TimeoutType timeoutType, - uint32_t timeoutMs); + virtual ~InternalErrorReporter(); - virtual ~InternalErrorReporter(); + virtual object_id_t getObjectId() const override; + virtual MessageQueueId_t getCommandQueue() const override; + virtual ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) override; + virtual dur_millis_t getPeriodicOperationFrequency() const override; + virtual LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override; + LocalDataPoolManager* getHkManagerHandle() override; - virtual object_id_t getObjectId() const override; - virtual MessageQueueId_t getCommandQueue() const override; - virtual ReturnValue_t initializeLocalDataPool( - localpool::DataPool& localDataPoolMap, - LocalDataPoolManager& poolManager) override; - virtual dur_millis_t getPeriodicOperationFrequency() const override; - virtual LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override; - LocalDataPoolManager* getHkManagerHandle() override; + virtual ReturnValue_t initialize() override; + virtual ReturnValue_t initializeAfterTaskCreation() override; + virtual ReturnValue_t performOperation(uint8_t opCode) override; - virtual ReturnValue_t initialize() override; - virtual ReturnValue_t initializeAfterTaskCreation() override; - virtual ReturnValue_t performOperation(uint8_t opCode) override; + virtual void queueMessageNotSent(); - virtual void queueMessageNotSent(); + virtual void lostTm(); - virtual void lostTm(); + virtual void storeFull(); - virtual void storeFull(); + virtual void setTaskIF(PeriodicTaskIF* task) override; - virtual void setTaskIF(PeriodicTaskIF* task) override; -protected: - MessageQueueIF* commandQueue; - LocalDataPoolManager poolManager; + protected: + MessageQueueIF* commandQueue; + LocalDataPoolManager poolManager; - PeriodicTaskIF* executingTask = nullptr; + PeriodicTaskIF* executingTask = nullptr; - MutexIF* mutex = nullptr; - MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING; - uint32_t timeoutMs = 20; + MutexIF* mutex = nullptr; + MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING; + uint32_t timeoutMs = 20; - sid_t internalErrorSid; - InternalErrorDataset internalErrorDataset; + sid_t internalErrorSid; + InternalErrorDataset internalErrorDataset; - bool diagnosticPrintout = true; + bool diagnosticPrintout = true; - uint32_t queueHits = 0; - uint32_t tmHits = 0; - uint32_t storeHits = 0; + uint32_t queueHits = 0; + uint32_t tmHits = 0; + uint32_t storeHits = 0; - uint32_t getAndResetQueueHits(); - uint32_t getQueueHits(); - void incrementQueueHits(); + uint32_t getAndResetQueueHits(); + uint32_t getQueueHits(); + void incrementQueueHits(); - uint32_t getAndResetTmHits(); - uint32_t getTmHits(); - void incrementTmHits(); - - uint32_t getAndResetStoreHits(); - uint32_t getStoreHits(); - void incrementStoreHits(); + uint32_t getAndResetTmHits(); + uint32_t getTmHits(); + void incrementTmHits(); + uint32_t getAndResetStoreHits(); + uint32_t getStoreHits(); + void incrementStoreHits(); }; #endif /* FSFW_INTERNALERROR_INTERNALERRORREPORTER_H_ */ diff --git a/src/fsfw/internalerror/InternalErrorReporterIF.h b/src/fsfw/internalerror/InternalErrorReporterIF.h index 3484c18f..9eb8e7d7 100644 --- a/src/fsfw/internalerror/InternalErrorReporterIF.h +++ b/src/fsfw/internalerror/InternalErrorReporterIF.h @@ -2,26 +2,23 @@ #define INTERNALERRORREPORTERIF_H_ class InternalErrorReporterIF { -public: - virtual ~InternalErrorReporterIF() { - } + public: + virtual ~InternalErrorReporterIF() {} - /** - * Thread safe - */ - virtual void queueMessageNotSent() = 0; - - /** - * Thread safe - */ - virtual void lostTm() = 0; - - /** - * Thread safe - */ - virtual void storeFull() = 0; + /** + * Thread safe + */ + virtual void queueMessageNotSent() = 0; + /** + * Thread safe + */ + virtual void lostTm() = 0; + /** + * Thread safe + */ + virtual void storeFull() = 0; }; #endif /* INTERNALERRORREPORTERIF_H_ */ diff --git a/src/fsfw/ipc/CommandMessage.cpp b/src/fsfw/ipc/CommandMessage.cpp index 9448d152..d6d214df 100644 --- a/src/fsfw/ipc/CommandMessage.cpp +++ b/src/fsfw/ipc/CommandMessage.cpp @@ -1,112 +1,96 @@ #include "fsfw/ipc/CommandMessage.h" -#include "fsfw/ipc/CommandMessageCleaner.h" #include +#include "fsfw/ipc/CommandMessageCleaner.h" + CommandMessage::CommandMessage() { - MessageQueueMessage::setMessageSize(DEFAULT_COMMAND_MESSAGE_SIZE); - setCommand(CMD_NONE); + MessageQueueMessage::setMessageSize(DEFAULT_COMMAND_MESSAGE_SIZE); + setCommand(CMD_NONE); } -CommandMessage::CommandMessage(Command_t command, uint32_t parameter1, - uint32_t parameter2) { - MessageQueueMessage::setMessageSize(DEFAULT_COMMAND_MESSAGE_SIZE); - setCommand(command); - setParameter(parameter1); - setParameter2(parameter2); +CommandMessage::CommandMessage(Command_t command, uint32_t parameter1, uint32_t parameter2) { + MessageQueueMessage::setMessageSize(DEFAULT_COMMAND_MESSAGE_SIZE); + setCommand(command); + setParameter(parameter1); + setParameter2(parameter2); } Command_t CommandMessage::getCommand() const { - Command_t command; - std::memcpy(&command, MessageQueueMessage::getData(), sizeof(Command_t)); - return command; + Command_t command; + std::memcpy(&command, MessageQueueMessage::getData(), sizeof(Command_t)); + return command; } void CommandMessage::setCommand(Command_t command) { - std::memcpy(MessageQueueMessage::getData(), &command, sizeof(Command_t)); + std::memcpy(MessageQueueMessage::getData(), &command, sizeof(Command_t)); } uint8_t CommandMessage::getMessageType() const { - // first byte of command ID. - return getCommand() >> 8 & 0xff; + // first byte of command ID. + return getCommand() >> 8 & 0xff; } uint32_t CommandMessage::getParameter() const { - uint32_t parameter1; - std::memcpy(¶meter1, this->getData(), sizeof(parameter1)); - return parameter1; + uint32_t parameter1; + std::memcpy(¶meter1, this->getData(), sizeof(parameter1)); + return parameter1; } void CommandMessage::setParameter(uint32_t parameter1) { - std::memcpy(this->getData(), ¶meter1, sizeof(parameter1)); + std::memcpy(this->getData(), ¶meter1, sizeof(parameter1)); } uint32_t CommandMessage::getParameter2() const { - uint32_t parameter2; - std::memcpy(¶meter2, this->getData() + sizeof(uint32_t), - sizeof(parameter2)); - return parameter2; + uint32_t parameter2; + std::memcpy(¶meter2, this->getData() + sizeof(uint32_t), sizeof(parameter2)); + return parameter2; } void CommandMessage::setParameter2(uint32_t parameter2) { - std::memcpy(this->getData() + sizeof(uint32_t), ¶meter2, - sizeof(parameter2)); + std::memcpy(this->getData() + sizeof(uint32_t), ¶meter2, sizeof(parameter2)); } uint32_t CommandMessage::getParameter3() const { - uint32_t parameter3; - std::memcpy(¶meter3, this->getData() + 2 * sizeof(uint32_t), - sizeof(parameter3)); - return parameter3; + uint32_t parameter3; + std::memcpy(¶meter3, this->getData() + 2 * sizeof(uint32_t), sizeof(parameter3)); + return parameter3; } void CommandMessage::setParameter3(uint32_t parameter3) { - std::memcpy(this->getData() + 2 * sizeof(uint32_t), ¶meter3, - sizeof(parameter3)); + std::memcpy(this->getData() + 2 * sizeof(uint32_t), ¶meter3, sizeof(parameter3)); } -size_t CommandMessage::getMinimumMessageSize() const { - return MINIMUM_COMMAND_MESSAGE_SIZE; -} +size_t CommandMessage::getMinimumMessageSize() const { return MINIMUM_COMMAND_MESSAGE_SIZE; } -void CommandMessage::clearCommandMessage() { - clear(); -} +void CommandMessage::clearCommandMessage() { clear(); } -void CommandMessage::clear() { - CommandMessageCleaner::clearCommandMessage(this); -} +void CommandMessage::clear() { CommandMessageCleaner::clearCommandMessage(this); } -bool CommandMessage::isClearedCommandMessage() { - return getCommand() == CMD_NONE; -} +bool CommandMessage::isClearedCommandMessage() { return getCommand() == CMD_NONE; } void CommandMessage::setToUnknownCommand() { - Command_t initialCommand = getCommand(); - this->clear(); - setReplyRejected(UNKNOWN_COMMAND, initialCommand); + Command_t initialCommand = getCommand(); + this->clear(); + setReplyRejected(UNKNOWN_COMMAND, initialCommand); } -void CommandMessage::setReplyRejected(ReturnValue_t reason, - Command_t initialCommand) { - setCommand(REPLY_REJECTED); - setParameter(reason); - setParameter2(initialCommand); +void CommandMessage::setReplyRejected(ReturnValue_t reason, Command_t initialCommand) { + setCommand(REPLY_REJECTED); + setParameter(reason); + setParameter2(initialCommand); } -ReturnValue_t CommandMessage::getReplyRejectedReason( - Command_t *initialCommand) const { - ReturnValue_t reason = getParameter(); - if(initialCommand != nullptr) { - *initialCommand = getParameter2(); - } - return reason; +ReturnValue_t CommandMessage::getReplyRejectedReason(Command_t* initialCommand) const { + ReturnValue_t reason = getParameter(); + if (initialCommand != nullptr) { + *initialCommand = getParameter2(); + } + return reason; } -uint8_t* CommandMessage::getData() { - return MessageQueueMessage::getData() + sizeof(Command_t); -} +uint8_t* CommandMessage::getData() { return MessageQueueMessage::getData() + sizeof(Command_t); } const uint8_t* CommandMessage::getData() const { - return MessageQueueMessage::getData() + sizeof(Command_t); + return MessageQueueMessage::getData() + sizeof(Command_t); } diff --git a/src/fsfw/ipc/CommandMessage.h b/src/fsfw/ipc/CommandMessage.h index 28822dd0..1392c699 100644 --- a/src/fsfw/ipc/CommandMessage.h +++ b/src/fsfw/ipc/CommandMessage.h @@ -2,9 +2,8 @@ #define FSFW_IPC_COMMANDMESSAGE_H_ #include "CommandMessageIF.h" - -#include "MessageQueueMessage.h" #include "FwMessageTypes.h" +#include "MessageQueueMessage.h" /** * @brief Default command message used to pass command messages between tasks. @@ -21,111 +20,107 @@ * currently has an internal message size of 28 bytes. * @author Bastian Baetz */ -class CommandMessage: public MessageQueueMessage, public CommandMessageIF { -public: - /** - * Default size can accomodate 3 4-byte parameters. - */ - static constexpr size_t DEFAULT_COMMAND_MESSAGE_SIZE = - CommandMessageIF::MINIMUM_COMMAND_MESSAGE_SIZE + - 3 * sizeof(uint32_t); +class CommandMessage : public MessageQueueMessage, public CommandMessageIF { + public: + /** + * Default size can accomodate 3 4-byte parameters. + */ + static constexpr size_t DEFAULT_COMMAND_MESSAGE_SIZE = + CommandMessageIF::MINIMUM_COMMAND_MESSAGE_SIZE + 3 * sizeof(uint32_t); - /** - * @brief Default Constructor, does not initialize anything. - * @details - * This constructor should be used when receiving a Message, as the - * content is filled by the MessageQueue. - */ - CommandMessage(); - /** - * This constructor creates a new message with all message content - * initialized - * - * @param command The DeviceHandlerCommand_t that will be sent - * @param parameter1 The first parameter - * @param parameter2 The second parameter - */ - CommandMessage(Command_t command, uint32_t parameter1, uint32_t parameter2); + /** + * @brief Default Constructor, does not initialize anything. + * @details + * This constructor should be used when receiving a Message, as the + * content is filled by the MessageQueue. + */ + CommandMessage(); + /** + * This constructor creates a new message with all message content + * initialized + * + * @param command The DeviceHandlerCommand_t that will be sent + * @param parameter1 The first parameter + * @param parameter2 The second parameter + */ + CommandMessage(Command_t command, uint32_t parameter1, uint32_t parameter2); - /** - * @brief Default Destructor - */ - virtual ~CommandMessage() {} + /** + * @brief Default Destructor + */ + virtual ~CommandMessage() {} - /** - * Read the DeviceHandlerCommand_t that is stored in the message, - * usually used after receiving. - * - * @return the Command stored in the Message - */ - virtual Command_t getCommand() const override; - /** - * Set the command type of the message. Default implementation also - * sets the message type, which will be the first byte of the command ID. - * @param the Command to be sent - */ - virtual void setCommand(Command_t command); + /** + * Read the DeviceHandlerCommand_t that is stored in the message, + * usually used after receiving. + * + * @return the Command stored in the Message + */ + virtual Command_t getCommand() const override; + /** + * Set the command type of the message. Default implementation also + * sets the message type, which will be the first byte of the command ID. + * @param the Command to be sent + */ + virtual void setCommand(Command_t command); - virtual uint8_t* getData() override; - virtual const uint8_t* getData() const override; + virtual uint8_t* getData() override; + virtual const uint8_t* getData() const override; - /** - * Get the first parameter of the message - * @return the first Parameter of the message - */ - uint32_t getParameter() const; - /** - * Set the first parameter of the message - * @param the first parameter of the message - */ - void setParameter(uint32_t parameter1); - uint32_t getParameter2() const; - void setParameter2(uint32_t parameter2); - uint32_t getParameter3() const; - void setParameter3(uint32_t parameter3); + /** + * Get the first parameter of the message + * @return the first Parameter of the message + */ + uint32_t getParameter() const; + /** + * Set the first parameter of the message + * @param the first parameter of the message + */ + void setParameter(uint32_t parameter1); + uint32_t getParameter2() const; + void setParameter2(uint32_t parameter2); + uint32_t getParameter3() const; + void setParameter3(uint32_t parameter3); - /** - * check if a message was cleared - * - * @return if the command is CMD_NONE - */ - bool isClearedCommandMessage(); + /** + * check if a message was cleared + * + * @return if the command is CMD_NONE + */ + bool isClearedCommandMessage(); - /** - * Sets the command to REPLY_REJECTED with parameter UNKNOWN_COMMAND. - * Is needed quite often, so we better code it once only. - */ - void setToUnknownCommand() override; + /** + * Sets the command to REPLY_REJECTED with parameter UNKNOWN_COMMAND. + * Is needed quite often, so we better code it once only. + */ + void setToUnknownCommand() override; - /** - * A command message can be rejected and needs to offer a function - * to set a rejected reply - * @param reason - * @param initialCommand - */ - void setReplyRejected(ReturnValue_t reason, - Command_t initialCommand) override; - /** - * Corrensonding getter function. - * @param initialCommand - * @return - */ - ReturnValue_t getReplyRejectedReason( - Command_t* initialCommand = nullptr) const override; + /** + * A command message can be rejected and needs to offer a function + * to set a rejected reply + * @param reason + * @param initialCommand + */ + void setReplyRejected(ReturnValue_t reason, Command_t initialCommand) override; + /** + * Corrensonding getter function. + * @param initialCommand + * @return + */ + ReturnValue_t getReplyRejectedReason(Command_t* initialCommand = nullptr) const override; + virtual void clear() override; + void clearCommandMessage(); - virtual void clear() override; - void clearCommandMessage(); + /** + * Extract message ID, which is the first byte of the command ID for the + * default implementation. + * @return + */ + virtual uint8_t getMessageType() const override; - /** - * Extract message ID, which is the first byte of the command ID for the - * default implementation. - * @return - */ - virtual uint8_t getMessageType() const override; - - /** MessageQueueMessageIF functions used for minimum size check. */ - size_t getMinimumMessageSize() const override; + /** MessageQueueMessageIF functions used for minimum size check. */ + size_t getMinimumMessageSize() const override; }; #endif /* FSFW_IPC_COMMANDMESSAGE_H_ */ diff --git a/src/fsfw/ipc/CommandMessageCleaner.cpp b/src/fsfw/ipc/CommandMessageCleaner.cpp index 0918d739..328441e6 100644 --- a/src/fsfw/ipc/CommandMessageCleaner.cpp +++ b/src/fsfw/ipc/CommandMessageCleaner.cpp @@ -1,58 +1,58 @@ -#include "fsfw/FSFW.h" #include "fsfw/ipc/CommandMessageCleaner.h" -#include "fsfw/memory/GenericFileSystemMessage.h" +#include "fsfw/FSFW.h" #include "fsfw/devicehandlers/DeviceHandlerMessage.h" #include "fsfw/health/HealthMessage.h" +#include "fsfw/housekeeping/HousekeepingMessage.h" +#include "fsfw/memory/GenericFileSystemMessage.h" #include "fsfw/memory/MemoryMessage.h" #include "fsfw/modes/ModeMessage.h" #include "fsfw/monitoring/MonitoringMessage.h" -#include "fsfw/subsystem/modes/ModeSequenceMessage.h" -#include "fsfw/housekeeping/HousekeepingMessage.h" #include "fsfw/parameters/ParameterMessage.h" +#include "fsfw/subsystem/modes/ModeSequenceMessage.h" #ifdef FSFW_ADD_TMSTORAGE #include "fsfw/tmstorage/TmStoreMessage.h" #endif void CommandMessageCleaner::clearCommandMessage(CommandMessage* message) { - switch(message->getMessageType()){ - case messagetypes::MODE_COMMAND: - ModeMessage::clear(message); - break; - case messagetypes::HEALTH_COMMAND: - HealthMessage::clear(message); - break; - case messagetypes::MODE_SEQUENCE: - ModeSequenceMessage::clear(message); - break; - case messagetypes::ACTION: - ActionMessage::clear(message); - break; - case messagetypes::DEVICE_HANDLER_COMMAND: - DeviceHandlerMessage::clear(message); - break; - case messagetypes::MEMORY: - MemoryMessage::clear(message); - break; - case messagetypes::MONITORING: - MonitoringMessage::clear(message); - break; + switch (message->getMessageType()) { + case messagetypes::MODE_COMMAND: + ModeMessage::clear(message); + break; + case messagetypes::HEALTH_COMMAND: + HealthMessage::clear(message); + break; + case messagetypes::MODE_SEQUENCE: + ModeSequenceMessage::clear(message); + break; + case messagetypes::ACTION: + ActionMessage::clear(message); + break; + case messagetypes::DEVICE_HANDLER_COMMAND: + DeviceHandlerMessage::clear(message); + break; + case messagetypes::MEMORY: + MemoryMessage::clear(message); + break; + case messagetypes::MONITORING: + MonitoringMessage::clear(message); + break; #ifdef FSFW_ADD_TMSTORAGE - case messagetypes::TM_STORE: - TmStoreMessage::clear(message); - break; + case messagetypes::TM_STORE: + TmStoreMessage::clear(message); + break; #endif - case messagetypes::PARAMETER: - ParameterMessage::clear(message); - break; - case messagetypes::HOUSEKEEPING: - HousekeepingMessage::clear(message); - break; - case messagetypes::FILE_SYSTEM_MESSAGE: - GenericFileSystemMessage::clear(message); - break; - default: - messagetypes::clearMissionMessage(message); - break; - } + case messagetypes::PARAMETER: + ParameterMessage::clear(message); + break; + case messagetypes::HOUSEKEEPING: + HousekeepingMessage::clear(message); + break; + case messagetypes::FILE_SYSTEM_MESSAGE: + GenericFileSystemMessage::clear(message); + break; + default: + messagetypes::clearMissionMessage(message); + break; + } } diff --git a/src/fsfw/ipc/CommandMessageCleaner.h b/src/fsfw/ipc/CommandMessageCleaner.h index 2bf4a193..a4c4ed95 100644 --- a/src/fsfw/ipc/CommandMessageCleaner.h +++ b/src/fsfw/ipc/CommandMessageCleaner.h @@ -5,12 +5,11 @@ namespace messagetypes { // Implemented in config. void clearMissionMessage(CommandMessage* message); -} +} // namespace messagetypes class CommandMessageCleaner { -public: - static void clearCommandMessage(CommandMessage* message); + public: + static void clearCommandMessage(CommandMessage* message); }; - #endif /* FRAMEWORK_IPC_COMMANDMESSAGECLEANER_H_ */ diff --git a/src/fsfw/ipc/CommandMessageIF.h b/src/fsfw/ipc/CommandMessageIF.h index 468e2469..aea08203 100644 --- a/src/fsfw/ipc/CommandMessageIF.h +++ b/src/fsfw/ipc/CommandMessageIF.h @@ -1,75 +1,72 @@ #ifndef FSFW_IPC_COMMANDMESSAGEIF_H_ #define FSFW_IPC_COMMANDMESSAGEIF_H_ -#include "MessageQueueMessageIF.h" -#include "FwMessageTypes.h" #include "../returnvalues/HasReturnvaluesIF.h" +#include "FwMessageTypes.h" +#include "MessageQueueMessageIF.h" -#define MAKE_COMMAND_ID( number ) ((MESSAGE_ID << 8) + (number)) +#define MAKE_COMMAND_ID(number) ((MESSAGE_ID << 8) + (number)) typedef uint16_t Command_t; class CommandMessageIF { -public: - /** - * Header consists of sender ID and command ID. - */ - static constexpr size_t HEADER_SIZE = MessageQueueMessageIF::HEADER_SIZE + sizeof(Command_t); - /** - * This minimum size is derived from the interface requirement to be able - * to set a rejected reply, which contains a returnvalue and the initial - * command. - */ - static constexpr size_t MINIMUM_COMMAND_MESSAGE_SIZE = CommandMessageIF::HEADER_SIZE + - sizeof(ReturnValue_t) + sizeof(Command_t); + public: + /** + * Header consists of sender ID and command ID. + */ + static constexpr size_t HEADER_SIZE = MessageQueueMessageIF::HEADER_SIZE + sizeof(Command_t); + /** + * This minimum size is derived from the interface requirement to be able + * to set a rejected reply, which contains a returnvalue and the initial + * command. + */ + static constexpr size_t MINIMUM_COMMAND_MESSAGE_SIZE = + CommandMessageIF::HEADER_SIZE + sizeof(ReturnValue_t) + sizeof(Command_t); - static constexpr Command_t makeCommandId(uint8_t messageId, uint8_t uniqueId) { - return ((messageId << 8) | uniqueId); - } + static constexpr Command_t makeCommandId(uint8_t messageId, uint8_t uniqueId) { + return ((messageId << 8) | uniqueId); + } - static const uint8_t INTERFACE_ID = CLASS_ID::COMMAND_MESSAGE; - static const ReturnValue_t UNKNOWN_COMMAND = MAKE_RETURN_CODE(1); + static const uint8_t INTERFACE_ID = CLASS_ID::COMMAND_MESSAGE; + static const ReturnValue_t UNKNOWN_COMMAND = MAKE_RETURN_CODE(1); - static const uint8_t MESSAGE_ID = messagetypes::COMMAND; - //! Used internally, shall be ignored - static const Command_t CMD_NONE = MAKE_COMMAND_ID( 0 ); - static const Command_t REPLY_COMMAND_OK = MAKE_COMMAND_ID( 1 ); - //! Reply indicating that the current command was rejected, - //! par1 should contain the error code - static const Command_t REPLY_REJECTED = MAKE_COMMAND_ID( 2 ); + static const uint8_t MESSAGE_ID = messagetypes::COMMAND; + //! Used internally, shall be ignored + static const Command_t CMD_NONE = MAKE_COMMAND_ID(0); + static const Command_t REPLY_COMMAND_OK = MAKE_COMMAND_ID(1); + //! Reply indicating that the current command was rejected, + //! par1 should contain the error code + static const Command_t REPLY_REJECTED = MAKE_COMMAND_ID(2); - virtual ~CommandMessageIF() {}; + virtual ~CommandMessageIF(){}; - /** - * A command message shall have a uint16_t command ID field. - * @return - */ - virtual Command_t getCommand() const = 0; - /** - * A command message shall have a uint8_t message type ID field. - * @return - */ - virtual uint8_t getMessageType() const = 0; + /** + * A command message shall have a uint16_t command ID field. + * @return + */ + virtual Command_t getCommand() const = 0; + /** + * A command message shall have a uint8_t message type ID field. + * @return + */ + virtual uint8_t getMessageType() const = 0; - /** - * A command message can be rejected and needs to offer a function - * to set a rejected reply - * @param reason - * @param initialCommand - */ - virtual void setReplyRejected(ReturnValue_t reason, - Command_t initialCommand) = 0; - /** - * Corrensonding getter function. - * @param initialCommand - * @return - */ - virtual ReturnValue_t getReplyRejectedReason( - Command_t* initialCommand = nullptr) const = 0; + /** + * A command message can be rejected and needs to offer a function + * to set a rejected reply + * @param reason + * @param initialCommand + */ + virtual void setReplyRejected(ReturnValue_t reason, Command_t initialCommand) = 0; + /** + * Corrensonding getter function. + * @param initialCommand + * @return + */ + virtual ReturnValue_t getReplyRejectedReason(Command_t* initialCommand = nullptr) const = 0; - virtual void setToUnknownCommand() = 0; - - virtual void clear() = 0; + virtual void setToUnknownCommand() = 0; + virtual void clear() = 0; }; #endif /* FSFW_IPC_COMMANDMESSAGEIF_H_ */ diff --git a/src/fsfw/ipc/FwMessageTypes.h b/src/fsfw/ipc/FwMessageTypes.h index 22fe9d0d..6bd3dc90 100644 --- a/src/fsfw/ipc/FwMessageTypes.h +++ b/src/fsfw/ipc/FwMessageTypes.h @@ -2,24 +2,24 @@ #define FRAMEWORK_IPC_FWMESSAGETYPES_H_ namespace messagetypes { -//Remember to add new Message Types to the clearCommandMessage function! +// Remember to add new Message Types to the clearCommandMessage function! enum FsfwMessageTypes { - COMMAND = 0, - MODE_COMMAND, - HEALTH_COMMAND, - MODE_SEQUENCE, - ACTION, - CFDP, - TM_STORE, - DEVICE_HANDLER_COMMAND, - MONITORING, - MEMORY, - PARAMETER, - FILE_SYSTEM_MESSAGE, - HOUSEKEEPING, + COMMAND = 0, + MODE_COMMAND, + HEALTH_COMMAND, + MODE_SEQUENCE, + ACTION, + CFDP, + TM_STORE, + DEVICE_HANDLER_COMMAND, + MONITORING, + MEMORY, + PARAMETER, + FILE_SYSTEM_MESSAGE, + HOUSEKEEPING, - FW_MESSAGES_COUNT, + FW_MESSAGES_COUNT, }; -} +} // namespace messagetypes #endif /* FRAMEWORK_IPC_FWMESSAGETYPES_H_ */ diff --git a/src/fsfw/ipc/MessageQueueIF.h b/src/fsfw/ipc/MessageQueueIF.h index 217174f6..9aef58b7 100644 --- a/src/fsfw/ipc/MessageQueueIF.h +++ b/src/fsfw/ipc/MessageQueueIF.h @@ -1,12 +1,11 @@ #ifndef FSFW_IPC_MESSAGEQUEUEIF_H_ #define FSFW_IPC_MESSAGEQUEUEIF_H_ -#include "messageQueueDefinitions.h" -#include "MessageQueueMessageIF.h" -#include "../returnvalues/HasReturnvaluesIF.h" - #include +#include "../returnvalues/HasReturnvaluesIF.h" +#include "MessageQueueMessageIF.h" +#include "messageQueueDefinitions.h" // COULDDO: We could support blocking calls // semaphores are being implemented, which makes this idea even more iteresting. @@ -16,158 +15,155 @@ * @brief Message Queue related software components */ class MessageQueueIF { -public: - static const MessageQueueId_t NO_QUEUE = 0; + public: + static const MessageQueueId_t NO_QUEUE = 0; - static const uint8_t INTERFACE_ID = CLASS_ID::MESSAGE_QUEUE_IF; - //! No new messages on the queue - static const ReturnValue_t EMPTY = MAKE_RETURN_CODE(1); - //! [EXPORT] : [COMMENT] No space left for more messages - static const ReturnValue_t FULL = MAKE_RETURN_CODE(2); - //! [EXPORT] : [COMMENT] Returned if a reply method was called without partner - static const ReturnValue_t NO_REPLY_PARTNER = MAKE_RETURN_CODE(3); - //! [EXPORT] : [COMMENT] Returned if the target destination is invalid. - static constexpr ReturnValue_t DESTINATION_INVALID = MAKE_RETURN_CODE(4); + static const uint8_t INTERFACE_ID = CLASS_ID::MESSAGE_QUEUE_IF; + //! No new messages on the queue + static const ReturnValue_t EMPTY = MAKE_RETURN_CODE(1); + //! [EXPORT] : [COMMENT] No space left for more messages + static const ReturnValue_t FULL = MAKE_RETURN_CODE(2); + //! [EXPORT] : [COMMENT] Returned if a reply method was called without partner + static const ReturnValue_t NO_REPLY_PARTNER = MAKE_RETURN_CODE(3); + //! [EXPORT] : [COMMENT] Returned if the target destination is invalid. + static constexpr ReturnValue_t DESTINATION_INVALID = MAKE_RETURN_CODE(4); - virtual ~MessageQueueIF() {} - /** - * @brief This operation sends a message to the last communication partner. - * @details - * This operation simplifies answering an incoming message by using the - * stored lastParnter information as destination. If there was no message - * received yet (i.e. lastPartner is zero), an error code is returned. - * @param message - * A pointer to a previously created message, which is sent. - * @return - * -@c RETURN_OK if ok - * -@c NO_REPLY_PARTNER Should return NO_REPLY_PARTNER if partner was found. - */ - virtual ReturnValue_t reply(MessageQueueMessageIF* message) = 0; + virtual ~MessageQueueIF() {} + /** + * @brief This operation sends a message to the last communication partner. + * @details + * This operation simplifies answering an incoming message by using the + * stored lastParnter information as destination. If there was no message + * received yet (i.e. lastPartner is zero), an error code is returned. + * @param message + * A pointer to a previously created message, which is sent. + * @return + * -@c RETURN_OK if ok + * -@c NO_REPLY_PARTNER Should return NO_REPLY_PARTNER if partner was found. + */ + virtual ReturnValue_t reply(MessageQueueMessageIF* message) = 0; - /** - * @brief This function reads available messages from the message queue - * and returns the sender. - * @details - * It works identically to the other receiveMessage call, but in addition - * returns the sender's queue id. - * @param message - * A pointer to a message in which the received data is stored. - * @param receivedFrom - * A pointer to a queue id in which the sender's id is stored. - */ - virtual ReturnValue_t receiveMessage(MessageQueueMessageIF* message, - MessageQueueId_t *receivedFrom) = 0; + /** + * @brief This function reads available messages from the message queue + * and returns the sender. + * @details + * It works identically to the other receiveMessage call, but in addition + * returns the sender's queue id. + * @param message + * A pointer to a message in which the received data is stored. + * @param receivedFrom + * A pointer to a queue id in which the sender's id is stored. + */ + virtual ReturnValue_t receiveMessage(MessageQueueMessageIF* message, + MessageQueueId_t* receivedFrom) = 0; - /** - * @brief This function reads available messages from the message queue. - * @details - * If data is available it is stored in the passed message pointer. - * The message's original content is overwritten and the sendFrom - * information is stored in theblastPartner attribute. Else, the lastPartner - * information remains untouched, the message's content is cleared and the - * function returns immediately. - * @param message - * A pointer to a message in which the received data is stored. - * @return -@c RETURN_OK on success - * -@c MessageQueueIF::EMPTY if queue is empty - */ - virtual ReturnValue_t receiveMessage(MessageQueueMessageIF* message) = 0; - /** - * Deletes all pending messages in the queue. - * @param count The number of flushed messages. - * @return RETURN_OK on success. - */ - virtual ReturnValue_t flush(uint32_t* count) = 0; - /** - * @brief This method returns the message queue - * id of the last communication partner. - */ - virtual MessageQueueId_t getLastPartner() const = 0; - /** - * @brief This method returns the message queue - * id of this class's message queue. - */ - virtual MessageQueueId_t getId() const = 0; + /** + * @brief This function reads available messages from the message queue. + * @details + * If data is available it is stored in the passed message pointer. + * The message's original content is overwritten and the sendFrom + * information is stored in theblastPartner attribute. Else, the lastPartner + * information remains untouched, the message's content is cleared and the + * function returns immediately. + * @param message + * A pointer to a message in which the received data is stored. + * @return -@c RETURN_OK on success + * -@c MessageQueueIF::EMPTY if queue is empty + */ + virtual ReturnValue_t receiveMessage(MessageQueueMessageIF* message) = 0; + /** + * Deletes all pending messages in the queue. + * @param count The number of flushed messages. + * @return RETURN_OK on success. + */ + virtual ReturnValue_t flush(uint32_t* count) = 0; + /** + * @brief This method returns the message queue + * id of the last communication partner. + */ + virtual MessageQueueId_t getLastPartner() const = 0; + /** + * @brief This method returns the message queue + * id of this class's message queue. + */ + virtual MessageQueueId_t getId() const = 0; - /** - * @brief With the sendMessage call, a queue message - * is sent to a receiving queue. - * @details - * This method takes the message provided, adds the sentFrom information - * and passes it on to the destination provided with an operating system - * call. The OS's returnvalue is returned. - * @param sendTo - * This parameter specifies the message queue id to send the message to. - * @param message - * This is a pointer to a previously created message, which is sent. - * @param sentFrom - * The sentFrom information can be set to inject the sender's queue id - * into the message. This variable is set to zero by default. - * @param ignoreFault - * If set to true, the internal software fault counter is not incremented - * if queue is full (if implemented). - * @return -@c RETURN_OK on success - * -@c MessageQueueIF::FULL if queue is full - */ - virtual ReturnValue_t sendMessageFrom( MessageQueueId_t sendTo, - MessageQueueMessageIF* message, MessageQueueId_t sentFrom, - bool ignoreFault = false ) = 0; + /** + * @brief With the sendMessage call, a queue message + * is sent to a receiving queue. + * @details + * This method takes the message provided, adds the sentFrom information + * and passes it on to the destination provided with an operating system + * call. The OS's returnvalue is returned. + * @param sendTo + * This parameter specifies the message queue id to send the message to. + * @param message + * This is a pointer to a previously created message, which is sent. + * @param sentFrom + * The sentFrom information can be set to inject the sender's queue id + * into the message. This variable is set to zero by default. + * @param ignoreFault + * If set to true, the internal software fault counter is not incremented + * if queue is full (if implemented). + * @return -@c RETURN_OK on success + * -@c MessageQueueIF::FULL if queue is full + */ + virtual ReturnValue_t sendMessageFrom(MessageQueueId_t sendTo, MessageQueueMessageIF* message, + MessageQueueId_t sentFrom, bool ignoreFault = false) = 0; - /** - * @brief This operation sends a message to the given destination. - * @details - * It directly uses the sendMessage call of the MessageQueueSender parent, - * but passes its queue id as "sentFrom" parameter. - * @param sendTo - * This parameter specifies the message queue id of the destination - * message queue. - * @param message - * A pointer to a previously created message, which is sent. - * @param ignoreFault - * If set to true, the internal software fault counter is not incremented - * if queue is full. - */ - virtual ReturnValue_t sendMessage( MessageQueueId_t sendTo, - MessageQueueMessageIF* message, bool ignoreFault = false ) = 0; + /** + * @brief This operation sends a message to the given destination. + * @details + * It directly uses the sendMessage call of the MessageQueueSender parent, + * but passes its queue id as "sentFrom" parameter. + * @param sendTo + * This parameter specifies the message queue id of the destination + * message queue. + * @param message + * A pointer to a previously created message, which is sent. + * @param ignoreFault + * If set to true, the internal software fault counter is not incremented + * if queue is full. + */ + virtual ReturnValue_t sendMessage(MessageQueueId_t sendTo, MessageQueueMessageIF* message, + bool ignoreFault = false) = 0; - /** - * @brief The sendToDefaultFrom method sends a queue message - * to the default destination. - * @details - * In all other aspects, it works identical to the sendMessage method. - * @param message - * This is a pointer to a previously created message, which is sent. - * @param sentFrom - * The sentFrom information can be set to inject the sender's queue id - * into the message. This variable is set to zero by default. - * @return -@c RETURN_OK on success - * -@c MessageQueueIF::FULL if queue is full - */ - virtual ReturnValue_t sendToDefaultFrom( MessageQueueMessageIF* message, - MessageQueueId_t sentFrom, bool ignoreFault = false ) = 0; - /** - * @brief This operation sends a message to the default destination. - * @details - * As in the sendMessage method, this function uses the sendToDefault - * call of the Implementation class and adds its queue id as - * "sentFrom" information. - * @param message A pointer to a previously created message, which is sent. - * @return -@c RETURN_OK on success - * -@c MessageQueueIF::FULL if queue is full - */ - virtual ReturnValue_t sendToDefault( MessageQueueMessageIF* message ) = 0; - /** - * @brief This method is a simple setter for the default destination. - */ - virtual void setDefaultDestination(MessageQueueId_t defaultDestination) = 0; - /** - * @brief This method is a simple getter for the default destination. - */ - virtual MessageQueueId_t getDefaultDestination() const = 0; + /** + * @brief The sendToDefaultFrom method sends a queue message + * to the default destination. + * @details + * In all other aspects, it works identical to the sendMessage method. + * @param message + * This is a pointer to a previously created message, which is sent. + * @param sentFrom + * The sentFrom information can be set to inject the sender's queue id + * into the message. This variable is set to zero by default. + * @return -@c RETURN_OK on success + * -@c MessageQueueIF::FULL if queue is full + */ + virtual ReturnValue_t sendToDefaultFrom(MessageQueueMessageIF* message, MessageQueueId_t sentFrom, + bool ignoreFault = false) = 0; + /** + * @brief This operation sends a message to the default destination. + * @details + * As in the sendMessage method, this function uses the sendToDefault + * call of the Implementation class and adds its queue id as + * "sentFrom" information. + * @param message A pointer to a previously created message, which is sent. + * @return -@c RETURN_OK on success + * -@c MessageQueueIF::FULL if queue is full + */ + virtual ReturnValue_t sendToDefault(MessageQueueMessageIF* message) = 0; + /** + * @brief This method is a simple setter for the default destination. + */ + virtual void setDefaultDestination(MessageQueueId_t defaultDestination) = 0; + /** + * @brief This method is a simple getter for the default destination. + */ + virtual MessageQueueId_t getDefaultDestination() const = 0; - virtual bool isDefaultDestinationSet() const = 0; + virtual bool isDefaultDestinationSet() const = 0; }; - - #endif /* FSFW_IPC_MESSAGEQUEUEIF_H_ */ diff --git a/src/fsfw/ipc/MessageQueueMessage.cpp b/src/fsfw/ipc/MessageQueueMessage.cpp index 62b826e9..6899915a 100644 --- a/src/fsfw/ipc/MessageQueueMessage.cpp +++ b/src/fsfw/ipc/MessageQueueMessage.cpp @@ -1,93 +1,71 @@ #include "fsfw/ipc/MessageQueueMessage.h" -#include "fsfw/serviceinterface/ServiceInterface.h" -#include "fsfw/globalfunctions/arrayprinter.h" #include -MessageQueueMessage::MessageQueueMessage() : - messageSize(getMinimumMessageSize()) { - memset(this->internalBuffer, 0, sizeof(this->internalBuffer)); +#include "fsfw/globalfunctions/arrayprinter.h" +#include "fsfw/serviceinterface/ServiceInterface.h" + +MessageQueueMessage::MessageQueueMessage() : messageSize(getMinimumMessageSize()) { + memset(this->internalBuffer, 0, sizeof(this->internalBuffer)); } -MessageQueueMessage::MessageQueueMessage(uint8_t* data, size_t size) : - messageSize(this->HEADER_SIZE + size) { - if (size <= this->MAX_DATA_SIZE) { - memcpy(this->getData(), data, size); - this->messageSize = this->HEADER_SIZE + size; - } - else { +MessageQueueMessage::MessageQueueMessage(uint8_t* data, size_t size) + : messageSize(this->HEADER_SIZE + size) { + if (size <= this->MAX_DATA_SIZE) { + memcpy(this->getData(), data, size); + this->messageSize = this->HEADER_SIZE + size; + } else { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "MessageQueueMessage: Passed size larger than maximum" - "allowed size! Setting content to 0" << std::endl; + sif::warning << "MessageQueueMessage: Passed size larger than maximum" + "allowed size! Setting content to 0" + << std::endl; #endif - memset(this->internalBuffer, 0, sizeof(this->internalBuffer)); - this->messageSize = this->HEADER_SIZE; - } + memset(this->internalBuffer, 0, sizeof(this->internalBuffer)); + this->messageSize = this->HEADER_SIZE; + } } -MessageQueueMessage::~MessageQueueMessage() { -} +MessageQueueMessage::~MessageQueueMessage() {} -const uint8_t* MessageQueueMessage::getBuffer() const { - return this->internalBuffer; -} +const uint8_t* MessageQueueMessage::getBuffer() const { return this->internalBuffer; } -uint8_t* MessageQueueMessage::getBuffer() { - return this->internalBuffer; -} +uint8_t* MessageQueueMessage::getBuffer() { return this->internalBuffer; } const uint8_t* MessageQueueMessage::getData() const { - return this->internalBuffer + this->HEADER_SIZE; + return this->internalBuffer + this->HEADER_SIZE; } -uint8_t* MessageQueueMessage::getData() { - return this->internalBuffer + this->HEADER_SIZE; -} +uint8_t* MessageQueueMessage::getData() { return this->internalBuffer + this->HEADER_SIZE; } MessageQueueId_t MessageQueueMessage::getSender() const { - MessageQueueId_t temp_id; - memcpy(&temp_id, this->internalBuffer, sizeof(MessageQueueId_t)); - return temp_id; + MessageQueueId_t temp_id; + memcpy(&temp_id, this->internalBuffer, sizeof(MessageQueueId_t)); + return temp_id; } void MessageQueueMessage::setSender(MessageQueueId_t setId) { - memcpy(this->internalBuffer, &setId, sizeof(MessageQueueId_t)); + memcpy(this->internalBuffer, &setId, sizeof(MessageQueueId_t)); } void MessageQueueMessage::print(bool printWholeMessage) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "MessageQueueMessage content: " << std::endl; + sif::debug << "MessageQueueMessage content: " << std::endl; #endif - if(printWholeMessage) { - arrayprinter::print(getData(), getMaximumMessageSize()); - } - else { - arrayprinter::print(getData(), getMessageSize()); - } - + if (printWholeMessage) { + arrayprinter::print(getData(), getMaximumMessageSize()); + } else { + arrayprinter::print(getData(), getMessageSize()); + } } -void MessageQueueMessage::clear() { - memset(this->getBuffer(), 0, this->MAX_MESSAGE_SIZE); -} +void MessageQueueMessage::clear() { memset(this->getBuffer(), 0, this->MAX_MESSAGE_SIZE); } -size_t MessageQueueMessage::getMessageSize() const { - return this->messageSize; -} +size_t MessageQueueMessage::getMessageSize() const { return this->messageSize; } -void MessageQueueMessage::setMessageSize(size_t messageSize) { - this->messageSize = messageSize; -} +void MessageQueueMessage::setMessageSize(size_t messageSize) { this->messageSize = messageSize; } -size_t MessageQueueMessage::getMinimumMessageSize() const { - return this->MIN_MESSAGE_SIZE; -} +size_t MessageQueueMessage::getMinimumMessageSize() const { return this->MIN_MESSAGE_SIZE; } -size_t MessageQueueMessage::getMaximumMessageSize() const { - return this->MAX_MESSAGE_SIZE; -} - -size_t MessageQueueMessage::getMaximumDataSize() const { - return this->MAX_DATA_SIZE; -} +size_t MessageQueueMessage::getMaximumMessageSize() const { return this->MAX_MESSAGE_SIZE; } +size_t MessageQueueMessage::getMaximumDataSize() const { return this->MAX_DATA_SIZE; } diff --git a/src/fsfw/ipc/MessageQueueMessage.h b/src/fsfw/ipc/MessageQueueMessage.h index e9ef6756..30e50ffe 100644 --- a/src/fsfw/ipc/MessageQueueMessage.h +++ b/src/fsfw/ipc/MessageQueueMessage.h @@ -1,9 +1,10 @@ #ifndef FSFW_IPC_MESSAGEQUEUEMESSAGE_H_ #define FSFW_IPC_MESSAGEQUEUEMESSAGE_H_ -#include "fsfw/ipc/MessageQueueMessageIF.h" #include +#include "fsfw/ipc/MessageQueueMessageIF.h" + /** * @brief This class is the representation and data organizer * for interprocess messages. @@ -22,129 +23,131 @@ * receive messages from other tasks. * @ingroup message_queue */ -class MessageQueueMessage: public MessageQueueMessageIF { -public: - /** - * @brief The class is initialized empty with this constructor. - * @details - * The messageSize attribute is set to the header's size and the whole - * content is set to zero. - */ - MessageQueueMessage(); - /** - * @brief With this constructor the class is initialized with - * the given content. - * @details - * If the passed message size fits into the buffer, the passed data is - * copied to the internal buffer and the messageSize information is set. - * Otherwise, messageSize is set to the header's size and the whole - * content is set to zero. - * @param data The data to be put in the message. - * @param size Size of the data to be copied. Must be smaller than - * MAX_MESSAGE_SIZE and larger than MIN_MESSAGE_SIZE. - */ - MessageQueueMessage(uint8_t* data, size_t size); +class MessageQueueMessage : public MessageQueueMessageIF { + public: + /** + * @brief The class is initialized empty with this constructor. + * @details + * The messageSize attribute is set to the header's size and the whole + * content is set to zero. + */ + MessageQueueMessage(); + /** + * @brief With this constructor the class is initialized with + * the given content. + * @details + * If the passed message size fits into the buffer, the passed data is + * copied to the internal buffer and the messageSize information is set. + * Otherwise, messageSize is set to the header's size and the whole + * content is set to zero. + * @param data The data to be put in the message. + * @param size Size of the data to be copied. Must be smaller than + * MAX_MESSAGE_SIZE and larger than MIN_MESSAGE_SIZE. + */ + MessageQueueMessage(uint8_t* data, size_t size); - /** - * @brief As no memory is allocated in this class, - * the destructor is empty. - */ - virtual ~MessageQueueMessage(); + /** + * @brief As no memory is allocated in this class, + * the destructor is empty. + */ + virtual ~MessageQueueMessage(); - /** - * @brief The size information of each message is stored in - * this attribute. - * @details - * It is public to simplify usage and to allow for passing the size - * address as a pointer. Care must be taken when inheriting from this class, - * as every child class is responsible for managing the size information by - * itself. When using the class to receive a message, the size information - * is updated automatically. - * - * Please note that the minimum size is limited by the size of the header - * while the maximum size is limited by the maximum allowed message size. - */ - size_t messageSize; - /** - * @brief This constant defines the maximum size of the data content, - * excluding the header. - * @details - * It may be changed if necessary, but in general should be kept - * as small as possible. - */ - static const size_t MAX_DATA_SIZE = 24; + /** + * @brief The size information of each message is stored in + * this attribute. + * @details + * It is public to simplify usage and to allow for passing the size + * address as a pointer. Care must be taken when inheriting from this class, + * as every child class is responsible for managing the size information by + * itself. When using the class to receive a message, the size information + * is updated automatically. + * + * Please note that the minimum size is limited by the size of the header + * while the maximum size is limited by the maximum allowed message size. + */ + size_t messageSize; + /** + * @brief This constant defines the maximum size of the data content, + * excluding the header. + * @details + * It may be changed if necessary, but in general should be kept + * as small as possible. + */ + static const size_t MAX_DATA_SIZE = 24; - /** - * @brief This constant defines the maximum total size in bytes - * of a sent message. - * @details - * It is the sum of the maximum data and the header size. Be aware that - * this constant is used to define the buffer sizes for every message - * queue in the system. So, a change here may have significant impact on - * the required resources. - */ - static constexpr size_t MAX_MESSAGE_SIZE = MAX_DATA_SIZE + HEADER_SIZE; - /** - * @brief Defines the minimum size of a message where only the - * header is included - */ - static constexpr size_t MIN_MESSAGE_SIZE = HEADER_SIZE; -private: - /** - * @brief This is the internal buffer that contains the - * actual message data. - */ - uint8_t internalBuffer[MAX_MESSAGE_SIZE]; -public: - /** - * @brief This method is used to get the complete data of the message. - */ - const uint8_t* getBuffer() const override; - /** - * @brief This method is used to get the complete data of the message. - */ - uint8_t* getBuffer() override; - /** - * @brief This method is used to fetch the data content of the message. - * @details - * It shall be used by child classes to add data at the right position. - */ - const uint8_t* getData() const override; - /** - * @brief This method is used to fetch the data content of the message. - * @details - * It shall be used by child classes to add data at the right position. - */ - uint8_t* getData() override; - /** - * @brief This method is used to extract the sender's message - * queue id information from a received message. - */ - MessageQueueId_t getSender() const override; - /** - * @brief With this method, the whole content - * and the message size is set to zero. - */ - void clear() override; + /** + * @brief This constant defines the maximum total size in bytes + * of a sent message. + * @details + * It is the sum of the maximum data and the header size. Be aware that + * this constant is used to define the buffer sizes for every message + * queue in the system. So, a change here may have significant impact on + * the required resources. + */ + static constexpr size_t MAX_MESSAGE_SIZE = MAX_DATA_SIZE + HEADER_SIZE; + /** + * @brief Defines the minimum size of a message where only the + * header is included + */ + static constexpr size_t MIN_MESSAGE_SIZE = HEADER_SIZE; - /** - * @brief This method is used to set the sender's message queue id - * information prior to ing the message. - * @param setId - * The message queue id that identifies the sending message queue. - */ - void setSender(MessageQueueId_t setId) override; + private: + /** + * @brief This is the internal buffer that contains the + * actual message data. + */ + uint8_t internalBuffer[MAX_MESSAGE_SIZE]; - virtual size_t getMessageSize() const override; - virtual void setMessageSize(size_t messageSize) override; - virtual size_t getMinimumMessageSize() const override; - virtual size_t getMaximumMessageSize() const override; - virtual size_t getMaximumDataSize() const override; + public: + /** + * @brief This method is used to get the complete data of the message. + */ + const uint8_t* getBuffer() const override; + /** + * @brief This method is used to get the complete data of the message. + */ + uint8_t* getBuffer() override; + /** + * @brief This method is used to fetch the data content of the message. + * @details + * It shall be used by child classes to add data at the right position. + */ + const uint8_t* getData() const override; + /** + * @brief This method is used to fetch the data content of the message. + * @details + * It shall be used by child classes to add data at the right position. + */ + uint8_t* getData() override; + /** + * @brief This method is used to extract the sender's message + * queue id information from a received message. + */ + MessageQueueId_t getSender() const override; + /** + * @brief With this method, the whole content + * and the message size is set to zero. + */ + void clear() override; - /** - * @brief This is a debug method that prints the content. - */ - void print(bool printWholeMessage); + /** + * @brief This method is used to set the sender's message queue id + * information prior to ing the message. + * @param setId + * The message queue id that identifies the sending message queue. + */ + void setSender(MessageQueueId_t setId) override; + + virtual size_t getMessageSize() const override; + virtual void setMessageSize(size_t messageSize) override; + virtual size_t getMinimumMessageSize() const override; + virtual size_t getMaximumMessageSize() const override; + virtual size_t getMaximumDataSize() const override; + + /** + * @brief This is a debug method that prints the content. + */ + void print(bool printWholeMessage); }; #endif /* FSFW_IPC_MESSAGEQUEUEMESSAGE_H_ */ diff --git a/src/fsfw/ipc/MessageQueueMessageIF.h b/src/fsfw/ipc/MessageQueueMessageIF.h index 893c30b5..dae28926 100644 --- a/src/fsfw/ipc/MessageQueueMessageIF.h +++ b/src/fsfw/ipc/MessageQueueMessageIF.h @@ -1,81 +1,78 @@ #ifndef FRAMEWORK_IPC_MESSAGEQUEUEMESSAGEIF_H_ #define FRAMEWORK_IPC_MESSAGEQUEUEMESSAGEIF_H_ -#include "messageQueueDefinitions.h" #include #include +#include "messageQueueDefinitions.h" + class MessageQueueMessageIF { -public: + public: + /** + * @brief This constants defines the size of the header, + * which is added to every message. + */ + static const size_t HEADER_SIZE = sizeof(MessageQueueId_t); - /** - * @brief This constants defines the size of the header, - * which is added to every message. - */ - static const size_t HEADER_SIZE = sizeof(MessageQueueId_t); + virtual ~MessageQueueMessageIF(){}; - virtual ~MessageQueueMessageIF() {}; + /** + * @brief With this method, the whole content and the message + * size is set to zero. + * @details + * Implementations should also take care to clear data which is stored + * indirectly (e.g. storage data). + */ + virtual void clear() = 0; - /** - * @brief With this method, the whole content and the message - * size is set to zero. - * @details - * Implementations should also take care to clear data which is stored - * indirectly (e.g. storage data). - */ - virtual void clear() = 0; + /** + * @brief Get read-only pointer to the complete data of the message. + * @return + */ + virtual const uint8_t* getBuffer() const = 0; - /** - * @brief Get read-only pointer to the complete data of the message. - * @return - */ - virtual const uint8_t* getBuffer() const = 0; + /** + * @brief This method is used to get the complete data of the message. + */ + virtual uint8_t* getBuffer() = 0; - /** - * @brief This method is used to get the complete data of the message. - */ - virtual uint8_t* getBuffer() = 0; + /** + * @brief This method is used to set the sender's message queue id + * information prior to sending the message. + * @param setId + * The message queue id that identifies the sending message queue. + */ + virtual void setSender(MessageQueueId_t setId) = 0; - /** - * @brief This method is used to set the sender's message queue id - * information prior to sending the message. - * @param setId - * The message queue id that identifies the sending message queue. - */ - virtual void setSender(MessageQueueId_t setId) = 0; + /** + * @brief This method is used to extract the sender's message queue id + * information from a received message. + */ + virtual MessageQueueId_t getSender() const = 0; - /** - * @brief This method is used to extract the sender's message queue id - * information from a received message. - */ - virtual MessageQueueId_t getSender() const = 0; + /** + * @brief This method is used to fetch the data content of the message. + * @details + * It shall be used by child classes to add data at the right position. + */ + virtual const uint8_t* getData() const = 0; + /** + * @brief This method is used to fetch the data content of the message. + * @details + * It shall be used by child classes to add data at the right position. + */ + virtual uint8_t* getData() = 0; - /** - * @brief This method is used to fetch the data content of the message. - * @details - * It shall be used by child classes to add data at the right position. - */ - virtual const uint8_t* getData() const = 0; - /** - * @brief This method is used to fetch the data content of the message. - * @details - * It shall be used by child classes to add data at the right position. - */ - virtual uint8_t* getData() = 0; - - /** - * Get constant message size of current message implementation. - * @return - */ - virtual size_t getMessageSize() const = 0; - - virtual void setMessageSize(size_t messageSize) = 0; - virtual size_t getMinimumMessageSize() const = 0; - virtual size_t getMaximumMessageSize() const = 0; - virtual size_t getMaximumDataSize() const = 0; + /** + * Get constant message size of current message implementation. + * @return + */ + virtual size_t getMessageSize() const = 0; + virtual void setMessageSize(size_t messageSize) = 0; + virtual size_t getMinimumMessageSize() const = 0; + virtual size_t getMaximumMessageSize() const = 0; + virtual size_t getMaximumDataSize() const = 0; }; - - #endif /* FRAMEWORK_IPC_MESSAGEQUEUEMESSAGEIF_H_ */ diff --git a/src/fsfw/ipc/MessageQueueSenderIF.h b/src/fsfw/ipc/MessageQueueSenderIF.h index 683c2908..a98862f6 100644 --- a/src/fsfw/ipc/MessageQueueSenderIF.h +++ b/src/fsfw/ipc/MessageQueueSenderIF.h @@ -1,26 +1,24 @@ #ifndef FSFW_IPC_MESSAGEQUEUESENDERIF_H_ #define FSFW_IPC_MESSAGEQUEUESENDERIF_H_ +#include "../objectmanager/ObjectManagerIF.h" #include "MessageQueueIF.h" #include "MessageQueueMessageIF.h" -#include "../objectmanager/ObjectManagerIF.h" class MessageQueueSenderIF { -public: + public: + virtual ~MessageQueueSenderIF() {} - virtual ~MessageQueueSenderIF() {} + /** + * Allows sending messages without actually "owning" a message queue. + * Not sure whether this is actually a good idea. + */ + static ReturnValue_t sendMessage(MessageQueueId_t sendTo, MessageQueueMessageIF* message, + MessageQueueId_t sentFrom = MessageQueueIF::NO_QUEUE, + bool ignoreFault = false); - /** - * Allows sending messages without actually "owning" a message queue. - * Not sure whether this is actually a good idea. - */ - static ReturnValue_t sendMessage(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, - MessageQueueId_t sentFrom = MessageQueueIF::NO_QUEUE, - bool ignoreFault = false); -private: - MessageQueueSenderIF() {} + private: + MessageQueueSenderIF() {} }; - #endif /* FSFW_IPC_MESSAGEQUEUESENDERIF_H_ */ diff --git a/src/fsfw/ipc/MutexFactory.h b/src/fsfw/ipc/MutexFactory.h index db505ff9..6e1988ee 100644 --- a/src/fsfw/ipc/MutexFactory.h +++ b/src/fsfw/ipc/MutexFactory.h @@ -8,27 +8,25 @@ * interface, but also is the base class for a singleton. */ class MutexFactory { -public: - virtual ~MutexFactory(); - /** - * Returns the single instance of MutexFactory. - * The implementation of #instance is found in its subclasses. - * Thus, we choose link-time variability of the instance. - */ - static MutexFactory* instance(); + public: + virtual ~MutexFactory(); + /** + * Returns the single instance of MutexFactory. + * The implementation of #instance is found in its subclasses. + * Thus, we choose link-time variability of the instance. + */ + static MutexFactory* instance(); - MutexIF* createMutex(); + MutexIF* createMutex(); - void deleteMutex(MutexIF* mutex); + void deleteMutex(MutexIF* mutex); -private: - /** - * External instantiation is not allowed. - */ - MutexFactory(); - static MutexFactory* factoryInstance; + private: + /** + * External instantiation is not allowed. + */ + MutexFactory(); + static MutexFactory* factoryInstance; }; - - #endif /* FSFW_IPC_MUTEXFACTORY_H_ */ diff --git a/src/fsfw/ipc/MutexGuard.h b/src/fsfw/ipc/MutexGuard.h index 9ee68c81..f7b90663 100644 --- a/src/fsfw/ipc/MutexGuard.h +++ b/src/fsfw/ipc/MutexGuard.h @@ -1,60 +1,57 @@ #ifndef FRAMEWORK_IPC_MUTEXGUARD_H_ #define FRAMEWORK_IPC_MUTEXGUARD_H_ -#include "MutexFactory.h" #include "../serviceinterface/ServiceInterface.h" +#include "MutexFactory.h" class MutexGuard { -public: - MutexGuard(MutexIF* mutex, MutexIF::TimeoutType timeoutType = - MutexIF::TimeoutType::BLOCKING, uint32_t timeoutMs = 0): - internalMutex(mutex) { - if(mutex == nullptr) { + public: + MutexGuard(MutexIF* mutex, MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::BLOCKING, + uint32_t timeoutMs = 0) + : internalMutex(mutex) { + if (mutex == nullptr) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "MutexGuard: Passed mutex is invalid!" << std::endl; + sif::error << "MutexGuard: Passed mutex is invalid!" << std::endl; #else - sif::printError("MutexGuard: Passed mutex is invalid!\n"); + sif::printError("MutexGuard: Passed mutex is invalid!\n"); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - return; - } - result = mutex->lockMutex(timeoutType, - timeoutMs); + return; + } + result = mutex->lockMutex(timeoutType, timeoutMs); #if FSFW_VERBOSE_LEVEL >= 1 - if(result == MutexIF::MUTEX_TIMEOUT) { + if (result == MutexIF::MUTEX_TIMEOUT) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "MutexGuard: Lock of mutex failed with timeout of " - << timeoutMs << " milliseconds!" << std::endl; + sif::error << "MutexGuard: Lock of mutex failed with timeout of " << timeoutMs + << " milliseconds!" << std::endl; #else - sif::printError("MutexGuard: Lock of mutex failed with timeout of %lu milliseconds\n", - timeoutMs); + sif::printError("MutexGuard: Lock of mutex failed with timeout of %lu milliseconds\n", + timeoutMs); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ - } - else if(result != HasReturnvaluesIF::RETURN_OK) { + } else if (result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "MutexGuard: Lock of Mutex failed with code " << result << std::endl; + sif::error << "MutexGuard: Lock of Mutex failed with code " << result << std::endl; #else - sif::printError("MutexGuard: Lock of Mutex failed with code %d\n", result); + sif::printError("MutexGuard: Lock of Mutex failed with code %d\n", result); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ - } + } #else #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - } + } - ReturnValue_t getLockResult() const { - return result; - } + ReturnValue_t getLockResult() const { return result; } - ~MutexGuard() { - if(internalMutex != nullptr) { - internalMutex->unlockMutex(); - } + ~MutexGuard() { + if (internalMutex != nullptr) { + internalMutex->unlockMutex(); } -private: - MutexIF* internalMutex; - ReturnValue_t result = HasReturnvaluesIF::RETURN_FAILED; + } + + private: + MutexIF* internalMutex; + ReturnValue_t result = HasReturnvaluesIF::RETURN_FAILED; }; #endif /* FRAMEWORK_IPC_MUTEXGUARD_H_ */ diff --git a/src/fsfw/ipc/MutexIF.h b/src/fsfw/ipc/MutexIF.h index 084b702b..0bdfa1f4 100644 --- a/src/fsfw/ipc/MutexIF.h +++ b/src/fsfw/ipc/MutexIF.h @@ -10,80 +10,78 @@ * @ingroup interface */ class MutexIF { -public: - /** - * Different types of timeout for the mutex lock. - */ - enum class TimeoutType { - POLLING, //!< If mutex is not available, return immediately - WAITING, //!< Wait a specified time for the mutex to become available - BLOCKING //!< Block indefinitely until the mutex becomes available. - }; + public: + /** + * Different types of timeout for the mutex lock. + */ + enum class TimeoutType { + POLLING, //!< If mutex is not available, return immediately + WAITING, //!< Wait a specified time for the mutex to become available + BLOCKING //!< Block indefinitely until the mutex becomes available. + }; - /** - * Lock the mutex. The timeout value will only be used for - * TimeoutType::WAITING - * @param timeoutType - * @param timeoutMs - * @return - */ - virtual ReturnValue_t lockMutex(TimeoutType timeoutType = - TimeoutType::BLOCKING, uint32_t timeoutMs = 0) = 0; - virtual ReturnValue_t unlockMutex() = 0; + /** + * Lock the mutex. The timeout value will only be used for + * TimeoutType::WAITING + * @param timeoutType + * @param timeoutMs + * @return + */ + virtual ReturnValue_t lockMutex(TimeoutType timeoutType = TimeoutType::BLOCKING, + uint32_t timeoutMs = 0) = 0; + virtual ReturnValue_t unlockMutex() = 0; - static const uint8_t INTERFACE_ID = CLASS_ID::MUTEX_IF; - /** - * The system lacked the necessary resources (other than memory) to initialize another mutex. - */ - static const ReturnValue_t NOT_ENOUGH_RESOURCES = MAKE_RETURN_CODE(1); - /** - * Insufficient memory to create or init Mutex - */ - static const ReturnValue_t INSUFFICIENT_MEMORY = MAKE_RETURN_CODE(2); - /** - * Caller does not have enough or right privilege - */ - static const ReturnValue_t NO_PRIVILEGE = MAKE_RETURN_CODE(3); - /** - * Wrong Attribute Setting - */ - static const ReturnValue_t WRONG_ATTRIBUTE_SETTING = MAKE_RETURN_CODE(4); - /** - * The mutex is already locked - */ - static const ReturnValue_t MUTEX_ALREADY_LOCKED = MAKE_RETURN_CODE(5); - /** - * Mutex object not found - */ - static const ReturnValue_t MUTEX_NOT_FOUND = MAKE_RETURN_CODE(6); - /** - * Mutex could not be locked because max amount of recursive locks - */ - static const ReturnValue_t MUTEX_MAX_LOCKS = MAKE_RETURN_CODE(7); - /** - * The current thread already owns this mutex - */ - static const ReturnValue_t CURR_THREAD_ALREADY_OWNS_MUTEX = MAKE_RETURN_CODE(8); - /** - * Current thread does not own this mutex - */ - static const ReturnValue_t CURR_THREAD_DOES_NOT_OWN_MUTEX = MAKE_RETURN_CODE(9); - /** - * The Mutex could not be blocked before timeout - */ - static const ReturnValue_t MUTEX_TIMEOUT = MAKE_RETURN_CODE(10); - /** - * Invalid Mutex ID - */ - static const ReturnValue_t MUTEX_INVALID_ID = MAKE_RETURN_CODE(11); - /** - * Mutex destroyed while waiting - */ - static const ReturnValue_t MUTEX_DESTROYED_WHILE_WAITING = MAKE_RETURN_CODE(12); + static const uint8_t INTERFACE_ID = CLASS_ID::MUTEX_IF; + /** + * The system lacked the necessary resources (other than memory) to initialize another mutex. + */ + static const ReturnValue_t NOT_ENOUGH_RESOURCES = MAKE_RETURN_CODE(1); + /** + * Insufficient memory to create or init Mutex + */ + static const ReturnValue_t INSUFFICIENT_MEMORY = MAKE_RETURN_CODE(2); + /** + * Caller does not have enough or right privilege + */ + static const ReturnValue_t NO_PRIVILEGE = MAKE_RETURN_CODE(3); + /** + * Wrong Attribute Setting + */ + static const ReturnValue_t WRONG_ATTRIBUTE_SETTING = MAKE_RETURN_CODE(4); + /** + * The mutex is already locked + */ + static const ReturnValue_t MUTEX_ALREADY_LOCKED = MAKE_RETURN_CODE(5); + /** + * Mutex object not found + */ + static const ReturnValue_t MUTEX_NOT_FOUND = MAKE_RETURN_CODE(6); + /** + * Mutex could not be locked because max amount of recursive locks + */ + static const ReturnValue_t MUTEX_MAX_LOCKS = MAKE_RETURN_CODE(7); + /** + * The current thread already owns this mutex + */ + static const ReturnValue_t CURR_THREAD_ALREADY_OWNS_MUTEX = MAKE_RETURN_CODE(8); + /** + * Current thread does not own this mutex + */ + static const ReturnValue_t CURR_THREAD_DOES_NOT_OWN_MUTEX = MAKE_RETURN_CODE(9); + /** + * The Mutex could not be blocked before timeout + */ + static const ReturnValue_t MUTEX_TIMEOUT = MAKE_RETURN_CODE(10); + /** + * Invalid Mutex ID + */ + static const ReturnValue_t MUTEX_INVALID_ID = MAKE_RETURN_CODE(11); + /** + * Mutex destroyed while waiting + */ + static const ReturnValue_t MUTEX_DESTROYED_WHILE_WAITING = MAKE_RETURN_CODE(12); - virtual ~MutexIF() {} + virtual ~MutexIF() {} }; - - #endif /* FRAMEWORK_IPC_MUTEXIF_H_ */ diff --git a/src/fsfw/ipc/QueueFactory.h b/src/fsfw/ipc/QueueFactory.h index 6fc0643e..864c456d 100644 --- a/src/fsfw/ipc/QueueFactory.h +++ b/src/fsfw/ipc/QueueFactory.h @@ -1,36 +1,37 @@ #ifndef FSFW_IPC_QUEUEFACTORY_H_ #define FSFW_IPC_QUEUEFACTORY_H_ +#include + #include "MessageQueueIF.h" #include "MessageQueueMessage.h" -#include - /** * Creates message queues. * This class is a "singleton" interface, i.e. it provides an * interface, but also is the base class for a singleton. */ class QueueFactory { -public: - virtual ~QueueFactory(); - /** - * Returns the single instance of QueueFactory. - * The implementation of #instance is found in its subclasses. - * Thus, we choose link-time variability of the instance. - */ - static QueueFactory* instance(); + public: + virtual ~QueueFactory(); + /** + * Returns the single instance of QueueFactory. + * The implementation of #instance is found in its subclasses. + * Thus, we choose link-time variability of the instance. + */ + static QueueFactory* instance(); - MessageQueueIF* createMessageQueue(uint32_t messageDepth = 3, - size_t maxMessageSize = MessageQueueMessage::MAX_MESSAGE_SIZE); + MessageQueueIF* createMessageQueue(uint32_t messageDepth = 3, + size_t maxMessageSize = MessageQueueMessage::MAX_MESSAGE_SIZE); - void deleteMessageQueue(MessageQueueIF* queue); -private: - /** - * External instantiation is not allowed. - */ - QueueFactory(); - static QueueFactory* factoryInstance; + void deleteMessageQueue(MessageQueueIF* queue); + + private: + /** + * External instantiation is not allowed. + */ + QueueFactory(); + static QueueFactory* factoryInstance; }; #endif /* FSFW_IPC_QUEUEFACTORY_H_ */ diff --git a/src/fsfw/memory/AcceptsMemoryMessagesIF.h b/src/fsfw/memory/AcceptsMemoryMessagesIF.h index 7491f47d..9eb90ad7 100644 --- a/src/fsfw/memory/AcceptsMemoryMessagesIF.h +++ b/src/fsfw/memory/AcceptsMemoryMessagesIF.h @@ -1,14 +1,13 @@ #ifndef FSFW_MEMORY_ACCEPTSMEMORYMESSAGESIF_H_ #define FSFW_MEMORY_ACCEPTSMEMORYMESSAGESIF_H_ +#include "../ipc/MessageQueueSenderIF.h" #include "HasMemoryIF.h" #include "MemoryMessage.h" -#include "../ipc/MessageQueueSenderIF.h" class AcceptsMemoryMessagesIF : public HasMemoryIF { -public: - virtual MessageQueueId_t getCommandQueue() const = 0; + public: + virtual MessageQueueId_t getCommandQueue() const = 0; }; - #endif /* FSFW_MEMORY_ACCEPTSMEMORYMESSAGESIF_H_ */ diff --git a/src/fsfw/memory/FileSystemArgsIF.h b/src/fsfw/memory/FileSystemArgsIF.h index 67d423ff..f1617f62 100644 --- a/src/fsfw/memory/FileSystemArgsIF.h +++ b/src/fsfw/memory/FileSystemArgsIF.h @@ -6,8 +6,8 @@ * Users can then dynamic_cast the base pointer to the require child pointer. */ class FileSystemArgsIF { -public: - virtual~ FileSystemArgsIF() {}; + public: + virtual ~FileSystemArgsIF(){}; }; #endif /* FSFW_SRC_FSFW_MEMORY_FILESYSTEMARGS_H_ */ diff --git a/src/fsfw/memory/GenericFileSystemMessage.cpp b/src/fsfw/memory/GenericFileSystemMessage.cpp index bd36d87b..805c7dcc 100644 --- a/src/fsfw/memory/GenericFileSystemMessage.cpp +++ b/src/fsfw/memory/GenericFileSystemMessage.cpp @@ -3,166 +3,164 @@ #include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/storagemanager/StorageManagerIF.h" -void GenericFileSystemMessage::setCreateFileCommand(CommandMessage* message, - store_address_t storeId) { - message->setCommand(CMD_CREATE_FILE); - message->setParameter2(storeId.raw); +void GenericFileSystemMessage::setCreateFileCommand(CommandMessage *message, + store_address_t storeId) { + message->setCommand(CMD_CREATE_FILE); + message->setParameter2(storeId.raw); } -void GenericFileSystemMessage::setDeleteFileCommand( - CommandMessage* message, store_address_t storeId) { - message->setCommand(CMD_DELETE_FILE); - message->setParameter2(storeId.raw); +void GenericFileSystemMessage::setDeleteFileCommand(CommandMessage *message, + store_address_t storeId) { + message->setCommand(CMD_DELETE_FILE); + message->setParameter2(storeId.raw); } -void GenericFileSystemMessage::setCreateDirectoryCommand( - CommandMessage* message, store_address_t storeId) { - message->setCommand(CMD_CREATE_DIRECTORY); - message->setParameter2(storeId.raw); +void GenericFileSystemMessage::setCreateDirectoryCommand(CommandMessage *message, + store_address_t storeId) { + message->setCommand(CMD_CREATE_DIRECTORY); + message->setParameter2(storeId.raw); } void GenericFileSystemMessage::setReportFileAttributesCommand(CommandMessage *message, - store_address_t storeId) { - message->setCommand(CMD_REPORT_FILE_ATTRIBUTES); - message->setParameter2(storeId.raw); + store_address_t storeId) { + message->setCommand(CMD_REPORT_FILE_ATTRIBUTES); + message->setParameter2(storeId.raw); } void GenericFileSystemMessage::setReportFileAttributesReply(CommandMessage *message, - store_address_t storeId) { - message->setCommand(REPLY_REPORT_FILE_ATTRIBUTES); - message->setParameter2(storeId.raw); + store_address_t storeId) { + message->setCommand(REPLY_REPORT_FILE_ATTRIBUTES); + message->setParameter2(storeId.raw); } -void GenericFileSystemMessage::setDeleteDirectoryCommand(CommandMessage* message, - store_address_t storeId, bool deleteRecursively) { - message->setCommand(CMD_DELETE_DIRECTORY); - message->setParameter(deleteRecursively); - message->setParameter2(storeId.raw); +void GenericFileSystemMessage::setDeleteDirectoryCommand(CommandMessage *message, + store_address_t storeId, + bool deleteRecursively) { + message->setCommand(CMD_DELETE_DIRECTORY); + message->setParameter(deleteRecursively); + message->setParameter2(storeId.raw); } void GenericFileSystemMessage::setLockFileCommand(CommandMessage *message, - store_address_t storeId) { - message->setCommand(CMD_LOCK_FILE); - message->setParameter2(storeId.raw); + store_address_t storeId) { + message->setCommand(CMD_LOCK_FILE); + message->setParameter2(storeId.raw); } void GenericFileSystemMessage::setUnlockFileCommand(CommandMessage *message, - store_address_t storeId) { - message->setCommand(CMD_UNLOCK_FILE); - message->setParameter2(storeId.raw); + store_address_t storeId) { + message->setCommand(CMD_UNLOCK_FILE); + message->setParameter2(storeId.raw); } void GenericFileSystemMessage::setSuccessReply(CommandMessage *message) { - message->setCommand(COMPLETION_SUCCESS); + message->setCommand(COMPLETION_SUCCESS); } -void GenericFileSystemMessage::setFailureReply(CommandMessage *message, - ReturnValue_t errorCode, uint32_t errorParam) { - message->setCommand(COMPLETION_FAILED); - message->setParameter(errorCode); - message->setParameter2(errorParam); +void GenericFileSystemMessage::setFailureReply(CommandMessage *message, ReturnValue_t errorCode, + uint32_t errorParam) { + message->setCommand(COMPLETION_FAILED); + message->setParameter(errorCode); + message->setParameter2(errorParam); } -store_address_t GenericFileSystemMessage::getStoreId(const CommandMessage* message) { - store_address_t temp; - temp.raw = message->getParameter2(); - return temp; +store_address_t GenericFileSystemMessage::getStoreId(const CommandMessage *message) { + store_address_t temp; + temp.raw = message->getParameter2(); + return temp; } -ReturnValue_t GenericFileSystemMessage::getFailureReply( - const CommandMessage *message, uint32_t* errorParam) { - if(errorParam != nullptr) { - *errorParam = message->getParameter2(); - } - return message->getParameter(); +ReturnValue_t GenericFileSystemMessage::getFailureReply(const CommandMessage *message, + uint32_t *errorParam) { + if (errorParam != nullptr) { + *errorParam = message->getParameter2(); + } + return message->getParameter(); } void GenericFileSystemMessage::setFinishStopWriteCommand(CommandMessage *message, - store_address_t storeId) { - message->setCommand(CMD_FINISH_APPEND_TO_FILE); - message->setParameter2(storeId.raw); + store_address_t storeId) { + message->setCommand(CMD_FINISH_APPEND_TO_FILE); + message->setParameter2(storeId.raw); } void GenericFileSystemMessage::setFinishStopWriteReply(CommandMessage *message, - store_address_t storeId) { - message->setCommand(REPLY_FINISH_APPEND); - message->setParameter2(storeId.raw); + store_address_t storeId) { + message->setCommand(REPLY_FINISH_APPEND); + message->setParameter2(storeId.raw); } -void GenericFileSystemMessage::setCopyCommand(CommandMessage* message, - store_address_t storeId) { - message->setCommand(CMD_COPY_FILE); - message->setParameter2(storeId.raw); +void GenericFileSystemMessage::setCopyCommand(CommandMessage *message, store_address_t storeId) { + message->setCommand(CMD_COPY_FILE); + message->setParameter2(storeId.raw); } -void GenericFileSystemMessage::setWriteCommand(CommandMessage* message, - store_address_t storeId) { - message->setCommand(CMD_APPEND_TO_FILE); - message->setParameter2(storeId.raw); +void GenericFileSystemMessage::setWriteCommand(CommandMessage *message, store_address_t storeId) { + message->setCommand(CMD_APPEND_TO_FILE); + message->setParameter2(storeId.raw); } -void GenericFileSystemMessage::setReadCommand(CommandMessage* message, - store_address_t storeId) { - message->setCommand(CMD_READ_FROM_FILE); - message->setParameter2(storeId.raw); +void GenericFileSystemMessage::setReadCommand(CommandMessage *message, store_address_t storeId) { + message->setCommand(CMD_READ_FROM_FILE); + message->setParameter2(storeId.raw); } -void GenericFileSystemMessage::setFinishAppendReply(CommandMessage* message, - store_address_t storageID) { - message->setCommand(REPLY_FINISH_APPEND); - message->setParameter2(storageID.raw); +void GenericFileSystemMessage::setFinishAppendReply(CommandMessage *message, + store_address_t storageID) { + message->setCommand(REPLY_FINISH_APPEND); + message->setParameter2(storageID.raw); } -void GenericFileSystemMessage::setReadReply(CommandMessage* message, - bool readFinished, store_address_t storeId) { - message->setCommand(REPLY_READ_FROM_FILE); - message->setParameter(readFinished); - message->setParameter2(storeId.raw); +void GenericFileSystemMessage::setReadReply(CommandMessage *message, bool readFinished, + store_address_t storeId) { + message->setCommand(REPLY_READ_FROM_FILE); + message->setParameter(readFinished); + message->setParameter2(storeId.raw); } void GenericFileSystemMessage::setReadFinishedReply(CommandMessage *message, - store_address_t storeId) { - message->setCommand(REPLY_READ_FINISHED_STOP); - message->setParameter2(storeId.raw); + store_address_t storeId) { + message->setCommand(REPLY_READ_FINISHED_STOP); + message->setParameter2(storeId.raw); } bool GenericFileSystemMessage::getReadReply(const CommandMessage *message, - store_address_t *storeId) { - if(storeId != nullptr) { - (*storeId).raw = message->getParameter2(); - } - return message->getParameter(); + store_address_t *storeId) { + if (storeId != nullptr) { + (*storeId).raw = message->getParameter2(); + } + return message->getParameter(); } store_address_t GenericFileSystemMessage::getDeleteDirectoryCommand(const CommandMessage *message, - bool &deleteRecursively) { - deleteRecursively = message->getParameter(); - return getStoreId(message); + bool &deleteRecursively) { + deleteRecursively = message->getParameter(); + return getStoreId(message); } -ReturnValue_t GenericFileSystemMessage::clear(CommandMessage* message) { - switch(message->getCommand()) { - case(CMD_CREATE_FILE): - case(CMD_DELETE_FILE): - case(CMD_CREATE_DIRECTORY): - case(CMD_REPORT_FILE_ATTRIBUTES): - case(REPLY_REPORT_FILE_ATTRIBUTES): - case(CMD_LOCK_FILE): - case(CMD_UNLOCK_FILE): - case(CMD_COPY_FILE): - case(REPLY_READ_FROM_FILE): - case(CMD_READ_FROM_FILE): - case(CMD_APPEND_TO_FILE): - case(CMD_FINISH_APPEND_TO_FILE): - case(REPLY_READ_FINISHED_STOP): - case(REPLY_FINISH_APPEND): { - store_address_t storeId = GenericFileSystemMessage::getStoreId(message); - auto ipcStore = ObjectManager::instance()->get(objects::IPC_STORE); - if(ipcStore == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - return ipcStore->deleteData(storeId); +ReturnValue_t GenericFileSystemMessage::clear(CommandMessage *message) { + switch (message->getCommand()) { + case (CMD_CREATE_FILE): + case (CMD_DELETE_FILE): + case (CMD_CREATE_DIRECTORY): + case (CMD_REPORT_FILE_ATTRIBUTES): + case (REPLY_REPORT_FILE_ATTRIBUTES): + case (CMD_LOCK_FILE): + case (CMD_UNLOCK_FILE): + case (CMD_COPY_FILE): + case (REPLY_READ_FROM_FILE): + case (CMD_READ_FROM_FILE): + case (CMD_APPEND_TO_FILE): + case (CMD_FINISH_APPEND_TO_FILE): + case (REPLY_READ_FINISHED_STOP): + case (REPLY_FINISH_APPEND): { + store_address_t storeId = GenericFileSystemMessage::getStoreId(message); + auto ipcStore = ObjectManager::instance()->get(objects::IPC_STORE); + if (ipcStore == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + return ipcStore->deleteData(storeId); } - } - return HasReturnvaluesIF::RETURN_OK; + } + return HasReturnvaluesIF::RETURN_OK; } diff --git a/src/fsfw/memory/GenericFileSystemMessage.h b/src/fsfw/memory/GenericFileSystemMessage.h index fcd2075d..af3780b8 100644 --- a/src/fsfw/memory/GenericFileSystemMessage.h +++ b/src/fsfw/memory/GenericFileSystemMessage.h @@ -1,13 +1,13 @@ #ifndef MISSION_MEMORY_GENERICFILESYSTEMMESSAGE_H_ #define MISSION_MEMORY_GENERICFILESYSTEMMESSAGE_H_ -#include - +#include #include #include -#include #include +#include + /** * @brief These messages are sent to an object implementing HasFilesystemIF. * @details @@ -16,102 +16,88 @@ * @author Jakob Meier, R. Mueller */ class GenericFileSystemMessage { -public: - /* Instantiation forbidden */ - GenericFileSystemMessage() = delete; + public: + /* Instantiation forbidden */ + GenericFileSystemMessage() = delete; - static const uint8_t MESSAGE_ID = messagetypes::FILE_SYSTEM_MESSAGE; - /* PUS standard (ECSS-E-ST-70-41C15 2016 p.654) */ - static const Command_t CMD_CREATE_FILE = MAKE_COMMAND_ID(1); - static const Command_t CMD_DELETE_FILE = MAKE_COMMAND_ID(2); - /** Report file attributes */ - static const Command_t CMD_REPORT_FILE_ATTRIBUTES = MAKE_COMMAND_ID(3); - static const Command_t REPLY_REPORT_FILE_ATTRIBUTES = MAKE_COMMAND_ID(4); - /** Command to lock a file, setting it read-only */ - static const Command_t CMD_LOCK_FILE = MAKE_COMMAND_ID(5); - /** Command to unlock a file, enabling further operations on it */ - static const Command_t CMD_UNLOCK_FILE = MAKE_COMMAND_ID(6); - /** - * Find file in repository, using a search pattern. - * Please note that * is the wildcard character. - * For example, when looking for all files which start with have the - * structure tm.bin, tm*.bin can be used. - */ - static const Command_t CMD_FIND_FILE = MAKE_COMMAND_ID(7); - static const Command_t CMD_CREATE_DIRECTORY = MAKE_COMMAND_ID(9); - static const Command_t CMD_DELETE_DIRECTORY = MAKE_COMMAND_ID(10); - static const Command_t CMD_RENAME_DIRECTORY = MAKE_COMMAND_ID(11); + static const uint8_t MESSAGE_ID = messagetypes::FILE_SYSTEM_MESSAGE; + /* PUS standard (ECSS-E-ST-70-41C15 2016 p.654) */ + static const Command_t CMD_CREATE_FILE = MAKE_COMMAND_ID(1); + static const Command_t CMD_DELETE_FILE = MAKE_COMMAND_ID(2); + /** Report file attributes */ + static const Command_t CMD_REPORT_FILE_ATTRIBUTES = MAKE_COMMAND_ID(3); + static const Command_t REPLY_REPORT_FILE_ATTRIBUTES = MAKE_COMMAND_ID(4); + /** Command to lock a file, setting it read-only */ + static const Command_t CMD_LOCK_FILE = MAKE_COMMAND_ID(5); + /** Command to unlock a file, enabling further operations on it */ + static const Command_t CMD_UNLOCK_FILE = MAKE_COMMAND_ID(6); + /** + * Find file in repository, using a search pattern. + * Please note that * is the wildcard character. + * For example, when looking for all files which start with have the + * structure tm.bin, tm*.bin can be used. + */ + static const Command_t CMD_FIND_FILE = MAKE_COMMAND_ID(7); + static const Command_t CMD_CREATE_DIRECTORY = MAKE_COMMAND_ID(9); + static const Command_t CMD_DELETE_DIRECTORY = MAKE_COMMAND_ID(10); + static const Command_t CMD_RENAME_DIRECTORY = MAKE_COMMAND_ID(11); - /** Dump contents of a repository */ - static const Command_t CMD_DUMP_REPOSITORY = MAKE_COMMAND_ID(12); - /** Repository dump reply */ - static const Command_t REPLY_DUMY_REPOSITORY = MAKE_COMMAND_ID(13); - static constexpr Command_t CMD_COPY_FILE = MAKE_COMMAND_ID(14); - static constexpr Command_t CMD_MOVE_FILE = MAKE_COMMAND_ID(15); + /** Dump contents of a repository */ + static const Command_t CMD_DUMP_REPOSITORY = MAKE_COMMAND_ID(12); + /** Repository dump reply */ + static const Command_t REPLY_DUMY_REPOSITORY = MAKE_COMMAND_ID(13); + static constexpr Command_t CMD_COPY_FILE = MAKE_COMMAND_ID(14); + static constexpr Command_t CMD_MOVE_FILE = MAKE_COMMAND_ID(15); - static const Command_t COMPLETION_SUCCESS = MAKE_COMMAND_ID(128); - static const Command_t COMPLETION_FAILED = MAKE_COMMAND_ID(129); + static const Command_t COMPLETION_SUCCESS = MAKE_COMMAND_ID(128); + static const Command_t COMPLETION_FAILED = MAKE_COMMAND_ID(129); - // These command IDs will remain until CFDP has been introduced and consolidated. - /** Append operation commands */ - static const Command_t CMD_APPEND_TO_FILE = MAKE_COMMAND_ID(130); - static const Command_t CMD_FINISH_APPEND_TO_FILE = MAKE_COMMAND_ID(131); - static const Command_t REPLY_FINISH_APPEND = MAKE_COMMAND_ID(132); + // These command IDs will remain until CFDP has been introduced and consolidated. + /** Append operation commands */ + static const Command_t CMD_APPEND_TO_FILE = MAKE_COMMAND_ID(130); + static const Command_t CMD_FINISH_APPEND_TO_FILE = MAKE_COMMAND_ID(131); + static const Command_t REPLY_FINISH_APPEND = MAKE_COMMAND_ID(132); - static const Command_t CMD_READ_FROM_FILE = MAKE_COMMAND_ID(140); - static const Command_t REPLY_READ_FROM_FILE = MAKE_COMMAND_ID(141); - static const Command_t CMD_STOP_READ = MAKE_COMMAND_ID(142); - static const Command_t REPLY_READ_FINISHED_STOP = MAKE_COMMAND_ID(143); + static const Command_t CMD_READ_FROM_FILE = MAKE_COMMAND_ID(140); + static const Command_t REPLY_READ_FROM_FILE = MAKE_COMMAND_ID(141); + static const Command_t CMD_STOP_READ = MAKE_COMMAND_ID(142); + static const Command_t REPLY_READ_FINISHED_STOP = MAKE_COMMAND_ID(143); - static void setLockFileCommand(CommandMessage* message, store_address_t storeId); - static void setUnlockFileCommand(CommandMessage* message, store_address_t storeId); + static void setLockFileCommand(CommandMessage* message, store_address_t storeId); + static void setUnlockFileCommand(CommandMessage* message, store_address_t storeId); - static void setCreateFileCommand(CommandMessage* message, - store_address_t storeId); - static void setDeleteFileCommand(CommandMessage* message, - store_address_t storeId); + static void setCreateFileCommand(CommandMessage* message, store_address_t storeId); + static void setDeleteFileCommand(CommandMessage* message, store_address_t storeId); - static void setReportFileAttributesCommand(CommandMessage* message, - store_address_t storeId); - static void setReportFileAttributesReply(CommandMessage* message, - store_address_t storeId); + static void setReportFileAttributesCommand(CommandMessage* message, store_address_t storeId); + static void setReportFileAttributesReply(CommandMessage* message, store_address_t storeId); - static void setCreateDirectoryCommand(CommandMessage* message, - store_address_t storeId); - static void setDeleteDirectoryCommand(CommandMessage* message, - store_address_t storeId, bool deleteRecursively); - static store_address_t getDeleteDirectoryCommand(const CommandMessage* message, - bool& deleteRecursively); + static void setCreateDirectoryCommand(CommandMessage* message, store_address_t storeId); + static void setDeleteDirectoryCommand(CommandMessage* message, store_address_t storeId, + bool deleteRecursively); + static store_address_t getDeleteDirectoryCommand(const CommandMessage* message, + bool& deleteRecursively); - static void setSuccessReply(CommandMessage* message); - static void setFailureReply(CommandMessage* message, - ReturnValue_t errorCode, uint32_t errorParam = 0); - static void setCopyCommand(CommandMessage* message, store_address_t storeId); + static void setSuccessReply(CommandMessage* message); + static void setFailureReply(CommandMessage* message, ReturnValue_t errorCode, + uint32_t errorParam = 0); + static void setCopyCommand(CommandMessage* message, store_address_t storeId); - static void setWriteCommand(CommandMessage* message, - store_address_t storeId); - static void setFinishStopWriteCommand(CommandMessage* message, - store_address_t storeId); - static void setFinishStopWriteReply(CommandMessage* message, - store_address_t storeId); - static void setFinishAppendReply(CommandMessage* message, - store_address_t storeId); + static void setWriteCommand(CommandMessage* message, store_address_t storeId); + static void setFinishStopWriteCommand(CommandMessage* message, store_address_t storeId); + static void setFinishStopWriteReply(CommandMessage* message, store_address_t storeId); + static void setFinishAppendReply(CommandMessage* message, store_address_t storeId); - static void setReadCommand(CommandMessage* message, - store_address_t storeId); - static void setReadFinishedReply(CommandMessage* message, - store_address_t storeId); - static void setReadReply(CommandMessage* message, bool readFinished, - store_address_t storeId); - static bool getReadReply(const CommandMessage* message, - store_address_t* storeId); + static void setReadCommand(CommandMessage* message, store_address_t storeId); + static void setReadFinishedReply(CommandMessage* message, store_address_t storeId); + static void setReadReply(CommandMessage* message, bool readFinished, store_address_t storeId); + static bool getReadReply(const CommandMessage* message, store_address_t* storeId); - static store_address_t getStoreId(const CommandMessage* message); - static ReturnValue_t getFailureReply(const CommandMessage* message, - uint32_t* errorParam = nullptr); - - static ReturnValue_t clear(CommandMessage* message); + static store_address_t getStoreId(const CommandMessage* message); + static ReturnValue_t getFailureReply(const CommandMessage* message, + uint32_t* errorParam = nullptr); + static ReturnValue_t clear(CommandMessage* message); }; #endif /* MISSION_MEMORY_GENERICFILESYSTEMMESSAGE_H_ */ diff --git a/src/fsfw/memory/HasFileSystemIF.h b/src/fsfw/memory/HasFileSystemIF.h index be2f8923..88a7db83 100644 --- a/src/fsfw/memory/HasFileSystemIF.h +++ b/src/fsfw/memory/HasFileSystemIF.h @@ -1,112 +1,113 @@ #ifndef FSFW_MEMORY_HASFILESYSTEMIF_H_ #define FSFW_MEMORY_HASFILESYSTEMIF_H_ -#include "FileSystemArgsIF.h" -#include "fsfw/returnvalues/HasReturnvaluesIF.h" -#include "fsfw/returnvalues/FwClassIds.h" -#include "fsfw/ipc/messageQueueDefinitions.h" - #include +#include "FileSystemArgsIF.h" +#include "fsfw/ipc/messageQueueDefinitions.h" +#include "fsfw/returnvalues/FwClassIds.h" +#include "fsfw/returnvalues/HasReturnvaluesIF.h" + /** * @brief Generic interface for objects which expose a file system to enable * message based file handling. * @author J. Meier, R. Mueller */ class HasFileSystemIF { -public: - static constexpr uint8_t INTERFACE_ID = CLASS_ID::FILE_SYSTEM; + public: + static constexpr uint8_t INTERFACE_ID = CLASS_ID::FILE_SYSTEM; - //! [EXPORT] : P1: Can be file system specific error code - static constexpr ReturnValue_t GENERIC_FILE_ERROR = MAKE_RETURN_CODE(0); - //! [EXPORT] : File system is currently busy - static constexpr ReturnValue_t IS_BUSY = MAKE_RETURN_CODE(1); - //! [EXPORT] : Invalid parameters like file name or repository path - static constexpr ReturnValue_t INVALID_PARAMETERS = MAKE_RETURN_CODE(2); + //! [EXPORT] : P1: Can be file system specific error code + static constexpr ReturnValue_t GENERIC_FILE_ERROR = MAKE_RETURN_CODE(0); + //! [EXPORT] : File system is currently busy + static constexpr ReturnValue_t IS_BUSY = MAKE_RETURN_CODE(1); + //! [EXPORT] : Invalid parameters like file name or repository path + static constexpr ReturnValue_t INVALID_PARAMETERS = MAKE_RETURN_CODE(2); - static constexpr ReturnValue_t FILE_DOES_NOT_EXIST = MAKE_RETURN_CODE(5); - static constexpr ReturnValue_t FILE_ALREADY_EXISTS = MAKE_RETURN_CODE(6); - static constexpr ReturnValue_t FILE_LOCKED = MAKE_RETURN_CODE(7); + static constexpr ReturnValue_t FILE_DOES_NOT_EXIST = MAKE_RETURN_CODE(5); + static constexpr ReturnValue_t FILE_ALREADY_EXISTS = MAKE_RETURN_CODE(6); + static constexpr ReturnValue_t FILE_LOCKED = MAKE_RETURN_CODE(7); - static constexpr ReturnValue_t DIRECTORY_DOES_NOT_EXIST = MAKE_RETURN_CODE(10); - static constexpr ReturnValue_t DIRECTORY_ALREADY_EXISTS = MAKE_RETURN_CODE(11); - static constexpr ReturnValue_t DIRECTORY_NOT_EMPTY = MAKE_RETURN_CODE(12); + static constexpr ReturnValue_t DIRECTORY_DOES_NOT_EXIST = MAKE_RETURN_CODE(10); + static constexpr ReturnValue_t DIRECTORY_ALREADY_EXISTS = MAKE_RETURN_CODE(11); + static constexpr ReturnValue_t DIRECTORY_NOT_EMPTY = MAKE_RETURN_CODE(12); - //! [EXPORT] : P1: Sequence number missing - static constexpr ReturnValue_t SEQUENCE_PACKET_MISSING_WRITE = MAKE_RETURN_CODE(15); - //! [EXPORT] : P1: Sequence number missing - static constexpr ReturnValue_t SEQUENCE_PACKET_MISSING_READ = MAKE_RETURN_CODE(16); + //! [EXPORT] : P1: Sequence number missing + static constexpr ReturnValue_t SEQUENCE_PACKET_MISSING_WRITE = MAKE_RETURN_CODE(15); + //! [EXPORT] : P1: Sequence number missing + static constexpr ReturnValue_t SEQUENCE_PACKET_MISSING_READ = MAKE_RETURN_CODE(16); - virtual ~HasFileSystemIF() {} + virtual ~HasFileSystemIF() {} - /** - * Function to get the MessageQueueId_t of the implementing object - * @return MessageQueueId_t of the object - */ - virtual MessageQueueId_t getCommandQueue() const = 0; + /** + * Function to get the MessageQueueId_t of the implementing object + * @return MessageQueueId_t of the object + */ + virtual MessageQueueId_t getCommandQueue() const = 0; - /** - * @brief Generic function to append to file. - * @param dirname Directory of the file - * @param filename The filename of the file - * @param data The data to write to the file - * @param size The size of the data to write - * @param packetNumber Current packet number. Can be used to verify that - * there are no missing packets. - * @param args Any other arguments which an implementation might require. - * @param bytesWritten Actual bytes written to file - * For large files the write procedure must be split in multiple calls - * to writeToFile - */ - virtual ReturnValue_t appendToFile(const char* repositoryPath, - const char* filename, const uint8_t* data, size_t size, - uint16_t packetNumber, FileSystemArgsIF* args = nullptr) = 0; + /** + * @brief Generic function to append to file. + * @param dirname Directory of the file + * @param filename The filename of the file + * @param data The data to write to the file + * @param size The size of the data to write + * @param packetNumber Current packet number. Can be used to verify that + * there are no missing packets. + * @param args Any other arguments which an implementation might require. + * @param bytesWritten Actual bytes written to file + * For large files the write procedure must be split in multiple calls + * to writeToFile + */ + virtual ReturnValue_t appendToFile(const char* repositoryPath, const char* filename, + const uint8_t* data, size_t size, uint16_t packetNumber, + FileSystemArgsIF* args = nullptr) = 0; - /** - * @brief Generic function to create a new file. - * @param repositoryPath - * @param filename - * @param data - * @param size - * @param args Any other arguments which an implementation might require - * @return - */ - virtual ReturnValue_t createFile(const char* repositoryPath, - const char* filename, const uint8_t* data = nullptr, - size_t size = 0, FileSystemArgsIF* args = nullptr) = 0; + /** + * @brief Generic function to create a new file. + * @param repositoryPath + * @param filename + * @param data + * @param size + * @param args Any other arguments which an implementation might require + * @return + */ + virtual ReturnValue_t createFile(const char* repositoryPath, const char* filename, + const uint8_t* data = nullptr, size_t size = 0, + FileSystemArgsIF* args = nullptr) = 0; - /** - * @brief Generic function to delete a file. - * @param repositoryPath - * @param filename - * @param args Any other arguments which an implementation might require - * @return - */ - virtual ReturnValue_t removeFile(const char* repositoryPath, - const char* filename, FileSystemArgsIF* args = nullptr) = 0; + /** + * @brief Generic function to delete a file. + * @param repositoryPath + * @param filename + * @param args Any other arguments which an implementation might require + * @return + */ + virtual ReturnValue_t removeFile(const char* repositoryPath, const char* filename, + FileSystemArgsIF* args = nullptr) = 0; - /** - * @brief Generic function to create a directory - * @param repositoryPath - * @param Equivalent to the -p flag in Unix systems. If some required parent directories - * do not exist, create them as well - * @param args Any other arguments which an implementation might require - * @return - */ - virtual ReturnValue_t createDirectory(const char* repositoryPath, const char* dirname, - bool createParentDirs, FileSystemArgsIF* args = nullptr) = 0; + /** + * @brief Generic function to create a directory + * @param repositoryPath + * @param Equivalent to the -p flag in Unix systems. If some required parent directories + * do not exist, create them as well + * @param args Any other arguments which an implementation might require + * @return + */ + virtual ReturnValue_t createDirectory(const char* repositoryPath, const char* dirname, + bool createParentDirs, + FileSystemArgsIF* args = nullptr) = 0; - /** - * @brief Generic function to remove a directory - * @param repositoryPath - * @param args Any other arguments which an implementation might require - */ - virtual ReturnValue_t removeDirectory(const char* repositoryPath, const char* dirname, - bool deleteRecurively = false, FileSystemArgsIF* args = nullptr) = 0; + /** + * @brief Generic function to remove a directory + * @param repositoryPath + * @param args Any other arguments which an implementation might require + */ + virtual ReturnValue_t removeDirectory(const char* repositoryPath, const char* dirname, + bool deleteRecurively = false, + FileSystemArgsIF* args = nullptr) = 0; - virtual ReturnValue_t renameFile(const char* repositoryPath, const char* oldFilename, - const char* newFilename, FileSystemArgsIF* args = nullptr) = 0; + virtual ReturnValue_t renameFile(const char* repositoryPath, const char* oldFilename, + const char* newFilename, FileSystemArgsIF* args = nullptr) = 0; }; - #endif /* FSFW_MEMORY_HASFILESYSTEMIF_H_ */ diff --git a/src/fsfw/memory/HasMemoryIF.h b/src/fsfw/memory/HasMemoryIF.h index 4096d1b7..7aa66377 100644 --- a/src/fsfw/memory/HasMemoryIF.h +++ b/src/fsfw/memory/HasMemoryIF.h @@ -4,44 +4,47 @@ #include "../returnvalues/HasReturnvaluesIF.h" class HasMemoryIF { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::HAS_MEMORY_IF; - static const ReturnValue_t DO_IT_MYSELF = MAKE_RETURN_CODE(1); - static const ReturnValue_t POINTS_TO_VARIABLE = MAKE_RETURN_CODE(2); - static const ReturnValue_t POINTS_TO_MEMORY = MAKE_RETURN_CODE(3); - static const ReturnValue_t ACTIVITY_COMPLETED = MAKE_RETURN_CODE(4); - static const ReturnValue_t POINTS_TO_VECTOR_UINT8 = MAKE_RETURN_CODE(5); - static const ReturnValue_t POINTS_TO_VECTOR_UINT16 = MAKE_RETURN_CODE(6); - static const ReturnValue_t POINTS_TO_VECTOR_UINT32 = MAKE_RETURN_CODE(7); - static const ReturnValue_t POINTS_TO_VECTOR_FLOAT = MAKE_RETURN_CODE(8); - static const ReturnValue_t DUMP_NOT_SUPPORTED = MAKE_RETURN_CODE(0xA0); - static const ReturnValue_t INVALID_SIZE = MAKE_RETURN_CODE(0xE0); - static const ReturnValue_t INVALID_ADDRESS = MAKE_RETURN_CODE(0xE1); - static const ReturnValue_t INVALID_CONTENT = MAKE_RETURN_CODE(0xE2); - static const ReturnValue_t UNALIGNED_ACCESS = MAKE_RETURN_CODE(0xE3); - static const ReturnValue_t WRITE_PROTECTED = MAKE_RETURN_CODE(0xE4); -// static const ReturnValue_t TARGET_BUSY = MAKE_RETURN_CODE(0xE5); - virtual ~HasMemoryIF() {} - virtual ReturnValue_t handleMemoryLoad(uint32_t address, const uint8_t* data, uint32_t size, uint8_t** dataPointer) = 0; - virtual ReturnValue_t handleMemoryDump(uint32_t address, uint32_t size, uint8_t** dataPointer, uint8_t* dumpTarget ) = 0; - /** - * Sets the address of the memory, if possible. - * startAddress is a proposal for an address, or the base address if multiple addresses are set. - */ - virtual ReturnValue_t setAddress( uint32_t* startAddress ) { return HasReturnvaluesIF::RETURN_FAILED; } - static bool memAccessWasSuccessful(ReturnValue_t result) { - switch (result) { - case DO_IT_MYSELF: - case POINTS_TO_MEMORY: - case POINTS_TO_VARIABLE: - case HasReturnvaluesIF::RETURN_OK: - case ACTIVITY_COMPLETED: - return true; - default: - return false; - } - } + public: + static const uint8_t INTERFACE_ID = CLASS_ID::HAS_MEMORY_IF; + static const ReturnValue_t DO_IT_MYSELF = MAKE_RETURN_CODE(1); + static const ReturnValue_t POINTS_TO_VARIABLE = MAKE_RETURN_CODE(2); + static const ReturnValue_t POINTS_TO_MEMORY = MAKE_RETURN_CODE(3); + static const ReturnValue_t ACTIVITY_COMPLETED = MAKE_RETURN_CODE(4); + static const ReturnValue_t POINTS_TO_VECTOR_UINT8 = MAKE_RETURN_CODE(5); + static const ReturnValue_t POINTS_TO_VECTOR_UINT16 = MAKE_RETURN_CODE(6); + static const ReturnValue_t POINTS_TO_VECTOR_UINT32 = MAKE_RETURN_CODE(7); + static const ReturnValue_t POINTS_TO_VECTOR_FLOAT = MAKE_RETURN_CODE(8); + static const ReturnValue_t DUMP_NOT_SUPPORTED = MAKE_RETURN_CODE(0xA0); + static const ReturnValue_t INVALID_SIZE = MAKE_RETURN_CODE(0xE0); + static const ReturnValue_t INVALID_ADDRESS = MAKE_RETURN_CODE(0xE1); + static const ReturnValue_t INVALID_CONTENT = MAKE_RETURN_CODE(0xE2); + static const ReturnValue_t UNALIGNED_ACCESS = MAKE_RETURN_CODE(0xE3); + static const ReturnValue_t WRITE_PROTECTED = MAKE_RETURN_CODE(0xE4); + // static const ReturnValue_t TARGET_BUSY = MAKE_RETURN_CODE(0xE5); + virtual ~HasMemoryIF() {} + virtual ReturnValue_t handleMemoryLoad(uint32_t address, const uint8_t* data, uint32_t size, + uint8_t** dataPointer) = 0; + virtual ReturnValue_t handleMemoryDump(uint32_t address, uint32_t size, uint8_t** dataPointer, + uint8_t* dumpTarget) = 0; + /** + * Sets the address of the memory, if possible. + * startAddress is a proposal for an address, or the base address if multiple addresses are set. + */ + virtual ReturnValue_t setAddress(uint32_t* startAddress) { + return HasReturnvaluesIF::RETURN_FAILED; + } + static bool memAccessWasSuccessful(ReturnValue_t result) { + switch (result) { + case DO_IT_MYSELF: + case POINTS_TO_MEMORY: + case POINTS_TO_VARIABLE: + case HasReturnvaluesIF::RETURN_OK: + case ACTIVITY_COMPLETED: + return true; + default: + return false; + } + } }; - #endif /* HASMEMORYIF_H_ */ diff --git a/src/fsfw/memory/MemoryHelper.cpp b/src/fsfw/memory/MemoryHelper.cpp index 2039a488..462a818e 100644 --- a/src/fsfw/memory/MemoryHelper.cpp +++ b/src/fsfw/memory/MemoryHelper.cpp @@ -1,196 +1,192 @@ #include "fsfw/memory/MemoryHelper.h" -#include "fsfw/memory/MemoryMessage.h" #include "fsfw/globalfunctions/CRC.h" +#include "fsfw/memory/MemoryMessage.h" #include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/serialize/EndianConverter.h" #include "fsfw/serviceinterface/ServiceInterface.h" -MemoryHelper::MemoryHelper(HasMemoryIF* workOnThis, - MessageQueueIF* useThisQueue): - workOnThis(workOnThis), queueToUse(useThisQueue), ipcAddress(), - lastCommand(CommandMessage::CMD_NONE), busy(false) { -} +MemoryHelper::MemoryHelper(HasMemoryIF* workOnThis, MessageQueueIF* useThisQueue) + : workOnThis(workOnThis), + queueToUse(useThisQueue), + ipcAddress(), + lastCommand(CommandMessage::CMD_NONE), + busy(false) {} ReturnValue_t MemoryHelper::handleMemoryCommand(CommandMessage* message) { - lastSender = message->getSender(); - lastCommand = message->getCommand(); - if (busy) { + lastSender = message->getSender(); + lastCommand = message->getCommand(); + if (busy) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "MemHelper: Busy!" << std::endl; + sif::debug << "MemHelper: Busy!" << std::endl; #endif - } - switch (lastCommand) { - case MemoryMessage::CMD_MEMORY_DUMP: - handleMemoryCheckOrDump(message); - return RETURN_OK; - case MemoryMessage::CMD_MEMORY_LOAD: - handleMemoryLoad(message); - return RETURN_OK; - case MemoryMessage::CMD_MEMORY_CHECK: - handleMemoryCheckOrDump(message); - return RETURN_OK; - default: - lastCommand = CommandMessage::CMD_NONE; - return UNKNOWN_CMD; - } + } + switch (lastCommand) { + case MemoryMessage::CMD_MEMORY_DUMP: + handleMemoryCheckOrDump(message); + return RETURN_OK; + case MemoryMessage::CMD_MEMORY_LOAD: + handleMemoryLoad(message); + return RETURN_OK; + case MemoryMessage::CMD_MEMORY_CHECK: + handleMemoryCheckOrDump(message); + return RETURN_OK; + default: + lastCommand = CommandMessage::CMD_NONE; + return UNKNOWN_CMD; + } } -void MemoryHelper::completeLoad(ReturnValue_t errorCode, - const uint8_t* dataToCopy, const size_t size, uint8_t* copyHere) { - busy = false; - switch (errorCode) { - case HasMemoryIF::DO_IT_MYSELF: - busy = true; - return; - case HasMemoryIF::POINTS_TO_MEMORY: - memcpy(copyHere, dataToCopy, size); - break; - case HasMemoryIF::POINTS_TO_VARIABLE: - EndianConverter::convertBigEndian(copyHere, dataToCopy, size); - break; - case HasMemoryIF::ACTIVITY_COMPLETED: - case RETURN_OK: - break; - default: - ipcStore->deleteData(ipcAddress); - CommandMessage reply; - MemoryMessage::setMemoryReplyFailed(&reply, errorCode, - MemoryMessage::CMD_MEMORY_LOAD); - queueToUse->sendMessage(lastSender, &reply); - return; - } - //Only reached on success - CommandMessage reply( CommandMessage::REPLY_COMMAND_OK, 0, 0); - queueToUse->sendMessage(lastSender, &reply); - ipcStore->deleteData(ipcAddress); +void MemoryHelper::completeLoad(ReturnValue_t errorCode, const uint8_t* dataToCopy, + const size_t size, uint8_t* copyHere) { + busy = false; + switch (errorCode) { + case HasMemoryIF::DO_IT_MYSELF: + busy = true; + return; + case HasMemoryIF::POINTS_TO_MEMORY: + memcpy(copyHere, dataToCopy, size); + break; + case HasMemoryIF::POINTS_TO_VARIABLE: + EndianConverter::convertBigEndian(copyHere, dataToCopy, size); + break; + case HasMemoryIF::ACTIVITY_COMPLETED: + case RETURN_OK: + break; + default: + ipcStore->deleteData(ipcAddress); + CommandMessage reply; + MemoryMessage::setMemoryReplyFailed(&reply, errorCode, MemoryMessage::CMD_MEMORY_LOAD); + queueToUse->sendMessage(lastSender, &reply); + return; + } + // Only reached on success + CommandMessage reply(CommandMessage::REPLY_COMMAND_OK, 0, 0); + queueToUse->sendMessage(lastSender, &reply); + ipcStore->deleteData(ipcAddress); } -void MemoryHelper::completeDump(ReturnValue_t errorCode, - const uint8_t* dataToCopy, const size_t size) { - busy = false; - CommandMessage reply; - MemoryMessage::setMemoryReplyFailed(&reply, errorCode, lastCommand); - switch (errorCode) { - case HasMemoryIF::DO_IT_MYSELF: - busy = true; - return; - case HasReturnvaluesIF::RETURN_OK: - case HasMemoryIF::POINTS_TO_MEMORY: - case HasMemoryIF::POINTS_TO_VARIABLE: - //"data" must be valid pointer! - if (errorCode == HasMemoryIF::POINTS_TO_VARIABLE) { - EndianConverter::convertBigEndian(reservedSpaceInIPC, dataToCopy, size); - } else { - memcpy(reservedSpaceInIPC, dataToCopy, size); - } - /* NO BREAK falls through*/ - case HasMemoryIF::ACTIVITY_COMPLETED: - switch (lastCommand) { - case MemoryMessage::CMD_MEMORY_DUMP: { - MemoryMessage::setMemoryDumpReply(&reply, ipcAddress); - break; - } - case MemoryMessage::CMD_MEMORY_CHECK: { - uint16_t crc = CRC::crc16ccitt(reservedSpaceInIPC, size); - //Delete data immediately, was temporary. - ipcStore->deleteData(ipcAddress); - MemoryMessage::setMemoryCheckReply(&reply, crc); - break; - } - default: - //This should never happen! - //Is it ok to send message? Otherwise: return; - ipcStore->deleteData(ipcAddress); - reply.setParameter(STATE_MISMATCH); - break; - } - break; - case HasMemoryIF::DUMP_NOT_SUPPORTED: - if (lastCommand == MemoryMessage::CMD_MEMORY_CHECK){ - MemoryMessage::setMemoryCheckReply(&reply, 0); - MemoryMessage::setCrcReturnValue(&reply,HasMemoryIF::DUMP_NOT_SUPPORTED); - } - ipcStore->deleteData(ipcAddress); - break; - default: - //Reply is already set to REJECTED. - ipcStore->deleteData(ipcAddress); - break; - } - if (queueToUse->sendMessage(lastSender, &reply) != RETURN_OK) { - reply.clear(); - } +void MemoryHelper::completeDump(ReturnValue_t errorCode, const uint8_t* dataToCopy, + const size_t size) { + busy = false; + CommandMessage reply; + MemoryMessage::setMemoryReplyFailed(&reply, errorCode, lastCommand); + switch (errorCode) { + case HasMemoryIF::DO_IT_MYSELF: + busy = true; + return; + case HasReturnvaluesIF::RETURN_OK: + case HasMemoryIF::POINTS_TO_MEMORY: + case HasMemoryIF::POINTS_TO_VARIABLE: + //"data" must be valid pointer! + if (errorCode == HasMemoryIF::POINTS_TO_VARIABLE) { + EndianConverter::convertBigEndian(reservedSpaceInIPC, dataToCopy, size); + } else { + memcpy(reservedSpaceInIPC, dataToCopy, size); + } + /* NO BREAK falls through*/ + case HasMemoryIF::ACTIVITY_COMPLETED: + switch (lastCommand) { + case MemoryMessage::CMD_MEMORY_DUMP: { + MemoryMessage::setMemoryDumpReply(&reply, ipcAddress); + break; + } + case MemoryMessage::CMD_MEMORY_CHECK: { + uint16_t crc = CRC::crc16ccitt(reservedSpaceInIPC, size); + // Delete data immediately, was temporary. + ipcStore->deleteData(ipcAddress); + MemoryMessage::setMemoryCheckReply(&reply, crc); + break; + } + default: + // This should never happen! + // Is it ok to send message? Otherwise: return; + ipcStore->deleteData(ipcAddress); + reply.setParameter(STATE_MISMATCH); + break; + } + break; + case HasMemoryIF::DUMP_NOT_SUPPORTED: + if (lastCommand == MemoryMessage::CMD_MEMORY_CHECK) { + MemoryMessage::setMemoryCheckReply(&reply, 0); + MemoryMessage::setCrcReturnValue(&reply, HasMemoryIF::DUMP_NOT_SUPPORTED); + } + ipcStore->deleteData(ipcAddress); + break; + default: + // Reply is already set to REJECTED. + ipcStore->deleteData(ipcAddress); + break; + } + if (queueToUse->sendMessage(lastSender, &reply) != RETURN_OK) { + reply.clear(); + } } -void MemoryHelper::swapMatrixCopy(uint8_t* out, const uint8_t *in, - size_t totalSize, uint8_t datatypeSize) { - if (totalSize % datatypeSize != 0){ - return; - } +void MemoryHelper::swapMatrixCopy(uint8_t* out, const uint8_t* in, size_t totalSize, + uint8_t datatypeSize) { + if (totalSize % datatypeSize != 0) { + return; + } - while (totalSize > 0){ - EndianConverter::convertBigEndian(out,in,datatypeSize); - out += datatypeSize; - in += datatypeSize; - totalSize -= datatypeSize; - } + while (totalSize > 0) { + EndianConverter::convertBigEndian(out, in, datatypeSize); + out += datatypeSize; + in += datatypeSize; + totalSize -= datatypeSize; + } } MemoryHelper::~MemoryHelper() { - //Nothing to destroy + // Nothing to destroy } void MemoryHelper::handleMemoryLoad(CommandMessage* message) { - uint32_t address = MemoryMessage::getAddress(message); - ipcAddress = MemoryMessage::getStoreID(message); - const uint8_t* p_data = NULL; - uint8_t* dataPointer = NULL; - size_t size = 0; - ReturnValue_t returnCode = ipcStore->getData(ipcAddress, &p_data, &size); - if (returnCode == RETURN_OK) { - returnCode = workOnThis->handleMemoryLoad(address, p_data, size, - &dataPointer); - completeLoad(returnCode, p_data, size, dataPointer); - } else { - //At least inform sender. - CommandMessage reply; - MemoryMessage::setMemoryReplyFailed(&reply, returnCode, - MemoryMessage::CMD_MEMORY_LOAD); - queueToUse->sendMessage(lastSender, &reply); - } + uint32_t address = MemoryMessage::getAddress(message); + ipcAddress = MemoryMessage::getStoreID(message); + const uint8_t* p_data = NULL; + uint8_t* dataPointer = NULL; + size_t size = 0; + ReturnValue_t returnCode = ipcStore->getData(ipcAddress, &p_data, &size); + if (returnCode == RETURN_OK) { + returnCode = workOnThis->handleMemoryLoad(address, p_data, size, &dataPointer); + completeLoad(returnCode, p_data, size, dataPointer); + } else { + // At least inform sender. + CommandMessage reply; + MemoryMessage::setMemoryReplyFailed(&reply, returnCode, MemoryMessage::CMD_MEMORY_LOAD); + queueToUse->sendMessage(lastSender, &reply); + } } void MemoryHelper::handleMemoryCheckOrDump(CommandMessage* message) { - uint32_t address = MemoryMessage::getAddress(message); - uint32_t size = MemoryMessage::getLength(message); - uint8_t* dataPointer = NULL; - ReturnValue_t returnCode = ipcStore->getFreeElement(&ipcAddress, size, - &reservedSpaceInIPC); - if (returnCode == RETURN_OK) { - returnCode = workOnThis->handleMemoryDump(address, size, &dataPointer, - reservedSpaceInIPC); - completeDump(returnCode, dataPointer, size); - } else { - CommandMessage reply; - MemoryMessage::setMemoryReplyFailed(&reply, returnCode, lastCommand); - queueToUse->sendMessage(lastSender, &reply); - } + uint32_t address = MemoryMessage::getAddress(message); + uint32_t size = MemoryMessage::getLength(message); + uint8_t* dataPointer = NULL; + ReturnValue_t returnCode = ipcStore->getFreeElement(&ipcAddress, size, &reservedSpaceInIPC); + if (returnCode == RETURN_OK) { + returnCode = workOnThis->handleMemoryDump(address, size, &dataPointer, reservedSpaceInIPC); + completeDump(returnCode, dataPointer, size); + } else { + CommandMessage reply; + MemoryMessage::setMemoryReplyFailed(&reply, returnCode, lastCommand); + queueToUse->sendMessage(lastSender, &reply); + } } ReturnValue_t MemoryHelper::initialize(MessageQueueIF* queueToUse_) { - if(queueToUse_ == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - this->queueToUse = queueToUse_; - return initialize(); + if (queueToUse_ == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + this->queueToUse = queueToUse_; + return initialize(); } ReturnValue_t MemoryHelper::initialize() { - ipcStore = ObjectManager::instance()->get(objects::IPC_STORE); - if (ipcStore != nullptr) { - return RETURN_OK; - } else { - return RETURN_FAILED; - } + ipcStore = ObjectManager::instance()->get(objects::IPC_STORE); + if (ipcStore != nullptr) { + return RETURN_OK; + } else { + return RETURN_FAILED; + } } diff --git a/src/fsfw/memory/MemoryHelper.h b/src/fsfw/memory/MemoryHelper.h index a651861c..7a645b79 100644 --- a/src/fsfw/memory/MemoryHelper.h +++ b/src/fsfw/memory/MemoryHelper.h @@ -1,49 +1,45 @@ #ifndef FSFW_MEMORY_MEMORYHELPER_H_ #define FSFW_MEMORY_MEMORYHELPER_H_ -#include "AcceptsMemoryMessagesIF.h" - #include "../ipc/CommandMessage.h" +#include "../ipc/MessageQueueIF.h" #include "../returnvalues/HasReturnvaluesIF.h" #include "../storagemanager/StorageManagerIF.h" -#include "../ipc/MessageQueueIF.h" +#include "AcceptsMemoryMessagesIF.h" /** * @brief TODO: documentation. */ class MemoryHelper : public HasReturnvaluesIF { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::MEMORY_HELPER; - static const ReturnValue_t UNKNOWN_CMD = MAKE_RETURN_CODE(0xE0); - static const ReturnValue_t INVALID_ADDRESS = MAKE_RETURN_CODE(0xE1); - static const ReturnValue_t INVALID_SIZE = MAKE_RETURN_CODE(0xE2); - static const ReturnValue_t STATE_MISMATCH = MAKE_RETURN_CODE(0xE3); + public: + static const uint8_t INTERFACE_ID = CLASS_ID::MEMORY_HELPER; + static const ReturnValue_t UNKNOWN_CMD = MAKE_RETURN_CODE(0xE0); + static const ReturnValue_t INVALID_ADDRESS = MAKE_RETURN_CODE(0xE1); + static const ReturnValue_t INVALID_SIZE = MAKE_RETURN_CODE(0xE2); + static const ReturnValue_t STATE_MISMATCH = MAKE_RETURN_CODE(0xE3); - MemoryHelper(HasMemoryIF* workOnThis, MessageQueueIF* useThisQueue); - ~MemoryHelper(); + MemoryHelper(HasMemoryIF* workOnThis, MessageQueueIF* useThisQueue); + ~MemoryHelper(); - ReturnValue_t handleMemoryCommand(CommandMessage* message); - void completeLoad(ReturnValue_t errorCode, - const uint8_t* dataToCopy = nullptr, const size_t size = 0, - uint8_t* copyHere = nullptr); - void completeDump(ReturnValue_t errorCode, - const uint8_t* dataToCopy = nullptr, const size_t size = 0); - void swapMatrixCopy(uint8_t *out, const uint8_t *in, size_t totalSize, - uint8_t datatypeSize); - ReturnValue_t initialize(MessageQueueIF* queueToUse_); - -private: - HasMemoryIF* workOnThis; - MessageQueueIF* queueToUse; - StorageManagerIF* ipcStore = nullptr; - store_address_t ipcAddress; - Command_t lastCommand; - MessageQueueId_t lastSender = MessageQueueIF::NO_QUEUE; - uint8_t* reservedSpaceInIPC = nullptr; - bool busy; - void handleMemoryLoad(CommandMessage* message); - void handleMemoryCheckOrDump(CommandMessage* message); - ReturnValue_t initialize(); + ReturnValue_t handleMemoryCommand(CommandMessage* message); + void completeLoad(ReturnValue_t errorCode, const uint8_t* dataToCopy = nullptr, + const size_t size = 0, uint8_t* copyHere = nullptr); + void completeDump(ReturnValue_t errorCode, const uint8_t* dataToCopy = nullptr, + const size_t size = 0); + void swapMatrixCopy(uint8_t* out, const uint8_t* in, size_t totalSize, uint8_t datatypeSize); + ReturnValue_t initialize(MessageQueueIF* queueToUse_); + private: + HasMemoryIF* workOnThis; + MessageQueueIF* queueToUse; + StorageManagerIF* ipcStore = nullptr; + store_address_t ipcAddress; + Command_t lastCommand; + MessageQueueId_t lastSender = MessageQueueIF::NO_QUEUE; + uint8_t* reservedSpaceInIPC = nullptr; + bool busy; + void handleMemoryLoad(CommandMessage* message); + void handleMemoryCheckOrDump(CommandMessage* message); + ReturnValue_t initialize(); }; #endif /* FSFW_MEMORY_MEMORYHELPER_H_ */ diff --git a/src/fsfw/memory/MemoryMessage.cpp b/src/fsfw/memory/MemoryMessage.cpp index 9df52609..541b34e6 100644 --- a/src/fsfw/memory/MemoryMessage.cpp +++ b/src/fsfw/memory/MemoryMessage.cpp @@ -3,105 +3,101 @@ #include "fsfw/objectmanager/ObjectManager.h" uint32_t MemoryMessage::getAddress(const CommandMessage* message) { - return message->getParameter(); + return message->getParameter(); } store_address_t MemoryMessage::getStoreID(const CommandMessage* message) { - store_address_t temp; - temp.raw = message->getParameter2(); - return temp; + store_address_t temp; + temp.raw = message->getParameter2(); + return temp; } uint32_t MemoryMessage::getLength(const CommandMessage* message) { - return message->getParameter2(); + return message->getParameter2(); } -void MemoryMessage::setMemoryDumpCommand(CommandMessage* message, - uint32_t address, uint32_t length) { - message->setCommand(CMD_MEMORY_DUMP); - message->setParameter( address ); - message->setParameter2( length ); +void MemoryMessage::setMemoryDumpCommand(CommandMessage* message, uint32_t address, + uint32_t length) { + message->setCommand(CMD_MEMORY_DUMP); + message->setParameter(address); + message->setParameter2(length); } -void MemoryMessage::setMemoryDumpReply(CommandMessage* message, - store_address_t storageID) { - message->setCommand(REPLY_MEMORY_DUMP); - message->setParameter2( storageID.raw ); +void MemoryMessage::setMemoryDumpReply(CommandMessage* message, store_address_t storageID) { + message->setCommand(REPLY_MEMORY_DUMP); + message->setParameter2(storageID.raw); } -void MemoryMessage::setMemoryLoadCommand(CommandMessage* message, - uint32_t address, store_address_t storageID) { - message->setCommand(CMD_MEMORY_LOAD); - message->setParameter( address ); - message->setParameter2( storageID.raw ); +void MemoryMessage::setMemoryLoadCommand(CommandMessage* message, uint32_t address, + store_address_t storageID) { + message->setCommand(CMD_MEMORY_LOAD); + message->setParameter(address); + message->setParameter2(storageID.raw); } ReturnValue_t MemoryMessage::getErrorCode(const CommandMessage* message) { - return message->getParameter(); + return message->getParameter(); } void MemoryMessage::clear(CommandMessage* message) { - switch (message->getCommand()) { - case CMD_MEMORY_LOAD: - case REPLY_MEMORY_DUMP: { - StorageManagerIF *ipcStore = ObjectManager::instance()->get( - objects::IPC_STORE); - if (ipcStore != NULL) { - ipcStore->deleteData(getStoreID(message)); - } - } - /* NO BREAK falls through*/ - case CMD_MEMORY_DUMP: - case CMD_MEMORY_CHECK: - case REPLY_MEMORY_CHECK: - case END_OF_MEMORY_COPY: - message->setCommand(CommandMessage::CMD_NONE); - message->setParameter(0); - message->setParameter2(0); - break; - } + switch (message->getCommand()) { + case CMD_MEMORY_LOAD: + case REPLY_MEMORY_DUMP: { + StorageManagerIF* ipcStore = + ObjectManager::instance()->get(objects::IPC_STORE); + if (ipcStore != NULL) { + ipcStore->deleteData(getStoreID(message)); + } + } + /* NO BREAK falls through*/ + case CMD_MEMORY_DUMP: + case CMD_MEMORY_CHECK: + case REPLY_MEMORY_CHECK: + case END_OF_MEMORY_COPY: + message->setCommand(CommandMessage::CMD_NONE); + message->setParameter(0); + message->setParameter2(0); + break; + } } -void MemoryMessage::setMemoryCheckCommand(CommandMessage* message, - uint32_t address, uint32_t length) { - message->setCommand(CMD_MEMORY_CHECK); - message->setParameter( address ); - message->setParameter2( length ); +void MemoryMessage::setMemoryCheckCommand(CommandMessage* message, uint32_t address, + uint32_t length) { + message->setCommand(CMD_MEMORY_CHECK); + message->setParameter(address); + message->setParameter2(length); } -void MemoryMessage::setMemoryCheckReply(CommandMessage* message, - uint16_t crc) { - message->setCommand(REPLY_MEMORY_CHECK); - message->setParameter( crc ); +void MemoryMessage::setMemoryCheckReply(CommandMessage* message, uint16_t crc) { + message->setCommand(REPLY_MEMORY_CHECK); + message->setParameter(crc); } -void MemoryMessage::setCrcReturnValue(CommandMessage* message, - ReturnValue_t returnValue){ - message->setParameter(returnValue<<16); +void MemoryMessage::setCrcReturnValue(CommandMessage* message, ReturnValue_t returnValue) { + message->setParameter(returnValue << 16); }; uint16_t MemoryMessage::getCrc(const CommandMessage* message) { - return (uint16_t)(message->getParameter()); + return (uint16_t)(message->getParameter()); } -ReturnValue_t MemoryMessage::getCrcReturnValue(const CommandMessage* message){ - return (message->getParameter()>>16); +ReturnValue_t MemoryMessage::getCrcReturnValue(const CommandMessage* message) { + return (message->getParameter() >> 16); } Command_t MemoryMessage::getInitialCommand(const CommandMessage* message) { - return message->getParameter2(); + return message->getParameter2(); } -void MemoryMessage::setMemoryReplyFailed(CommandMessage* message, - ReturnValue_t errorCode, Command_t initialCommand) { - message->setCommand(REPLY_MEMORY_FAILED); - message->setParameter(errorCode); - message->setParameter2(initialCommand); +void MemoryMessage::setMemoryReplyFailed(CommandMessage* message, ReturnValue_t errorCode, + Command_t initialCommand) { + message->setCommand(REPLY_MEMORY_FAILED); + message->setParameter(errorCode); + message->setParameter2(initialCommand); } void MemoryMessage::setMemoryCopyEnd(CommandMessage* message) { - message->setCommand(END_OF_MEMORY_COPY); - message->setParameter(0); - message->setParameter2(0); + message->setCommand(END_OF_MEMORY_COPY); + message->setParameter(0); + message->setParameter2(0); } - diff --git a/src/fsfw/memory/MemoryMessage.h b/src/fsfw/memory/MemoryMessage.h index 05b9926d..dad7383e 100644 --- a/src/fsfw/memory/MemoryMessage.h +++ b/src/fsfw/memory/MemoryMessage.h @@ -4,45 +4,40 @@ #include "../ipc/CommandMessage.h" #include "../storagemanager/StorageManagerIF.h" - class MemoryMessage { -public: - // Instantiation forbidden. - MemoryMessage() = delete; + public: + // Instantiation forbidden. + MemoryMessage() = delete; - static const uint8_t MESSAGE_ID = messagetypes::MEMORY; - static const Command_t CMD_MEMORY_LOAD = MAKE_COMMAND_ID( 0x01 ); - static const Command_t CMD_MEMORY_DUMP = MAKE_COMMAND_ID( 0x02 ); - static const Command_t CMD_MEMORY_CHECK = MAKE_COMMAND_ID( 0x03 ); - static const Command_t REPLY_MEMORY_DUMP = MAKE_COMMAND_ID( 0x10 ); - static const Command_t REPLY_MEMORY_CHECK = MAKE_COMMAND_ID( 0x30 ); - static const Command_t REPLY_MEMORY_FAILED = MAKE_COMMAND_ID( 0xE0 ); - static const Command_t END_OF_MEMORY_COPY = MAKE_COMMAND_ID(0xF0); + static const uint8_t MESSAGE_ID = messagetypes::MEMORY; + static const Command_t CMD_MEMORY_LOAD = MAKE_COMMAND_ID(0x01); + static const Command_t CMD_MEMORY_DUMP = MAKE_COMMAND_ID(0x02); + static const Command_t CMD_MEMORY_CHECK = MAKE_COMMAND_ID(0x03); + static const Command_t REPLY_MEMORY_DUMP = MAKE_COMMAND_ID(0x10); + static const Command_t REPLY_MEMORY_CHECK = MAKE_COMMAND_ID(0x30); + static const Command_t REPLY_MEMORY_FAILED = MAKE_COMMAND_ID(0xE0); + static const Command_t END_OF_MEMORY_COPY = MAKE_COMMAND_ID(0xF0); - static uint32_t getAddress( const CommandMessage* message ); - static store_address_t getStoreID(const CommandMessage* message); - static uint32_t getLength( const CommandMessage* message ); - static ReturnValue_t getErrorCode(const CommandMessage* message); - static uint16_t getCrc(const CommandMessage* message ); - static ReturnValue_t getCrcReturnValue(const CommandMessage* message); - static Command_t getInitialCommand(const CommandMessage* message); + static uint32_t getAddress(const CommandMessage* message); + static store_address_t getStoreID(const CommandMessage* message); + static uint32_t getLength(const CommandMessage* message); + static ReturnValue_t getErrorCode(const CommandMessage* message); + static uint16_t getCrc(const CommandMessage* message); + static ReturnValue_t getCrcReturnValue(const CommandMessage* message); + static Command_t getInitialCommand(const CommandMessage* message); - static void setMemoryDumpCommand(CommandMessage* message, - uint32_t address, uint32_t length ); - static void setMemoryDumpReply(CommandMessage* message, - store_address_t storageID); - static void setMemoryLoadCommand(CommandMessage* message, - uint32_t address, store_address_t storageID ); - static void setMemoryCheckCommand(CommandMessage* message, - uint32_t address, uint32_t length); - static void setMemoryCheckReply(CommandMessage* message, - uint16_t crc); - static void setMemoryReplyFailed(CommandMessage* message, - ReturnValue_t errorCode, Command_t initialCommand); - static void setMemoryCopyEnd(CommandMessage* message); - static void setCrcReturnValue(CommandMessage*, ReturnValue_t returnValue); + static void setMemoryDumpCommand(CommandMessage* message, uint32_t address, uint32_t length); + static void setMemoryDumpReply(CommandMessage* message, store_address_t storageID); + static void setMemoryLoadCommand(CommandMessage* message, uint32_t address, + store_address_t storageID); + static void setMemoryCheckCommand(CommandMessage* message, uint32_t address, uint32_t length); + static void setMemoryCheckReply(CommandMessage* message, uint16_t crc); + static void setMemoryReplyFailed(CommandMessage* message, ReturnValue_t errorCode, + Command_t initialCommand); + static void setMemoryCopyEnd(CommandMessage* message); + static void setCrcReturnValue(CommandMessage*, ReturnValue_t returnValue); - static void clear(CommandMessage* message); + static void clear(CommandMessage* message); }; #endif /* FSFW_MEMORY_MEMORYMESSAGE_H_ */ diff --git a/src/fsfw/modes/HasModesIF.h b/src/fsfw/modes/HasModesIF.h index c29a0a96..0ebe77d8 100644 --- a/src/fsfw/modes/HasModesIF.h +++ b/src/fsfw/modes/HasModesIF.h @@ -1,51 +1,66 @@ #ifndef FSFW_MODES_HASMODESIF_H_ #define FSFW_MODES_HASMODESIF_H_ -#include "ModeHelper.h" -#include "ModeMessage.h" -#include "../events/Event.h" -#include "../returnvalues/HasReturnvaluesIF.h" #include +#include "../events/Event.h" +#include "../returnvalues/HasReturnvaluesIF.h" +#include "ModeHelper.h" +#include "ModeMessage.h" class HasModesIF { - friend class ModeHelper; -public: - static const uint8_t INTERFACE_ID = CLASS_ID::HAS_MODES_IF; - static const ReturnValue_t INVALID_MODE = MAKE_RETURN_CODE(0x01); - static const ReturnValue_t TRANS_NOT_ALLOWED = MAKE_RETURN_CODE(0x02); - static const ReturnValue_t IN_TRANSITION = MAKE_RETURN_CODE(0x03); - static const ReturnValue_t INVALID_SUBMODE = MAKE_RETURN_CODE(0x04); + friend class ModeHelper; - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::SYSTEM_MANAGER; - static const Event CHANGING_MODE = MAKE_EVENT(0, severity::INFO); //!< An object announces changing the mode. p1: target mode. p2: target submode - static const Event MODE_INFO = MAKE_EVENT(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 MODE_TRANSITION_FAILED = MAKE_EVENT(3, severity::LOW); - static const Event CANT_KEEP_MODE = MAKE_EVENT(4, severity::HIGH); - static const Event OBJECT_IN_INVALID_MODE = MAKE_EVENT(5, severity::LOW); //!< Indicates a bug or configuration failure: Object is in a mode it should never be in. - static const Event FORCING_MODE = MAKE_EVENT(6, severity::MEDIUM); //!< The mode is changed, but for some reason, the change is forced, i.e. EXTERNAL_CONTROL ignored. p1: target mode. p2: target submode - static const Event MODE_CMD_REJECTED = MAKE_EVENT(7, severity::LOW); //!< A mode command was rejected by the called object. Par1: called object id, Par2: return code. + public: + static const uint8_t INTERFACE_ID = CLASS_ID::HAS_MODES_IF; + static const ReturnValue_t INVALID_MODE = MAKE_RETURN_CODE(0x01); + static const ReturnValue_t TRANS_NOT_ALLOWED = MAKE_RETURN_CODE(0x02); + static const ReturnValue_t IN_TRANSITION = MAKE_RETURN_CODE(0x03); + static const ReturnValue_t INVALID_SUBMODE = MAKE_RETURN_CODE(0x04); - static const Mode_t MODE_ON = 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 interpreted - static const Mode_t MODE_OFF = 0; //!< The device is powered off. The only command accepted in this mode is a mode change to on. - static const Submode_t SUBMODE_NONE = 0; //!< To avoid checks against magic number "0". + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::SYSTEM_MANAGER; + static const Event CHANGING_MODE = + MAKE_EVENT(0, severity::INFO); //!< An object announces changing the mode. p1: target mode. + //!< p2: target submode + static const Event MODE_INFO = MAKE_EVENT( + 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 MODE_TRANSITION_FAILED = MAKE_EVENT(3, severity::LOW); + static const Event CANT_KEEP_MODE = MAKE_EVENT(4, severity::HIGH); + static const Event OBJECT_IN_INVALID_MODE = + MAKE_EVENT(5, severity::LOW); //!< Indicates a bug or configuration failure: Object is in a + //!< mode it should never be in. + static const Event FORCING_MODE = MAKE_EVENT( + 6, severity::MEDIUM); //!< The mode is changed, but for some reason, the change is forced, + //!< i.e. EXTERNAL_CONTROL ignored. p1: target mode. p2: target submode + static const Event MODE_CMD_REJECTED = + MAKE_EVENT(7, severity::LOW); //!< A mode command was rejected by the called object. Par1: + //!< called object id, Par2: return code. - virtual ~HasModesIF() {} - virtual MessageQueueId_t getCommandQueue() const = 0; - virtual void getMode(Mode_t *mode, Submode_t *submode) = 0; + static const Mode_t MODE_ON = + 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 + //!< interpreted + static const Mode_t MODE_OFF = 0; //!< The device is powered off. The only command accepted in + //!< this mode is a mode change to on. + static const Submode_t SUBMODE_NONE = 0; //!< To avoid checks against magic number "0". -protected: - virtual ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, - uint32_t *msToReachTheMode) { - return HasReturnvaluesIF::RETURN_FAILED; - } + virtual ~HasModesIF() {} + virtual MessageQueueId_t getCommandQueue() const = 0; + virtual void getMode(Mode_t *mode, Submode_t *submode) = 0; - virtual void startTransition(Mode_t mode, Submode_t submode) {} + protected: + virtual ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, + uint32_t *msToReachTheMode) { + return HasReturnvaluesIF::RETURN_FAILED; + } - virtual void setToExternalControl() {} + virtual void startTransition(Mode_t mode, Submode_t submode) {} - virtual void announceMode(bool recursive) {} + virtual void setToExternalControl() {} + + virtual void announceMode(bool recursive) {} }; #endif /*FSFW_MODES_HASMODESIF_H_ */ diff --git a/src/fsfw/modes/ModeHelper.cpp b/src/fsfw/modes/ModeHelper.cpp index d2c5067d..2ea392ab 100644 --- a/src/fsfw/modes/ModeHelper.cpp +++ b/src/fsfw/modes/ModeHelper.cpp @@ -1,137 +1,108 @@ -#include "fsfw/modes/HasModesIF.h" #include "fsfw/modes/ModeHelper.h" #include "fsfw/ipc/MessageQueueSenderIF.h" +#include "fsfw/modes/HasModesIF.h" #include "fsfw/serviceinterface/ServiceInterface.h" -ModeHelper::ModeHelper(HasModesIF *owner) : - commandedMode(HasModesIF::MODE_OFF), - commandedSubmode(HasModesIF::SUBMODE_NONE), - owner(owner), forced(false) {} +ModeHelper::ModeHelper(HasModesIF* owner) + : commandedMode(HasModesIF::MODE_OFF), + commandedSubmode(HasModesIF::SUBMODE_NONE), + owner(owner), + forced(false) {} -ModeHelper::~ModeHelper() { - -} +ModeHelper::~ModeHelper() {} ReturnValue_t ModeHelper::handleModeCommand(CommandMessage* command) { - CommandMessage reply; - Mode_t mode; - Submode_t submode; - switch (command->getCommand()) { - case ModeMessage::CMD_MODE_COMMAND_FORCED: - forced = true; - /* NO BREAK falls through*/ - case ModeMessage::CMD_MODE_COMMAND: { - mode = ModeMessage::getMode(command); - submode = ModeMessage::getSubmode(command); - uint32_t timeout; - ReturnValue_t result = owner->checkModeCommand(mode, submode, &timeout); - if (result != HasReturnvaluesIF::RETURN_OK) { - ModeMessage::setCantReachMode(&reply, result); - MessageQueueSenderIF::sendMessage(command->getSender(), &reply, - owner->getCommandQueue()); - break; - } - //Free to start transition - theOneWhoCommandedAMode = command->getSender(); - commandedMode = mode; - commandedSubmode = submode; + CommandMessage reply; + Mode_t mode; + Submode_t submode; + switch (command->getCommand()) { + case ModeMessage::CMD_MODE_COMMAND_FORCED: + forced = true; + /* NO BREAK falls through*/ + case ModeMessage::CMD_MODE_COMMAND: { + mode = ModeMessage::getMode(command); + submode = ModeMessage::getSubmode(command); + uint32_t timeout; + ReturnValue_t result = owner->checkModeCommand(mode, submode, &timeout); + if (result != HasReturnvaluesIF::RETURN_OK) { + ModeMessage::setCantReachMode(&reply, result); + MessageQueueSenderIF::sendMessage(command->getSender(), &reply, owner->getCommandQueue()); + break; + } + // Free to start transition + theOneWhoCommandedAMode = command->getSender(); + commandedMode = mode; + commandedSubmode = submode; - if ((parentQueueId != MessageQueueIF::NO_QUEUE) - && (theOneWhoCommandedAMode != parentQueueId)) { - owner->setToExternalControl(); - } + if ((parentQueueId != MessageQueueIF::NO_QUEUE) && + (theOneWhoCommandedAMode != parentQueueId)) { + owner->setToExternalControl(); + } - countdown.setTimeout(timeout); - owner->startTransition(mode, submode); - } - break; - case ModeMessage::CMD_MODE_READ: { - owner->getMode(&mode, &submode); - ModeMessage::setModeMessage(&reply, ModeMessage::REPLY_MODE_REPLY, mode, - submode); - MessageQueueSenderIF::sendMessage(command->getSender(), &reply, - owner->getCommandQueue()); - } - break; - case ModeMessage::CMD_MODE_ANNOUNCE: - owner->announceMode(false); - break; - case ModeMessage::CMD_MODE_ANNOUNCE_RECURSIVELY: - owner->announceMode(true); - break; - default: - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + countdown.setTimeout(timeout); + owner->startTransition(mode, submode); + } break; + case ModeMessage::CMD_MODE_READ: { + owner->getMode(&mode, &submode); + ModeMessage::setModeMessage(&reply, ModeMessage::REPLY_MODE_REPLY, mode, submode); + MessageQueueSenderIF::sendMessage(command->getSender(), &reply, owner->getCommandQueue()); + } break; + case ModeMessage::CMD_MODE_ANNOUNCE: + owner->announceMode(false); + break; + case ModeMessage::CMD_MODE_ANNOUNCE_RECURSIVELY: + owner->announceMode(true); + break; + default: + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t ModeHelper::initialize(MessageQueueId_t parentQueueId) { - setParentQueue(parentQueueId); - return initialize(); + setParentQueue(parentQueueId); + return initialize(); } void ModeHelper::modeChanged(Mode_t ownerMode, Submode_t ownerSubmode) { - forced = false; - sendModeReplyMessage(ownerMode, ownerSubmode); - sendModeInfoMessage(ownerMode, ownerSubmode); - theOneWhoCommandedAMode = MessageQueueIF::NO_QUEUE; + forced = false; + sendModeReplyMessage(ownerMode, ownerSubmode); + sendModeInfoMessage(ownerMode, ownerSubmode); + theOneWhoCommandedAMode = MessageQueueIF::NO_QUEUE; } -void ModeHelper::sendModeReplyMessage(Mode_t ownerMode, - Submode_t ownerSubmode) { - CommandMessage reply; - if (theOneWhoCommandedAMode != MessageQueueIF::NO_QUEUE) - { - if (ownerMode != commandedMode or ownerSubmode != commandedSubmode) - { - ModeMessage::setModeMessage(&reply, - ModeMessage::REPLY_WRONG_MODE_REPLY, ownerMode, - ownerSubmode); - } - else - { - ModeMessage::setModeMessage(&reply, ModeMessage::REPLY_MODE_REPLY, - ownerMode, ownerSubmode); - } - MessageQueueSenderIF::sendMessage(theOneWhoCommandedAMode, &reply, - owner->getCommandQueue()); - } +void ModeHelper::sendModeReplyMessage(Mode_t ownerMode, Submode_t ownerSubmode) { + CommandMessage reply; + if (theOneWhoCommandedAMode != MessageQueueIF::NO_QUEUE) { + if (ownerMode != commandedMode or ownerSubmode != commandedSubmode) { + ModeMessage::setModeMessage(&reply, ModeMessage::REPLY_WRONG_MODE_REPLY, ownerMode, + ownerSubmode); + } else { + ModeMessage::setModeMessage(&reply, ModeMessage::REPLY_MODE_REPLY, ownerMode, ownerSubmode); + } + MessageQueueSenderIF::sendMessage(theOneWhoCommandedAMode, &reply, owner->getCommandQueue()); + } } -void ModeHelper::sendModeInfoMessage(Mode_t ownerMode, - Submode_t ownerSubmode) { - CommandMessage reply; - if (theOneWhoCommandedAMode != parentQueueId - and parentQueueId != MessageQueueIF::NO_QUEUE) - { - ModeMessage::setModeMessage(&reply, ModeMessage::REPLY_MODE_INFO, - ownerMode, ownerSubmode); - MessageQueueSenderIF::sendMessage(parentQueueId, &reply, - owner->getCommandQueue()); - } +void ModeHelper::sendModeInfoMessage(Mode_t ownerMode, Submode_t ownerSubmode) { + CommandMessage reply; + if (theOneWhoCommandedAMode != parentQueueId and parentQueueId != MessageQueueIF::NO_QUEUE) { + ModeMessage::setModeMessage(&reply, ModeMessage::REPLY_MODE_INFO, ownerMode, ownerSubmode); + MessageQueueSenderIF::sendMessage(parentQueueId, &reply, owner->getCommandQueue()); + } } -void ModeHelper::startTimer(uint32_t timeoutMs) { - countdown.setTimeout(timeoutMs); -} +void ModeHelper::startTimer(uint32_t timeoutMs) { countdown.setTimeout(timeoutMs); } void ModeHelper::setParentQueue(MessageQueueId_t parentQueueId) { - this->parentQueueId = parentQueueId; + this->parentQueueId = parentQueueId; } -ReturnValue_t ModeHelper::initialize(void) { - return HasReturnvaluesIF::RETURN_OK; -} +ReturnValue_t ModeHelper::initialize(void) { return HasReturnvaluesIF::RETURN_OK; } -bool ModeHelper::isTimedOut() { - return countdown.hasTimedOut(); -} +bool ModeHelper::isTimedOut() { return countdown.hasTimedOut(); } -bool ModeHelper::isForced() { - return forced; -} +bool ModeHelper::isForced() { return forced; } -void ModeHelper::setForced(bool forced) { - this->forced = forced; -} +void ModeHelper::setForced(bool forced) { this->forced = forced; } diff --git a/src/fsfw/modes/ModeHelper.h b/src/fsfw/modes/ModeHelper.h index 27928a29..4d0479db 100644 --- a/src/fsfw/modes/ModeHelper.h +++ b/src/fsfw/modes/ModeHelper.h @@ -9,45 +9,47 @@ class HasModesIF; class ModeHelper { -public: - MessageQueueId_t theOneWhoCommandedAMode = MessageQueueIF::NO_QUEUE; - Mode_t commandedMode; - Submode_t commandedSubmode; + public: + MessageQueueId_t theOneWhoCommandedAMode = MessageQueueIF::NO_QUEUE; + Mode_t commandedMode; + Submode_t commandedSubmode; - ModeHelper(HasModesIF *owner); - virtual ~ModeHelper(); + ModeHelper(HasModesIF *owner); + virtual ~ModeHelper(); - ReturnValue_t handleModeCommand(CommandMessage *message); + ReturnValue_t handleModeCommand(CommandMessage *message); - /** - * @param parentQueue the Queue id of the parent object. - * Set to 0 if no parent present - */ - void setParentQueue(MessageQueueId_t parentQueueId); + /** + * @param parentQueue the Queue id of the parent object. + * Set to 0 if no parent present + */ + void setParentQueue(MessageQueueId_t parentQueueId); - ReturnValue_t initialize(MessageQueueId_t parentQueueId); + ReturnValue_t initialize(MessageQueueId_t parentQueueId); - ReturnValue_t initialize(void); + ReturnValue_t initialize(void); - void modeChanged(Mode_t mode, Submode_t submode); + void modeChanged(Mode_t mode, Submode_t submode); - void startTimer(uint32_t timeoutMs); + void startTimer(uint32_t timeoutMs); - bool isTimedOut(); + bool isTimedOut(); - bool isForced(); + bool isForced(); - void setForced(bool forced); -protected: - HasModesIF *owner; - MessageQueueId_t parentQueueId = MessageQueueIF::NO_QUEUE; + void setForced(bool forced); - Countdown countdown; + protected: + HasModesIF *owner; + MessageQueueId_t parentQueueId = MessageQueueIF::NO_QUEUE; - bool forced; -private: - void sendModeReplyMessage(Mode_t ownerMode, Submode_t ownerSubmode); - void sendModeInfoMessage(Mode_t ownerMode, Submode_t ownerSubmode); + Countdown countdown; + + bool forced; + + private: + void sendModeReplyMessage(Mode_t ownerMode, Submode_t ownerSubmode); + void sendModeInfoMessage(Mode_t ownerMode, Submode_t ownerSubmode); }; #endif /* FSFW_MODES_MODEHELPER_H_ */ diff --git a/src/fsfw/modes/ModeMessage.cpp b/src/fsfw/modes/ModeMessage.cpp index a228304d..ecc52c94 100644 --- a/src/fsfw/modes/ModeMessage.cpp +++ b/src/fsfw/modes/ModeMessage.cpp @@ -1,31 +1,26 @@ #include "fsfw/modes/ModeMessage.h" -Mode_t ModeMessage::getMode(const CommandMessage* message) { - return message->getParameter(); -} +Mode_t ModeMessage::getMode(const CommandMessage* message) { return message->getParameter(); } Submode_t ModeMessage::getSubmode(const CommandMessage* message) { - return message->getParameter2(); + return message->getParameter2(); } -void ModeMessage::setModeMessage(CommandMessage* message, - Command_t command, Mode_t mode, Submode_t submode) { - message->setCommand( command ); - message->setParameter( mode ); - message->setParameter2( submode ); +void ModeMessage::setModeMessage(CommandMessage* message, Command_t command, Mode_t mode, + Submode_t submode) { + message->setCommand(command); + message->setParameter(mode); + message->setParameter2(submode); } ReturnValue_t ModeMessage::getCantReachModeReason(const CommandMessage* message) { - return message->getParameter(); + return message->getParameter(); } -void ModeMessage::clear(CommandMessage* message) { - message->setCommand(CommandMessage::CMD_NONE); -} +void ModeMessage::clear(CommandMessage* message) { message->setCommand(CommandMessage::CMD_NONE); } -void ModeMessage::setCantReachMode(CommandMessage* message, - ReturnValue_t reason) { - message->setCommand(REPLY_CANT_REACH_MODE); - message->setParameter(reason); - message->setParameter2(0); +void ModeMessage::setCantReachMode(CommandMessage* message, ReturnValue_t reason) { + message->setCommand(REPLY_CANT_REACH_MODE); + message->setParameter(reason); + message->setParameter2(0); } diff --git a/src/fsfw/modes/ModeMessage.h b/src/fsfw/modes/ModeMessage.h index 856996cf..e3638ee0 100644 --- a/src/fsfw/modes/ModeMessage.h +++ b/src/fsfw/modes/ModeMessage.h @@ -7,28 +7,46 @@ typedef uint32_t Mode_t; typedef uint8_t Submode_t; class ModeMessage { -private: - ModeMessage(); -public: - static const uint8_t MESSAGE_ID = messagetypes::MODE_COMMAND; - static const Command_t CMD_MODE_COMMAND = 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, as this will break the subsystem mode machine!! - static const Command_t CMD_MODE_COMMAND_FORCED = MAKE_COMMAND_ID(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 replies, as this will break the subsystem mode machine!! - static const Command_t REPLY_MODE_REPLY = MAKE_COMMAND_ID(0x02);//!> Reply to a CMD_MODE_COMMAND or CMD_MODE_READ - static const Command_t REPLY_MODE_INFO = MAKE_COMMAND_ID(0x03); //!> Unrequested info about the current mode (used for composites to inform their container of a changed mode) - static const Command_t REPLY_CANT_REACH_MODE = MAKE_COMMAND_ID(0x04); //!> Reply in case a mode command can't be executed. Par1: returnCode, Par2: 0 - static const Command_t REPLY_WRONG_MODE_REPLY = 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 the mode that was reached - static const Command_t CMD_MODE_READ = MAKE_COMMAND_ID(0x06);//!> Command to read the current mode and reply with a REPLY_MODE_REPLY - static const Command_t CMD_MODE_ANNOUNCE = MAKE_COMMAND_ID(0x07);//!> Command to trigger an ModeInfo Event. This command does NOT have a reply. - static const Command_t CMD_MODE_ANNOUNCE_RECURSIVELY = 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. + private: + ModeMessage(); - static Mode_t getMode(const CommandMessage* message); - static Submode_t getSubmode(const CommandMessage* message); - static ReturnValue_t getCantReachModeReason(const CommandMessage* message); + public: + static const uint8_t MESSAGE_ID = messagetypes::MODE_COMMAND; + static const Command_t CMD_MODE_COMMAND = + 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, + //!as this will break the subsystem mode machine!! + static const Command_t CMD_MODE_COMMAND_FORCED = MAKE_COMMAND_ID( + 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 + //!replies, as this will break the subsystem mode machine!! + static const Command_t REPLY_MODE_REPLY = + MAKE_COMMAND_ID(0x02); //!> Reply to a CMD_MODE_COMMAND or CMD_MODE_READ + static const Command_t REPLY_MODE_INFO = + MAKE_COMMAND_ID(0x03); //!> Unrequested info about the current mode (used for composites to + //!inform their container of a changed mode) + static const Command_t REPLY_CANT_REACH_MODE = MAKE_COMMAND_ID( + 0x04); //!> Reply in case a mode command can't be executed. Par1: returnCode, Par2: 0 + static const Command_t REPLY_WRONG_MODE_REPLY = + 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 + //!the mode that was reached + static const Command_t CMD_MODE_READ = MAKE_COMMAND_ID( + 0x06); //!> Command to read the current mode and reply with a REPLY_MODE_REPLY + static const Command_t CMD_MODE_ANNOUNCE = MAKE_COMMAND_ID( + 0x07); //!> Command to trigger an ModeInfo Event. This command does NOT have a reply. + static const Command_t CMD_MODE_ANNOUNCE_RECURSIVELY = + 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. - static void setModeMessage(CommandMessage* message, - Command_t command, Mode_t mode, Submode_t submode); - static void setCantReachMode(CommandMessage* message, ReturnValue_t reason); - static void clear(CommandMessage* message); + static Mode_t getMode(const CommandMessage* message); + static Submode_t getSubmode(const CommandMessage* message); + static ReturnValue_t getCantReachModeReason(const CommandMessage* message); + + static void setModeMessage(CommandMessage* message, Command_t command, Mode_t mode, + Submode_t submode); + static void setCantReachMode(CommandMessage* message, ReturnValue_t reason); + static void clear(CommandMessage* message); }; #endif /* FSFW_MODES_MODEMESSAGE_H_ */ diff --git a/src/fsfw/monitoring/AbsLimitMonitor.h b/src/fsfw/monitoring/AbsLimitMonitor.h index f3bbf04c..c6400166 100644 --- a/src/fsfw/monitoring/AbsLimitMonitor.h +++ b/src/fsfw/monitoring/AbsLimitMonitor.h @@ -1,82 +1,79 @@ #ifndef FSFW_MONITORING_ABSLIMITMONITOR_H_ #define FSFW_MONITORING_ABSLIMITMONITOR_H_ -#include "monitoringConf.h" -#include "MonitorBase.h" #include -template -class AbsLimitMonitor: public MonitorBase { -public: - AbsLimitMonitor(object_id_t reporterId, uint8_t monitorId, - gp_id_t globalPoolId, uint16_t confirmationLimit, T limit, - Event violationEvent = MonitoringIF::VALUE_OUT_OF_RANGE, - bool aboveIsViolation = true) : - MonitorBase(reporterId, monitorId, globalPoolId, - confirmationLimit), - limit(limit), violationEvent(violationEvent), - aboveIsViolation(aboveIsViolation) { - } - virtual ~AbsLimitMonitor() { - } - virtual ReturnValue_t checkSample(T sample, T* crossedLimit) { - *crossedLimit = limit; - if (aboveIsViolation) { - if ((std::abs(sample) > limit)) { - return MonitoringIF::OUT_OF_RANGE; - } - } else { - if ((std::abs(sample) < limit)) { - return MonitoringIF::OUT_OF_RANGE; - } - } - return HasReturnvaluesIF::RETURN_OK; //We're not out of range. - } +#include "MonitorBase.h" +#include "monitoringConf.h" - virtual ReturnValue_t getParameter(uint8_t domainId, uint16_t parameterId, - ParameterWrapper *parameterWrapper, - const ParameterWrapper *newValues, uint16_t startAtIndex) { - ReturnValue_t result = this->MonitorBase::getParameter(domainId, - parameterId, parameterWrapper, newValues, startAtIndex); - // We'll reuse the DOMAIN_ID of MonitorReporter, - // as we know the parameterIds used there. - if (result != this->INVALID_IDENTIFIER_ID) { - return result; - } - switch (parameterId) { - case 10: - parameterWrapper->set(this->limit); - break; - default: - return this->INVALID_IDENTIFIER_ID; - } - return HasReturnvaluesIF::RETURN_OK; - } - bool isOutOfLimits() { - if (this->oldState == MonitoringIF::OUT_OF_RANGE) { - return true; - } else { - return false; - } - } - void setLimit(T value) { - limit = value; - } -protected: - void sendTransitionEvent(T currentValue, ReturnValue_t state) { - switch (state) { - case MonitoringIF::OUT_OF_RANGE: - EventManagerIF::triggerEvent(this->reportingId, - violationEvent, this->globalPoolId.objectId, - this->globalPoolId.localPoolId); - break; - default: - break; - } - } - T limit; - const Event violationEvent; - const bool aboveIsViolation; +template +class AbsLimitMonitor : public MonitorBase { + public: + AbsLimitMonitor(object_id_t reporterId, uint8_t monitorId, gp_id_t globalPoolId, + uint16_t confirmationLimit, T limit, + Event violationEvent = MonitoringIF::VALUE_OUT_OF_RANGE, + bool aboveIsViolation = true) + : MonitorBase(reporterId, monitorId, globalPoolId, confirmationLimit), + limit(limit), + violationEvent(violationEvent), + aboveIsViolation(aboveIsViolation) {} + virtual ~AbsLimitMonitor() {} + virtual ReturnValue_t checkSample(T sample, T *crossedLimit) { + *crossedLimit = limit; + if (aboveIsViolation) { + if ((std::abs(sample) > limit)) { + return MonitoringIF::OUT_OF_RANGE; + } + } else { + if ((std::abs(sample) < limit)) { + return MonitoringIF::OUT_OF_RANGE; + } + } + return HasReturnvaluesIF::RETURN_OK; // We're not out of range. + } + + virtual ReturnValue_t getParameter(uint8_t domainId, uint16_t parameterId, + ParameterWrapper *parameterWrapper, + const ParameterWrapper *newValues, uint16_t startAtIndex) { + ReturnValue_t result = this->MonitorBase::getParameter( + domainId, parameterId, parameterWrapper, newValues, startAtIndex); + // We'll reuse the DOMAIN_ID of MonitorReporter, + // as we know the parameterIds used there. + if (result != this->INVALID_IDENTIFIER_ID) { + return result; + } + switch (parameterId) { + case 10: + parameterWrapper->set(this->limit); + break; + default: + return this->INVALID_IDENTIFIER_ID; + } + return HasReturnvaluesIF::RETURN_OK; + } + bool isOutOfLimits() { + if (this->oldState == MonitoringIF::OUT_OF_RANGE) { + return true; + } else { + return false; + } + } + void setLimit(T value) { limit = value; } + + protected: + void sendTransitionEvent(T currentValue, ReturnValue_t state) { + switch (state) { + case MonitoringIF::OUT_OF_RANGE: + EventManagerIF::triggerEvent(this->reportingId, violationEvent, this->globalPoolId.objectId, + this->globalPoolId.localPoolId); + break; + default: + break; + } + } + T limit; + const Event violationEvent; + const bool aboveIsViolation; }; #endif /* FSFW_MONITORING_ABSLIMITMONITOR_H_ */ diff --git a/src/fsfw/monitoring/HasMonitorsIF.h b/src/fsfw/monitoring/HasMonitorsIF.h index 20520952..a55d8c31 100644 --- a/src/fsfw/monitoring/HasMonitorsIF.h +++ b/src/fsfw/monitoring/HasMonitorsIF.h @@ -1,25 +1,24 @@ #ifndef FSFW_MONITORING_HASMONITORSIF_H_ #define FSFW_MONITORING_HASMONITORSIF_H_ -#include "monitoringConf.h" #include "../events/EventReportingProxyIF.h" -#include "../objectmanager/ObjectManagerIF.h" #include "../ipc/MessageQueueSenderIF.h" +#include "../objectmanager/ObjectManagerIF.h" +#include "monitoringConf.h" class HasMonitorsIF { -public: - static const uint8_t MAX_N_PARAMETER = 10; -// static const uint8_t MAX_N_LIMIT_ID = 10; - virtual ReturnValue_t setCheckingOfParameters(uint8_t checkingStrategy, - bool forOnePid = false, uint32_t parameterId = 0) = 0; - virtual ReturnValue_t modifyParameterMonitor(uint8_t limitType, - uint32_t parameterId, const uint8_t* data, uint32_t size) = 0; - virtual ReturnValue_t modifyObjectMonitor(uint32_t objectId, - const uint8_t* data, const uint32_t size) = 0; - virtual void setAllMonitorsToUnchecked() = 0; - virtual MessageQueueId_t getCommandQueue() const = 0; - virtual ~HasMonitorsIF() { - } + public: + static const uint8_t MAX_N_PARAMETER = 10; + // static const uint8_t MAX_N_LIMIT_ID = 10; + virtual ReturnValue_t setCheckingOfParameters(uint8_t checkingStrategy, bool forOnePid = false, + uint32_t parameterId = 0) = 0; + virtual ReturnValue_t modifyParameterMonitor(uint8_t limitType, uint32_t parameterId, + const uint8_t* data, uint32_t size) = 0; + virtual ReturnValue_t modifyObjectMonitor(uint32_t objectId, const uint8_t* data, + const uint32_t size) = 0; + virtual void setAllMonitorsToUnchecked() = 0; + virtual MessageQueueId_t getCommandQueue() const = 0; + virtual ~HasMonitorsIF() {} }; #endif /* FSFW_MONITORING_HASMONITORSIF_H_ */ diff --git a/src/fsfw/monitoring/LimitMonitor.h b/src/fsfw/monitoring/LimitMonitor.h index 2565ebaa..229f1dc2 100644 --- a/src/fsfw/monitoring/LimitMonitor.h +++ b/src/fsfw/monitoring/LimitMonitor.h @@ -1,8 +1,8 @@ #ifndef FRAMEWORK_MONITORING_LIMITMONITOR_H_ #define FRAMEWORK_MONITORING_LIMITMONITOR_H_ -#include "monitoringConf.h" #include "MonitorBase.h" +#include "monitoringConf.h" /** * Variant of a limit checking class. @@ -10,91 +10,85 @@ * Functionality is more or less the same, but does not use * heavy weight MonitoringIF. */ -template -class LimitMonitor: public MonitorBase { -public: - LimitMonitor(object_id_t reporterId, uint8_t monitorId, - gp_id_t globalPoolId, uint16_t confirmationLimit, T lowerLimit, - T upperLimit, Event belowLowEvent = - MonitoringIF::VALUE_BELOW_LOW_LIMIT, - Event aboveHighEvent = MonitoringIF::VALUE_ABOVE_HIGH_LIMIT) : - MonitorBase(reporterId, monitorId, globalPoolId, - confirmationLimit), - lowerLimit(lowerLimit), upperLimit(upperLimit), - belowLowEvent(belowLowEvent), aboveHighEvent(aboveHighEvent) { - } - virtual ~LimitMonitor() { - } - virtual ReturnValue_t checkSample(T sample, T* crossedLimit) { - *crossedLimit = 0.0; - if (sample > upperLimit) { - *crossedLimit = upperLimit; - return MonitoringIF::ABOVE_HIGH_LIMIT; - } else if (sample < lowerLimit) { - *crossedLimit = lowerLimit; - return MonitoringIF::BELOW_LOW_LIMIT; - } else { - return HasReturnvaluesIF::RETURN_OK; //Within limits. - } - } +template +class LimitMonitor : public MonitorBase { + public: + LimitMonitor(object_id_t reporterId, uint8_t monitorId, gp_id_t globalPoolId, + uint16_t confirmationLimit, T lowerLimit, T upperLimit, + Event belowLowEvent = MonitoringIF::VALUE_BELOW_LOW_LIMIT, + Event aboveHighEvent = MonitoringIF::VALUE_ABOVE_HIGH_LIMIT) + : MonitorBase(reporterId, monitorId, globalPoolId, confirmationLimit), + lowerLimit(lowerLimit), + upperLimit(upperLimit), + belowLowEvent(belowLowEvent), + aboveHighEvent(aboveHighEvent) {} + virtual ~LimitMonitor() {} + virtual ReturnValue_t checkSample(T sample, T *crossedLimit) { + *crossedLimit = 0.0; + if (sample > upperLimit) { + *crossedLimit = upperLimit; + return MonitoringIF::ABOVE_HIGH_LIMIT; + } else if (sample < lowerLimit) { + *crossedLimit = lowerLimit; + return MonitoringIF::BELOW_LOW_LIMIT; + } else { + return HasReturnvaluesIF::RETURN_OK; // Within limits. + } + } - virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, - ParameterWrapper *parameterWrapper, const ParameterWrapper *newValues, - uint16_t startAtIndex) { - ReturnValue_t result = this->MonitorBase::getParameter(domainId, - uniqueId, parameterWrapper, newValues, startAtIndex); - //We'll reuse the DOMAIN_ID of MonitorReporter, as we know the parameterIds used there. - if (result != this->INVALID_IDENTIFIER_ID) { - return result; - } - switch (uniqueId) { - case 10: - parameterWrapper->set(this->lowerLimit); - break; - case 11: - parameterWrapper->set(this->upperLimit); - break; - default: - return this->INVALID_IDENTIFIER_ID; - } - return HasReturnvaluesIF::RETURN_OK; - } - bool isOutOfLimits() { - if (this->oldState == MonitoringIF::ABOVE_HIGH_LIMIT or - this->oldState == MonitoringIF::BELOW_LOW_LIMIT) { - return true; - } else { - return false; - } - } + virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, + ParameterWrapper *parameterWrapper, + const ParameterWrapper *newValues, uint16_t startAtIndex) { + ReturnValue_t result = this->MonitorBase::getParameter(domainId, uniqueId, parameterWrapper, + newValues, startAtIndex); + // We'll reuse the DOMAIN_ID of MonitorReporter, as we know the parameterIds used there. + if (result != this->INVALID_IDENTIFIER_ID) { + return result; + } + switch (uniqueId) { + case 10: + parameterWrapper->set(this->lowerLimit); + break; + case 11: + parameterWrapper->set(this->upperLimit); + break; + default: + return this->INVALID_IDENTIFIER_ID; + } + return HasReturnvaluesIF::RETURN_OK; + } + bool isOutOfLimits() { + if (this->oldState == MonitoringIF::ABOVE_HIGH_LIMIT or + this->oldState == MonitoringIF::BELOW_LOW_LIMIT) { + return true; + } else { + return false; + } + } - T getLowerLimit() const { - return lowerLimit; - } + T getLowerLimit() const { return lowerLimit; } - T getUpperLimit() const { - return upperLimit; - } + T getUpperLimit() const { return upperLimit; } -protected: - void sendTransitionEvent(T currentValue, ReturnValue_t state) { - switch (state) { - case MonitoringIF::BELOW_LOW_LIMIT: - EventManagerIF::triggerEvent(this->reportingId, belowLowEvent, - this->globalPoolId.objectId, this->globalPoolId.localPoolId); - break; - case MonitoringIF::ABOVE_HIGH_LIMIT: - EventManagerIF::triggerEvent(this->reportingId, aboveHighEvent, - this->globalPoolId.objectId, this->globalPoolId.localPoolId); - break; - default: - break; - } - } - T lowerLimit; - T upperLimit; - const Event belowLowEvent; - const Event aboveHighEvent; + protected: + void sendTransitionEvent(T currentValue, ReturnValue_t state) { + switch (state) { + case MonitoringIF::BELOW_LOW_LIMIT: + EventManagerIF::triggerEvent(this->reportingId, belowLowEvent, this->globalPoolId.objectId, + this->globalPoolId.localPoolId); + break; + case MonitoringIF::ABOVE_HIGH_LIMIT: + EventManagerIF::triggerEvent(this->reportingId, aboveHighEvent, this->globalPoolId.objectId, + this->globalPoolId.localPoolId); + break; + default: + break; + } + } + T lowerLimit; + T upperLimit; + const Event belowLowEvent; + const Event aboveHighEvent; }; #endif /* FRAMEWORK_MONITORING_LIMITMONITOR_H_ */ diff --git a/src/fsfw/monitoring/LimitViolationReporter.cpp b/src/fsfw/monitoring/LimitViolationReporter.cpp index a0b8a4cb..43ecf4d3 100644 --- a/src/fsfw/monitoring/LimitViolationReporter.cpp +++ b/src/fsfw/monitoring/LimitViolationReporter.cpp @@ -1,55 +1,54 @@ #include "fsfw/monitoring/LimitViolationReporter.h" + #include "fsfw/monitoring/MonitoringIF.h" #include "fsfw/monitoring/ReceivesMonitoringReportsIF.h" - #include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/serialize/SerializeAdapter.h" ReturnValue_t LimitViolationReporter::sendLimitViolationReport(const SerializeIF* data) { - ReturnValue_t result = checkClassLoaded(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - store_address_t storeId; - uint8_t* dataTarget = nullptr; - size_t maxSize = data->getSerializedSize(); - if (maxSize > MonitoringIF::VIOLATION_REPORT_MAX_SIZE) { - return MonitoringIF::INVALID_SIZE; - } - result = ipcStore->getFreeElement(&storeId, maxSize, - &dataTarget); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - size_t size = 0; - result = data->serialize(&dataTarget, &size, maxSize, SerializeIF::Endianness::BIG); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - CommandMessage report; - MonitoringMessage::setLimitViolationReport(&report, storeId); - return MessageQueueSenderIF::sendMessage(reportQueue, &report); + ReturnValue_t result = checkClassLoaded(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + store_address_t storeId; + uint8_t* dataTarget = nullptr; + size_t maxSize = data->getSerializedSize(); + if (maxSize > MonitoringIF::VIOLATION_REPORT_MAX_SIZE) { + return MonitoringIF::INVALID_SIZE; + } + result = ipcStore->getFreeElement(&storeId, maxSize, &dataTarget); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + size_t size = 0; + result = data->serialize(&dataTarget, &size, maxSize, SerializeIF::Endianness::BIG); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + CommandMessage report; + MonitoringMessage::setLimitViolationReport(&report, storeId); + return MessageQueueSenderIF::sendMessage(reportQueue, &report); } ReturnValue_t LimitViolationReporter::checkClassLoaded() { - if (reportQueue == 0) { - ReceivesMonitoringReportsIF* receiver = ObjectManager::instance()->get< - ReceivesMonitoringReportsIF>(reportingTarget); - if (receiver == nullptr) { - return ObjectManagerIF::NOT_FOUND; - } - reportQueue = receiver->getCommandQueue(); - } - if (ipcStore == nullptr) { - ipcStore = ObjectManager::instance()->get(objects::IPC_STORE); - if (ipcStore == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - } - return HasReturnvaluesIF::RETURN_OK; + if (reportQueue == 0) { + ReceivesMonitoringReportsIF* receiver = + ObjectManager::instance()->get(reportingTarget); + if (receiver == nullptr) { + return ObjectManagerIF::NOT_FOUND; + } + reportQueue = receiver->getCommandQueue(); + } + if (ipcStore == nullptr) { + ipcStore = ObjectManager::instance()->get(objects::IPC_STORE); + if (ipcStore == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + } + return HasReturnvaluesIF::RETURN_OK; } -//Lazy initialization. +// Lazy initialization. MessageQueueId_t LimitViolationReporter::reportQueue = 0; StorageManagerIF* LimitViolationReporter::ipcStore = nullptr; object_id_t LimitViolationReporter::reportingTarget = 0; diff --git a/src/fsfw/monitoring/LimitViolationReporter.h b/src/fsfw/monitoring/LimitViolationReporter.h index b254e312..06b3ba74 100644 --- a/src/fsfw/monitoring/LimitViolationReporter.h +++ b/src/fsfw/monitoring/LimitViolationReporter.h @@ -7,26 +7,28 @@ #ifndef LIMITVIOLATIONREPORTER_H_ #define LIMITVIOLATIONREPORTER_H_ -#include "monitoringConf.h" +#include "../ipc/MessageQueueSenderIF.h" #include "../returnvalues/HasReturnvaluesIF.h" #include "../serialize/SerializeIF.h" #include "../storagemanager/StorageManagerIF.h" -#include "../ipc/MessageQueueSenderIF.h" +#include "monitoringConf.h" -namespace Factory{ +namespace Factory { void setStaticFrameworkObjectIds(); } class LimitViolationReporter { - friend void (Factory::setStaticFrameworkObjectIds)(); -public: - static ReturnValue_t sendLimitViolationReport(const SerializeIF* data); -private: - static object_id_t reportingTarget; - static MessageQueueId_t reportQueue; - static StorageManagerIF* ipcStore; - static ReturnValue_t checkClassLoaded(); - LimitViolationReporter(); + friend void(Factory::setStaticFrameworkObjectIds)(); + + public: + static ReturnValue_t sendLimitViolationReport(const SerializeIF* data); + + private: + static object_id_t reportingTarget; + static MessageQueueId_t reportQueue; + static StorageManagerIF* ipcStore; + static ReturnValue_t checkClassLoaded(); + LimitViolationReporter(); }; #endif /* LIMITVIOLATIONREPORTER_H_ */ diff --git a/src/fsfw/monitoring/MonitorBase.h b/src/fsfw/monitoring/MonitorBase.h index 261b3eac..b2653d75 100644 --- a/src/fsfw/monitoring/MonitorBase.h +++ b/src/fsfw/monitoring/MonitorBase.h @@ -1,14 +1,12 @@ #ifndef FSFW_MONITORING_MONITORBASE_H_ #define FSFW_MONITORING_MONITORBASE_H_ -#include "monitoringConf.h" +#include "../datapoollocal/LocalPoolVariable.h" #include "LimitViolationReporter.h" +#include "MonitorReporter.h" #include "MonitoringIF.h" #include "MonitoringMessageContent.h" -#include "MonitorReporter.h" - -#include "../datapoollocal/LocalPoolVariable.h" - +#include "monitoringConf.h" /** * @brief Base class for monitoring of parameters. @@ -21,59 +19,54 @@ * In addition, it provides default implementations for fetching the * parameter sample from the data pool and a simple confirmation counter. */ -template -class MonitorBase: public MonitorReporter { -public: +template +class MonitorBase : public MonitorReporter { + public: + MonitorBase(object_id_t reporterId, uint8_t monitorId, gp_id_t globalPoolId, + uint16_t confirmationLimit) + : MonitorReporter(reporterId, monitorId, globalPoolId, confirmationLimit), + poolVariable(globalPoolId) {} - MonitorBase(object_id_t reporterId, uint8_t monitorId, - gp_id_t globalPoolId, uint16_t confirmationLimit): - MonitorReporter(reporterId, monitorId, globalPoolId, - confirmationLimit), - poolVariable(globalPoolId) { - } + virtual ~MonitorBase() {} - virtual ~MonitorBase() { - } + virtual ReturnValue_t check() { + // 1. Fetch sample of type T, return validity. + T sample = 0; + ReturnValue_t validity = fetchSample(&sample); - virtual ReturnValue_t check() { - // 1. Fetch sample of type T, return validity. - T sample = 0; - ReturnValue_t validity = fetchSample(&sample); + // 2. If returning from fetch != OK, parameter is invalid. + // Report (if oldState is != invalidity). + if (validity != HasReturnvaluesIF::RETURN_OK) { + this->monitorStateIs(validity, sample, 0); + } else { + // 3. Otherwise, check sample. + this->oldState = doCheck(sample); + } + return this->oldState; + } + virtual ReturnValue_t doCheck(T sample) { + T crossedLimit = 0.0; + ReturnValue_t currentState = checkSample(sample, &crossedLimit); + return this->monitorStateIs(currentState, sample, crossedLimit); + } - // 2. If returning from fetch != OK, parameter is invalid. - // Report (if oldState is != invalidity). - if (validity != HasReturnvaluesIF::RETURN_OK) { - this->monitorStateIs(validity, sample, 0); - } else { - //3. Otherwise, check sample. - this->oldState = doCheck(sample); - } - return this->oldState; - } - virtual ReturnValue_t doCheck(T sample) { - T crossedLimit = 0.0; - ReturnValue_t currentState = checkSample(sample, &crossedLimit); - return this->monitorStateIs(currentState,sample, crossedLimit); - } + // Abstract or default. + virtual ReturnValue_t checkSample(T sample, T* crossedLimit) = 0; - // Abstract or default. - virtual ReturnValue_t checkSample(T sample, T* crossedLimit) = 0; + protected: + virtual ReturnValue_t fetchSample(T* sample) { + ReturnValue_t result = poolVariable.read(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (not poolVariable.isValid()) { + return MonitoringIF::INVALID; + } + *sample = poolVariable.value; + return HasReturnvaluesIF::RETURN_OK; + } -protected: - - virtual ReturnValue_t fetchSample(T* sample) { - ReturnValue_t result = poolVariable.read(); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if (not poolVariable.isValid()) { - return MonitoringIF::INVALID; - } - *sample = poolVariable.value; - return HasReturnvaluesIF::RETURN_OK; - } - - LocalPoolVariable poolVariable; + LocalPoolVariable poolVariable; }; #endif /* FSFW_MONITORING_MONITORBASE_H_ */ diff --git a/src/fsfw/monitoring/MonitorReporter.h b/src/fsfw/monitoring/MonitorReporter.h index e27d0101..bcbaf26d 100644 --- a/src/fsfw/monitoring/MonitorReporter.h +++ b/src/fsfw/monitoring/MonitorReporter.h @@ -1,186 +1,166 @@ #ifndef FSFW_MONITORING_MONITORREPORTER_H_ #define FSFW_MONITORING_MONITORREPORTER_H_ -#include "monitoringConf.h" -#include "LimitViolationReporter.h" -#include "MonitoringIF.h" -#include "MonitoringMessageContent.h" - #include "../datapoollocal/localPoolDefinitions.h" #include "../events/EventManagerIF.h" #include "../parameters/HasParametersIF.h" +#include "LimitViolationReporter.h" +#include "MonitoringIF.h" +#include "MonitoringMessageContent.h" +#include "monitoringConf.h" -template -class MonitorReporter: public HasParametersIF { -public: +template +class MonitorReporter : public HasParametersIF { + public: + static const uint8_t ENABLED = 1; + static const uint8_t DISABLED = 0; - static const uint8_t ENABLED = 1; - static const uint8_t DISABLED = 0; + // TODO: Adapt to use SID instead of parameter ID. - // TODO: Adapt to use SID instead of parameter ID. + MonitorReporter(object_id_t reportingId, uint8_t monitorId, gp_id_t globalPoolId, + uint16_t confirmationLimit) + : monitorId(monitorId), + globalPoolId(globalPoolId), + reportingId(reportingId), + oldState(MonitoringIF::UNCHECKED), + reportingEnabled(ENABLED), + eventEnabled(ENABLED), + currentCounter(0), + confirmationLimit(confirmationLimit) {} - MonitorReporter(object_id_t reportingId, uint8_t monitorId, - gp_id_t globalPoolId, uint16_t confirmationLimit) : - monitorId(monitorId), globalPoolId(globalPoolId), - reportingId(reportingId), oldState(MonitoringIF::UNCHECKED), - reportingEnabled(ENABLED), eventEnabled(ENABLED), currentCounter(0), - confirmationLimit(confirmationLimit) { - } + virtual ~MonitorReporter() {} - virtual ~MonitorReporter() { - } + ReturnValue_t monitorStateIs(ReturnValue_t state, T parameterValue = 0, T crossedLimit = 0) { + if (state != oldState) { + if (isConfirmed(state)) { + if (eventEnabled == ENABLED) { + sendTransitionEvent(parameterValue, state); + } + if (reportingEnabled == ENABLED) { + sendTransitionReport(parameterValue, crossedLimit, state); + } + oldState = state; + } else { + // This is to ensure confirmation works. + // Needs to be reset to be able to confirm against oldState again next time. + return oldState; + } + } else { + resetConfirmation(); + } + return state; + } - ReturnValue_t monitorStateIs(ReturnValue_t state, T parameterValue = 0, - T crossedLimit = 0) { - if (state != oldState) { - if (isConfirmed(state)) { - if (eventEnabled == ENABLED) { - sendTransitionEvent(parameterValue, state); - } - if (reportingEnabled == ENABLED) { - sendTransitionReport(parameterValue, crossedLimit, state); - } - oldState = state; - } else { - //This is to ensure confirmation works. - //Needs to be reset to be able to confirm against oldState again next time. - return oldState; - } - } else { - resetConfirmation(); - } - return state; - } + virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, + ParameterWrapper *parameterWrapper, + const ParameterWrapper *newValues, uint16_t startAtIndex) { + if (domainId != monitorId) { + return INVALID_DOMAIN_ID; + } + switch (uniqueId) { + case 0: + parameterWrapper->set(this->confirmationLimit); + break; + case 1: + parameterWrapper->set(this->reportingEnabled); + break; + case 2: + parameterWrapper->set(this->eventEnabled); + break; + default: + return INVALID_IDENTIFIER_ID; + } + return HasReturnvaluesIF::RETURN_OK; + } + virtual ReturnValue_t setToUnchecked() { return setToState(MonitoringIF::UNCHECKED); } + virtual ReturnValue_t setToInvalid() { return setToState(MonitoringIF::INVALID); } + object_id_t getReporterId() const { return reportingId; } - virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, - ParameterWrapper *parameterWrapper, const ParameterWrapper *newValues, - uint16_t startAtIndex) { - if (domainId != monitorId) { - return INVALID_DOMAIN_ID; - } - switch (uniqueId) { - case 0: - parameterWrapper->set(this->confirmationLimit); - break; - case 1: - parameterWrapper->set(this->reportingEnabled); - break; - case 2: - parameterWrapper->set(this->eventEnabled); - break; - default: - return INVALID_IDENTIFIER_ID; - } - return HasReturnvaluesIF::RETURN_OK; - } - virtual ReturnValue_t setToUnchecked() { - return setToState(MonitoringIF::UNCHECKED); - } - virtual ReturnValue_t setToInvalid() { - return setToState(MonitoringIF::INVALID); - } - object_id_t getReporterId() const { - return reportingId; - } + void setEventEnabled(uint8_t eventEnabled) { this->eventEnabled = eventEnabled; } - void setEventEnabled(uint8_t eventEnabled) { - this->eventEnabled = eventEnabled; - } + void setReportingEnabled(uint8_t reportingEnabled) { this->reportingEnabled = reportingEnabled; } - void setReportingEnabled(uint8_t reportingEnabled) { - this->reportingEnabled = reportingEnabled; - } + bool isEventEnabled() const { return (eventEnabled == ENABLED); } - bool isEventEnabled() const { - return (eventEnabled == ENABLED); - } + protected: + const uint8_t monitorId; + const gp_id_t globalPoolId; + object_id_t reportingId; + ReturnValue_t oldState; -protected: - const uint8_t monitorId; - const gp_id_t globalPoolId; - object_id_t reportingId; - ReturnValue_t oldState; + uint8_t reportingEnabled; - uint8_t reportingEnabled; + uint8_t eventEnabled; - uint8_t eventEnabled; + uint16_t currentCounter; + uint16_t confirmationLimit; - uint16_t currentCounter; - uint16_t confirmationLimit; + bool isConfirmed(ReturnValue_t state) { + // Confirm INVALID and UNCHECKED immediately. + if (state == MonitoringIF::INVALID || state == MonitoringIF::UNCHECKED) { + currentCounter = 0; + return true; + } + return doesChildConfirm(state); + } - bool isConfirmed(ReturnValue_t state) { - //Confirm INVALID and UNCHECKED immediately. - if (state == MonitoringIF::INVALID - || state == MonitoringIF::UNCHECKED) { - currentCounter = 0; - return true; - } - return doesChildConfirm(state); - } - - /** - * This is the most simple form of confirmation. - * A counter counts any violation and compares the number to maxCounter. - * @param state The state, indicating the type of violation. Not used here. - * @return true if counter > maxCounter, else false. - */ - virtual bool doesChildConfirm(ReturnValue_t state) { - currentCounter += 1; - if (currentCounter > confirmationLimit) { - currentCounter = 0; - return true; - } else { - return false; - } - } - /** - * This method needs to reset the confirmation in case a valid sample was found. - * Here, simply resets the current counter. - */ - virtual void resetConfirmation() { - currentCounter = 0; - } - /** - * Default version of sending transitional events. - * Should be overridden from specialized monitors. - * @param currentValue The current value which was monitored. - * @param state The state the monitor changed to. - */ - virtual void sendTransitionEvent(T currentValue, ReturnValue_t state) { - switch(state) { - case MonitoringIF::UNCHECKED: - case MonitoringIF::UNSELECTED: - case MonitoringIF::INVALID: - case HasReturnvaluesIF::RETURN_OK: - break; - default: - EventManagerIF::triggerEvent(reportingId, - MonitoringIF::MONITOR_CHANGED_STATE, state); - break; - } - } - /** - * Default implementation for sending transition report. - * May be overridden, but is seldom necessary. - * @param parameterValue Current value of the parameter - * @param crossedLimit The limit crossed (if applicable). - * @param state Current state the monitor is in. - */ - virtual void sendTransitionReport(T parameterValue, T crossedLimit, - ReturnValue_t state) { - MonitoringReportContent report(globalPoolId, - parameterValue, crossedLimit, oldState, state); - LimitViolationReporter::sendLimitViolationReport(&report); - } - ReturnValue_t setToState(ReturnValue_t state) { - if (oldState != state && reportingEnabled) { - MonitoringReportContent report(globalPoolId, 0, 0, oldState, - state); - LimitViolationReporter::sendLimitViolationReport(&report); - oldState = state; - } - return HasReturnvaluesIF::RETURN_OK; - } + /** + * This is the most simple form of confirmation. + * A counter counts any violation and compares the number to maxCounter. + * @param state The state, indicating the type of violation. Not used here. + * @return true if counter > maxCounter, else false. + */ + virtual bool doesChildConfirm(ReturnValue_t state) { + currentCounter += 1; + if (currentCounter > confirmationLimit) { + currentCounter = 0; + return true; + } else { + return false; + } + } + /** + * This method needs to reset the confirmation in case a valid sample was found. + * Here, simply resets the current counter. + */ + virtual void resetConfirmation() { currentCounter = 0; } + /** + * Default version of sending transitional events. + * Should be overridden from specialized monitors. + * @param currentValue The current value which was monitored. + * @param state The state the monitor changed to. + */ + virtual void sendTransitionEvent(T currentValue, ReturnValue_t state) { + switch (state) { + case MonitoringIF::UNCHECKED: + case MonitoringIF::UNSELECTED: + case MonitoringIF::INVALID: + case HasReturnvaluesIF::RETURN_OK: + break; + default: + EventManagerIF::triggerEvent(reportingId, MonitoringIF::MONITOR_CHANGED_STATE, state); + break; + } + } + /** + * Default implementation for sending transition report. + * May be overridden, but is seldom necessary. + * @param parameterValue Current value of the parameter + * @param crossedLimit The limit crossed (if applicable). + * @param state Current state the monitor is in. + */ + virtual void sendTransitionReport(T parameterValue, T crossedLimit, ReturnValue_t state) { + MonitoringReportContent report(globalPoolId, parameterValue, crossedLimit, oldState, state); + LimitViolationReporter::sendLimitViolationReport(&report); + } + ReturnValue_t setToState(ReturnValue_t state) { + if (oldState != state && reportingEnabled) { + MonitoringReportContent report(globalPoolId, 0, 0, oldState, state); + LimitViolationReporter::sendLimitViolationReport(&report); + oldState = state; + } + return HasReturnvaluesIF::RETURN_OK; + } }; #endif /* FSFW_MONITORING_MONITORREPORTER_H_ */ diff --git a/src/fsfw/monitoring/MonitoringIF.h b/src/fsfw/monitoring/MonitoringIF.h index 9c35b419..12eb566f 100644 --- a/src/fsfw/monitoring/MonitoringIF.h +++ b/src/fsfw/monitoring/MonitoringIF.h @@ -1,65 +1,63 @@ #ifndef FSFW_MONITORING_MONITORINGIF_H_ #define FSFW_MONITORING_MONITORINGIF_H_ -#include "monitoringConf.h" -#include "MonitoringMessage.h" #include "../serialize/SerializeIF.h" +#include "MonitoringMessage.h" +#include "monitoringConf.h" class MonitoringIF : public SerializeIF { -public: - static const uint8_t VIOLATION_REPORT_MAX_SIZE = 32; - static const uint8_t LIMIT_TYPE_NO_TYPE = 0xFF; - static const uint8_t LIMIT_TYPE_LIMIT_CHECK = 0; - static const uint8_t LIMIT_TYPE_DELTA_CHECK = 1; - static const uint8_t LIMIT_TYPE_ABSOLUTE_CHECK = 2; - static const uint8_t LIMIT_TYPE_OBJECT = 128; + public: + static const uint8_t VIOLATION_REPORT_MAX_SIZE = 32; + static const uint8_t LIMIT_TYPE_NO_TYPE = 0xFF; + static const uint8_t LIMIT_TYPE_LIMIT_CHECK = 0; + static const uint8_t LIMIT_TYPE_DELTA_CHECK = 1; + static const uint8_t LIMIT_TYPE_ABSOLUTE_CHECK = 2; + static const uint8_t LIMIT_TYPE_OBJECT = 128; - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::FDIR_2; - static const Event MONITOR_CHANGED_STATE = MAKE_EVENT(1, severity::LOW); - static const Event VALUE_BELOW_LOW_LIMIT = MAKE_EVENT(2, severity::LOW); - static const Event VALUE_ABOVE_HIGH_LIMIT = MAKE_EVENT(3, severity::LOW); - static const Event VALUE_OUT_OF_RANGE = MAKE_EVENT(4, severity::LOW); + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::FDIR_2; + static const Event MONITOR_CHANGED_STATE = MAKE_EVENT(1, severity::LOW); + static const Event VALUE_BELOW_LOW_LIMIT = MAKE_EVENT(2, severity::LOW); + static const Event VALUE_ABOVE_HIGH_LIMIT = MAKE_EVENT(3, severity::LOW); + static const Event VALUE_OUT_OF_RANGE = MAKE_EVENT(4, severity::LOW); - static const uint8_t INTERFACE_ID = CLASS_ID::LIMITS_IF; - static const ReturnValue_t UNCHECKED = MAKE_RETURN_CODE(1); - static const ReturnValue_t INVALID = MAKE_RETURN_CODE(2); - static const ReturnValue_t UNSELECTED = MAKE_RETURN_CODE(3); - static const ReturnValue_t BELOW_LOW_LIMIT = MAKE_RETURN_CODE(4); -// static const ReturnValue_t CHECKING_STATUS_BELOW_LOW_THRESHOLD = MAKE_RETURN_CODE(4); -// static const ReturnValue_t CHECKING_STATUS_ABOVE_HIGH_THRESHOLD = MAKE_RETURN_CODE(5); - static const ReturnValue_t ABOVE_HIGH_LIMIT = MAKE_RETURN_CODE(5); - static const ReturnValue_t UNEXPECTED_VALUE = MAKE_RETURN_CODE(6); - static const ReturnValue_t OUT_OF_RANGE = MAKE_RETURN_CODE(7); + static const uint8_t INTERFACE_ID = CLASS_ID::LIMITS_IF; + static const ReturnValue_t UNCHECKED = MAKE_RETURN_CODE(1); + static const ReturnValue_t INVALID = MAKE_RETURN_CODE(2); + static const ReturnValue_t UNSELECTED = MAKE_RETURN_CODE(3); + static const ReturnValue_t BELOW_LOW_LIMIT = MAKE_RETURN_CODE(4); + // static const ReturnValue_t CHECKING_STATUS_BELOW_LOW_THRESHOLD = MAKE_RETURN_CODE(4); + // static const ReturnValue_t CHECKING_STATUS_ABOVE_HIGH_THRESHOLD = MAKE_RETURN_CODE(5); + static const ReturnValue_t ABOVE_HIGH_LIMIT = MAKE_RETURN_CODE(5); + static const ReturnValue_t UNEXPECTED_VALUE = MAKE_RETURN_CODE(6); + static const ReturnValue_t OUT_OF_RANGE = MAKE_RETURN_CODE(7); + static const ReturnValue_t FIRST_SAMPLE = MAKE_RETURN_CODE(0xA0); + static const ReturnValue_t INVALID_SIZE = MAKE_RETURN_CODE(0xE0); + static const ReturnValue_t WRONG_TYPE = MAKE_RETURN_CODE(0xE1); + static const ReturnValue_t WRONG_PID = MAKE_RETURN_CODE(0xE2); + static const ReturnValue_t WRONG_LIMIT_ID = MAKE_RETURN_CODE(0xE3); + static const ReturnValue_t MONITOR_NOT_FOUND = MAKE_RETURN_CODE(0xEE); - static const ReturnValue_t FIRST_SAMPLE = MAKE_RETURN_CODE(0xA0); - static const ReturnValue_t INVALID_SIZE = MAKE_RETURN_CODE(0xE0); - static const ReturnValue_t WRONG_TYPE = MAKE_RETURN_CODE(0xE1); - static const ReturnValue_t WRONG_PID = MAKE_RETURN_CODE(0xE2); - static const ReturnValue_t WRONG_LIMIT_ID = MAKE_RETURN_CODE(0xE3); - static const ReturnValue_t MONITOR_NOT_FOUND = MAKE_RETURN_CODE(0xEE); + static const uint8_t REPORT_NONE = 0; + static const uint8_t REPORT_EVENTS_ONLY = 1; + static const uint8_t REPORT_REPORTS_ONLY = 2; + static const uint8_t REPORT_ALL = 3; - static const uint8_t REPORT_NONE = 0; - static const uint8_t REPORT_EVENTS_ONLY = 1; - static const uint8_t REPORT_REPORTS_ONLY = 2; - static const uint8_t REPORT_ALL = 3; - -// static const ReturnValue_t STILL_IN_LOW_WARNING = MAKE_RETURN_CODE(0x11); -// static const ReturnValue_t STILL_IN_LOW_LIMIT = MAKE_RETURN_CODE(0x12); -// static const ReturnValue_t STILL_IN_HIGH_WARNING = MAKE_RETURN_CODE(0x13); -// static const ReturnValue_t STILL_IN_HIGH_LIMIT = MAKE_RETURN_CODE(0x14); -// static const ReturnValue_t VARIABLE_IS_INVALID = MAKE_RETURN_CODE(0xE0); -// static const ReturnValue_t INVALID_SIZE = MAKE_RETURN_CODE(0xE1); -// static const ReturnValue_t INVALID_ID = MAKE_RETURN_CODE(0xE2); - virtual ReturnValue_t check() = 0; - virtual ReturnValue_t setLimits( uint8_t type, const uint8_t* data, uint32_t size) = 0; - virtual ReturnValue_t setChecking(uint8_t strategy) = 0; - virtual ReturnValue_t setToUnchecked() = 0; - virtual uint8_t getLimitType() const = 0; - virtual uint32_t getLimitId() const = 0; -// virtual ReturnValue_t setEventReporting(bool active) = 0; - virtual ~MonitoringIF() { - } + // static const ReturnValue_t STILL_IN_LOW_WARNING = MAKE_RETURN_CODE(0x11); + // static const ReturnValue_t STILL_IN_LOW_LIMIT = MAKE_RETURN_CODE(0x12); + // static const ReturnValue_t STILL_IN_HIGH_WARNING = MAKE_RETURN_CODE(0x13); + // static const ReturnValue_t STILL_IN_HIGH_LIMIT = MAKE_RETURN_CODE(0x14); + // static const ReturnValue_t VARIABLE_IS_INVALID = MAKE_RETURN_CODE(0xE0); + // static const ReturnValue_t INVALID_SIZE = MAKE_RETURN_CODE(0xE1); + // static const ReturnValue_t INVALID_ID = MAKE_RETURN_CODE(0xE2); + virtual ReturnValue_t check() = 0; + virtual ReturnValue_t setLimits(uint8_t type, const uint8_t* data, uint32_t size) = 0; + virtual ReturnValue_t setChecking(uint8_t strategy) = 0; + virtual ReturnValue_t setToUnchecked() = 0; + virtual uint8_t getLimitType() const = 0; + virtual uint32_t getLimitId() const = 0; + // virtual ReturnValue_t setEventReporting(bool active) = 0; + virtual ~MonitoringIF() {} }; #endif /* FSFW_MONITORING_MONITORINGIF_H_ */ diff --git a/src/fsfw/monitoring/MonitoringMessage.cpp b/src/fsfw/monitoring/MonitoringMessage.cpp index 8bbb7765..1e259093 100644 --- a/src/fsfw/monitoring/MonitoringMessage.cpp +++ b/src/fsfw/monitoring/MonitoringMessage.cpp @@ -1,38 +1,37 @@ #include "fsfw/monitoring/MonitoringMessage.h" + #include "fsfw/objectmanager/ObjectManager.h" -MonitoringMessage::~MonitoringMessage() { +MonitoringMessage::~MonitoringMessage() {} + +void MonitoringMessage::setLimitViolationReport(CommandMessage* message, store_address_t storeId) { + setTypicalMessage(message, LIMIT_VIOLATION_REPORT, storeId); } -void MonitoringMessage::setLimitViolationReport(CommandMessage* message, - store_address_t storeId) { - setTypicalMessage(message, LIMIT_VIOLATION_REPORT, storeId); -} - -void MonitoringMessage::setTypicalMessage(CommandMessage* message, - Command_t type, store_address_t storeId) { - message->setCommand(type); - message->setParameter2(storeId.raw); +void MonitoringMessage::setTypicalMessage(CommandMessage* message, Command_t type, + store_address_t storeId) { + message->setCommand(type); + message->setParameter2(storeId.raw); } store_address_t MonitoringMessage::getStoreId(const CommandMessage* message) { - store_address_t temp; - temp.raw = message->getParameter2(); - return temp; + store_address_t temp; + temp.raw = message->getParameter2(); + return temp; } void MonitoringMessage::clear(CommandMessage* message) { - message->setCommand(CommandMessage::CMD_NONE); - switch (message->getCommand()) { - case MonitoringMessage::LIMIT_VIOLATION_REPORT: { - StorageManagerIF *ipcStore = ObjectManager::instance()->get( - objects::IPC_STORE); - if (ipcStore != NULL) { - ipcStore->deleteData(getStoreId(message)); - } - break; - } - default: - break; - } + message->setCommand(CommandMessage::CMD_NONE); + switch (message->getCommand()) { + case MonitoringMessage::LIMIT_VIOLATION_REPORT: { + StorageManagerIF* ipcStore = + ObjectManager::instance()->get(objects::IPC_STORE); + if (ipcStore != NULL) { + ipcStore->deleteData(getStoreId(message)); + } + break; + } + default: + break; + } } diff --git a/src/fsfw/monitoring/MonitoringMessage.h b/src/fsfw/monitoring/MonitoringMessage.h index a625e388..9695120b 100644 --- a/src/fsfw/monitoring/MonitoringMessage.h +++ b/src/fsfw/monitoring/MonitoringMessage.h @@ -1,22 +1,21 @@ #ifndef MONITORINGMESSAGE_H_ #define MONITORINGMESSAGE_H_ -#include "monitoringConf.h" #include "fsfw/ipc/CommandMessage.h" #include "fsfw/storagemanager/StorageManagerIF.h" +#include "monitoringConf.h" -class MonitoringMessage: public CommandMessage { -public: - static const uint8_t MESSAGE_ID = messagetypes::MONITORING; - //Object id could be useful, but we better manage that on service level (register potential reporters). - static const Command_t LIMIT_VIOLATION_REPORT = MAKE_COMMAND_ID(10); - virtual ~MonitoringMessage(); - static void setLimitViolationReport(CommandMessage* message, store_address_t storeId); - static void clear(CommandMessage* message); - static store_address_t getStoreId(const CommandMessage* message); - static void setTypicalMessage(CommandMessage* message, Command_t type, store_address_t storeId); - +class MonitoringMessage : public CommandMessage { + public: + static const uint8_t MESSAGE_ID = messagetypes::MONITORING; + // Object id could be useful, but we better manage that on service level (register potential + // reporters). + static const Command_t LIMIT_VIOLATION_REPORT = MAKE_COMMAND_ID(10); + virtual ~MonitoringMessage(); + static void setLimitViolationReport(CommandMessage* message, store_address_t storeId); + static void clear(CommandMessage* message); + static store_address_t getStoreId(const CommandMessage* message); + static void setTypicalMessage(CommandMessage* message, Command_t type, store_address_t storeId); }; - #endif /* MONITORINGMESSAGE_H_ */ diff --git a/src/fsfw/monitoring/MonitoringMessageContent.h b/src/fsfw/monitoring/MonitoringMessageContent.h index cf8c8752..0ac455eb 100644 --- a/src/fsfw/monitoring/MonitoringMessageContent.h +++ b/src/fsfw/monitoring/MonitoringMessageContent.h @@ -1,90 +1,99 @@ #ifndef FSFW_MONITORING_MONITORINGMESSAGECONTENT_H_ #define FSFW_MONITORING_MONITORINGMESSAGECONTENT_H_ -#include "monitoringConf.h" -#include "HasMonitorsIF.h" -#include "MonitoringIF.h" - #include "../datapoollocal/localPoolDefinitions.h" #include "../objectmanager/ObjectManager.h" #include "../serialize/SerialBufferAdapter.h" #include "../serialize/SerialFixedArrayListAdapter.h" -#include "../serialize/SerializeElement.h" #include "../serialize/SerialLinkedListAdapter.h" +#include "../serialize/SerializeElement.h" #include "../serviceinterface/ServiceInterface.h" #include "../timemanager/TimeStamperIF.h" +#include "HasMonitorsIF.h" +#include "MonitoringIF.h" +#include "monitoringConf.h" -namespace Factory{ +namespace Factory { void setStaticFrameworkObjectIds(); } -//PID(uint32_t), TYPE, LIMIT_ID, value,limitValue, previous, later, timestamp +// PID(uint32_t), TYPE, LIMIT_ID, value,limitValue, previous, later, timestamp /** * @brief Does magic. * @tparam T */ -template -class MonitoringReportContent: public SerialLinkedListAdapter { - friend void (Factory::setStaticFrameworkObjectIds)(); -public: - SerializeElement monitorId; - SerializeElement parameterObjectId; - SerializeElement localPoolId; - SerializeElement parameterValue; - SerializeElement limitValue; - SerializeElement oldState; - SerializeElement newState; - uint8_t rawTimestamp[TimeStamperIF::MISSION_TIMESTAMP_SIZE]; - SerializeElement> timestampSerializer; - TimeStamperIF* timeStamper; - MonitoringReportContent() : - SerialLinkedListAdapter(¶meterObjectId), - monitorId(0), parameterObjectId(0), - localPoolId(0), parameterValue(0), - limitValue(0), oldState(0), newState(0), - rawTimestamp( { 0 }), timestampSerializer(rawTimestamp, - sizeof(rawTimestamp)), timeStamper(NULL) { - setAllNext(); - } - MonitoringReportContent(gp_id_t globalPoolId, T value, T limitValue, - ReturnValue_t oldState, ReturnValue_t newState) : - SerialLinkedListAdapter(¶meterObjectId), - monitorId(0), parameterObjectId(globalPoolId.objectId), - localPoolId(globalPoolId.localPoolId), - parameterValue(value), limitValue(limitValue), - oldState(oldState), newState(newState), - timestampSerializer(rawTimestamp, sizeof(rawTimestamp)), - timeStamper(NULL) { - setAllNext(); - if (checkAndSetStamper()) { - timeStamper->addTimeStamp(rawTimestamp, sizeof(rawTimestamp)); - } - } -private: +template +class MonitoringReportContent : public SerialLinkedListAdapter { + friend void(Factory::setStaticFrameworkObjectIds)(); - static object_id_t timeStamperId; - void setAllNext() { - parameterObjectId.setNext(¶meterValue); - parameterValue.setNext(&limitValue); - limitValue.setNext(&oldState); - oldState.setNext(&newState); - newState.setNext(×tampSerializer); - } - bool checkAndSetStamper() { - if (timeStamper == nullptr) { - timeStamper = ObjectManager::instance()->get( timeStamperId ); - if ( timeStamper == nullptr ) { + public: + SerializeElement monitorId; + SerializeElement parameterObjectId; + SerializeElement localPoolId; + SerializeElement parameterValue; + SerializeElement limitValue; + SerializeElement oldState; + SerializeElement newState; + uint8_t rawTimestamp[TimeStamperIF::MISSION_TIMESTAMP_SIZE]; + SerializeElement> timestampSerializer; + TimeStamperIF* timeStamper; + MonitoringReportContent() + : SerialLinkedListAdapter(¶meterObjectId), + monitorId(0), + parameterObjectId(0), + localPoolId(0), + parameterValue(0), + limitValue(0), + oldState(0), + newState(0), + rawTimestamp({0}), + timestampSerializer(rawTimestamp, sizeof(rawTimestamp)), + timeStamper(NULL) { + setAllNext(); + } + MonitoringReportContent(gp_id_t globalPoolId, T value, T limitValue, ReturnValue_t oldState, + ReturnValue_t newState) + : SerialLinkedListAdapter(¶meterObjectId), + monitorId(0), + parameterObjectId(globalPoolId.objectId), + localPoolId(globalPoolId.localPoolId), + parameterValue(value), + limitValue(limitValue), + oldState(oldState), + newState(newState), + timestampSerializer(rawTimestamp, sizeof(rawTimestamp)), + timeStamper(NULL) { + setAllNext(); + if (checkAndSetStamper()) { + timeStamper->addTimeStamp(rawTimestamp, sizeof(rawTimestamp)); + } + } + + private: + static object_id_t timeStamperId; + void setAllNext() { + parameterObjectId.setNext(¶meterValue); + parameterValue.setNext(&limitValue); + limitValue.setNext(&oldState); + oldState.setNext(&newState); + newState.setNext(×tampSerializer); + } + bool checkAndSetStamper() { + if (timeStamper == nullptr) { + timeStamper = ObjectManager::instance()->get(timeStamperId); + if (timeStamper == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "MonitoringReportContent::checkAndSetStamper: " - "Stamper not found!" << std::endl; + sif::error << "MonitoringReportContent::checkAndSetStamper: " + "Stamper not found!" + << std::endl; #endif - return false; - } - } - return true; - } + return false; + } + } + return true; + } }; -template +template object_id_t MonitoringReportContent::timeStamperId = 0; #endif /* FSFW_MONITORING_MONITORINGMESSAGECONTENT_H_ */ diff --git a/src/fsfw/monitoring/ReceivesMonitoringReportsIF.h b/src/fsfw/monitoring/ReceivesMonitoringReportsIF.h index 6c126c84..f42fb5c4 100644 --- a/src/fsfw/monitoring/ReceivesMonitoringReportsIF.h +++ b/src/fsfw/monitoring/ReceivesMonitoringReportsIF.h @@ -1,16 +1,13 @@ #ifndef RECEIVESMONITORINGREPORTSIF_H_ #define RECEIVESMONITORINGREPORTSIF_H_ -#include "monitoringConf.h" #include "fsfw/ipc/messageQueueDefinitions.h" +#include "monitoringConf.h" class ReceivesMonitoringReportsIF { -public: - virtual MessageQueueId_t getCommandQueue() const = 0; - virtual ~ReceivesMonitoringReportsIF() { - } + public: + virtual MessageQueueId_t getCommandQueue() const = 0; + virtual ~ReceivesMonitoringReportsIF() {} }; - - #endif /* RECEIVESMONITORINGREPORTSIF_H_ */ diff --git a/src/fsfw/monitoring/TriplexMonitor.h b/src/fsfw/monitoring/TriplexMonitor.h index ff995b5d..1d9182aa 100644 --- a/src/fsfw/monitoring/TriplexMonitor.h +++ b/src/fsfw/monitoring/TriplexMonitor.h @@ -1,156 +1,151 @@ #ifndef FRAMEWORK_MONITORING_TRIPLEXMONITOR_H_ #define FRAMEWORK_MONITORING_TRIPLEXMONITOR_H_ -#include "monitoringConf.h" #include "../datapool/DataSet.h" #include "../datapool/PIDReaderList.h" #include "../health/HealthTableIF.h" -#include "../parameters/HasParametersIF.h" #include "../objectmanager/ObjectManager.h" +#include "../parameters/HasParametersIF.h" +#include "monitoringConf.h" - -//SHOULDDO: This is by far not perfect. Could be merged with new Monitor classes. But still, it's over-engineering. -template +// SHOULDDO: This is by far not perfect. Could be merged with new Monitor classes. But still, it's +// over-engineering. +template class TriplexMonitor : public HasParametersIF { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::TRIPLE_REDUNDACY_CHECK; - static const ReturnValue_t NOT_ENOUGH_SENSORS = MAKE_RETURN_CODE(1); - static const ReturnValue_t LOWEST_VALUE_OOL = MAKE_RETURN_CODE(2); - static const ReturnValue_t HIGHEST_VALUE_OOL = MAKE_RETURN_CODE(3); - static const ReturnValue_t BOTH_VALUES_OOL = MAKE_RETURN_CODE(4); - static const ReturnValue_t DUPLEX_OOL = MAKE_RETURN_CODE(5); + public: + static const uint8_t INTERFACE_ID = CLASS_ID::TRIPLE_REDUNDACY_CHECK; + static const ReturnValue_t NOT_ENOUGH_SENSORS = MAKE_RETURN_CODE(1); + static const ReturnValue_t LOWEST_VALUE_OOL = MAKE_RETURN_CODE(2); + static const ReturnValue_t HIGHEST_VALUE_OOL = MAKE_RETURN_CODE(3); + static const ReturnValue_t BOTH_VALUES_OOL = MAKE_RETURN_CODE(4); + static const ReturnValue_t DUPLEX_OOL = MAKE_RETURN_CODE(5); - static const uint8_t THREE = 3; + static const uint8_t THREE = 3; - TriplexMonitor(const uint32_t parameterIds[3], uint8_t domainId, const T initialLimit, - Event eventTripleCheck, Event eventDualCheck) : - values(parameterIds, &dataSet), limit(initialLimit), eventTripleCheck( - eventTripleCheck), eventDualCheck(eventDualCheck), healthTable( - NULL), domainId(domainId) { + TriplexMonitor(const uint32_t parameterIds[3], uint8_t domainId, const T initialLimit, + Event eventTripleCheck, Event eventDualCheck) + : values(parameterIds, &dataSet), + limit(initialLimit), + eventTripleCheck(eventTripleCheck), + eventDualCheck(eventDualCheck), + healthTable(NULL), + domainId(domainId) {} + virtual ~TriplexMonitor() {} + ReturnValue_t check() { + dataSet.read(); + // check health and validity + uint8_t availableIndex[2] = {0, 0}; + bool first = true; + uint8_t nAvailable = 0; + for (uint8_t count = 0; count < THREE; count++) { + if (values[count].isValid() && checkObjectHealthState(count)) { + if (first) { + availableIndex[0] = count; + first = false; + } else { + // Might be filled twice, but then it's not needed anyway. + availableIndex[1] = count; + } + nAvailable++; + } + } + ReturnValue_t result = HasReturnvaluesIF::RETURN_FAILED; + switch (nAvailable) { + case 3: + result = doTriplexMonitoring(); + break; + case 2: + result = doDuplexMonitoring(availableIndex); + break; + default: + result = NOT_ENOUGH_SENSORS; + break; + } + dataSet.commit(); + return result; + } + ReturnValue_t initialize() { + healthTable = ObjectManager::instance()->get(objects::HEALTH_TABLE); + if (healthTable == NULL) { + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; + } - } - virtual ~TriplexMonitor() { - } - ReturnValue_t check() { - dataSet.read(); - //check health and validity - uint8_t availableIndex[2] = { 0, 0 }; - bool first = true; - uint8_t nAvailable = 0; - for (uint8_t count = 0; count < THREE; count++) { - if (values[count].isValid() && checkObjectHealthState(count)) { - if (first) { - availableIndex[0] = count; - first = false; - } else { - //Might be filled twice, but then it's not needed anyway. - availableIndex[1] = count; - } - nAvailable++; - } - } - ReturnValue_t result = HasReturnvaluesIF::RETURN_FAILED; - switch (nAvailable) { - case 3: - result = doTriplexMonitoring(); - break; - case 2: - result = doDuplexMonitoring(availableIndex); - break; - default: - result = NOT_ENOUGH_SENSORS; - break; - } - dataSet.commit(); - return result; - } - ReturnValue_t initialize() { - healthTable = ObjectManager::instance()->get(objects::HEALTH_TABLE); - if (healthTable == NULL) { - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; - } + ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, ParameterWrapper *parameterWrapper, + const ParameterWrapper *newValues, uint16_t startAtIndex) { + if (domainId != this->domainId) { + return INVALID_DOMAIN_ID; + } + switch (uniqueId) { + case 0: + parameterWrapper->set(limit); + break; + default: + return INVALID_IDENTIFIER_ID; + } + return HasReturnvaluesIF::RETURN_OK; + } - ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, - ParameterWrapper *parameterWrapper, const ParameterWrapper *newValues, - uint16_t startAtIndex) { - if (domainId != this->domainId) { - return INVALID_DOMAIN_ID; - } - switch (uniqueId) { - case 0: - parameterWrapper->set(limit); - break; - default: - return INVALID_IDENTIFIER_ID; - } - return HasReturnvaluesIF::RETURN_OK; - } + protected: + DataSet dataSet; + PIDReaderList values; + T limit; + Event eventTripleCheck; + Event eventDualCheck; + HealthTableIF *healthTable; + uint8_t domainId; + ReturnValue_t doTriplexMonitoring() { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + // Find middle value, by ordering indices + uint8_t index[3] = {0, 1, 2}; + if (values[index[0]].value > values[index[1]].value) { + std::swap(index[0], index[1]); + } + if (values[index[0]].value > values[index[2]].value) { + std::swap(index[0], index[2]); + } + if (values[index[1]].value > values[index[2]].value) { + std::swap(index[1], index[2]); + } + // Test if smallest value is out-of-limit. + if (values[index[0]] < (values[index[1]] - limit)) { + EventManagerIF::triggerEvent(getRefereneceObject(index[0]), eventTripleCheck, + LOWEST_VALUE_OOL, 0); + result = LOWEST_VALUE_OOL; + } + // Test if largest value is out-of-limit. + if (values[index[2]] > (values[index[1]] + limit)) { + EventManagerIF::triggerEvent(getRefereneceObject(index[2]), eventTripleCheck, + HIGHEST_VALUE_OOL, 0); + if (result == HasReturnvaluesIF::RETURN_OK) { + result = HIGHEST_VALUE_OOL; + } else { + result = BOTH_VALUES_OOL; + } + } + return result; + } -protected: - DataSet dataSet; - PIDReaderList values; - T limit; - Event eventTripleCheck; - Event eventDualCheck; - HealthTableIF* healthTable; - uint8_t domainId; - ReturnValue_t doTriplexMonitoring() { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - //Find middle value, by ordering indices - uint8_t index[3] = { 0, 1, 2 }; - if (values[index[0]].value > values[index[1]].value) { - std::swap(index[0], index[1]); - } - if (values[index[0]].value > values[index[2]].value) { - std::swap(index[0], index[2]); - } - if (values[index[1]].value > values[index[2]].value) { - std::swap(index[1], index[2]); - } - //Test if smallest value is out-of-limit. - if (values[index[0]] < (values[index[1]] - limit)) { - EventManagerIF::triggerEvent(getRefereneceObject(index[0]), - eventTripleCheck, LOWEST_VALUE_OOL, 0); - result = LOWEST_VALUE_OOL; - } - //Test if largest value is out-of-limit. - if (values[index[2]] > (values[index[1]] + limit)) { - EventManagerIF::triggerEvent(getRefereneceObject(index[2]), - eventTripleCheck, HIGHEST_VALUE_OOL, 0); - if (result == HasReturnvaluesIF::RETURN_OK) { - result = HIGHEST_VALUE_OOL; - } else { - result = BOTH_VALUES_OOL; - } - } - return result; - } - - ReturnValue_t doDuplexMonitoring(uint8_t index[2]) { - T mean = (values[index[0]] + values[index[1]]) / 2; - if (values[index[0]] > values[index[1]]) { - if (values[index[0]] > (mean + limit)) { - EventManagerIF::triggerEvent(getRefereneceObject(index[0]), - eventDualCheck, 0, 0); - EventManagerIF::triggerEvent(getRefereneceObject(index[1]), - eventDualCheck, 0, 0); - return DUPLEX_OOL; - } - } else { - if (values[index[1]] > (mean + limit)) { - EventManagerIF::triggerEvent(getRefereneceObject(index[0]), - eventDualCheck, 0, 0); - EventManagerIF::triggerEvent(getRefereneceObject(index[1]), - eventDualCheck, 0, 0); - return DUPLEX_OOL; - } - } - return HasReturnvaluesIF::RETURN_OK; - } - virtual bool checkObjectHealthState(uint8_t valueIndex) = 0; - virtual object_id_t getRefereneceObject(uint8_t valueIndex) = 0; + ReturnValue_t doDuplexMonitoring(uint8_t index[2]) { + T mean = (values[index[0]] + values[index[1]]) / 2; + if (values[index[0]] > values[index[1]]) { + if (values[index[0]] > (mean + limit)) { + EventManagerIF::triggerEvent(getRefereneceObject(index[0]), eventDualCheck, 0, 0); + EventManagerIF::triggerEvent(getRefereneceObject(index[1]), eventDualCheck, 0, 0); + return DUPLEX_OOL; + } + } else { + if (values[index[1]] > (mean + limit)) { + EventManagerIF::triggerEvent(getRefereneceObject(index[0]), eventDualCheck, 0, 0); + EventManagerIF::triggerEvent(getRefereneceObject(index[1]), eventDualCheck, 0, 0); + return DUPLEX_OOL; + } + } + return HasReturnvaluesIF::RETURN_OK; + } + virtual bool checkObjectHealthState(uint8_t valueIndex) = 0; + virtual object_id_t getRefereneceObject(uint8_t valueIndex) = 0; }; #endif /* FRAMEWORK_MONITORING_TRIPLEXMONITOR_H_ */ diff --git a/src/fsfw/monitoring/TwoValueLimitMonitor.h b/src/fsfw/monitoring/TwoValueLimitMonitor.h index cd34391c..79b8c4bb 100644 --- a/src/fsfw/monitoring/TwoValueLimitMonitor.h +++ b/src/fsfw/monitoring/TwoValueLimitMonitor.h @@ -1,45 +1,43 @@ #ifndef FRAMEWORK_MONITORING_TWOVALUELIMITMONITOR_H_ #define FRAMEWORK_MONITORING_TWOVALUELIMITMONITOR_H_ -#include "monitoringConf.h" #include "LimitMonitor.h" +#include "monitoringConf.h" -template -class TwoValueLimitMonitor: public LimitMonitor { -public: - TwoValueLimitMonitor(object_id_t reporterId, uint8_t monitorId, - uint32_t lowParameterId, uint32_t highParameterId, - uint16_t confirmationLimit, T lowerLimit, T upperLimit, - Event belowLowEvent = MonitoringIF::VALUE_BELOW_LOW_LIMIT, - Event aboveHighEvent = MonitoringIF::VALUE_ABOVE_HIGH_LIMIT) : - LimitMonitor(reporterId, monitorId, lowParameterId, - confirmationLimit, lowerLimit, upperLimit, belowLowEvent, - aboveHighEvent), highValueParameterId(highParameterId) { - } - virtual ~TwoValueLimitMonitor() { - } - ReturnValue_t doCheck(T lowSample, T highSample) { - T crossedLimit; - ReturnValue_t currentState = this->checkSample(lowSample, &crossedLimit); - if (currentState != HasReturnvaluesIF::RETURN_OK) { - return this->monitorStateIs(currentState, lowSample, crossedLimit); - } - currentState = this->checkSample(highSample, &crossedLimit); - return this->monitorStateIs(currentState, highSample, crossedLimit); - } -protected: - virtual void sendTransitionReport(T parameterValue, T crossedLimit, - ReturnValue_t state) { - uint32_t usedParameterId = this->parameterId; - if (state == MonitoringIF::ABOVE_HIGH_LIMIT) { - usedParameterId = this->highValueParameterId; - } - MonitoringReportContent report(usedParameterId, parameterValue, - crossedLimit, this->oldState, state); - LimitViolationReporter::sendLimitViolationReport(&report); - } -private: - const uint32_t highValueParameterId; +template +class TwoValueLimitMonitor : public LimitMonitor { + public: + TwoValueLimitMonitor(object_id_t reporterId, uint8_t monitorId, uint32_t lowParameterId, + uint32_t highParameterId, uint16_t confirmationLimit, T lowerLimit, + T upperLimit, Event belowLowEvent = MonitoringIF::VALUE_BELOW_LOW_LIMIT, + Event aboveHighEvent = MonitoringIF::VALUE_ABOVE_HIGH_LIMIT) + : LimitMonitor(reporterId, monitorId, lowParameterId, confirmationLimit, lowerLimit, + upperLimit, belowLowEvent, aboveHighEvent), + highValueParameterId(highParameterId) {} + virtual ~TwoValueLimitMonitor() {} + ReturnValue_t doCheck(T lowSample, T highSample) { + T crossedLimit; + ReturnValue_t currentState = this->checkSample(lowSample, &crossedLimit); + if (currentState != HasReturnvaluesIF::RETURN_OK) { + return this->monitorStateIs(currentState, lowSample, crossedLimit); + } + currentState = this->checkSample(highSample, &crossedLimit); + return this->monitorStateIs(currentState, highSample, crossedLimit); + } + + protected: + virtual void sendTransitionReport(T parameterValue, T crossedLimit, ReturnValue_t state) { + uint32_t usedParameterId = this->parameterId; + if (state == MonitoringIF::ABOVE_HIGH_LIMIT) { + usedParameterId = this->highValueParameterId; + } + MonitoringReportContent report(usedParameterId, parameterValue, crossedLimit, this->oldState, + state); + LimitViolationReporter::sendLimitViolationReport(&report); + } + + private: + const uint32_t highValueParameterId; }; #endif /* FRAMEWORK_MONITORING_TWOVALUELIMITMONITOR_H_ */ diff --git a/src/fsfw/objectmanager/ObjectManager.cpp b/src/fsfw/objectmanager/ObjectManager.cpp index 639688ab..2017938a 100644 --- a/src/fsfw/objectmanager/ObjectManager.cpp +++ b/src/fsfw/objectmanager/ObjectManager.cpp @@ -1,4 +1,5 @@ #include "fsfw/objectmanager/ObjectManager.h" + #include "fsfw/serviceinterface/ServiceInterface.h" #if FSFW_CPP_OSTREAM_ENABLED == 1 @@ -9,137 +10,133 @@ ObjectManager* ObjectManager::objManagerInstance = nullptr; ObjectManager* ObjectManager::instance() { - if(objManagerInstance == nullptr) { - objManagerInstance = new ObjectManager(); - } - return objManagerInstance; + if (objManagerInstance == nullptr) { + objManagerInstance = new ObjectManager(); + } + return objManagerInstance; } -void ObjectManager::setObjectFactoryFunction(produce_function_t objFactoryFunc, void *factoryArgs) { - this->objectFactoryFunction = objFactoryFunc; - this->factoryArgs = factoryArgs; +void ObjectManager::setObjectFactoryFunction(produce_function_t objFactoryFunc, void* factoryArgs) { + this->objectFactoryFunction = objFactoryFunc; + this->factoryArgs = factoryArgs; } - ObjectManager::ObjectManager() {} - ObjectManager::~ObjectManager() { - for (auto const& iter : objectList) { - delete iter.second; - } + for (auto const& iter : objectList) { + delete iter.second; + } } -ReturnValue_t ObjectManager::insert( object_id_t id, SystemObjectIF* object) { - auto returnPair = objectList.emplace(id, object); - if (returnPair.second) { +ReturnValue_t ObjectManager::insert(object_id_t id, SystemObjectIF* object) { + auto returnPair = objectList.emplace(id, object); + if (returnPair.second) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - // sif::debug << "ObjectManager::insert: Object " << std::hex - // << (int)id << std::dec << " inserted." << std::endl; + // sif::debug << "ObjectManager::insert: Object " << std::hex + // << (int)id << std::dec << " inserted." << std::endl; #endif - return this->RETURN_OK; - } else { + return this->RETURN_OK; + } else { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "ObjectManager::insert: Object ID " << std::hex << - static_cast(id) << std::dec << " is already in use!" << std::endl; - sif::error << "Terminating program" << std::endl; + sif::error << "ObjectManager::insert: Object ID " << std::hex << static_cast(id) + << std::dec << " is already in use!" << std::endl; + sif::error << "Terminating program" << std::endl; #else - sif::printError("ObjectManager::insert: Object ID 0x%08x is already in use!\n", - static_cast(id)); - sif::printError("Terminating program"); + sif::printError("ObjectManager::insert: Object ID 0x%08x is already in use!\n", + static_cast(id)); + sif::printError("Terminating program"); #endif - //This is very severe and difficult to handle in other places. - std::exit(INSERTION_FAILED); - } + // This is very severe and difficult to handle in other places. + std::exit(INSERTION_FAILED); + } } -ReturnValue_t ObjectManager::remove( object_id_t id ) { - if ( this->getSystemObject(id) != NULL ) { - this->objectList.erase( id ); +ReturnValue_t ObjectManager::remove(object_id_t id) { + if (this->getSystemObject(id) != NULL) { + this->objectList.erase(id); #if FSFW_CPP_OSTREAM_ENABLED == 1 - //sif::debug << "ObjectManager::removeObject: Object " << std::hex - // << (int)id << std::dec << " removed." << std::endl; + // sif::debug << "ObjectManager::removeObject: Object " << std::hex + // << (int)id << std::dec << " removed." << std::endl; #endif - return RETURN_OK; - } else { + return RETURN_OK; + } else { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "ObjectManager::removeObject: Requested object " - << std::hex << (int)id << std::dec << " not found." << std::endl; + sif::error << "ObjectManager::removeObject: Requested object " << std::hex << (int)id + << std::dec << " not found." << std::endl; #endif - return NOT_FOUND; - } + return NOT_FOUND; + } } - - -SystemObjectIF* ObjectManager::getSystemObject( object_id_t id ) { - auto listIter = this->objectList.find( id ); - if (listIter == this->objectList.end() ) { - return nullptr; - } else { - return listIter->second; - } +SystemObjectIF* ObjectManager::getSystemObject(object_id_t id) { + auto listIter = this->objectList.find(id); + if (listIter == this->objectList.end()) { + return nullptr; + } else { + return listIter->second; + } } void ObjectManager::initialize() { - if(objectFactoryFunction == nullptr) { + if (objectFactoryFunction == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "ObjectManager::initialize: Passed produceObjects " - "functions is nullptr!" << std::endl; + sif::error << "ObjectManager::initialize: Passed produceObjects " + "functions is nullptr!" + << std::endl; #else - sif::printError("ObjectManager::initialize: Passed produceObjects functions is nullptr!\n"); + sif::printError("ObjectManager::initialize: Passed produceObjects functions is nullptr!\n"); #endif - return; - } - objectFactoryFunction(factoryArgs); - ReturnValue_t result = RETURN_FAILED; - uint32_t errorCount = 0; - for (auto const& it : objectList) { - result = it.second->initialize(); - if ( result != RETURN_OK ) { + return; + } + objectFactoryFunction(factoryArgs); + ReturnValue_t result = RETURN_FAILED; + uint32_t errorCount = 0; + for (auto const& it : objectList) { + result = it.second->initialize(); + if (result != RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - object_id_t var = it.first; - sif::error << "ObjectManager::initialize: Object 0x" << std::hex << - std::setw(8) << std::setfill('0')<< var << " failed to " - "initialize with code 0x" << result << std::dec << - std::setfill(' ') << std::endl; + object_id_t var = it.first; + sif::error << "ObjectManager::initialize: Object 0x" << std::hex << std::setw(8) + << std::setfill('0') << var + << " failed to " + "initialize with code 0x" + << result << std::dec << std::setfill(' ') << std::endl; #endif - errorCount++; - } - } - if (errorCount > 0) { + errorCount++; + } + } + if (errorCount > 0) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "ObjectManager::ObjectManager: Counted " << errorCount - << " failed initializations." << std::endl; + sif::error << "ObjectManager::ObjectManager: Counted " << errorCount + << " failed initializations." << std::endl; #endif - } - //Init was successful. Now check successful interconnections. - errorCount = 0; - for (auto const& it : objectList) { - result = it.second->checkObjectConnections(); - if ( result != RETURN_OK ) { + } + // Init was successful. Now check successful interconnections. + errorCount = 0; + for (auto const& it : objectList) { + result = it.second->checkObjectConnections(); + if (result != RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "ObjectManager::ObjectManager: Object 0x" << std::hex << - (int) it.first << " connection check failed with code 0x" << result << - std::dec << std::endl; + sif::error << "ObjectManager::ObjectManager: Object 0x" << std::hex << (int)it.first + << " connection check failed with code 0x" << result << std::dec << std::endl; #endif - errorCount++; - } - } - if (errorCount > 0) { + errorCount++; + } + } + if (errorCount > 0) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "ObjectManager::ObjectManager: Counted " << errorCount - << " failed connection checks." << std::endl; + sif::error << "ObjectManager::ObjectManager: Counted " << errorCount + << " failed connection checks." << std::endl; #endif - } + } } void ObjectManager::printList() { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "ObjectManager: Object List contains:" << std::endl; - for (auto const& it : objectList) { - sif::debug << std::hex << it.first << " | " << it.second << std::endl; - - } + sif::debug << "ObjectManager: Object List contains:" << std::endl; + for (auto const& it : objectList) { + sif::debug << std::hex << it.first << " | " << it.second << std::endl; + } #endif } diff --git a/src/fsfw/objectmanager/ObjectManager.h b/src/fsfw/objectmanager/ObjectManager.h index 9f5f0c37..50e4af00 100644 --- a/src/fsfw/objectmanager/ObjectManager.h +++ b/src/fsfw/objectmanager/ObjectManager.h @@ -1,10 +1,10 @@ #ifndef FSFW_OBJECTMANAGER_OBJECTMANAGER_H_ #define FSFW_OBJECTMANAGER_OBJECTMANAGER_H_ -#include "ObjectManagerIF.h" -#include "SystemObjectIF.h" #include +#include "ObjectManagerIF.h" +#include "SystemObjectIF.h" /** * @brief This class implements a global object manager. @@ -20,59 +20,59 @@ * @author Bastian Baetz */ class ObjectManager : public ObjectManagerIF { -public: + public: + using produce_function_t = void (*)(void* args); - using produce_function_t = void (*) (void* args); + /** + * Returns the single instance of TaskFactory. + * The implementation of #instance is found in its subclasses. + * Thus, we choose link-time variability of the instance. + */ + static ObjectManager* instance(); - /** - * Returns the single instance of TaskFactory. - * The implementation of #instance is found in its subclasses. - * Thus, we choose link-time variability of the instance. - */ - static ObjectManager* instance(); + void setObjectFactoryFunction(produce_function_t prodFunc, void* args); - void setObjectFactoryFunction(produce_function_t prodFunc, void* args); + template + T* get(object_id_t id); - template T* get( object_id_t id ); + /** + * @brief In the class's destructor, all objects in the list are deleted. + */ + virtual ~ObjectManager(); + ReturnValue_t insert(object_id_t id, SystemObjectIF* object) override; + ReturnValue_t remove(object_id_t id) override; + void initialize() override; + void printList() override; - /** - * @brief In the class's destructor, all objects in the list are deleted. - */ - virtual ~ObjectManager(); - ReturnValue_t insert(object_id_t id, SystemObjectIF* object) override; - ReturnValue_t remove(object_id_t id) override; - void initialize() override; - void printList() override; + protected: + SystemObjectIF* getSystemObject(object_id_t id) override; + /** + * @brief This attribute is initialized with the factory function + * that creates new objects. + * @details The function is called if an object was requested with + * getSystemObject, but not found in objectList. + * @param The id of the object to be created. + * @return Returns a pointer to the newly created object or NULL. + */ + produce_function_t objectFactoryFunction = nullptr; + void* factoryArgs = nullptr; -protected: - SystemObjectIF* getSystemObject(object_id_t id) override; - /** - * @brief This attribute is initialized with the factory function - * that creates new objects. - * @details The function is called if an object was requested with - * getSystemObject, but not found in objectList. - * @param The id of the object to be created. - * @return Returns a pointer to the newly created object or NULL. - */ - produce_function_t objectFactoryFunction = nullptr; - void* factoryArgs = nullptr; + private: + ObjectManager(); -private: - ObjectManager(); - - /** - * @brief This is the map of all initialized objects in the manager. - * @details Objects in the List must inherit the SystemObjectIF. - */ - std::map objectList; - static ObjectManager* objManagerInstance; + /** + * @brief This is the map of all initialized objects in the manager. + * @details Objects in the List must inherit the SystemObjectIF. + */ + std::map objectList; + static ObjectManager* objManagerInstance; }; // Documentation can be found in the class method declaration above template -T* ObjectManager::get( object_id_t id ) { - SystemObjectIF* temp = this->getSystemObject(id); - return dynamic_cast(temp); +T* ObjectManager::get(object_id_t id) { + SystemObjectIF* temp = this->getSystemObject(id); + return dynamic_cast(temp); } #endif /* FSFW_OBJECTMANAGER_OBJECTMANAGER_H_ */ diff --git a/src/fsfw/objectmanager/ObjectManagerIF.h b/src/fsfw/objectmanager/ObjectManagerIF.h index 561ff352..32a0942f 100644 --- a/src/fsfw/objectmanager/ObjectManagerIF.h +++ b/src/fsfw/objectmanager/ObjectManagerIF.h @@ -1,10 +1,10 @@ #ifndef FSFW_OBJECTMANAGER_OBJECTMANAGERIF_H_ #define FSFW_OBJECTMANAGER_OBJECTMANAGERIF_H_ -#include "frameworkObjects.h" -#include "SystemObjectIF.h" #include "../returnvalues/HasReturnvaluesIF.h" #include "../serviceinterface/ServiceInterface.h" +#include "SystemObjectIF.h" +#include "frameworkObjects.h" /** * @brief This class provides an interface to the global object manager. @@ -17,52 +17,53 @@ * @ingroup system_objects */ class ObjectManagerIF : public HasReturnvaluesIF { -public: - static constexpr uint8_t INTERFACE_ID = CLASS_ID::OBJECT_MANAGER_IF; - static constexpr ReturnValue_t INSERTION_FAILED = MAKE_RETURN_CODE( 1 ); - static constexpr ReturnValue_t NOT_FOUND = MAKE_RETURN_CODE( 2 ); - //!< Can be used if the initialization of a SystemObject failed. - static constexpr ReturnValue_t CHILD_INIT_FAILED = MAKE_RETURN_CODE( 3 ); - static constexpr ReturnValue_t INTERNAL_ERR_REPORTER_UNINIT = MAKE_RETURN_CODE( 4 ); + public: + static constexpr uint8_t INTERFACE_ID = CLASS_ID::OBJECT_MANAGER_IF; + static constexpr ReturnValue_t INSERTION_FAILED = MAKE_RETURN_CODE(1); + static constexpr ReturnValue_t NOT_FOUND = MAKE_RETURN_CODE(2); + //!< Can be used if the initialization of a SystemObject failed. + static constexpr ReturnValue_t CHILD_INIT_FAILED = MAKE_RETURN_CODE(3); + static constexpr ReturnValue_t INTERNAL_ERR_REPORTER_UNINIT = MAKE_RETURN_CODE(4); -protected: - /** - * @brief This method is used to hide the template-based get call from - * a specific implementation. - * @details So, an implementation only has to implement this call. - * @param id The object id of the requested object. - * @return The method returns a pointer to an object implementing (at - * least) the SystemObjectIF, or NULL. - */ - virtual SystemObjectIF* getSystemObject( object_id_t id ) = 0; -public: - /** - * @brief This is the empty virtual destructor as requested by C++ interfaces. - */ - virtual ~ObjectManagerIF( void ) {}; - /** - * @brief With this call, new objects are inserted to the list. - * @details The implementation shall return an error code in case the - * object can't be added (e.g. the id is already in use). - * @param id The new id to be added to the list. - * @param object A pointer to the object to be added. - * @return @li INSERTION_FAILED in case the object could not be inserted. - * @li RETURN_OK in case the object was successfully inserted - */ - virtual ReturnValue_t insert( object_id_t id, SystemObjectIF* object ) = 0; - /** - * @brief With this call, an object is removed from the list. - * @param id The object id of the object to be removed. - * @return @li NOT_FOUND in case the object was not found - * @li RETURN_OK in case the object was successfully removed - */ - virtual ReturnValue_t remove( object_id_t id ) = 0; - virtual void initialize() = 0; - /** - * @brief This is a debug function, that prints the current content of the - * object list. - */ - virtual void printList() = 0; + protected: + /** + * @brief This method is used to hide the template-based get call from + * a specific implementation. + * @details So, an implementation only has to implement this call. + * @param id The object id of the requested object. + * @return The method returns a pointer to an object implementing (at + * least) the SystemObjectIF, or NULL. + */ + virtual SystemObjectIF* getSystemObject(object_id_t id) = 0; + + public: + /** + * @brief This is the empty virtual destructor as requested by C++ interfaces. + */ + virtual ~ObjectManagerIF(void){}; + /** + * @brief With this call, new objects are inserted to the list. + * @details The implementation shall return an error code in case the + * object can't be added (e.g. the id is already in use). + * @param id The new id to be added to the list. + * @param object A pointer to the object to be added. + * @return @li INSERTION_FAILED in case the object could not be inserted. + * @li RETURN_OK in case the object was successfully inserted + */ + virtual ReturnValue_t insert(object_id_t id, SystemObjectIF* object) = 0; + /** + * @brief With this call, an object is removed from the list. + * @param id The object id of the object to be removed. + * @return @li NOT_FOUND in case the object was not found + * @li RETURN_OK in case the object was successfully removed + */ + virtual ReturnValue_t remove(object_id_t id) = 0; + virtual void initialize() = 0; + /** + * @brief This is a debug function, that prints the current content of the + * object list. + */ + virtual void printList() = 0; }; #endif /* OBJECTMANAGERIF_H_ */ diff --git a/src/fsfw/objectmanager/SystemObject.cpp b/src/fsfw/objectmanager/SystemObject.cpp index bad38975..7f8acfd8 100644 --- a/src/fsfw/objectmanager/SystemObject.cpp +++ b/src/fsfw/objectmanager/SystemObject.cpp @@ -1,37 +1,31 @@ -#include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/objectmanager/SystemObject.h" -#include "fsfw/events/EventManagerIF.h" -SystemObject::SystemObject(object_id_t setObjectId, bool doRegister) : - objectId(setObjectId), registered(doRegister) { - if (registered) { - ObjectManager::instance()->insert(objectId, this); - } +#include "fsfw/events/EventManagerIF.h" +#include "fsfw/objectmanager/ObjectManager.h" + +SystemObject::SystemObject(object_id_t setObjectId, bool doRegister) + : objectId(setObjectId), registered(doRegister) { + if (registered) { + ObjectManager::instance()->insert(objectId, this); + } } SystemObject::~SystemObject() { - if (registered) { - ObjectManager::instance()->remove(objectId); - } + if (registered) { + ObjectManager::instance()->remove(objectId); + } } -object_id_t SystemObject::getObjectId() const { - return objectId; +object_id_t SystemObject::getObjectId() const { return objectId; } + +void SystemObject::triggerEvent(Event event, uint32_t parameter1, uint32_t parameter2) { + EventManagerIF::triggerEvent(objectId, event, parameter1, parameter2); } -void SystemObject::triggerEvent(Event event, uint32_t parameter1, - uint32_t parameter2) { - EventManagerIF::triggerEvent(objectId, event, parameter1, parameter2); -} +ReturnValue_t SystemObject::initialize() { return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t SystemObject::initialize() { - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t SystemObject::checkObjectConnections() { - return HasReturnvaluesIF::RETURN_OK; -} +ReturnValue_t SystemObject::checkObjectConnections() { return HasReturnvaluesIF::RETURN_OK; } void SystemObject::forwardEvent(Event event, uint32_t parameter1, uint32_t parameter2) const { - EventManagerIF::triggerEvent(objectId, event, parameter1, parameter2); + EventManagerIF::triggerEvent(objectId, event, parameter1, parameter2); } diff --git a/src/fsfw/objectmanager/SystemObject.h b/src/fsfw/objectmanager/SystemObject.h index e7d2ae2b..6d5b8303 100644 --- a/src/fsfw/objectmanager/SystemObject.h +++ b/src/fsfw/objectmanager/SystemObject.h @@ -16,43 +16,41 @@ * @author Ulrich Mohr * @ingroup system_objects */ -class SystemObject: public SystemObjectIF { -private: - /** - * @brief This is the id the class instant got assigned. - */ - const object_id_t objectId; - const bool registered; -public: +class SystemObject : public SystemObjectIF { + private: + /** + * @brief This is the id the class instant got assigned. + */ + const object_id_t objectId; + const bool registered; - /** - * Helper function to send Event Messages to the Event Manager - * @param event - * @param parameter1 - * @param parameter2 - */ - virtual void triggerEvent(Event event, uint32_t parameter1 = 0, - uint32_t parameter2 = 0); + public: + /** + * Helper function to send Event Messages to the Event Manager + * @param event + * @param parameter1 + * @param parameter2 + */ + virtual void triggerEvent(Event event, uint32_t parameter1 = 0, uint32_t parameter2 = 0); - /** - * @brief The class's constructor. - * @details In the constructor, the object id is set and the class is - * inserted in the object manager. - * @param setObjectId The id the object shall have. - * @param doRegister Determines if the object is registered in - * the global object manager. - */ - SystemObject(object_id_t setObjectId, bool doRegister = true); - /** - * @brief On destruction, the object removes itself from the list. - */ - virtual ~SystemObject(); - object_id_t getObjectId() const override; - virtual ReturnValue_t initialize() override; - virtual ReturnValue_t checkObjectConnections(); + /** + * @brief The class's constructor. + * @details In the constructor, the object id is set and the class is + * inserted in the object manager. + * @param setObjectId The id the object shall have. + * @param doRegister Determines if the object is registered in + * the global object manager. + */ + SystemObject(object_id_t setObjectId, bool doRegister = true); + /** + * @brief On destruction, the object removes itself from the list. + */ + virtual ~SystemObject(); + object_id_t getObjectId() const override; + virtual ReturnValue_t initialize() override; + virtual ReturnValue_t checkObjectConnections(); - virtual void forwardEvent(Event event, uint32_t parameter1 = 0, - uint32_t parameter2 = 0) const; + virtual void forwardEvent(Event event, uint32_t parameter1 = 0, uint32_t parameter2 = 0) const; }; #endif /* FSFW_OBJECTMANAGER_SYSTEMOBJECT_H_ */ diff --git a/src/fsfw/objectmanager/SystemObjectIF.h b/src/fsfw/objectmanager/SystemObjectIF.h index 315fde9b..72fe9044 100644 --- a/src/fsfw/objectmanager/SystemObjectIF.h +++ b/src/fsfw/objectmanager/SystemObjectIF.h @@ -1,9 +1,10 @@ #ifndef FSFW_OBJECTMANAGER_SYSTEMOBJECTIF_H_ #define FSFW_OBJECTMANAGER_SYSTEMOBJECTIF_H_ +#include + #include "../events/EventReportingProxyIF.h" #include "../returnvalues/HasReturnvaluesIF.h" -#include /** * @defgroup system_objects Software System Object Management * The classes to create System Objects and classes to manage these are @@ -26,37 +27,37 @@ typedef uint32_t object_id_t; * @ingroup system_objects */ class SystemObjectIF : public EventReportingProxyIF { -public: - /** - * This is a simple getter to return the object identifier. - * @return Returns the object id of this object. - */ - virtual object_id_t getObjectId() const = 0; - /** - * The empty virtual destructor as required for C++ interfaces. - */ - virtual ~SystemObjectIF() {} - /** - * @brief Initializes the object. - * There are initialization steps which can also be done in the constructor. - * However, there is no clean way to get a returnvalue from a constructor. - * Furthermore some components require other system object to be created - * which might not have been built yet. - * Therefore, a two-step initialization resolves this problem and prevents - * circular dependencies of not-fully initialized objects on start up. - * @return - @c RETURN_OK in case the initialization was successful - * - @c RETURN_FAILED otherwise - */ - virtual ReturnValue_t initialize() = 0; - /** - * @brief Checks if all object-object interconnections are satisfying - * for operation. - * Some objects need certain other objects (or a certain number), to be - * registered as children. These checks can be done in this method. - * @return - @c RETURN_OK in case the check was successful - * - @c any other code otherwise - */ - virtual ReturnValue_t checkObjectConnections() = 0; + public: + /** + * This is a simple getter to return the object identifier. + * @return Returns the object id of this object. + */ + virtual object_id_t getObjectId() const = 0; + /** + * The empty virtual destructor as required for C++ interfaces. + */ + virtual ~SystemObjectIF() {} + /** + * @brief Initializes the object. + * There are initialization steps which can also be done in the constructor. + * However, there is no clean way to get a returnvalue from a constructor. + * Furthermore some components require other system object to be created + * which might not have been built yet. + * Therefore, a two-step initialization resolves this problem and prevents + * circular dependencies of not-fully initialized objects on start up. + * @return - @c RETURN_OK in case the initialization was successful + * - @c RETURN_FAILED otherwise + */ + virtual ReturnValue_t initialize() = 0; + /** + * @brief Checks if all object-object interconnections are satisfying + * for operation. + * Some objects need certain other objects (or a certain number), to be + * registered as children. These checks can be done in this method. + * @return - @c RETURN_OK in case the check was successful + * - @c any other code otherwise + */ + virtual ReturnValue_t checkObjectConnections() = 0; }; #endif /* #ifndef FSFW_OBJECTMANAGER_SYSTEMOBJECTIF_H_ */ diff --git a/src/fsfw/objectmanager/frameworkObjects.h b/src/fsfw/objectmanager/frameworkObjects.h index ff7d9341..cc233c0f 100644 --- a/src/fsfw/objectmanager/frameworkObjects.h +++ b/src/fsfw/objectmanager/frameworkObjects.h @@ -5,39 +5,37 @@ // The objects will be instantiated in the ID order namespace objects { -enum framework_objects: object_id_t { - FSFW_OBJECTS_START = 0x53000000, - // Default verification reporter. - PUS_SERVICE_1_VERIFICATION = 0x53000001, - PUS_SERVICE_2_DEVICE_ACCESS = 0x53000002, - PUS_SERVICE_3_HOUSEKEEPING = 0x53000003, - PUS_SERVICE_5_EVENT_REPORTING = 0x53000005, - PUS_SERVICE_8_FUNCTION_MGMT = 0x53000008, - PUS_SERVICE_9_TIME_MGMT = 0x53000009, - PUS_SERVICE_17_TEST = 0x53000017, - PUS_SERVICE_20_PARAMETERS = 0x53000020, - PUS_SERVICE_200_MODE_MGMT = 0x53000200, - PUS_SERVICE_201_HEALTH = 0x53000201, +enum framework_objects : object_id_t { + FSFW_OBJECTS_START = 0x53000000, + // Default verification reporter. + PUS_SERVICE_1_VERIFICATION = 0x53000001, + PUS_SERVICE_2_DEVICE_ACCESS = 0x53000002, + PUS_SERVICE_3_HOUSEKEEPING = 0x53000003, + PUS_SERVICE_5_EVENT_REPORTING = 0x53000005, + PUS_SERVICE_8_FUNCTION_MGMT = 0x53000008, + PUS_SERVICE_9_TIME_MGMT = 0x53000009, + PUS_SERVICE_17_TEST = 0x53000017, + PUS_SERVICE_20_PARAMETERS = 0x53000020, + PUS_SERVICE_200_MODE_MGMT = 0x53000200, + PUS_SERVICE_201_HEALTH = 0x53000201, - /* CFDP Distributer */ - CFDP_PACKET_DISTRIBUTOR = 0x53001000, + /* CFDP Distributer */ + CFDP_PACKET_DISTRIBUTOR = 0x53001000, - //Generic IDs for IPC, modes, health, events - HEALTH_TABLE = 0x53010000, - // MODE_STORE = 0x53010100, - EVENT_MANAGER = 0x53030000, - INTERNAL_ERROR_REPORTER = 0x53040000, - IPC_STORE = 0x534f0300, - //IDs for PUS Packet Communication - TC_STORE = 0x534f0100, - TM_STORE = 0x534f0200, - TIME_STAMPER = 0x53500010, + // Generic IDs for IPC, modes, health, events + HEALTH_TABLE = 0x53010000, + // MODE_STORE = 0x53010100, + EVENT_MANAGER = 0x53030000, + INTERNAL_ERROR_REPORTER = 0x53040000, + IPC_STORE = 0x534f0300, + // IDs for PUS Packet Communication + TC_STORE = 0x534f0100, + TM_STORE = 0x534f0200, + TIME_STAMPER = 0x53500010, - FSFW_OBJECTS_END = 0x53ffffff, - NO_OBJECT = 0xFFFFFFFF + FSFW_OBJECTS_END = 0x53ffffff, + NO_OBJECT = 0xFFFFFFFF }; } - - #endif /* FSFW_OBJECTMANAGER_FRAMEWORKOBJECTS_H_ */ diff --git a/src/fsfw/osal/Endiness.h b/src/fsfw/osal/Endiness.h index 281b715b..29118c3f 100644 --- a/src/fsfw/osal/Endiness.h +++ b/src/fsfw/osal/Endiness.h @@ -1,15 +1,14 @@ #ifndef FRAMEWORK_OSAL_ENDINESS_H_ #define FRAMEWORK_OSAL_ENDINESS_H_ - /* * BSD-style endian declaration */ #ifndef BIG_ENDIAN -#define BIG_ENDIAN 4321 +#define BIG_ENDIAN 4321 #endif #ifndef LITTLE_ENDIAN -#define LITTLE_ENDIAN 1234 +#define LITTLE_ENDIAN 1234 #endif // This is a GCC C extension @@ -25,15 +24,14 @@ #else #ifdef WIN32 -#include #include +#include #if REG_DWORD == REG_DWORD_LITTLE_ENDIAN #define BYTE_ORDER_SYSTEM LITTLE_ENDIAN #else #define BYTE_ORDER_SYSTEM BIG_ENDIAN #endif - #else #error __BYTE_ORDER__ not defined #endif @@ -42,7 +40,4 @@ #endif - - - #endif /* FRAMEWORK_OSAL_ENDINESS_H_ */ diff --git a/src/fsfw/osal/InternalErrorCodes.h b/src/fsfw/osal/InternalErrorCodes.h index e7522875..5924d4c9 100644 --- a/src/fsfw/osal/InternalErrorCodes.h +++ b/src/fsfw/osal/InternalErrorCodes.h @@ -4,36 +4,37 @@ #include "fsfw/returnvalues/HasReturnvaluesIF.h" class InternalErrorCodes { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::INTERNAL_ERROR_CODES; + public: + static const uint8_t INTERFACE_ID = CLASS_ID::INTERNAL_ERROR_CODES; - static const ReturnValue_t NO_CONFIGURATION_TABLE = MAKE_RETURN_CODE(0x01 ); - static const ReturnValue_t NO_CPU_TABLE = MAKE_RETURN_CODE(0x02 ); - static const ReturnValue_t INVALID_WORKSPACE_ADDRESS = MAKE_RETURN_CODE(0x03 ); - static const ReturnValue_t TOO_LITTLE_WORKSPACE = MAKE_RETURN_CODE(0x04 ); - static const ReturnValue_t WORKSPACE_ALLOCATION = MAKE_RETURN_CODE(0x05 ); - static const ReturnValue_t INTERRUPT_STACK_TOO_SMALL = MAKE_RETURN_CODE(0x06 ); - static const ReturnValue_t THREAD_EXITTED = MAKE_RETURN_CODE(0x07 ); - static const ReturnValue_t INCONSISTENT_MP_INFORMATION = MAKE_RETURN_CODE(0x08 ); - static const ReturnValue_t INVALID_NODE = MAKE_RETURN_CODE(0x09 ); - static const ReturnValue_t NO_MPCI = MAKE_RETURN_CODE(0x0a ); - static const ReturnValue_t BAD_PACKET = MAKE_RETURN_CODE(0x0b ); - static const ReturnValue_t OUT_OF_PACKETS = MAKE_RETURN_CODE(0x0c ); - static const ReturnValue_t OUT_OF_GLOBAL_OBJECTS = MAKE_RETURN_CODE(0x0d ); - static const ReturnValue_t OUT_OF_PROXIES = MAKE_RETURN_CODE(0x0e ); - static const ReturnValue_t INVALID_GLOBAL_ID = MAKE_RETURN_CODE(0x0f ); - static const ReturnValue_t BAD_STACK_HOOK = MAKE_RETURN_CODE(0x10 ); - static const ReturnValue_t BAD_ATTRIBUTES = MAKE_RETURN_CODE(0x11 ); - static const ReturnValue_t IMPLEMENTATION_KEY_CREATE_INCONSISTENCY = MAKE_RETURN_CODE(0x12 ); - static const ReturnValue_t IMPLEMENTATION_BLOCKING_OPERATION_CANCEL = MAKE_RETURN_CODE(0x13 ); - static const ReturnValue_t MUTEX_OBTAIN_FROM_BAD_STATE = MAKE_RETURN_CODE(0x14 ); - static const ReturnValue_t UNLIMITED_AND_MAXIMUM_IS_0 = MAKE_RETURN_CODE(0x15 ); + static const ReturnValue_t NO_CONFIGURATION_TABLE = MAKE_RETURN_CODE(0x01); + static const ReturnValue_t NO_CPU_TABLE = MAKE_RETURN_CODE(0x02); + static const ReturnValue_t INVALID_WORKSPACE_ADDRESS = MAKE_RETURN_CODE(0x03); + static const ReturnValue_t TOO_LITTLE_WORKSPACE = MAKE_RETURN_CODE(0x04); + static const ReturnValue_t WORKSPACE_ALLOCATION = MAKE_RETURN_CODE(0x05); + static const ReturnValue_t INTERRUPT_STACK_TOO_SMALL = MAKE_RETURN_CODE(0x06); + static const ReturnValue_t THREAD_EXITTED = MAKE_RETURN_CODE(0x07); + static const ReturnValue_t INCONSISTENT_MP_INFORMATION = MAKE_RETURN_CODE(0x08); + static const ReturnValue_t INVALID_NODE = MAKE_RETURN_CODE(0x09); + static const ReturnValue_t NO_MPCI = MAKE_RETURN_CODE(0x0a); + static const ReturnValue_t BAD_PACKET = MAKE_RETURN_CODE(0x0b); + static const ReturnValue_t OUT_OF_PACKETS = MAKE_RETURN_CODE(0x0c); + static const ReturnValue_t OUT_OF_GLOBAL_OBJECTS = MAKE_RETURN_CODE(0x0d); + static const ReturnValue_t OUT_OF_PROXIES = MAKE_RETURN_CODE(0x0e); + static const ReturnValue_t INVALID_GLOBAL_ID = MAKE_RETURN_CODE(0x0f); + static const ReturnValue_t BAD_STACK_HOOK = MAKE_RETURN_CODE(0x10); + static const ReturnValue_t BAD_ATTRIBUTES = MAKE_RETURN_CODE(0x11); + static const ReturnValue_t IMPLEMENTATION_KEY_CREATE_INCONSISTENCY = MAKE_RETURN_CODE(0x12); + static const ReturnValue_t IMPLEMENTATION_BLOCKING_OPERATION_CANCEL = MAKE_RETURN_CODE(0x13); + static const ReturnValue_t MUTEX_OBTAIN_FROM_BAD_STATE = MAKE_RETURN_CODE(0x14); + static const ReturnValue_t UNLIMITED_AND_MAXIMUM_IS_0 = MAKE_RETURN_CODE(0x15); - virtual ~InternalErrorCodes(); + virtual ~InternalErrorCodes(); - static ReturnValue_t translate(uint8_t code); -private: - InternalErrorCodes(); + static ReturnValue_t translate(uint8_t code); + + private: + InternalErrorCodes(); }; #endif /* INTERNALERRORCODES_H_ */ diff --git a/src/fsfw/osal/common/TcpIpBase.cpp b/src/fsfw/osal/common/TcpIpBase.cpp index b6b64e13..67e71053 100644 --- a/src/fsfw/osal/common/TcpIpBase.cpp +++ b/src/fsfw/osal/common/TcpIpBase.cpp @@ -1,4 +1,5 @@ #include "fsfw/osal/common/TcpIpBase.h" + #include "fsfw/platform.h" #ifdef PLATFORM_UNIX @@ -6,48 +7,45 @@ #include #endif -TcpIpBase::TcpIpBase() { - -} +TcpIpBase::TcpIpBase() {} ReturnValue_t TcpIpBase::initialize() { #ifdef _WIN32 - /* Initiates Winsock DLL. */ - WSAData wsaData; - WORD wVersionRequested = MAKEWORD(2, 2); - int err = WSAStartup(wVersionRequested, &wsaData); - if (err != 0) { - /* Tell the user that we could not find a usable Winsock DLL. */ + /* Initiates Winsock DLL. */ + WSAData wsaData; + WORD wVersionRequested = MAKEWORD(2, 2); + int err = WSAStartup(wVersionRequested, &wsaData); + if (err != 0) { + /* Tell the user that we could not find a usable Winsock DLL. */ #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "TmTcWinUdpBridge::TmTcWinUdpBridge: WSAStartup failed with error: " << - err << std::endl; + sif::error << "TmTcWinUdpBridge::TmTcWinUdpBridge: WSAStartup failed with error: " << err + << std::endl; #endif - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; + } #endif - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } TcpIpBase::~TcpIpBase() { - closeSocket(serverSocket); + closeSocket(serverSocket); #ifdef _WIN32 - WSACleanup(); + WSACleanup(); #endif } int TcpIpBase::closeSocket(socket_t socket) { #ifdef PLATFORM_WIN - return closesocket(socket); + return closesocket(socket); #elif defined(PLATFORM_UNIX) - return close(socket); + return close(socket); #endif } int TcpIpBase::getLastSocketError() { #ifdef PLATFORM_WIN - return WSAGetLastError(); + return WSAGetLastError(); #elif defined(PLATFORM_UNIX) - return errno; + return errno; #endif } - diff --git a/src/fsfw/osal/common/TcpIpBase.h b/src/fsfw/osal/common/TcpIpBase.h index fe6a763c..ccbd12ca 100644 --- a/src/fsfw/osal/common/TcpIpBase.h +++ b/src/fsfw/osal/common/TcpIpBase.h @@ -1,8 +1,8 @@ #ifndef FSFW_OSAL_COMMON_TCPIPIF_H_ #define FSFW_OSAL_COMMON_TCPIPIF_H_ -#include "../../returnvalues/HasReturnvaluesIF.h" #include "../../platform.h" +#include "../../returnvalues/HasReturnvaluesIF.h" #ifdef PLATFORM_WIN #include @@ -11,37 +11,34 @@ #endif class TcpIpBase { -protected: - + protected: #ifdef PLATFORM_WIN - static constexpr int SHUT_RECV = SD_RECEIVE; - static constexpr int SHUT_SEND = SD_SEND; - static constexpr int SHUT_BOTH = SD_BOTH; + static constexpr int SHUT_RECV = SD_RECEIVE; + static constexpr int SHUT_SEND = SD_SEND; + static constexpr int SHUT_BOTH = SD_BOTH; - using socket_t = SOCKET; + using socket_t = SOCKET; #elif defined(PLATFORM_UNIX) - using socket_t = int; + using socket_t = int; - static constexpr int INVALID_SOCKET = -1; - static constexpr int SOCKET_ERROR = -1; + static constexpr int INVALID_SOCKET = -1; + static constexpr int SOCKET_ERROR = -1; - static constexpr int SHUT_RECV = SHUT_RD; - static constexpr int SHUT_SEND = SHUT_WR; - static constexpr int SHUT_BOTH = SHUT_RDWR; + static constexpr int SHUT_RECV = SHUT_RD; + static constexpr int SHUT_SEND = SHUT_WR; + static constexpr int SHUT_BOTH = SHUT_RDWR; #endif - TcpIpBase(); - virtual ~TcpIpBase(); + TcpIpBase(); + virtual ~TcpIpBase(); - ReturnValue_t initialize(); + ReturnValue_t initialize(); - int closeSocket(socket_t socket); + int closeSocket(socket_t socket); - int getLastSocketError(); - - socket_t serverSocket = 0; + int getLastSocketError(); + socket_t serverSocket = 0; }; - #endif /* FSFW_OSAL_COMMON_TCPIPIF_H_ */ diff --git a/src/fsfw/osal/common/TcpTmTcBridge.cpp b/src/fsfw/osal/common/TcpTmTcBridge.cpp index 3cd03c36..4b2bea73 100644 --- a/src/fsfw/osal/common/TcpTmTcBridge.cpp +++ b/src/fsfw/osal/common/TcpTmTcBridge.cpp @@ -1,9 +1,9 @@ -#include "fsfw/platform.h" #include "fsfw/osal/common/TcpTmTcBridge.h" -#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/ipc/MutexGuard.h" #include "fsfw/osal/common/TcpTmTcBridge.h" +#include "fsfw/platform.h" +#include "fsfw/serviceinterface/ServiceInterface.h" #ifdef PLATFORM_WIN @@ -11,65 +11,61 @@ #elif defined PLATFORM_UNIX -#include #include +#include #endif -TcpTmTcBridge::TcpTmTcBridge(object_id_t objectId, object_id_t tcDestination, - object_id_t tmStoreId, object_id_t tcStoreId): - TmTcBridge(objectId, tcDestination, tmStoreId, tcStoreId) { - mutex = MutexFactory::instance()->createMutex(); - // Connection is always up, TM is requested by connecting to server and receiving packets - registerCommConnect(); +TcpTmTcBridge::TcpTmTcBridge(object_id_t objectId, object_id_t tcDestination, object_id_t tmStoreId, + object_id_t tcStoreId) + : TmTcBridge(objectId, tcDestination, tmStoreId, tcStoreId) { + mutex = MutexFactory::instance()->createMutex(); + // Connection is always up, TM is requested by connecting to server and receiving packets + registerCommConnect(); } ReturnValue_t TcpTmTcBridge::initialize() { - ReturnValue_t result = TmTcBridge::initialize(); - if(result != HasReturnvaluesIF::RETURN_OK) { + ReturnValue_t result = TmTcBridge::initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "TcpTmTcBridge::initialize: TmTcBridge initialization failed!" - << std::endl; + sif::error << "TcpTmTcBridge::initialize: TmTcBridge initialization failed!" << std::endl; #else - sif::printError("TcpTmTcBridge::initialize: TmTcBridge initialization failed!\n"); + sif::printError("TcpTmTcBridge::initialize: TmTcBridge initialization failed!\n"); #endif - return result; - } + return result; + } - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } TcpTmTcBridge::~TcpTmTcBridge() { - if(mutex != nullptr) { - MutexFactory::instance()->deleteMutex(mutex); - } + if (mutex != nullptr) { + MutexFactory::instance()->deleteMutex(mutex); + } } ReturnValue_t TcpTmTcBridge::handleTm() { - // Simply store the telemetry in the FIFO, the server will use it to access the TM - MutexGuard guard(mutex, timeoutType, mutexTimeoutMs); - TmTcMessage message; - ReturnValue_t status = HasReturnvaluesIF::RETURN_OK; - for (ReturnValue_t result = tmTcReceptionQueue->receiveMessage(&message); - result == HasReturnvaluesIF::RETURN_OK; - result = tmTcReceptionQueue->receiveMessage(&message)) - { - status = storeDownlinkData(&message); - if(status != HasReturnvaluesIF::RETURN_OK) { - break; - } + // Simply store the telemetry in the FIFO, the server will use it to access the TM + MutexGuard guard(mutex, timeoutType, mutexTimeoutMs); + TmTcMessage message; + ReturnValue_t status = HasReturnvaluesIF::RETURN_OK; + for (ReturnValue_t result = tmTcReceptionQueue->receiveMessage(&message); + result == HasReturnvaluesIF::RETURN_OK; + result = tmTcReceptionQueue->receiveMessage(&message)) { + status = storeDownlinkData(&message); + if (status != HasReturnvaluesIF::RETURN_OK) { + break; } - return HasReturnvaluesIF::RETURN_OK; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t TcpTmTcBridge::sendTm(const uint8_t *data, size_t dataLen) { - // Not used. The Server uses the FIFO to access and send the telemetry. - return HasReturnvaluesIF::RETURN_OK; + // Not used. The Server uses the FIFO to access and send the telemetry. + return HasReturnvaluesIF::RETURN_OK; } - -void TcpTmTcBridge::setMutexProperties(MutexIF::TimeoutType timeoutType, - dur_millis_t timeoutMs) { - this->timeoutType = timeoutType; - this->mutexTimeoutMs = timeoutMs; +void TcpTmTcBridge::setMutexProperties(MutexIF::TimeoutType timeoutType, dur_millis_t timeoutMs) { + this->timeoutType = timeoutType; + this->mutexTimeoutMs = timeoutMs; } diff --git a/src/fsfw/osal/common/TcpTmTcBridge.h b/src/fsfw/osal/common/TcpTmTcBridge.h index dc46f1f0..504592cc 100644 --- a/src/fsfw/osal/common/TcpTmTcBridge.h +++ b/src/fsfw/osal/common/TcpTmTcBridge.h @@ -25,45 +25,41 @@ * server. This bridge will also be the default destination for telecommands, but the telecommands * will be relayed to a specified tcDestination directly. */ -class TcpTmTcBridge: - public TmTcBridge { - friend class TcpTmTcServer; -public: +class TcpTmTcBridge : public TmTcBridge { + friend class TcpTmTcServer; - /** - * Constructor - * @param objectId Object ID of the TcpTmTcBridge. - * @param tcDestination Destination for received TC packets. Any received telecommands will - * be sent there directly. The destination object needs to implement - * AcceptsTelecommandsIF. - * @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 - */ - TcpTmTcBridge(object_id_t objectId, object_id_t tcDestination, - object_id_t tmStoreId = objects::TM_STORE, - object_id_t tcStoreId = objects::TC_STORE); - virtual~ TcpTmTcBridge(); + public: + /** + * Constructor + * @param objectId Object ID of the TcpTmTcBridge. + * @param tcDestination Destination for received TC packets. Any received telecommands will + * be sent there directly. The destination object needs to implement + * AcceptsTelecommandsIF. + * @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 + */ + TcpTmTcBridge(object_id_t objectId, object_id_t tcDestination, + object_id_t tmStoreId = objects::TM_STORE, + object_id_t tcStoreId = objects::TC_STORE); + virtual ~TcpTmTcBridge(); - /** - * Set properties of internal mutex. - */ - void setMutexProperties(MutexIF::TimeoutType timeoutType, dur_millis_t timeoutMs); + /** + * Set properties of internal mutex. + */ + void setMutexProperties(MutexIF::TimeoutType timeoutType, dur_millis_t timeoutMs); - ReturnValue_t initialize() override; + ReturnValue_t initialize() override; + protected: + ReturnValue_t handleTm() override; + virtual ReturnValue_t sendTm(const uint8_t* data, size_t dataLen) override; -protected: - ReturnValue_t handleTm() override; - virtual ReturnValue_t sendTm(const uint8_t * data, size_t dataLen) override; - -private: - - //! Access to the FIFO needs to be mutex protected because it is used by the bridge and - //! the server. - MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING; - dur_millis_t mutexTimeoutMs = 20; - MutexIF* mutex; + private: + //! Access to the FIFO needs to be mutex protected because it is used by the bridge and + //! the server. + MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING; + dur_millis_t mutexTimeoutMs = 20; + MutexIF* mutex; }; #endif /* FSFW_OSAL_COMMON_TCPTMTCBRIDGE_H_ */ - diff --git a/src/fsfw/osal/common/TcpTmTcServer.cpp b/src/fsfw/osal/common/TcpTmTcServer.cpp index 7e6853fc..2e6910c5 100644 --- a/src/fsfw/osal/common/TcpTmTcServer.cpp +++ b/src/fsfw/osal/common/TcpTmTcServer.cpp @@ -1,19 +1,18 @@ -#include "fsfw/platform.h" -#include "fsfw/FSFW.h" - #include "TcpTmTcServer.h" -#include "TcpTmTcBridge.h" -#include "tcpipHelpers.h" -#include "fsfw/tmtcservices/SpacePacketParser.h" -#include "fsfw/tasks/TaskFactory.h" -#include "fsfw/globalfunctions/arrayprinter.h" +#include "TcpTmTcBridge.h" +#include "fsfw/FSFW.h" #include "fsfw/container/SharedRingBuffer.h" +#include "fsfw/globalfunctions/arrayprinter.h" #include "fsfw/ipc/MessageQueueSenderIF.h" #include "fsfw/ipc/MutexGuard.h" #include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/platform.h" #include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/tasks/TaskFactory.h" +#include "fsfw/tmtcservices/SpacePacketParser.h" #include "fsfw/tmtcservices/TmTcMessage.h" +#include "tcpipHelpers.h" #ifdef PLATFORM_WIN #include @@ -25,393 +24,385 @@ const std::string TcpTmTcServer::DEFAULT_SERVER_PORT = tcpip::DEFAULT_SERVER_PORT; TcpTmTcServer::TcpTmTcServer(object_id_t objectId, object_id_t tmtcTcpBridge, - size_t receptionBufferSize, size_t ringBufferSize, std::string customTcpServerPort, - ReceptionModes receptionMode): - SystemObject(objectId), tmtcBridgeId(tmtcTcpBridge), receptionMode(receptionMode), - tcpConfig(customTcpServerPort), receptionBuffer(receptionBufferSize), - ringBuffer(ringBufferSize, true) { -} + size_t receptionBufferSize, size_t ringBufferSize, + std::string customTcpServerPort, ReceptionModes receptionMode) + : SystemObject(objectId), + tmtcBridgeId(tmtcTcpBridge), + receptionMode(receptionMode), + tcpConfig(customTcpServerPort), + receptionBuffer(receptionBufferSize), + ringBuffer(ringBufferSize, true) {} ReturnValue_t TcpTmTcServer::initialize() { - using namespace tcpip; + using namespace tcpip; - ReturnValue_t result = TcpIpBase::initialize(); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + ReturnValue_t result = TcpIpBase::initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - switch(receptionMode) { - case(ReceptionModes::SPACE_PACKETS): { - spacePacketParser = new SpacePacketParser(validPacketIds); - if(spacePacketParser == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } + switch (receptionMode) { + case (ReceptionModes::SPACE_PACKETS): { + spacePacketParser = new SpacePacketParser(validPacketIds); + if (spacePacketParser == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } #if defined PLATFORM_UNIX - tcpConfig.tcpFlags |= MSG_DONTWAIT; + tcpConfig.tcpFlags |= MSG_DONTWAIT; #endif } - } - tcStore = ObjectManager::instance()->get(objects::TC_STORE); - if (tcStore == nullptr) { + } + tcStore = ObjectManager::instance()->get(objects::TC_STORE); + if (tcStore == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "TcpTmTcServer::initialize: TC store uninitialized!" << std::endl; + sif::error << "TcpTmTcServer::initialize: TC store uninitialized!" << std::endl; #else - sif::printError("TcpTmTcServer::initialize: TC store uninitialized!\n"); + sif::printError("TcpTmTcServer::initialize: TC store uninitialized!\n"); #endif - return ObjectManagerIF::CHILD_INIT_FAILED; - } + return ObjectManagerIF::CHILD_INIT_FAILED; + } - tmtcBridge = ObjectManager::instance()->get(tmtcBridgeId); + tmtcBridge = ObjectManager::instance()->get(tmtcBridgeId); - int retval = 0; - struct addrinfo *addrResult = nullptr; - struct addrinfo hints = {}; + int retval = 0; + struct addrinfo* addrResult = nullptr; + struct addrinfo hints = {}; - hints.ai_family = AF_INET; - hints.ai_socktype = SOCK_STREAM; - hints.ai_protocol = IPPROTO_TCP; - hints.ai_flags = AI_PASSIVE; + hints.ai_family = AF_INET; + hints.ai_socktype = SOCK_STREAM; + hints.ai_protocol = IPPROTO_TCP; + hints.ai_flags = AI_PASSIVE; - // Listen to all addresses (0.0.0.0) by using AI_PASSIVE in the hint flags - retval = getaddrinfo(nullptr, tcpConfig.tcpPort.c_str(), &hints, &addrResult); - if (retval != 0) { - handleError(Protocol::TCP, ErrorSources::GETADDRINFO_CALL); - return HasReturnvaluesIF::RETURN_FAILED; - } - - // Open TCP (stream) socket - listenerTcpSocket = socket(addrResult->ai_family, addrResult->ai_socktype, - addrResult->ai_protocol); - if(listenerTcpSocket == INVALID_SOCKET) { - freeaddrinfo(addrResult); - handleError(Protocol::TCP, ErrorSources::SOCKET_CALL); - return HasReturnvaluesIF::RETURN_FAILED; - } - - // Bind to the address found by getaddrinfo - retval = bind(listenerTcpSocket, addrResult->ai_addr, static_cast(addrResult->ai_addrlen)); - if(retval == SOCKET_ERROR) { - freeaddrinfo(addrResult); - handleError(Protocol::TCP, ErrorSources::BIND_CALL); - return HasReturnvaluesIF::RETURN_FAILED; - } + // Listen to all addresses (0.0.0.0) by using AI_PASSIVE in the hint flags + retval = getaddrinfo(nullptr, tcpConfig.tcpPort.c_str(), &hints, &addrResult); + if (retval != 0) { + handleError(Protocol::TCP, ErrorSources::GETADDRINFO_CALL); + return HasReturnvaluesIF::RETURN_FAILED; + } + // Open TCP (stream) socket + listenerTcpSocket = + socket(addrResult->ai_family, addrResult->ai_socktype, addrResult->ai_protocol); + if (listenerTcpSocket == INVALID_SOCKET) { freeaddrinfo(addrResult); - return HasReturnvaluesIF::RETURN_OK; + handleError(Protocol::TCP, ErrorSources::SOCKET_CALL); + return HasReturnvaluesIF::RETURN_FAILED; + } + + // Bind to the address found by getaddrinfo + retval = bind(listenerTcpSocket, addrResult->ai_addr, static_cast(addrResult->ai_addrlen)); + if (retval == SOCKET_ERROR) { + freeaddrinfo(addrResult); + handleError(Protocol::TCP, ErrorSources::BIND_CALL); + return HasReturnvaluesIF::RETURN_FAILED; + } + + freeaddrinfo(addrResult); + return HasReturnvaluesIF::RETURN_OK; } - -TcpTmTcServer::~TcpTmTcServer() { - closeSocket(listenerTcpSocket); -} +TcpTmTcServer::~TcpTmTcServer() { closeSocket(listenerTcpSocket); } ReturnValue_t TcpTmTcServer::performOperation(uint8_t opCode) { - using namespace tcpip; - // If a connection is accepted, the corresponding socket will be assigned to the new socket - socket_t connSocket = 0; - // sockaddr clientSockAddr = {}; - // socklen_t connectorSockAddrLen = 0; - int retval = 0; + using namespace tcpip; + // If a connection is accepted, the corresponding socket will be assigned to the new socket + socket_t connSocket = 0; + // sockaddr clientSockAddr = {}; + // socklen_t connectorSockAddrLen = 0; + int retval = 0; - // Listen for connection requests permanently for lifetime of program - while(true) { - retval = listen(listenerTcpSocket, tcpConfig.tcpBacklog); - if(retval == SOCKET_ERROR) { - handleError(Protocol::TCP, ErrorSources::LISTEN_CALL, 500); - continue; - } - - //connSocket = accept(listenerTcpSocket, &clientSockAddr, &connectorSockAddrLen); - connSocket = accept(listenerTcpSocket, nullptr, nullptr); - - if(connSocket == INVALID_SOCKET) { - handleError(Protocol::TCP, ErrorSources::ACCEPT_CALL, 500); - closeSocket(connSocket); - continue; - }; - - handleServerOperation(connSocket); - - // Done, shut down connection and go back to listening for client requests - retval = shutdown(connSocket, SHUT_BOTH); - if(retval != 0) { - handleError(Protocol::TCP, ErrorSources::SHUTDOWN_CALL); - } - closeSocket(connSocket); - connSocket = 0; + // Listen for connection requests permanently for lifetime of program + while (true) { + retval = listen(listenerTcpSocket, tcpConfig.tcpBacklog); + if (retval == SOCKET_ERROR) { + handleError(Protocol::TCP, ErrorSources::LISTEN_CALL, 500); + continue; } - return HasReturnvaluesIF::RETURN_OK; + + // connSocket = accept(listenerTcpSocket, &clientSockAddr, &connectorSockAddrLen); + connSocket = accept(listenerTcpSocket, nullptr, nullptr); + + if (connSocket == INVALID_SOCKET) { + handleError(Protocol::TCP, ErrorSources::ACCEPT_CALL, 500); + closeSocket(connSocket); + continue; + }; + + handleServerOperation(connSocket); + + // Done, shut down connection and go back to listening for client requests + retval = shutdown(connSocket, SHUT_BOTH); + if (retval != 0) { + handleError(Protocol::TCP, ErrorSources::SHUTDOWN_CALL); + } + closeSocket(connSocket); + connSocket = 0; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t TcpTmTcServer::initializeAfterTaskCreation() { - if(tmtcBridge == nullptr) { - return ObjectManagerIF::CHILD_INIT_FAILED; - } - /* Initialize the destination after task creation. This ensures - that the destination has already been set in the TMTC bridge. */ - targetTcDestination = tmtcBridge->getRequestQueue(); - tcStore = tmtcBridge->tcStore; - tmStore = tmtcBridge->tmStore; - return HasReturnvaluesIF::RETURN_OK; + if (tmtcBridge == nullptr) { + return ObjectManagerIF::CHILD_INIT_FAILED; + } + /* Initialize the destination after task creation. This ensures + that the destination has already been set in the TMTC bridge. */ + targetTcDestination = tmtcBridge->getRequestQueue(); + tcStore = tmtcBridge->tcStore; + tmStore = tmtcBridge->tmStore; + return HasReturnvaluesIF::RETURN_OK; } void TcpTmTcServer::handleServerOperation(socket_t& connSocket) { #if defined PLATFORM_WIN - setSocketNonBlocking(connSocket); + setSocketNonBlocking(connSocket); #endif - while (true) { - int retval = recv( - connSocket, - reinterpret_cast(receptionBuffer.data()), - receptionBuffer.capacity(), - tcpConfig.tcpFlags - ); - if(retval == 0) { - size_t availableReadData = ringBuffer.getAvailableReadData(); - if(availableReadData > lastRingBufferSize) { - handleTcRingBufferData(availableReadData); - } - return; - } - else if(retval > 0) { - // The ring buffer was configured for overwrite, so the returnvalue does not need to - // be checked for now - ringBuffer.writeData(receptionBuffer.data(), retval); - } - else if(retval < 0) { - int errorValue = getLastSocketError(); + while (true) { + int retval = recv(connSocket, reinterpret_cast(receptionBuffer.data()), + receptionBuffer.capacity(), tcpConfig.tcpFlags); + if (retval == 0) { + size_t availableReadData = ringBuffer.getAvailableReadData(); + if (availableReadData > lastRingBufferSize) { + handleTcRingBufferData(availableReadData); + } + return; + } else if (retval > 0) { + // The ring buffer was configured for overwrite, so the returnvalue does not need to + // be checked for now + ringBuffer.writeData(receptionBuffer.data(), retval); + } else if (retval < 0) { + int errorValue = getLastSocketError(); #if defined PLATFORM_UNIX - int wouldBlockValue = EAGAIN; + int wouldBlockValue = EAGAIN; #elif defined PLATFORM_WIN - int wouldBlockValue = WSAEWOULDBLOCK; + int wouldBlockValue = WSAEWOULDBLOCK; #endif - if(errorValue == wouldBlockValue) { - // No data available. Check whether any packets have been read, then send back - // telemetry if available - bool tcAvailable = false; - bool tmSent = false; - size_t availableReadData = ringBuffer.getAvailableReadData(); - if(availableReadData > lastRingBufferSize) { - tcAvailable = true; - handleTcRingBufferData(availableReadData); - } - ReturnValue_t result = handleTmSending(connSocket, tmSent); - if(result == CONN_BROKEN) { - return; - } - if(not tcAvailable and not tmSent) { - TaskFactory::delayTask(tcpConfig.tcpLoopDelay); - } - } - else { - tcpip::handleError(tcpip::Protocol::TCP, tcpip::ErrorSources::RECV_CALL, 300); - } + if (errorValue == wouldBlockValue) { + // No data available. Check whether any packets have been read, then send back + // telemetry if available + bool tcAvailable = false; + bool tmSent = false; + size_t availableReadData = ringBuffer.getAvailableReadData(); + if (availableReadData > lastRingBufferSize) { + tcAvailable = true; + handleTcRingBufferData(availableReadData); } + ReturnValue_t result = handleTmSending(connSocket, tmSent); + if (result == CONN_BROKEN) { + return; + } + if (not tcAvailable and not tmSent) { + TaskFactory::delayTask(tcpConfig.tcpLoopDelay); + } + } else { + tcpip::handleError(tcpip::Protocol::TCP, tcpip::ErrorSources::RECV_CALL, 300); + } } + } } ReturnValue_t TcpTmTcServer::handleTcReception(uint8_t* spacePacket, size_t packetSize) { - if(wiretappingEnabled) { + if (wiretappingEnabled) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "Received TC:" << std::endl; + sif::info << "Received TC:" << std::endl; #else - sif::printInfo("Received TC:\n"); + sif::printInfo("Received TC:\n"); #endif - arrayprinter::print(spacePacket, packetSize); - } + arrayprinter::print(spacePacket, packetSize); + } - if(spacePacket == nullptr or packetSize == 0) { - return HasReturnvaluesIF::RETURN_FAILED; - } - store_address_t storeId; - ReturnValue_t result = tcStore->addData(&storeId, spacePacket, packetSize); - if (result != HasReturnvaluesIF::RETURN_OK) { + if (spacePacket == nullptr or packetSize == 0) { + return HasReturnvaluesIF::RETURN_FAILED; + } + store_address_t storeId; + ReturnValue_t result = tcStore->addData(&storeId, spacePacket, packetSize); + if (result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "TcpTmTcServer::handleServerOperation: Data storage with packet size" << - packetSize << " failed" << std::endl; + sif::warning << "TcpTmTcServer::handleServerOperation: Data storage with packet size" + << packetSize << " failed" << std::endl; #else - sif::printWarning("TcpTmTcServer::handleServerOperation: Data storage with packet size %d " - "failed\n", packetSize); + sif::printWarning( + "TcpTmTcServer::handleServerOperation: Data storage with packet size %d " + "failed\n", + packetSize); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - return result; - } - - TmTcMessage message(storeId); - - result = MessageQueueSenderIF::sendMessage(targetTcDestination, &message); - if (result != HasReturnvaluesIF::RETURN_OK) { -#if FSFW_VERBOSE_LEVEL >= 1 -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "TcpTmTcServer::handleServerOperation: " - " Sending message to queue failed" << std::endl; -#else - sif::printWarning("TcpTmTcServer::handleServerOperation: " - " Sending message to queue failed\n"); -#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ -#endif /* FSFW_VERBOSE_LEVEL >= 1 */ - tcStore->deleteData(storeId); - } return result; + } + + TmTcMessage message(storeId); + + result = MessageQueueSenderIF::sendMessage(targetTcDestination, &message); + if (result != HasReturnvaluesIF::RETURN_OK) { +#if FSFW_VERBOSE_LEVEL >= 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "TcpTmTcServer::handleServerOperation: " + " Sending message to queue failed" + << std::endl; +#else + sif::printWarning( + "TcpTmTcServer::handleServerOperation: " + " Sending message to queue failed\n"); +#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ +#endif /* FSFW_VERBOSE_LEVEL >= 1 */ + tcStore->deleteData(storeId); + } + return result; } -std::string TcpTmTcServer::getTcpPort() const { - return tcpConfig.tcpPort; -} +std::string TcpTmTcServer::getTcpPort() const { return tcpConfig.tcpPort; } void TcpTmTcServer::setSpacePacketParsingOptions(std::vector validPacketIds) { - this->validPacketIds = validPacketIds; + this->validPacketIds = validPacketIds; } -TcpTmTcServer::TcpConfig& TcpTmTcServer::getTcpConfigStruct() { - return tcpConfig; -} +TcpTmTcServer::TcpConfig& TcpTmTcServer::getTcpConfigStruct() { return tcpConfig; } ReturnValue_t TcpTmTcServer::handleTmSending(socket_t connSocket, bool& tmSent) { - // Access to the FIFO is mutex protected because it is filled by the bridge - MutexGuard(tmtcBridge->mutex, tmtcBridge->timeoutType, tmtcBridge->mutexTimeoutMs); - store_address_t storeId; - while((not tmtcBridge->tmFifo->empty()) and - (tmtcBridge->packetSentCounter < tmtcBridge->sentPacketsPerCycle)) { - // Send can fail, so only peek from the FIFO - tmtcBridge->tmFifo->peek(&storeId); + // Access to the FIFO is mutex protected because it is filled by the bridge + MutexGuard(tmtcBridge->mutex, tmtcBridge->timeoutType, tmtcBridge->mutexTimeoutMs); + store_address_t storeId; + while ((not tmtcBridge->tmFifo->empty()) and + (tmtcBridge->packetSentCounter < tmtcBridge->sentPacketsPerCycle)) { + // Send can fail, so only peek from the FIFO + tmtcBridge->tmFifo->peek(&storeId); - // Using the store accessor will take care of deleting TM from the store automatically - ConstStorageAccessor storeAccessor(storeId); - ReturnValue_t result = tmStore->getData(storeId, storeAccessor); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if(wiretappingEnabled) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "Sending TM:" << std::endl; -#else - sif::printInfo("Sending TM:\n"); -#endif - arrayprinter::print(storeAccessor.data(), storeAccessor.size()); - } - int retval = send(connSocket, - reinterpret_cast(storeAccessor.data()), - storeAccessor.size(), - tcpConfig.tcpTmFlags); - if(retval == static_cast(storeAccessor.size())) { - // Packet sent, clear FIFO entry - tmtcBridge->tmFifo->pop(); - tmSent = true; - - } - else if(retval <= 0) { - // Assume that the client has closed the connection here for now - handleSocketError(storeAccessor); - return CONN_BROKEN; - } + // Using the store accessor will take care of deleting TM from the store automatically + ConstStorageAccessor storeAccessor(storeId); + ReturnValue_t result = tmStore->getData(storeId, storeAccessor); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; } - return HasReturnvaluesIF::RETURN_OK; + if (wiretappingEnabled) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::info << "Sending TM:" << std::endl; +#else + sif::printInfo("Sending TM:\n"); +#endif + arrayprinter::print(storeAccessor.data(), storeAccessor.size()); + } + int retval = send(connSocket, reinterpret_cast(storeAccessor.data()), + storeAccessor.size(), tcpConfig.tcpTmFlags); + if (retval == static_cast(storeAccessor.size())) { + // Packet sent, clear FIFO entry + tmtcBridge->tmFifo->pop(); + tmSent = true; + + } else if (retval <= 0) { + // Assume that the client has closed the connection here for now + handleSocketError(storeAccessor); + return CONN_BROKEN; + } + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t TcpTmTcServer::handleTcRingBufferData(size_t availableReadData) { - ReturnValue_t status = HasReturnvaluesIF::RETURN_OK; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - size_t readAmount = availableReadData; - lastRingBufferSize = availableReadData; - if(readAmount >= ringBuffer.getMaxSize()) { + ReturnValue_t status = HasReturnvaluesIF::RETURN_OK; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + size_t readAmount = availableReadData; + lastRingBufferSize = availableReadData; + if (readAmount >= ringBuffer.getMaxSize()) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - // Possible configuration error, too much data or/and data coming in too fast, - // requiring larger buffers - sif::warning << "TcpTmTcServer::handleServerOperation: Ring buffer reached " << - "fill count" << std::endl; + // Possible configuration error, too much data or/and data coming in too fast, + // requiring larger buffers + sif::warning << "TcpTmTcServer::handleServerOperation: Ring buffer reached " + << "fill count" << std::endl; #else - sif::printWarning("TcpTmTcServer::handleServerOperation: Ring buffer reached " - "fill count"); + sif::printWarning( + "TcpTmTcServer::handleServerOperation: Ring buffer reached " + "fill count"); #endif #endif - } - if(readAmount >= receptionBuffer.size()) { + } + if (readAmount >= receptionBuffer.size()) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - // Possible configuration error, too much data or/and data coming in too fast, - // requiring larger buffers - sif::warning << "TcpTmTcServer::handleServerOperation: " - "Reception buffer too small " << std::endl; + // Possible configuration error, too much data or/and data coming in too fast, + // requiring larger buffers + sif::warning << "TcpTmTcServer::handleServerOperation: " + "Reception buffer too small " + << std::endl; #else - sif::printWarning("TcpTmTcServer::handleServerOperation: Reception buffer too small\n"); + sif::printWarning("TcpTmTcServer::handleServerOperation: Reception buffer too small\n"); #endif #endif - readAmount = receptionBuffer.size(); + readAmount = receptionBuffer.size(); + } + ringBuffer.readData(receptionBuffer.data(), readAmount, true); + const uint8_t* bufPtr = receptionBuffer.data(); + const uint8_t** bufPtrPtr = &bufPtr; + size_t startIdx = 0; + size_t foundSize = 0; + size_t readLen = 0; + while (readLen < readAmount) { + result = + spacePacketParser->parseSpacePackets(bufPtrPtr, readAmount, startIdx, foundSize, readLen); + switch (result) { + case (SpacePacketParser::NO_PACKET_FOUND): + case (SpacePacketParser::SPLIT_PACKET): { + break; + } + case (HasReturnvaluesIF::RETURN_OK): { + result = handleTcReception(receptionBuffer.data() + startIdx, foundSize); + if (result != HasReturnvaluesIF::RETURN_OK) { + status = result; + } + } } - ringBuffer.readData(receptionBuffer.data(), readAmount, true); - const uint8_t* bufPtr = receptionBuffer.data(); - const uint8_t** bufPtrPtr = &bufPtr; - size_t startIdx = 0; - size_t foundSize = 0; - size_t readLen = 0; - while(readLen < readAmount) { - result = spacePacketParser->parseSpacePackets(bufPtrPtr, readAmount, - startIdx, foundSize, readLen); - switch(result) { - case(SpacePacketParser::NO_PACKET_FOUND): - case(SpacePacketParser::SPLIT_PACKET): { - break; - } - case(HasReturnvaluesIF::RETURN_OK): { - result = handleTcReception(receptionBuffer.data() + startIdx, foundSize); - if(result != HasReturnvaluesIF::RETURN_OK) { - status = result; - } - } - } - ringBuffer.deleteData(foundSize); - lastRingBufferSize = ringBuffer.getAvailableReadData(); - std::memset(receptionBuffer.data() + startIdx, 0, foundSize); - } - return status; + ringBuffer.deleteData(foundSize); + lastRingBufferSize = ringBuffer.getAvailableReadData(); + std::memset(receptionBuffer.data() + startIdx, 0, foundSize); + } + return status; } -void TcpTmTcServer::enableWiretapping(bool enable) { - this->wiretappingEnabled = enable; -} +void TcpTmTcServer::enableWiretapping(bool enable) { this->wiretappingEnabled = enable; } -void TcpTmTcServer::handleSocketError(ConstStorageAccessor &accessor) { - // Don't delete data - accessor.release(); - auto socketError = getLastSocketError(); - switch(socketError) { +void TcpTmTcServer::handleSocketError(ConstStorageAccessor& accessor) { + // Don't delete data + accessor.release(); + auto socketError = getLastSocketError(); + switch (socketError) { #if defined PLATFORM_WIN - case(WSAECONNRESET): { - // See https://docs.microsoft.com/en-us/windows/win32/api/winsock2/nf-winsock2-send - // Remote client might have shut down connection - return; + case (WSAECONNRESET): { + // See https://docs.microsoft.com/en-us/windows/win32/api/winsock2/nf-winsock2-send + // Remote client might have shut down connection + return; } #else - case(EPIPE): { - // See https://man7.org/linux/man-pages/man2/send.2.html - // Remote client might have shut down connection - return; + case (EPIPE): { + // See https://man7.org/linux/man-pages/man2/send.2.html + // Remote client might have shut down connection + return; } #endif default: { - tcpip::handleError(tcpip::Protocol::TCP, tcpip::ErrorSources::SEND_CALL); - } + tcpip::handleError(tcpip::Protocol::TCP, tcpip::ErrorSources::SEND_CALL); } + } } #if defined PLATFORM_WIN -void TcpTmTcServer::setSocketNonBlocking(socket_t &connSocket) { - u_long iMode = 1; - int iResult = ioctlsocket(connSocket, FIONBIO, &iMode); - if(iResult != NO_ERROR) { +void TcpTmTcServer::setSocketNonBlocking(socket_t& connSocket) { + u_long iMode = 1; + int iResult = ioctlsocket(connSocket, FIONBIO, &iMode); + if (iResult != NO_ERROR) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "TcpTmTcServer::handleServerOperation: Setting socket" - " non-blocking failed with error " << iResult; + sif::warning << "TcpTmTcServer::handleServerOperation: Setting socket" + " non-blocking failed with error " + << iResult; #else - sif::printWarning("TcpTmTcServer::handleServerOperation: Setting socket" - " non-blocking failed with error %d\n", iResult); + sif::printWarning( + "TcpTmTcServer::handleServerOperation: Setting socket" + " non-blocking failed with error %d\n", + iResult); #endif #endif - } + } } #endif diff --git a/src/fsfw/osal/common/TcpTmTcServer.h b/src/fsfw/osal/common/TcpTmTcServer.h index 64726a30..d062a0ce 100644 --- a/src/fsfw/osal/common/TcpTmTcServer.h +++ b/src/fsfw/osal/common/TcpTmTcServer.h @@ -2,14 +2,13 @@ #define FSFW_OSAL_COMMON_TCP_TMTC_SERVER_H_ #include "TcpIpBase.h" - -#include "fsfw/platform.h" -#include "fsfw/osal/common/tcpipHelpers.h" -#include "fsfw/ipc/messageQueueDefinitions.h" #include "fsfw/container/SimpleRingBuffer.h" #include "fsfw/ipc/MessageQueueIF.h" -#include "fsfw/objectmanager/frameworkObjects.h" +#include "fsfw/ipc/messageQueueDefinitions.h" #include "fsfw/objectmanager/SystemObject.h" +#include "fsfw/objectmanager/frameworkObjects.h" +#include "fsfw/osal/common/tcpipHelpers.h" +#include "fsfw/platform.h" #include "fsfw/storagemanager/StorageManagerIF.h" #include "fsfw/tasks/ExecutableObjectIF.h" @@ -39,105 +38,101 @@ class SpacePacketParser; * * The server will listen to a specific port on all addresses (0.0.0.0). */ -class TcpTmTcServer: - public SystemObject, - public TcpIpBase, - public ExecutableObjectIF { -public: - enum class ReceptionModes { - SPACE_PACKETS - }; +class TcpTmTcServer : public SystemObject, public TcpIpBase, public ExecutableObjectIF { + public: + enum class ReceptionModes { SPACE_PACKETS }; - struct TcpConfig { - public: - TcpConfig(std::string tcpPort): tcpPort(tcpPort) {} - - /** - * Passed to the recv call - */ - int tcpFlags = 0; - int tcpBacklog = 3; - - /** - * If no telecommands packets are being received and no telemetry is being sent, - * the TCP server will delay periodically by this amount to decrease the CPU load - */ - uint32_t tcpLoopDelay = DEFAULT_LOOP_DELAY_MS ; - /** - * Passed to the send call - */ - int tcpTmFlags = 0; - - const std::string tcpPort; - }; - - static const std::string DEFAULT_SERVER_PORT; - - static constexpr size_t ETHERNET_MTU_SIZE = 1500; - static constexpr size_t RING_BUFFER_SIZE = ETHERNET_MTU_SIZE * 3; - static constexpr uint32_t DEFAULT_LOOP_DELAY_MS = 200; + struct TcpConfig { + public: + TcpConfig(std::string tcpPort) : tcpPort(tcpPort) {} /** - * TCP Server Constructor - * @param objectId Object ID of the TCP Server - * @param tmtcTcpBridge Object ID of the TCP TMTC Bridge object - * @param receptionBufferSize This will be the size of the reception buffer. Default buffer - * size will be the Ethernet MTU size - * @param customTcpServerPort The user can specify another port than the default (7301) here. + * Passed to the recv call */ - TcpTmTcServer(object_id_t objectId, object_id_t tmtcTcpBridge, - size_t receptionBufferSize = RING_BUFFER_SIZE, - size_t ringBufferSize = RING_BUFFER_SIZE, - std::string customTcpServerPort = DEFAULT_SERVER_PORT, - ReceptionModes receptionMode = ReceptionModes::SPACE_PACKETS); - virtual~ TcpTmTcServer(); - - void enableWiretapping(bool enable); + int tcpFlags = 0; + int tcpBacklog = 3; /** - * Get a handle to the TCP configuration struct, which can be used to configure TCP - * properties - * @return + * If no telecommands packets are being received and no telemetry is being sent, + * the TCP server will delay periodically by this amount to decrease the CPU load */ - TcpConfig& getTcpConfigStruct(); - void setSpacePacketParsingOptions(std::vector validPacketIds); + uint32_t tcpLoopDelay = DEFAULT_LOOP_DELAY_MS; + /** + * Passed to the send call + */ + int tcpTmFlags = 0; - ReturnValue_t initialize() override; - ReturnValue_t performOperation(uint8_t opCode) override; - ReturnValue_t initializeAfterTaskCreation() override; + const std::string tcpPort; + }; - std::string getTcpPort() const; + static const std::string DEFAULT_SERVER_PORT; -protected: - StorageManagerIF* tcStore = nullptr; - StorageManagerIF* tmStore = nullptr; -private: - static constexpr ReturnValue_t CONN_BROKEN = HasReturnvaluesIF::makeReturnCode(1, 0); - //! TMTC bridge is cached. - object_id_t tmtcBridgeId = objects::NO_OBJECT; - TcpTmTcBridge* tmtcBridge = nullptr; - bool wiretappingEnabled = false; + static constexpr size_t ETHERNET_MTU_SIZE = 1500; + static constexpr size_t RING_BUFFER_SIZE = ETHERNET_MTU_SIZE * 3; + static constexpr uint32_t DEFAULT_LOOP_DELAY_MS = 200; - ReceptionModes receptionMode; - TcpConfig tcpConfig; - struct sockaddr tcpAddress; - socket_t listenerTcpSocket = 0; + /** + * TCP Server Constructor + * @param objectId Object ID of the TCP Server + * @param tmtcTcpBridge Object ID of the TCP TMTC Bridge object + * @param receptionBufferSize This will be the size of the reception buffer. Default buffer + * size will be the Ethernet MTU size + * @param customTcpServerPort The user can specify another port than the default (7301) here. + */ + TcpTmTcServer(object_id_t objectId, object_id_t tmtcTcpBridge, + size_t receptionBufferSize = RING_BUFFER_SIZE, + size_t ringBufferSize = RING_BUFFER_SIZE, + std::string customTcpServerPort = DEFAULT_SERVER_PORT, + ReceptionModes receptionMode = ReceptionModes::SPACE_PACKETS); + virtual ~TcpTmTcServer(); - MessageQueueId_t targetTcDestination = MessageQueueIF::NO_QUEUE; + void enableWiretapping(bool enable); - std::vector receptionBuffer; - SimpleRingBuffer ringBuffer; - std::vector validPacketIds; - SpacePacketParser* spacePacketParser = nullptr; - uint8_t lastRingBufferSize = 0; + /** + * Get a handle to the TCP configuration struct, which can be used to configure TCP + * properties + * @return + */ + TcpConfig& getTcpConfigStruct(); + void setSpacePacketParsingOptions(std::vector validPacketIds); - virtual void handleServerOperation(socket_t& connSocket); - ReturnValue_t handleTcReception(uint8_t* spacePacket, size_t packetSize); - ReturnValue_t handleTmSending(socket_t connSocket, bool& tmSent); - ReturnValue_t handleTcRingBufferData(size_t availableReadData); - void handleSocketError(ConstStorageAccessor& accessor); + ReturnValue_t initialize() override; + ReturnValue_t performOperation(uint8_t opCode) override; + ReturnValue_t initializeAfterTaskCreation() override; + + std::string getTcpPort() const; + + protected: + StorageManagerIF* tcStore = nullptr; + StorageManagerIF* tmStore = nullptr; + + private: + static constexpr ReturnValue_t CONN_BROKEN = HasReturnvaluesIF::makeReturnCode(1, 0); + //! TMTC bridge is cached. + object_id_t tmtcBridgeId = objects::NO_OBJECT; + TcpTmTcBridge* tmtcBridge = nullptr; + bool wiretappingEnabled = false; + + ReceptionModes receptionMode; + TcpConfig tcpConfig; + struct sockaddr tcpAddress; + socket_t listenerTcpSocket = 0; + + MessageQueueId_t targetTcDestination = MessageQueueIF::NO_QUEUE; + + std::vector receptionBuffer; + SimpleRingBuffer ringBuffer; + std::vector validPacketIds; + SpacePacketParser* spacePacketParser = nullptr; + uint8_t lastRingBufferSize = 0; + + virtual void handleServerOperation(socket_t& connSocket); + ReturnValue_t handleTcReception(uint8_t* spacePacket, size_t packetSize); + ReturnValue_t handleTmSending(socket_t connSocket, bool& tmSent); + ReturnValue_t handleTcRingBufferData(size_t availableReadData); + void handleSocketError(ConstStorageAccessor& accessor); #if defined PLATFORM_WIN - void setSocketNonBlocking(socket_t& connSocket); + void setSocketNonBlocking(socket_t& connSocket); #endif }; diff --git a/src/fsfw/osal/common/UdpTcPollingTask.cpp b/src/fsfw/osal/common/UdpTcPollingTask.cpp index 35e086ee..ab982a3c 100644 --- a/src/fsfw/osal/common/UdpTcPollingTask.cpp +++ b/src/fsfw/osal/common/UdpTcPollingTask.cpp @@ -1,179 +1,169 @@ #include "fsfw/osal/common/UdpTcPollingTask.h" -#include "fsfw/osal/common/tcpipHelpers.h" -#include "fsfw/platform.h" #include "fsfw/globalfunctions/arrayprinter.h" -#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/osal/common/tcpipHelpers.h" +#include "fsfw/platform.h" +#include "fsfw/serviceinterface/ServiceInterface.h" #ifdef PLATFORM_WIN #include #elif defined(PLATFORM_UNIX) -#include #include +#include #endif //! Debugging preprocessor define. -#define FSFW_UDP_RECV_WIRETAPPING_ENABLED 0 +#define FSFW_UDP_RECV_WIRETAPPING_ENABLED 0 -UdpTcPollingTask::UdpTcPollingTask(object_id_t objectId, - object_id_t tmtcUdpBridge, size_t maxRecvSize, - double timeoutSeconds): SystemObject(objectId), - tmtcBridgeId(tmtcUdpBridge) { - if(frameSize > 0) { - this->frameSize = frameSize; - } - else { - this->frameSize = DEFAULT_MAX_RECV_SIZE; - } +UdpTcPollingTask::UdpTcPollingTask(object_id_t objectId, object_id_t tmtcUdpBridge, + size_t maxRecvSize, double timeoutSeconds) + : SystemObject(objectId), tmtcBridgeId(tmtcUdpBridge) { + if (frameSize > 0) { + this->frameSize = frameSize; + } else { + this->frameSize = DEFAULT_MAX_RECV_SIZE; + } - /* Set up reception buffer with specified frame size. - For now, it is assumed that only one frame is held in the buffer! */ - receptionBuffer.reserve(this->frameSize); - receptionBuffer.resize(this->frameSize); + /* Set up reception buffer with specified frame size. + For now, it is assumed that only one frame is held in the buffer! */ + receptionBuffer.reserve(this->frameSize); + receptionBuffer.resize(this->frameSize); - if(timeoutSeconds == -1) { - receptionTimeout = DEFAULT_TIMEOUT; - } - else { - receptionTimeout = timevalOperations::toTimeval(timeoutSeconds); - } + if (timeoutSeconds == -1) { + receptionTimeout = DEFAULT_TIMEOUT; + } else { + receptionTimeout = timevalOperations::toTimeval(timeoutSeconds); + } } UdpTcPollingTask::~UdpTcPollingTask() {} ReturnValue_t UdpTcPollingTask::performOperation(uint8_t opCode) { - /* Sender Address is cached here. */ - struct sockaddr senderAddress; - socklen_t senderAddressSize = sizeof(senderAddress); + /* Sender Address is cached here. */ + struct sockaddr senderAddress; + socklen_t senderAddressSize = sizeof(senderAddress); - /* Poll for new UDP datagrams in permanent loop. */ - while(true) { - int bytesReceived = recvfrom( - this->serverSocket, - reinterpret_cast(receptionBuffer.data()), - frameSize, - receptionFlags, - &senderAddress, - &senderAddressSize - ); - if(bytesReceived == SOCKET_ERROR) { - /* Handle error */ + /* Poll for new UDP datagrams in permanent loop. */ + while (true) { + int bytesReceived = + recvfrom(this->serverSocket, reinterpret_cast(receptionBuffer.data()), frameSize, + receptionFlags, &senderAddress, &senderAddressSize); + if (bytesReceived == SOCKET_ERROR) { + /* Handle error */ #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "UdpTcPollingTask::performOperation: Reception error." << std::endl; + sif::error << "UdpTcPollingTask::performOperation: Reception error." << std::endl; #endif - tcpip::handleError(tcpip::Protocol::UDP, tcpip::ErrorSources::RECVFROM_CALL, 1000); - continue; - } + tcpip::handleError(tcpip::Protocol::UDP, tcpip::ErrorSources::RECVFROM_CALL, 1000); + continue; + } #if FSFW_UDP_RECV_WIRETAPPING_ENABLED == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "UdpTcPollingTask::performOperation: " << bytesReceived << - " bytes received" << std::endl; + sif::debug << "UdpTcPollingTask::performOperation: " << bytesReceived << " bytes received" + << std::endl; #else #endif #endif /* FSFW_UDP_RCV_WIRETAPPING_ENABLED == 1 */ - ReturnValue_t result = handleSuccessfullTcRead(bytesReceived); - if(result != HasReturnvaluesIF::RETURN_FAILED) { - - } - tmtcBridge->checkAndSetClientAddress(senderAddress); + ReturnValue_t result = handleSuccessfullTcRead(bytesReceived); + if (result != HasReturnvaluesIF::RETURN_FAILED) { } - return HasReturnvaluesIF::RETURN_OK; + tmtcBridge->checkAndSetClientAddress(senderAddress); + } + return HasReturnvaluesIF::RETURN_OK; } - ReturnValue_t UdpTcPollingTask::handleSuccessfullTcRead(size_t bytesRead) { - store_address_t storeId; + store_address_t storeId; #if FSFW_UDP_RECV_WIRETAPPING_ENABLED == 1 - arrayprinter::print(receptionBuffer.data(), bytesRead); + arrayprinter::print(receptionBuffer.data(), bytesRead); #endif - ReturnValue_t result = tcStore->addData(&storeId, receptionBuffer.data(), bytesRead); - if (result != HasReturnvaluesIF::RETURN_OK) { + ReturnValue_t result = tcStore->addData(&storeId, receptionBuffer.data(), bytesRead); + if (result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning<< "UdpTcPollingTask::transferPusToSoftwareBus: Data storage failed." << - std::endl; - sif::warning << "Packet size: " << bytesRead << std::endl; + sif::warning << "UdpTcPollingTask::transferPusToSoftwareBus: Data storage failed." << std::endl; + sif::warning << "Packet size: " << bytesRead << std::endl; #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; + } - TmTcMessage message(storeId); + TmTcMessage message(storeId); - result = MessageQueueSenderIF::sendMessage(targetTcDestination, &message); - if (result != HasReturnvaluesIF::RETURN_OK) { + result = MessageQueueSenderIF::sendMessage(targetTcDestination, &message); + if (result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "UdpTcPollingTask::handleSuccessfullTcRead: " - " Sending message to queue failed" << std::endl; + sif::warning << "UdpTcPollingTask::handleSuccessfullTcRead: " + " Sending message to queue failed" + << std::endl; #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - tcStore->deleteData(storeId); - } - return result; + tcStore->deleteData(storeId); + } + return result; } ReturnValue_t UdpTcPollingTask::initialize() { - tcStore = ObjectManager::instance()->get(objects::TC_STORE); - if (tcStore == nullptr) { + tcStore = ObjectManager::instance()->get(objects::TC_STORE); + if (tcStore == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "UdpTcPollingTask::initialize: TC store uninitialized!" << std::endl; + sif::error << "UdpTcPollingTask::initialize: TC store uninitialized!" << std::endl; #endif - return ObjectManagerIF::CHILD_INIT_FAILED; - } + return ObjectManagerIF::CHILD_INIT_FAILED; + } - tmtcBridge = ObjectManager::instance()->get(tmtcBridgeId); - if(tmtcBridge == nullptr) { + tmtcBridge = ObjectManager::instance()->get(tmtcBridgeId); + if (tmtcBridge == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "UdpTcPollingTask::initialize: Invalid TMTC bridge object!" << - std::endl; + sif::error << "UdpTcPollingTask::initialize: Invalid TMTC bridge object!" << std::endl; #endif - return ObjectManagerIF::CHILD_INIT_FAILED; - } + return ObjectManagerIF::CHILD_INIT_FAILED; + } - ReturnValue_t result = TcpIpBase::initialize(); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + ReturnValue_t result = TcpIpBase::initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t UdpTcPollingTask::initializeAfterTaskCreation() { - /* Initialize the destination after task creation. This ensures - that the destination has already been set in the TMTC bridge. */ - targetTcDestination = tmtcBridge->getRequestQueue(); - /* The server socket is set up in the bridge intialization. Calling this function here - ensures that it is set up regardless of which class was initialized first */ - this->serverSocket = tmtcBridge->serverSocket; - return HasReturnvaluesIF::RETURN_OK; + /* Initialize the destination after task creation. This ensures + that the destination has already been set in the TMTC bridge. */ + targetTcDestination = tmtcBridge->getRequestQueue(); + /* The server socket is set up in the bridge intialization. Calling this function here + ensures that it is set up regardless of which class was initialized first */ + this->serverSocket = tmtcBridge->serverSocket; + return HasReturnvaluesIF::RETURN_OK; } void UdpTcPollingTask::setTimeout(double timeoutSeconds) { #ifdef PLATFORM_WIN - DWORD timeoutMs = timeoutSeconds * 1000.0; - int result = setsockopt(serverSocket, SOL_SOCKET, SO_RCVTIMEO, - reinterpret_cast(&timeoutMs), sizeof(DWORD)); - if(result == -1) { + DWORD timeoutMs = timeoutSeconds * 1000.0; + int result = setsockopt(serverSocket, SOL_SOCKET, SO_RCVTIMEO, + reinterpret_cast(&timeoutMs), sizeof(DWORD)); + if (result == -1) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "TcWinUdpPollingTask::TcSocketPollingTask: Setting " - "receive timeout failed with " << strerror(errno) << std::endl; + sif::error << "TcWinUdpPollingTask::TcSocketPollingTask: Setting " + "receive timeout failed with " + << strerror(errno) << std::endl; #endif - } + } #elif defined(PLATFORM_UNIX) - timeval tval; - tval = timevalOperations::toTimeval(timeoutSeconds); - int result = setsockopt(serverSocket, SOL_SOCKET, SO_RCVTIMEO, - &tval, sizeof(receptionTimeout)); - if(result == -1) { + timeval tval; + tval = timevalOperations::toTimeval(timeoutSeconds); + int result = setsockopt(serverSocket, SOL_SOCKET, SO_RCVTIMEO, &tval, sizeof(receptionTimeout)); + if (result == -1) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "TcSocketPollingTask::TcSocketPollingTask: Setting " - "receive timeout failed with " << strerror(errno) << std::endl; + sif::error << "TcSocketPollingTask::TcSocketPollingTask: Setting " + "receive timeout failed with " + << strerror(errno) << std::endl; #endif - } + } #endif } diff --git a/src/fsfw/osal/common/UdpTcPollingTask.h b/src/fsfw/osal/common/UdpTcPollingTask.h index 9a680fb8..afcd32a1 100644 --- a/src/fsfw/osal/common/UdpTcPollingTask.h +++ b/src/fsfw/osal/common/UdpTcPollingTask.h @@ -1,13 +1,13 @@ #ifndef FSFW_OSAL_COMMON_UDPTCPOLLINGTASK_H_ #define FSFW_OSAL_COMMON_UDPTCPOLLINGTASK_H_ -#include "UdpTmTcBridge.h" -#include "../../objectmanager/SystemObject.h" -#include "../../tasks/ExecutableObjectIF.h" -#include "../../storagemanager/StorageManagerIF.h" - #include +#include "../../objectmanager/SystemObject.h" +#include "../../storagemanager/StorageManagerIF.h" +#include "../../tasks/ExecutableObjectIF.h" +#include "UdpTmTcBridge.h" + /** * @brief This class can be used with the UdpTmTcBridge to implement a UDP server * for receiving and sending PUS TMTC. @@ -15,47 +15,45 @@ * This task is exclusively used to poll telecommands from a given socket and transfer them * to the FSFW software bus. It used the blocking recvfrom call to do this. */ -class UdpTcPollingTask: - public TcpIpBase, - public SystemObject, - public ExecutableObjectIF { - friend class TmTcWinUdpBridge; -public: - static constexpr size_t DEFAULT_MAX_RECV_SIZE = 1500; - //! 0.5 default milliseconds timeout for now. - static constexpr timeval DEFAULT_TIMEOUT = {0, 500}; +class UdpTcPollingTask : public TcpIpBase, public SystemObject, public ExecutableObjectIF { + friend class TmTcWinUdpBridge; - UdpTcPollingTask(object_id_t objectId, object_id_t tmtcUdpBridge, - size_t maxRecvSize = 0, double timeoutSeconds = -1); - virtual~ UdpTcPollingTask(); + public: + static constexpr size_t DEFAULT_MAX_RECV_SIZE = 1500; + //! 0.5 default milliseconds timeout for now. + static constexpr timeval DEFAULT_TIMEOUT = {0, 500}; - /** - * Turn on optional timeout for UDP polling. In the default mode, - * the receive function will block until a packet is received. - * @param timeoutSeconds - */ - void setTimeout(double timeoutSeconds); + UdpTcPollingTask(object_id_t objectId, object_id_t tmtcUdpBridge, size_t maxRecvSize = 0, + double timeoutSeconds = -1); + virtual ~UdpTcPollingTask(); - virtual ReturnValue_t performOperation(uint8_t opCode) override; - virtual ReturnValue_t initialize() override; - virtual ReturnValue_t initializeAfterTaskCreation() override; + /** + * Turn on optional timeout for UDP polling. In the default mode, + * the receive function will block until a packet is received. + * @param timeoutSeconds + */ + void setTimeout(double timeoutSeconds); -protected: - StorageManagerIF* tcStore = nullptr; + virtual ReturnValue_t performOperation(uint8_t opCode) override; + virtual ReturnValue_t initialize() override; + virtual ReturnValue_t initializeAfterTaskCreation() override; -private: - //! TMTC bridge is cached. - object_id_t tmtcBridgeId = objects::NO_OBJECT; - UdpTmTcBridge* tmtcBridge = nullptr; - MessageQueueId_t targetTcDestination = MessageQueueIF::NO_QUEUE; - int receptionFlags = 0; + protected: + StorageManagerIF* tcStore = nullptr; - std::vector receptionBuffer; + private: + //! TMTC bridge is cached. + object_id_t tmtcBridgeId = objects::NO_OBJECT; + UdpTmTcBridge* tmtcBridge = nullptr; + MessageQueueId_t targetTcDestination = MessageQueueIF::NO_QUEUE; + int receptionFlags = 0; - size_t frameSize = 0; - timeval receptionTimeout; + std::vector receptionBuffer; - ReturnValue_t handleSuccessfullTcRead(size_t bytesRead); + size_t frameSize = 0; + timeval receptionTimeout; + + ReturnValue_t handleSuccessfullTcRead(size_t bytesRead); }; #endif /* FSFW_OSAL_COMMON_UDPTCPOLLINGTASK_H_ */ diff --git a/src/fsfw/osal/common/UdpTmTcBridge.cpp b/src/fsfw/osal/common/UdpTmTcBridge.cpp index 734a2b15..0efe1c74 100644 --- a/src/fsfw/osal/common/UdpTmTcBridge.cpp +++ b/src/fsfw/osal/common/UdpTmTcBridge.cpp @@ -1,166 +1,156 @@ #include "fsfw/osal/common/UdpTmTcBridge.h" -#include "fsfw/osal/common/tcpipHelpers.h" +#include "fsfw/ipc/MutexGuard.h" +#include "fsfw/osal/common/tcpipHelpers.h" #include "fsfw/platform.h" #include "fsfw/serviceinterface/ServiceInterface.h" -#include "fsfw/ipc/MutexGuard.h" #ifdef PLATFORM_WIN #include #elif defined(PLATFORM_UNIX) -#include #include +#include #endif //! Debugging preprocessor define. #ifndef FSFW_UDP_SEND_WIRETAPPING_ENABLED -#define FSFW_UDP_SEND_WIRETAPPING_ENABLED 0 +#define FSFW_UDP_SEND_WIRETAPPING_ENABLED 0 #endif -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, - std::string udpServerPort, object_id_t tmStoreId, object_id_t tcStoreId): - TmTcBridge(objectId, tcDestination, tmStoreId, tcStoreId) { - if(udpServerPort == "") { - this->udpServerPort = DEFAULT_SERVER_PORT; - } - else { - this->udpServerPort = udpServerPort; - } + std::string udpServerPort, object_id_t tmStoreId, + object_id_t tcStoreId) + : TmTcBridge(objectId, tcDestination, tmStoreId, tcStoreId) { + if (udpServerPort == "") { + this->udpServerPort = DEFAULT_SERVER_PORT; + } else { + this->udpServerPort = udpServerPort; + } - mutex = MutexFactory::instance()->createMutex(); - communicationLinkUp = false; + mutex = MutexFactory::instance()->createMutex(); + communicationLinkUp = false; } ReturnValue_t UdpTmTcBridge::initialize() { - ReturnValue_t result = TmTcBridge::initialize(); - if(result != HasReturnvaluesIF::RETURN_OK) { + ReturnValue_t result = TmTcBridge::initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "UdpTmTcBridge::initialize: TmTcBridge initialization failed!" - << std::endl; + sif::error << "UdpTmTcBridge::initialize: TmTcBridge initialization failed!" << std::endl; #endif - return result; - } - + return result; + } #ifdef _WIN32 - /* Initiates Winsock DLL. */ - WSAData wsaData; - WORD wVersionRequested = MAKEWORD(2, 2); - int err = WSAStartup(wVersionRequested, &wsaData); - if (err != 0) { - /* Tell the user that we could not find a usable */ - /* Winsock DLL. */ + /* Initiates Winsock DLL. */ + WSAData wsaData; + WORD wVersionRequested = MAKEWORD(2, 2); + int err = WSAStartup(wVersionRequested, &wsaData); + if (err != 0) { + /* Tell the user that we could not find a usable */ + /* Winsock DLL. */ #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "UdpTmTcBridge::UdpTmTcBridge: WSAStartup failed with error: " << - err << std::endl; + sif::error << "UdpTmTcBridge::UdpTmTcBridge: WSAStartup failed with error: " << err + << std::endl; #else - sif::printError("UdpTmTcBridge::UdpTmTcBridge: WSAStartup failed with error: %d\n", - err); + sif::printError("UdpTmTcBridge::UdpTmTcBridge: WSAStartup failed with error: %d\n", err); #endif - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; + } #endif - struct addrinfo *addrResult = nullptr; - struct addrinfo hints = {}; + struct addrinfo *addrResult = nullptr; + struct addrinfo hints = {}; - hints.ai_family = AF_INET; - hints.ai_socktype = SOCK_DGRAM; - hints.ai_protocol = IPPROTO_UDP; - hints.ai_flags = AI_PASSIVE; + hints.ai_family = AF_INET; + hints.ai_socktype = SOCK_DGRAM; + hints.ai_protocol = IPPROTO_UDP; + hints.ai_flags = AI_PASSIVE; - /* Set up UDP socket: - https://en.wikipedia.org/wiki/Getaddrinfo - Passing nullptr as the first parameter and specifying AI_PASSIVE in hints will cause - getaddrinfo to assign the address 0.0.0.0 (any address) */ - int retval = getaddrinfo(nullptr, udpServerPort.c_str(), &hints, &addrResult); - if (retval != 0) { - tcpip::handleError(tcpip::Protocol::UDP, tcpip::ErrorSources::GETADDRINFO_CALL); - return HasReturnvaluesIF::RETURN_FAILED; - } + /* Set up UDP socket: + https://en.wikipedia.org/wiki/Getaddrinfo + Passing nullptr as the first parameter and specifying AI_PASSIVE in hints will cause + getaddrinfo to assign the address 0.0.0.0 (any address) */ + int retval = getaddrinfo(nullptr, udpServerPort.c_str(), &hints, &addrResult); + if (retval != 0) { + tcpip::handleError(tcpip::Protocol::UDP, tcpip::ErrorSources::GETADDRINFO_CALL); + return HasReturnvaluesIF::RETURN_FAILED; + } - serverSocket = socket(addrResult->ai_family, addrResult->ai_socktype, addrResult->ai_protocol); - if(serverSocket == INVALID_SOCKET) { - freeaddrinfo(addrResult); - tcpip::handleError(tcpip::Protocol::UDP, tcpip::ErrorSources::SOCKET_CALL); - return HasReturnvaluesIF::RETURN_FAILED; - } + serverSocket = socket(addrResult->ai_family, addrResult->ai_socktype, addrResult->ai_protocol); + if (serverSocket == INVALID_SOCKET) { + freeaddrinfo(addrResult); + tcpip::handleError(tcpip::Protocol::UDP, tcpip::ErrorSources::SOCKET_CALL); + return HasReturnvaluesIF::RETURN_FAILED; + } #if FSFW_UDP_SEND_WIRETAPPING_ENABLED == 1 - tcpip::printAddress(addrResult->ai_addr); + tcpip::printAddress(addrResult->ai_addr); #endif - retval = bind(serverSocket, addrResult->ai_addr, static_cast(addrResult->ai_addrlen)); - if(retval != 0) { - freeaddrinfo(addrResult); - tcpip::handleError(tcpip::Protocol::UDP, tcpip::ErrorSources::BIND_CALL); - return HasReturnvaluesIF::RETURN_FAILED; - } + retval = bind(serverSocket, addrResult->ai_addr, static_cast(addrResult->ai_addrlen)); + if (retval != 0) { freeaddrinfo(addrResult); - return HasReturnvaluesIF::RETURN_OK; + tcpip::handleError(tcpip::Protocol::UDP, tcpip::ErrorSources::BIND_CALL); + return HasReturnvaluesIF::RETURN_FAILED; + } + freeaddrinfo(addrResult); + return HasReturnvaluesIF::RETURN_OK; } UdpTmTcBridge::~UdpTmTcBridge() { - if(mutex != nullptr) { - MutexFactory::instance()->deleteMutex(mutex); - } + if (mutex != nullptr) { + MutexFactory::instance()->deleteMutex(mutex); + } } -std::string UdpTmTcBridge::getUdpPort() const { - return udpServerPort; -} +std::string UdpTmTcBridge::getUdpPort() const { return udpServerPort; } ReturnValue_t UdpTmTcBridge::sendTm(const uint8_t *data, size_t dataLen) { - int flags = 0; + int flags = 0; - /* The target address can be set by different threads so this lock ensures thread-safety */ - MutexGuard lock(mutex, timeoutType, mutexTimeoutMs); + /* The target address can be set by different threads so this lock ensures thread-safety */ + MutexGuard lock(mutex, timeoutType, mutexTimeoutMs); #if FSFW_UDP_SEND_WIRETAPPING_ENABLED == 1 - tcpip::printAddress(&clientAddress); + tcpip::printAddress(&clientAddress); #endif - int bytesSent = sendto( - serverSocket, - reinterpret_cast(data), - dataLen, - flags, - &clientAddress, - clientAddressLen - ); - if(bytesSent == SOCKET_ERROR) { + int bytesSent = sendto(serverSocket, reinterpret_cast(data), dataLen, flags, + &clientAddress, clientAddressLen); + if (bytesSent == SOCKET_ERROR) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "TmTcUdpBridge::sendTm: Send operation failed." << std::endl; + sif::warning << "TmTcUdpBridge::sendTm: Send operation failed." << std::endl; #endif - 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 - sif::debug << "TmTcUdpBridge::sendTm: " << bytesSent << " bytes were" - " sent." << std::endl; + sif::debug << "TmTcUdpBridge::sendTm: " << bytesSent + << " bytes were" + " sent." + << std::endl; #endif - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } -void UdpTmTcBridge::checkAndSetClientAddress(sockaddr& newAddress) { - /* The target address can be set by different threads so this lock ensures thread-safety */ - MutexGuard lock(mutex, timeoutType, mutexTimeoutMs); +void UdpTmTcBridge::checkAndSetClientAddress(sockaddr &newAddress) { + /* The target address can be set by different threads so this lock ensures thread-safety */ + MutexGuard lock(mutex, timeoutType, mutexTimeoutMs); #if FSFW_UDP_SEND_WIRETAPPING_ENABLED == 1 - tcpip::printAddress(&newAddress); - tcpip::printAddress(&clientAddress); + tcpip::printAddress(&newAddress); + tcpip::printAddress(&clientAddress); #endif - registerCommConnect(); + registerCommConnect(); - /* Set new IP address to reply to */ - clientAddress = newAddress; - clientAddressLen = sizeof(clientAddress); + /* Set new IP address to reply to */ + clientAddress = newAddress; + clientAddressLen = sizeof(clientAddress); } -void UdpTmTcBridge::setMutexProperties(MutexIF::TimeoutType timeoutType, - dur_millis_t timeoutMs) { - this->timeoutType = timeoutType; - this->mutexTimeoutMs = timeoutMs; +void UdpTmTcBridge::setMutexProperties(MutexIF::TimeoutType timeoutType, dur_millis_t timeoutMs) { + this->timeoutType = timeoutType; + this->mutexTimeoutMs = timeoutMs; } diff --git a/src/fsfw/osal/common/UdpTmTcBridge.h b/src/fsfw/osal/common/UdpTmTcBridge.h index 4d634e64..78843ccd 100644 --- a/src/fsfw/osal/common/UdpTmTcBridge.h +++ b/src/fsfw/osal/common/UdpTmTcBridge.h @@ -22,44 +22,42 @@ * destination for telecommands, but the telecommands will be relayed to a specified tcDestination * directly. */ -class UdpTmTcBridge: - public TmTcBridge, - public TcpIpBase { - friend class UdpTcPollingTask; -public: - /* The ports chosen here should not be used by any other process. */ - static const std::string DEFAULT_SERVER_PORT; +class UdpTmTcBridge : public TmTcBridge, public TcpIpBase { + friend class UdpTcPollingTask; - UdpTmTcBridge(object_id_t objectId, object_id_t tcDestination, - std::string udpServerPort = "", object_id_t tmStoreId = objects::TM_STORE, - object_id_t tcStoreId = objects::TC_STORE); - virtual~ UdpTmTcBridge(); + public: + /* The ports chosen here should not be used by any other process. */ + static const std::string DEFAULT_SERVER_PORT; - /** - * Set properties of internal mutex. - */ - void setMutexProperties(MutexIF::TimeoutType timeoutType, dur_millis_t timeoutMs); + UdpTmTcBridge(object_id_t objectId, object_id_t tcDestination, std::string udpServerPort = "", + object_id_t tmStoreId = objects::TM_STORE, + object_id_t tcStoreId = objects::TC_STORE); + virtual ~UdpTmTcBridge(); - ReturnValue_t initialize() override; + /** + * Set properties of internal mutex. + */ + void setMutexProperties(MutexIF::TimeoutType timeoutType, dur_millis_t timeoutMs); - void checkAndSetClientAddress(sockaddr& clientAddress); + ReturnValue_t initialize() override; - std::string getUdpPort() const; + void checkAndSetClientAddress(sockaddr& clientAddress); -protected: - virtual ReturnValue_t sendTm(const uint8_t * data, size_t dataLen) override; + std::string getUdpPort() const; -private: - std::string udpServerPort; + protected: + virtual ReturnValue_t sendTm(const uint8_t* data, size_t dataLen) override; - struct sockaddr clientAddress; - socklen_t clientAddressLen = 0; + private: + std::string udpServerPort; - //! Access to the client address is mutex protected as it is set by another task. - MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING; - dur_millis_t mutexTimeoutMs = 20; - MutexIF* mutex; + struct sockaddr clientAddress; + socklen_t clientAddressLen = 0; + + //! Access to the client address is mutex protected as it is set by another task. + MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING; + dur_millis_t mutexTimeoutMs = 20; + MutexIF* mutex; }; #endif /* FSFW_OSAL_COMMON_TMTCUDPBRIDGE_H_ */ - diff --git a/src/fsfw/osal/common/tcpipCommon.cpp b/src/fsfw/osal/common/tcpipCommon.cpp index 2551496d..7594079f 100644 --- a/src/fsfw/osal/common/tcpipCommon.cpp +++ b/src/fsfw/osal/common/tcpipCommon.cpp @@ -1,5 +1,6 @@ -#include "fsfw/platform.h" #include "fsfw/osal/common/tcpipCommon.h" + +#include "fsfw/platform.h" #include "fsfw/serviceinterface/ServiceInterface.h" #ifdef PLATFORM_WIN @@ -7,82 +8,68 @@ #endif void tcpip::determineErrorStrings(Protocol protocol, ErrorSources errorSrc, std::string &protStr, - std::string &srcString) { - if(protocol == Protocol::TCP) { - protStr = "TCP"; - } - else if(protocol == Protocol::UDP) { - protStr = "UDP"; - } - else { - protStr = "Unknown protocol"; - } + std::string &srcString) { + if (protocol == Protocol::TCP) { + protStr = "TCP"; + } else if (protocol == Protocol::UDP) { + protStr = "UDP"; + } else { + protStr = "Unknown protocol"; + } - if(errorSrc == ErrorSources::SETSOCKOPT_CALL) { - srcString = "setsockopt call"; - } - if(errorSrc == ErrorSources::BIND_CALL) { - srcString = "bind call"; - } - else if(errorSrc == ErrorSources::SOCKET_CALL) { - srcString = "socket call"; - } - else if(errorSrc == ErrorSources::LISTEN_CALL) { - srcString = "listen call"; - } - else if(errorSrc == ErrorSources::ACCEPT_CALL) { - srcString = "accept call"; - } - else if(errorSrc == ErrorSources::RECVFROM_CALL) { - srcString = "recvfrom call"; - } - else if(errorSrc == ErrorSources::SEND_CALL) { - srcString = "send call"; - } - else if(errorSrc == ErrorSources::SENDTO_CALL) { - srcString = "sendto call"; - } - else if(errorSrc == ErrorSources::GETADDRINFO_CALL) { - srcString = "getaddrinfo call"; - } - else if(errorSrc == ErrorSources::SHUTDOWN_CALL) { - srcString = "shutdown call"; - } - else { - srcString = "unknown call"; - } + if (errorSrc == ErrorSources::SETSOCKOPT_CALL) { + srcString = "setsockopt call"; + } + if (errorSrc == ErrorSources::BIND_CALL) { + srcString = "bind call"; + } else if (errorSrc == ErrorSources::SOCKET_CALL) { + srcString = "socket call"; + } else if (errorSrc == ErrorSources::LISTEN_CALL) { + srcString = "listen call"; + } else if (errorSrc == ErrorSources::ACCEPT_CALL) { + srcString = "accept call"; + } else if (errorSrc == ErrorSources::RECVFROM_CALL) { + srcString = "recvfrom call"; + } else if (errorSrc == ErrorSources::SEND_CALL) { + srcString = "send call"; + } else if (errorSrc == ErrorSources::SENDTO_CALL) { + srcString = "sendto call"; + } else if (errorSrc == ErrorSources::GETADDRINFO_CALL) { + srcString = "getaddrinfo call"; + } else if (errorSrc == ErrorSources::SHUTDOWN_CALL) { + srcString = "shutdown call"; + } else { + srcString = "unknown call"; + } } -void tcpip::printAddress(struct sockaddr* addr) { - char ipAddress[INET6_ADDRSTRLEN] = {}; - const char* stringPtr = NULL; - switch(addr->sa_family) { +void tcpip::printAddress(struct sockaddr *addr) { + char ipAddress[INET6_ADDRSTRLEN] = {}; + const char *stringPtr = NULL; + switch (addr->sa_family) { case AF_INET: { - struct sockaddr_in *addrIn = reinterpret_cast(addr); - stringPtr = inet_ntop(AF_INET, &(addrIn->sin_addr), ipAddress, INET_ADDRSTRLEN); - break; + struct sockaddr_in *addrIn = reinterpret_cast(addr); + stringPtr = inet_ntop(AF_INET, &(addrIn->sin_addr), ipAddress, INET_ADDRSTRLEN); + break; } case AF_INET6: { - struct sockaddr_in6 *addrIn = reinterpret_cast(addr); - stringPtr = inet_ntop(AF_INET6, &(addrIn->sin6_addr), ipAddress, INET6_ADDRSTRLEN); - break; - } + struct sockaddr_in6 *addrIn = reinterpret_cast(addr); + stringPtr = inet_ntop(AF_INET6, &(addrIn->sin6_addr), ipAddress, INET6_ADDRSTRLEN); + break; } + } #if FSFW_CPP_OSTREAM_ENABLED == 1 - if(stringPtr == NULL) { - sif::debug << "Could not convert IP address to text representation, error code " - << errno << std::endl; - } - else { - sif::debug << "IP Address Sender: " << ipAddress << std::endl; - } + if (stringPtr == NULL) { + sif::debug << "Could not convert IP address to text representation, error code " << errno + << std::endl; + } else { + sif::debug << "IP Address Sender: " << ipAddress << std::endl; + } #else - if(stringPtr == NULL) { - sif::printDebug("Could not convert IP address to text representation, error code %d\n", - errno); - } - else { - sif::printDebug("IP Address Sender: %s\n", ipAddress); - } + if (stringPtr == NULL) { + sif::printDebug("Could not convert IP address to text representation, error code %d\n", errno); + } else { + sif::printDebug("IP Address Sender: %s\n", ipAddress); + } #endif } diff --git a/src/fsfw/osal/common/tcpipCommon.h b/src/fsfw/osal/common/tcpipCommon.h index 5a04144e..c632c2f6 100644 --- a/src/fsfw/osal/common/tcpipCommon.h +++ b/src/fsfw/osal/common/tcpipCommon.h @@ -1,44 +1,42 @@ #ifndef FSFW_OSAL_COMMON_TCPIPCOMMON_H_ #define FSFW_OSAL_COMMON_TCPIPCOMMON_H_ -#include "fsfw/timemanager/clockDefinitions.h" #include +#include "fsfw/timemanager/clockDefinitions.h" + #ifdef _WIN32 #include #else -#include #include +#include #endif namespace tcpip { static constexpr char DEFAULT_SERVER_PORT[] = "7301"; -enum class Protocol { - UDP, - TCP -}; +enum class Protocol { UDP, TCP }; enum class ErrorSources { - GETADDRINFO_CALL, - SOCKET_CALL, - SETSOCKOPT_CALL, - BIND_CALL, - RECV_CALL, - RECVFROM_CALL, - LISTEN_CALL, - ACCEPT_CALL, - SEND_CALL, - SENDTO_CALL, - SHUTDOWN_CALL + GETADDRINFO_CALL, + SOCKET_CALL, + SETSOCKOPT_CALL, + BIND_CALL, + RECV_CALL, + RECVFROM_CALL, + LISTEN_CALL, + ACCEPT_CALL, + SEND_CALL, + SENDTO_CALL, + SHUTDOWN_CALL }; void determineErrorStrings(Protocol protocol, ErrorSources errorSrc, std::string& protStr, - std::string& srcString); + std::string& srcString); void printAddress(struct sockaddr* addr); -} +} // namespace tcpip #endif /* FSFW_OSAL_COMMON_TCPIPCOMMON_H_ */ diff --git a/src/fsfw/osal/common/tcpipHelpers.h b/src/fsfw/osal/common/tcpipHelpers.h index bf9a7b5a..f78f4fc2 100644 --- a/src/fsfw/osal/common/tcpipHelpers.h +++ b/src/fsfw/osal/common/tcpipHelpers.h @@ -10,6 +10,4 @@ void handleError(Protocol protocol, ErrorSources errorSrc, dur_millis_t sleepDur } - - #endif /* FSFW_OSAL_WINDOWS_TCPIPHELPERS_H_ */ diff --git a/src/fsfw/osal/freertos/BinSemaphUsingTask.cpp b/src/fsfw/osal/freertos/BinSemaphUsingTask.cpp index 637c1925..7ffd61d3 100644 --- a/src/fsfw/osal/freertos/BinSemaphUsingTask.cpp +++ b/src/fsfw/osal/freertos/BinSemaphUsingTask.cpp @@ -1,106 +1,95 @@ #include "fsfw/osal/freertos/BinSemaphUsingTask.h" + #include "fsfw/osal/freertos/TaskManagement.h" #include "fsfw/serviceinterface/ServiceInterface.h" -#if (tskKERNEL_VERSION_MAJOR == 8 && tskKERNEL_VERSION_MINOR > 2) || \ - tskKERNEL_VERSION_MAJOR > 8 +#if (tskKERNEL_VERSION_MAJOR == 8 && tskKERNEL_VERSION_MINOR > 2) || tskKERNEL_VERSION_MAJOR > 8 BinarySemaphoreUsingTask::BinarySemaphoreUsingTask() { - handle = TaskManagement::getCurrentTaskHandle(); - if(handle == nullptr) { + handle = TaskManagement::getCurrentTaskHandle(); + if (handle == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Could not retrieve task handle. Please ensure the" - "constructor was called inside a task." << std::endl; + sif::error << "Could not retrieve task handle. Please ensure the" + "constructor was called inside a task." + << std::endl; #endif - } - xTaskNotifyGive(handle); + } + xTaskNotifyGive(handle); } BinarySemaphoreUsingTask::~BinarySemaphoreUsingTask() { - // Clear notification value on destruction. - xTaskNotifyAndQuery(handle, 0, eSetValueWithOverwrite, nullptr); + // Clear notification value on destruction. + xTaskNotifyAndQuery(handle, 0, eSetValueWithOverwrite, nullptr); } void BinarySemaphoreUsingTask::refreshTaskHandle() { - handle = TaskManagement::getCurrentTaskHandle(); + handle = TaskManagement::getCurrentTaskHandle(); } -ReturnValue_t BinarySemaphoreUsingTask::acquire(TimeoutType timeoutType, - uint32_t timeoutMs) { - TickType_t timeout = 0; - if(timeoutType == TimeoutType::POLLING) { - timeout = 0; - } - else if(timeoutType == TimeoutType::WAITING){ - timeout = pdMS_TO_TICKS(timeoutMs); - } - else { - timeout = portMAX_DELAY; - } - return acquireWithTickTimeout(timeoutType, timeout); +ReturnValue_t BinarySemaphoreUsingTask::acquire(TimeoutType timeoutType, uint32_t timeoutMs) { + TickType_t timeout = 0; + if (timeoutType == TimeoutType::POLLING) { + timeout = 0; + } else if (timeoutType == TimeoutType::WAITING) { + timeout = pdMS_TO_TICKS(timeoutMs); + } else { + timeout = portMAX_DELAY; + } + return acquireWithTickTimeout(timeoutType, timeout); } -ReturnValue_t BinarySemaphoreUsingTask::acquireWithTickTimeout( - TimeoutType timeoutType, TickType_t timeoutTicks) { - BaseType_t returncode = ulTaskNotifyTake(pdTRUE, timeoutTicks); - if (returncode == pdPASS) { - return HasReturnvaluesIF::RETURN_OK; - } - else { - return SemaphoreIF::SEMAPHORE_TIMEOUT; - } +ReturnValue_t BinarySemaphoreUsingTask::acquireWithTickTimeout(TimeoutType timeoutType, + TickType_t timeoutTicks) { + BaseType_t returncode = ulTaskNotifyTake(pdTRUE, timeoutTicks); + if (returncode == pdPASS) { + return HasReturnvaluesIF::RETURN_OK; + } else { + return SemaphoreIF::SEMAPHORE_TIMEOUT; + } } -ReturnValue_t BinarySemaphoreUsingTask::release() { - return release(this->handle); +ReturnValue_t BinarySemaphoreUsingTask::release() { return release(this->handle); } + +ReturnValue_t BinarySemaphoreUsingTask::release(TaskHandle_t taskHandle) { + if (getSemaphoreCounter(taskHandle) == 1) { + return SemaphoreIF::SEMAPHORE_NOT_OWNED; + } + BaseType_t returncode = xTaskNotifyGive(taskHandle); + if (returncode == pdPASS) { + return HasReturnvaluesIF::RETURN_OK; + } else { + // This should never happen. + return HasReturnvaluesIF::RETURN_FAILED; + } } -ReturnValue_t BinarySemaphoreUsingTask::release( - TaskHandle_t taskHandle) { - if(getSemaphoreCounter(taskHandle) == 1) { - return SemaphoreIF::SEMAPHORE_NOT_OWNED; - } - BaseType_t returncode = xTaskNotifyGive(taskHandle); - if (returncode == pdPASS) { - return HasReturnvaluesIF::RETURN_OK; - } - else { - // This should never happen. - return HasReturnvaluesIF::RETURN_FAILED; - } -} - -TaskHandle_t BinarySemaphoreUsingTask::getTaskHandle() { - return handle; -} +TaskHandle_t BinarySemaphoreUsingTask::getTaskHandle() { return handle; } uint8_t BinarySemaphoreUsingTask::getSemaphoreCounter() const { - return getSemaphoreCounter(this->handle); + return getSemaphoreCounter(this->handle); } -uint8_t BinarySemaphoreUsingTask::getSemaphoreCounter( - TaskHandle_t taskHandle) { - uint32_t notificationValue; - xTaskNotifyAndQuery(taskHandle, 0, eNoAction, ¬ificationValue); - return notificationValue; +uint8_t BinarySemaphoreUsingTask::getSemaphoreCounter(TaskHandle_t taskHandle) { + uint32_t notificationValue; + xTaskNotifyAndQuery(taskHandle, 0, eNoAction, ¬ificationValue); + return notificationValue; } // Be careful with the stack size here. This is called from an ISR! -ReturnValue_t BinarySemaphoreUsingTask::releaseFromISR( - TaskHandle_t taskHandle, BaseType_t * higherPriorityTaskWoken) { - if(getSemaphoreCounterFromISR(taskHandle, higherPriorityTaskWoken) == 1) { - return SemaphoreIF::SEMAPHORE_NOT_OWNED; - } - vTaskNotifyGiveFromISR(taskHandle, higherPriorityTaskWoken); - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t BinarySemaphoreUsingTask::releaseFromISR(TaskHandle_t taskHandle, + BaseType_t* higherPriorityTaskWoken) { + if (getSemaphoreCounterFromISR(taskHandle, higherPriorityTaskWoken) == 1) { + return SemaphoreIF::SEMAPHORE_NOT_OWNED; + } + vTaskNotifyGiveFromISR(taskHandle, higherPriorityTaskWoken); + return HasReturnvaluesIF::RETURN_OK; } -uint8_t BinarySemaphoreUsingTask::getSemaphoreCounterFromISR( - TaskHandle_t taskHandle, BaseType_t* higherPriorityTaskWoken) { - uint32_t notificationValue = 0; - xTaskNotifyAndQueryFromISR(taskHandle, 0, eNoAction, ¬ificationValue, - higherPriorityTaskWoken); - return notificationValue; +uint8_t BinarySemaphoreUsingTask::getSemaphoreCounterFromISR(TaskHandle_t taskHandle, + BaseType_t* higherPriorityTaskWoken) { + uint32_t notificationValue = 0; + xTaskNotifyAndQueryFromISR(taskHandle, 0, eNoAction, ¬ificationValue, higherPriorityTaskWoken); + return notificationValue; } #endif /* (tskKERNEL_VERSION_MAJOR == 8 && tskKERNEL_VERSION_MINOR > 2) || \ diff --git a/src/fsfw/osal/freertos/BinSemaphUsingTask.h b/src/fsfw/osal/freertos/BinSemaphUsingTask.h index 0645b1fa..34b0d031 100644 --- a/src/fsfw/osal/freertos/BinSemaphUsingTask.h +++ b/src/fsfw/osal/freertos/BinSemaphUsingTask.h @@ -1,14 +1,12 @@ #ifndef FSFW_OSAL_FREERTOS_BINSEMAPHUSINGTASK_H_ #define FSFW_OSAL_FREERTOS_BINSEMAPHUSINGTASK_H_ +#include "FreeRTOS.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" #include "fsfw/tasks/SemaphoreIF.h" - -#include "FreeRTOS.h" #include "task.h" -#if (tskKERNEL_VERSION_MAJOR == 8 && tskKERNEL_VERSION_MINOR > 2) || \ - tskKERNEL_VERSION_MAJOR > 8 +#if (tskKERNEL_VERSION_MAJOR == 8 && tskKERNEL_VERSION_MINOR > 2) || tskKERNEL_VERSION_MAJOR > 8 /** * @brief Binary Semaphore implementation using the task notification value. @@ -22,72 +20,70 @@ * (for example in the initializeAfterTaskCreation() function) or * by calling refreshTaskHandle() with the correct executing task. */ -class BinarySemaphoreUsingTask: public SemaphoreIF, - public HasReturnvaluesIF { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::SEMAPHORE_IF; +class BinarySemaphoreUsingTask : public SemaphoreIF, public HasReturnvaluesIF { + public: + static const uint8_t INTERFACE_ID = CLASS_ID::SEMAPHORE_IF; - //! @brief Default ctor - BinarySemaphoreUsingTask(); - //! @brief Default dtor - virtual~ BinarySemaphoreUsingTask(); + //! @brief Default ctor + BinarySemaphoreUsingTask(); + //! @brief Default dtor + virtual ~BinarySemaphoreUsingTask(); - /** - * This function can be used to get the correct task handle from the - * currently executing task. - * - * This is required because the task notification value will be used - * as a binary semaphore, and the semaphore might be created by another - * task. - */ - void refreshTaskHandle(); + /** + * This function can be used to get the correct task handle from the + * currently executing task. + * + * This is required because the task notification value will be used + * as a binary semaphore, and the semaphore might be created by another + * task. + */ + void refreshTaskHandle(); - ReturnValue_t acquire(TimeoutType timeoutType = TimeoutType::BLOCKING, - uint32_t timeoutMs = portMAX_DELAY) override; - ReturnValue_t release() override; - uint8_t getSemaphoreCounter() const override; - static uint8_t getSemaphoreCounter(TaskHandle_t taskHandle); - static uint8_t getSemaphoreCounterFromISR(TaskHandle_t taskHandle, - BaseType_t* higherPriorityTaskWoken); + ReturnValue_t acquire(TimeoutType timeoutType = TimeoutType::BLOCKING, + uint32_t timeoutMs = portMAX_DELAY) override; + ReturnValue_t release() override; + uint8_t getSemaphoreCounter() const override; + static uint8_t getSemaphoreCounter(TaskHandle_t taskHandle); + static uint8_t getSemaphoreCounterFromISR(TaskHandle_t taskHandle, + BaseType_t* higherPriorityTaskWoken); - /** - * Same as acquire() with timeout in FreeRTOS ticks. - * @param timeoutTicks - * @return - @c RETURN_OK on success - * - @c RETURN_FAILED on failure - */ - ReturnValue_t acquireWithTickTimeout( - TimeoutType timeoutType = TimeoutType::BLOCKING, - TickType_t timeoutTicks = portMAX_DELAY); + /** + * Same as acquire() with timeout in FreeRTOS ticks. + * @param timeoutTicks + * @return - @c RETURN_OK on success + * - @c RETURN_FAILED on failure + */ + ReturnValue_t acquireWithTickTimeout(TimeoutType timeoutType = TimeoutType::BLOCKING, + TickType_t timeoutTicks = portMAX_DELAY); - /** - * Get handle to the task related to the semaphore. - * @return - */ - TaskHandle_t getTaskHandle(); + /** + * Get handle to the task related to the semaphore. + * @return + */ + TaskHandle_t getTaskHandle(); - /** - * Wrapper function to give back semaphore from handle - * @param semaphore - * @return - @c RETURN_OK on success - * - @c RETURN_FAILED on failure - */ - static ReturnValue_t release(TaskHandle_t taskToNotify); + /** + * Wrapper function to give back semaphore from handle + * @param semaphore + * @return - @c RETURN_OK on success + * - @c RETURN_FAILED on failure + */ + static ReturnValue_t release(TaskHandle_t taskToNotify); - /** - * Wrapper function to give back semaphore from handle when called from an ISR - * @param semaphore - * @param higherPriorityTaskWoken This will be set to pdPASS if a task with - * a higher priority was unblocked. A context switch should be requested - * from an ISR if this is the case (see TaskManagement functions) - * @return - @c RETURN_OK on success - * - @c RETURN_FAILED on failure - */ - static ReturnValue_t releaseFromISR(TaskHandle_t taskToNotify, - BaseType_t* higherPriorityTaskWoken); + /** + * Wrapper function to give back semaphore from handle when called from an ISR + * @param semaphore + * @param higherPriorityTaskWoken This will be set to pdPASS if a task with + * a higher priority was unblocked. A context switch should be requested + * from an ISR if this is the case (see TaskManagement functions) + * @return - @c RETURN_OK on success + * - @c RETURN_FAILED on failure + */ + static ReturnValue_t releaseFromISR(TaskHandle_t taskToNotify, + BaseType_t* higherPriorityTaskWoken); -protected: - TaskHandle_t handle; + protected: + TaskHandle_t handle; }; #endif /* (tskKERNEL_VERSION_MAJOR == 8 && tskKERNEL_VERSION_MINOR > 2) || \ diff --git a/src/fsfw/osal/freertos/BinarySemaphore.cpp b/src/fsfw/osal/freertos/BinarySemaphore.cpp index 4ec5d30f..6e53380c 100644 --- a/src/fsfw/osal/freertos/BinarySemaphore.cpp +++ b/src/fsfw/osal/freertos/BinarySemaphore.cpp @@ -1,114 +1,98 @@ #include "fsfw/osal/freertos/BinarySemaphore.h" + #include "fsfw/osal/freertos/TaskManagement.h" #include "fsfw/serviceinterface/ServiceInterface.h" BinarySemaphore::BinarySemaphore() { - handle = xSemaphoreCreateBinary(); - if(handle == nullptr) { + handle = xSemaphoreCreateBinary(); + if (handle == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Semaphore: Binary semaph creation failure" << std::endl; + sif::error << "Semaphore: Binary semaph creation failure" << std::endl; #endif - } - // Initiated semaphore must be given before it can be taken. - xSemaphoreGive(handle); + } + // Initiated semaphore must be given before it can be taken. + xSemaphoreGive(handle); } -BinarySemaphore::~BinarySemaphore() { - vSemaphoreDelete(handle); -} +BinarySemaphore::~BinarySemaphore() { vSemaphoreDelete(handle); } BinarySemaphore::BinarySemaphore(BinarySemaphore&& s) { - handle = xSemaphoreCreateBinary(); - if(handle == nullptr) { + handle = xSemaphoreCreateBinary(); + if (handle == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Binary semaphore creation failure" << std::endl; + sif::error << "Binary semaphore creation failure" << std::endl; +#endif + } + xSemaphoreGive(handle); +} + +BinarySemaphore& BinarySemaphore::operator=(BinarySemaphore&& s) { + if (&s != this) { + handle = xSemaphoreCreateBinary(); + if (handle == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::error << "Binary semaphore creation failure" << std::endl; #endif } xSemaphoreGive(handle); + } + return *this; } -BinarySemaphore& BinarySemaphore::operator =( - BinarySemaphore&& s) { - if(&s != this) { - handle = xSemaphoreCreateBinary(); - if(handle == nullptr) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Binary semaphore creation failure" << std::endl; -#endif - } - xSemaphoreGive(handle); - } - return *this; -} - -ReturnValue_t BinarySemaphore::acquire(TimeoutType timeoutType, - uint32_t timeoutMs) { - TickType_t timeout = 0; - if(timeoutType == TimeoutType::POLLING) { - timeout = 0; - } - else if(timeoutType == TimeoutType::WAITING){ - timeout = pdMS_TO_TICKS(timeoutMs); - } - else { - timeout = portMAX_DELAY; - } - return acquireWithTickTimeout(timeoutType, timeout); +ReturnValue_t BinarySemaphore::acquire(TimeoutType timeoutType, uint32_t timeoutMs) { + TickType_t timeout = 0; + if (timeoutType == TimeoutType::POLLING) { + timeout = 0; + } else if (timeoutType == TimeoutType::WAITING) { + timeout = pdMS_TO_TICKS(timeoutMs); + } else { + timeout = portMAX_DELAY; + } + return acquireWithTickTimeout(timeoutType, timeout); } ReturnValue_t BinarySemaphore::acquireWithTickTimeout(TimeoutType timeoutType, - TickType_t timeoutTicks) { - if(handle == nullptr) { - return SemaphoreIF::SEMAPHORE_INVALID; - } + TickType_t timeoutTicks) { + if (handle == nullptr) { + return SemaphoreIF::SEMAPHORE_INVALID; + } - BaseType_t returncode = xSemaphoreTake(handle, timeoutTicks); - if (returncode == pdPASS) { - return HasReturnvaluesIF::RETURN_OK; - } - else { - return SemaphoreIF::SEMAPHORE_TIMEOUT; - } + BaseType_t returncode = xSemaphoreTake(handle, timeoutTicks); + if (returncode == pdPASS) { + return HasReturnvaluesIF::RETURN_OK; + } else { + return SemaphoreIF::SEMAPHORE_TIMEOUT; + } } -ReturnValue_t BinarySemaphore::release() { - return release(handle); -} +ReturnValue_t BinarySemaphore::release() { return release(handle); } ReturnValue_t BinarySemaphore::release(SemaphoreHandle_t semaphore) { - if (semaphore == nullptr) { - return SemaphoreIF::SEMAPHORE_INVALID; - } - BaseType_t returncode = xSemaphoreGive(semaphore); - if (returncode == pdPASS) { - return HasReturnvaluesIF::RETURN_OK; - } - else { - return SemaphoreIF::SEMAPHORE_NOT_OWNED; - } + if (semaphore == nullptr) { + return SemaphoreIF::SEMAPHORE_INVALID; + } + BaseType_t returncode = xSemaphoreGive(semaphore); + if (returncode == pdPASS) { + return HasReturnvaluesIF::RETURN_OK; + } else { + return SemaphoreIF::SEMAPHORE_NOT_OWNED; + } } -uint8_t BinarySemaphore::getSemaphoreCounter() const { - return uxSemaphoreGetCount(handle); -} - -SemaphoreHandle_t BinarySemaphore::getSemaphore() { - return handle; -} +uint8_t BinarySemaphore::getSemaphoreCounter() const { return uxSemaphoreGetCount(handle); } +SemaphoreHandle_t BinarySemaphore::getSemaphore() { return handle; } // Be careful with the stack size here. This is called from an ISR! -ReturnValue_t BinarySemaphore::releaseFromISR( - SemaphoreHandle_t semaphore, BaseType_t * higherPriorityTaskWoken) { - if (semaphore == nullptr) { - return SemaphoreIF::SEMAPHORE_INVALID; - } - BaseType_t returncode = xSemaphoreGiveFromISR(semaphore, - higherPriorityTaskWoken); - if (returncode == pdPASS) { - return HasReturnvaluesIF::RETURN_OK; - } - else { - return SemaphoreIF::SEMAPHORE_NOT_OWNED; - } +ReturnValue_t BinarySemaphore::releaseFromISR(SemaphoreHandle_t semaphore, + BaseType_t* higherPriorityTaskWoken) { + if (semaphore == nullptr) { + return SemaphoreIF::SEMAPHORE_INVALID; + } + BaseType_t returncode = xSemaphoreGiveFromISR(semaphore, higherPriorityTaskWoken); + if (returncode == pdPASS) { + return HasReturnvaluesIF::RETURN_OK; + } else { + return SemaphoreIF::SEMAPHORE_NOT_OWNED; + } } diff --git a/src/fsfw/osal/freertos/BinarySemaphore.h b/src/fsfw/osal/freertos/BinarySemaphore.h index 1ae56ff6..e2ca3c9d 100644 --- a/src/fsfw/osal/freertos/BinarySemaphore.h +++ b/src/fsfw/osal/freertos/BinarySemaphore.h @@ -1,10 +1,9 @@ #ifndef FSFW_OSAL_FREERTOS_BINARYSEMPAHORE_H_ #define FSFW_OSAL_FREERTOS_BINARYSEMPAHORE_H_ +#include "FreeRTOS.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" #include "fsfw/tasks/SemaphoreIF.h" - -#include "FreeRTOS.h" #include "semphr.h" /** @@ -23,85 +22,84 @@ * @author R. Mueller * @ingroup osal */ -class BinarySemaphore: public SemaphoreIF, - public HasReturnvaluesIF { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::SEMAPHORE_IF; +class BinarySemaphore : public SemaphoreIF, public HasReturnvaluesIF { + public: + static const uint8_t INTERFACE_ID = CLASS_ID::SEMAPHORE_IF; - //! @brief Default ctor - BinarySemaphore(); - //! @brief Copy ctor, deleted explicitely. - BinarySemaphore(const BinarySemaphore&) = delete; - //! @brief Copy assignment, deleted explicitely. - BinarySemaphore& operator=(const BinarySemaphore&) = delete; - //! @brief Move ctor - BinarySemaphore (BinarySemaphore &&); - //! @brief Move assignment - BinarySemaphore & operator=(BinarySemaphore &&); - //! @brief Destructor - virtual ~BinarySemaphore(); + //! @brief Default ctor + BinarySemaphore(); + //! @brief Copy ctor, deleted explicitely. + BinarySemaphore(const BinarySemaphore &) = delete; + //! @brief Copy assignment, deleted explicitely. + BinarySemaphore &operator=(const BinarySemaphore &) = delete; + //! @brief Move ctor + BinarySemaphore(BinarySemaphore &&); + //! @brief Move assignment + BinarySemaphore &operator=(BinarySemaphore &&); + //! @brief Destructor + virtual ~BinarySemaphore(); - uint8_t getSemaphoreCounter() const override; + uint8_t getSemaphoreCounter() const override; - /** - * Take the binary semaphore. - * If the semaphore has already been taken, the task will be blocked - * for a maximum of #timeoutMs or until the semaphore is given back, - * for example by an ISR or another task. - * @param timeoutMs - * @return -@c RETURN_OK on success - * -@c SemaphoreIF::SEMAPHORE_TIMEOUT on timeout - */ - ReturnValue_t acquire(TimeoutType timeoutType = - TimeoutType::BLOCKING, uint32_t timeoutMs = portMAX_DELAY) override; + /** + * Take the binary semaphore. + * If the semaphore has already been taken, the task will be blocked + * for a maximum of #timeoutMs or until the semaphore is given back, + * for example by an ISR or another task. + * @param timeoutMs + * @return -@c RETURN_OK on success + * -@c SemaphoreIF::SEMAPHORE_TIMEOUT on timeout + */ + ReturnValue_t acquire(TimeoutType timeoutType = TimeoutType::BLOCKING, + uint32_t timeoutMs = portMAX_DELAY) override; - /** - * Same as lockBinarySemaphore() with timeout in FreeRTOS ticks. - * @param timeoutTicks - * @return -@c RETURN_OK on success - * -@c SemaphoreIF::SEMAPHORE_TIMEOUT on timeout - */ - ReturnValue_t acquireWithTickTimeout(TimeoutType timeoutType = - TimeoutType::BLOCKING, TickType_t timeoutTicks = portMAX_DELAY); + /** + * Same as lockBinarySemaphore() with timeout in FreeRTOS ticks. + * @param timeoutTicks + * @return -@c RETURN_OK on success + * -@c SemaphoreIF::SEMAPHORE_TIMEOUT on timeout + */ + ReturnValue_t acquireWithTickTimeout(TimeoutType timeoutType = TimeoutType::BLOCKING, + TickType_t timeoutTicks = portMAX_DELAY); - /** - * Release the binary semaphore. - * @return -@c RETURN_OK on success - * -@c SemaphoreIF::SEMAPHORE_NOT_OWNED if the semaphores is - * already available. - */ - ReturnValue_t release() override; + /** + * Release the binary semaphore. + * @return -@c RETURN_OK on success + * -@c SemaphoreIF::SEMAPHORE_NOT_OWNED if the semaphores is + * already available. + */ + ReturnValue_t release() override; - /** - * Get Handle to the semaphore. - * @return - */ - SemaphoreHandle_t getSemaphore(); + /** + * Get Handle to the semaphore. + * @return + */ + SemaphoreHandle_t getSemaphore(); - /** - * Wrapper function to give back semaphore from handle - * @param semaphore - * @return -@c RETURN_OK on success - * -@c SemaphoreIF::SEMAPHORE_NOT_OWNED if the semaphores is - * already available. - */ - static ReturnValue_t release(SemaphoreHandle_t semaphore); + /** + * Wrapper function to give back semaphore from handle + * @param semaphore + * @return -@c RETURN_OK on success + * -@c SemaphoreIF::SEMAPHORE_NOT_OWNED if the semaphores is + * already available. + */ + static ReturnValue_t release(SemaphoreHandle_t semaphore); - /** - * Wrapper function to give back semaphore from handle when called from an ISR - * @param semaphore - * @param higherPriorityTaskWoken This will be set to pdPASS if a task with - * a higher priority was unblocked. A context switch from an ISR should - * then be requested (see TaskManagement functions) - * @return -@c RETURN_OK on success - * -@c SemaphoreIF::SEMAPHORE_NOT_OWNED if the semaphores is - * already available. - */ - static ReturnValue_t releaseFromISR(SemaphoreHandle_t semaphore, - BaseType_t * higherPriorityTaskWoken); + /** + * Wrapper function to give back semaphore from handle when called from an ISR + * @param semaphore + * @param higherPriorityTaskWoken This will be set to pdPASS if a task with + * a higher priority was unblocked. A context switch from an ISR should + * then be requested (see TaskManagement functions) + * @return -@c RETURN_OK on success + * -@c SemaphoreIF::SEMAPHORE_NOT_OWNED if the semaphores is + * already available. + */ + static ReturnValue_t releaseFromISR(SemaphoreHandle_t semaphore, + BaseType_t *higherPriorityTaskWoken); -protected: - SemaphoreHandle_t handle; + protected: + SemaphoreHandle_t handle; }; #endif /* FSFW_OSAL_FREERTOS_BINARYSEMPAHORE_H_ */ diff --git a/src/fsfw/osal/freertos/Clock.cpp b/src/fsfw/osal/freertos/Clock.cpp index eddf2fec..05083968 100644 --- a/src/fsfw/osal/freertos/Clock.cpp +++ b/src/fsfw/osal/freertos/Clock.cpp @@ -1,136 +1,127 @@ -#include "fsfw/osal/freertos/Timekeeper.h" - #include "fsfw/timemanager/Clock.h" -#include "fsfw/globalfunctions/timevalOperations.h" - -#include "FreeRTOS.h" -#include "task.h" #include #include -//TODO sanitize input? -//TODO much of this code can be reused for tick-only systems +#include "FreeRTOS.h" +#include "fsfw/globalfunctions/timevalOperations.h" +#include "fsfw/osal/freertos/Timekeeper.h" +#include "task.h" + +// TODO sanitize input? +// TODO much of this code can be reused for tick-only systems uint16_t Clock::leapSeconds = 0; MutexIF* Clock::timeMutex = nullptr; -uint32_t Clock::getTicksPerSecond(void) { - return 1000; -} +uint32_t Clock::getTicksPerSecond(void) { return 1000; } ReturnValue_t Clock::setClock(const TimeOfDay_t* time) { + timeval time_timeval; - timeval time_timeval; + ReturnValue_t result = convertTimeOfDayToTimeval(time, &time_timeval); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - ReturnValue_t result = convertTimeOfDayToTimeval(time, &time_timeval); - if (result != HasReturnvaluesIF::RETURN_OK){ - return result; - } - - return setClock(&time_timeval); + return setClock(&time_timeval); } ReturnValue_t Clock::setClock(const timeval* time) { - timeval uptime = getUptime(); + timeval uptime = getUptime(); - timeval offset = *time - uptime; + timeval offset = *time - uptime; - Timekeeper::instance()->setOffset(offset); + Timekeeper::instance()->setOffset(offset); - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t Clock::getClock_timeval(timeval* time) { - timeval uptime = getUptime(); + timeval uptime = getUptime(); - timeval offset = Timekeeper::instance()->getOffset(); + timeval offset = Timekeeper::instance()->getOffset(); - *time = offset + uptime; + *time = offset + uptime; - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t Clock::getUptime(timeval* uptime) { - *uptime = getUptime(); + *uptime = getUptime(); - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } timeval Clock::getUptime() { - TickType_t ticksSinceStart = xTaskGetTickCount(); - return Timekeeper::ticksToTimeval(ticksSinceStart); + TickType_t ticksSinceStart = xTaskGetTickCount(); + return Timekeeper::ticksToTimeval(ticksSinceStart); } ReturnValue_t Clock::getUptime(uint32_t* uptimeMs) { - timeval uptime = getUptime(); - *uptimeMs = uptime.tv_sec * 1000 + uptime.tv_usec / 1000; - return HasReturnvaluesIF::RETURN_OK; + timeval uptime = getUptime(); + *uptimeMs = uptime.tv_sec * 1000 + uptime.tv_usec / 1000; + return HasReturnvaluesIF::RETURN_OK; } - -//uint32_t Clock::getUptimeSeconds() { +// uint32_t Clock::getUptimeSeconds() { // timeval uptime = getUptime(); // return uptime.tv_sec; -//} - +// } ReturnValue_t Clock::getClock_usecs(uint64_t* time) { - timeval time_timeval; - ReturnValue_t result = getClock_timeval(&time_timeval); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - *time = time_timeval.tv_sec * 1000000 + time_timeval.tv_usec; - return HasReturnvaluesIF::RETURN_OK; + timeval time_timeval; + ReturnValue_t result = getClock_timeval(&time_timeval); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + *time = time_timeval.tv_sec * 1000000 + time_timeval.tv_usec; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t Clock::getDateAndTime(TimeOfDay_t* time) { - timeval time_timeval; - ReturnValue_t result = getClock_timeval(&time_timeval); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - struct tm time_tm; + timeval time_timeval; + ReturnValue_t result = getClock_timeval(&time_timeval); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + struct tm time_tm; - gmtime_r(&time_timeval.tv_sec,&time_tm); + gmtime_r(&time_timeval.tv_sec, &time_tm); - time->year = time_tm.tm_year + 1900; - time->month = time_tm.tm_mon + 1; - time->day = time_tm.tm_mday; + time->year = time_tm.tm_year + 1900; + time->month = time_tm.tm_mon + 1; + time->day = time_tm.tm_mday; - time->hour = time_tm.tm_hour; - time->minute = time_tm.tm_min; - time->second = time_tm.tm_sec; + time->hour = time_tm.tm_hour; + time->minute = time_tm.tm_min; + time->second = time_tm.tm_sec; - time->usecond = time_timeval.tv_usec; + time->usecond = time_timeval.tv_usec; - - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t Clock::convertTimeOfDayToTimeval(const TimeOfDay_t* from, - timeval* to) { - struct tm time_tm = {}; +ReturnValue_t Clock::convertTimeOfDayToTimeval(const TimeOfDay_t* from, timeval* to) { + struct tm time_tm = {}; - time_tm.tm_year = from->year - 1900; - time_tm.tm_mon = from->month - 1; - time_tm.tm_mday = from->day; + time_tm.tm_year = from->year - 1900; + time_tm.tm_mon = from->month - 1; + time_tm.tm_mday = from->day; - time_tm.tm_hour = from->hour; - time_tm.tm_min = from->minute; - time_tm.tm_sec = from->second; + time_tm.tm_hour = from->hour; + time_tm.tm_min = from->minute; + time_tm.tm_sec = from->second; - time_t seconds = mktime(&time_tm); + time_t seconds = mktime(&time_tm); - to->tv_sec = seconds; - to->tv_usec = from->usecond; - //Fails in 2038.. - return HasReturnvaluesIF::RETURN_OK; + to->tv_sec = seconds; + to->tv_usec = from->usecond; + // Fails in 2038.. + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t Clock::convertTimevalToJD2000(timeval time, double* JD2000) { - *JD2000 = (time.tv_sec - 946728000. + time.tv_usec / 1000000.) / 24. - / 3600.; - return HasReturnvaluesIF::RETURN_OK; + *JD2000 = (time.tv_sec - 946728000. + time.tv_usec / 1000000.) / 24. / 3600.; + return HasReturnvaluesIF::RETURN_OK; } diff --git a/src/fsfw/osal/freertos/CountingSemaphUsingTask.cpp b/src/fsfw/osal/freertos/CountingSemaphUsingTask.cpp index a34a6508..0e4d967d 100644 --- a/src/fsfw/osal/freertos/CountingSemaphUsingTask.cpp +++ b/src/fsfw/osal/freertos/CountingSemaphUsingTask.cpp @@ -1,126 +1,114 @@ #include "fsfw/osal/freertos/CountingSemaphUsingTask.h" -#include "fsfw/osal/freertos/TaskManagement.h" +#include "fsfw/osal/freertos/TaskManagement.h" #include "fsfw/serviceinterface/ServiceInterface.h" -#if (tskKERNEL_VERSION_MAJOR == 8 && tskKERNEL_VERSION_MINOR > 2) || \ - tskKERNEL_VERSION_MAJOR > 8 +#if (tskKERNEL_VERSION_MAJOR == 8 && tskKERNEL_VERSION_MINOR > 2) || tskKERNEL_VERSION_MAJOR > 8 -CountingSemaphoreUsingTask::CountingSemaphoreUsingTask(const uint8_t maxCount, - uint8_t initCount): maxCount(maxCount) { - if(initCount > maxCount) { +CountingSemaphoreUsingTask::CountingSemaphoreUsingTask(const uint8_t maxCount, uint8_t initCount) + : maxCount(maxCount) { + if (initCount > maxCount) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "CountingSemaphoreUsingTask: Max count bigger than " - "intial cout. Setting initial count to max count." << std::endl; + sif::error << "CountingSemaphoreUsingTask: Max count bigger than " + "intial cout. Setting initial count to max count." + << std::endl; #endif - initCount = maxCount; - } + initCount = maxCount; + } - handle = TaskManagement::getCurrentTaskHandle(); - if(handle == nullptr) { + handle = TaskManagement::getCurrentTaskHandle(); + if (handle == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "CountingSemaphoreUsingTask: Could not retrieve task " - "handle. Please ensure the constructor was called inside a " - "task." << std::endl; + sif::error << "CountingSemaphoreUsingTask: Could not retrieve task " + "handle. Please ensure the constructor was called inside a " + "task." + << std::endl; #endif - } + } - uint32_t oldNotificationValue; - xTaskNotifyAndQuery(handle, 0, eSetValueWithOverwrite, - &oldNotificationValue); - if(oldNotificationValue != 0) { + uint32_t oldNotificationValue; + xTaskNotifyAndQuery(handle, 0, eSetValueWithOverwrite, &oldNotificationValue); + if (oldNotificationValue != 0) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "CountinSemaphoreUsingTask: Semaphore initiated but " - "current notification value is not 0. Please ensure the " - "notification value is not used for other purposes!" << std::endl; + sif::warning << "CountinSemaphoreUsingTask: Semaphore initiated but " + "current notification value is not 0. Please ensure the " + "notification value is not used for other purposes!" + << std::endl; #endif - } - for(int i = 0; i < initCount; i++) { - xTaskNotifyGive(handle); - } + } + for (int i = 0; i < initCount; i++) { + xTaskNotifyGive(handle); + } } CountingSemaphoreUsingTask::~CountingSemaphoreUsingTask() { - // Clear notification value on destruction. - // If this is not desired, don't call the destructor - // (or implement a boolean which disables the reset) - xTaskNotifyAndQuery(handle, 0, eSetValueWithOverwrite, nullptr); + // Clear notification value on destruction. + // If this is not desired, don't call the destructor + // (or implement a boolean which disables the reset) + xTaskNotifyAndQuery(handle, 0, eSetValueWithOverwrite, nullptr); } -ReturnValue_t CountingSemaphoreUsingTask::acquire(TimeoutType timeoutType, - uint32_t timeoutMs) { - TickType_t timeout = 0; - if(timeoutType == TimeoutType::POLLING) { - timeout = 0; - } - else if(timeoutType == TimeoutType::WAITING){ - timeout = pdMS_TO_TICKS(timeoutMs); - } - else { - timeout = portMAX_DELAY; - } - return acquireWithTickTimeout(timeoutType, timeout); - +ReturnValue_t CountingSemaphoreUsingTask::acquire(TimeoutType timeoutType, uint32_t timeoutMs) { + TickType_t timeout = 0; + if (timeoutType == TimeoutType::POLLING) { + timeout = 0; + } else if (timeoutType == TimeoutType::WAITING) { + timeout = pdMS_TO_TICKS(timeoutMs); + } else { + timeout = portMAX_DELAY; + } + return acquireWithTickTimeout(timeoutType, timeout); } -ReturnValue_t CountingSemaphoreUsingTask::acquireWithTickTimeout( - TimeoutType timeoutType, TickType_t timeoutTicks) { - // Decrement notfication value without resetting it. - BaseType_t oldCount = ulTaskNotifyTake(pdFALSE, timeoutTicks); - if (getSemaphoreCounter() == oldCount - 1) { - return HasReturnvaluesIF::RETURN_OK; - } - else { - return SemaphoreIF::SEMAPHORE_TIMEOUT; - } +ReturnValue_t CountingSemaphoreUsingTask::acquireWithTickTimeout(TimeoutType timeoutType, + TickType_t timeoutTicks) { + // Decrement notfication value without resetting it. + BaseType_t oldCount = ulTaskNotifyTake(pdFALSE, timeoutTicks); + if (getSemaphoreCounter() == oldCount - 1) { + return HasReturnvaluesIF::RETURN_OK; + } else { + return SemaphoreIF::SEMAPHORE_TIMEOUT; + } } ReturnValue_t CountingSemaphoreUsingTask::release() { - if(getSemaphoreCounter() == maxCount) { - return SemaphoreIF::SEMAPHORE_NOT_OWNED; - } - return release(handle); + if (getSemaphoreCounter() == maxCount) { + return SemaphoreIF::SEMAPHORE_NOT_OWNED; + } + return release(handle); } -ReturnValue_t CountingSemaphoreUsingTask::release( - TaskHandle_t taskToNotify) { - BaseType_t returncode = xTaskNotifyGive(taskToNotify); - if (returncode == pdPASS) { - return HasReturnvaluesIF::RETURN_OK; - } - else { - // This should never happen. - return HasReturnvaluesIF::RETURN_FAILED; - } +ReturnValue_t CountingSemaphoreUsingTask::release(TaskHandle_t taskToNotify) { + BaseType_t returncode = xTaskNotifyGive(taskToNotify); + if (returncode == pdPASS) { + return HasReturnvaluesIF::RETURN_OK; + } else { + // This should never happen. + return HasReturnvaluesIF::RETURN_FAILED; + } } - uint8_t CountingSemaphoreUsingTask::getSemaphoreCounter() const { - uint32_t notificationValue = 0; - xTaskNotifyAndQuery(handle, 0, eNoAction, ¬ificationValue); - return notificationValue; + uint32_t notificationValue = 0; + xTaskNotifyAndQuery(handle, 0, eNoAction, ¬ificationValue); + return notificationValue; } -TaskHandle_t CountingSemaphoreUsingTask::getTaskHandle() { - return handle; -} +TaskHandle_t CountingSemaphoreUsingTask::getTaskHandle() { return handle; } -ReturnValue_t CountingSemaphoreUsingTask::releaseFromISR( - TaskHandle_t taskToNotify, BaseType_t* higherPriorityTaskWoken) { - vTaskNotifyGiveFromISR(taskToNotify, higherPriorityTaskWoken); - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t CountingSemaphoreUsingTask::releaseFromISR(TaskHandle_t taskToNotify, + BaseType_t* higherPriorityTaskWoken) { + vTaskNotifyGiveFromISR(taskToNotify, higherPriorityTaskWoken); + return HasReturnvaluesIF::RETURN_OK; } uint8_t CountingSemaphoreUsingTask::getSemaphoreCounterFromISR( - TaskHandle_t task, BaseType_t* higherPriorityTaskWoken) { - uint32_t notificationValue; - xTaskNotifyAndQueryFromISR(task, 0, eNoAction, ¬ificationValue, - higherPriorityTaskWoken); - return notificationValue; + TaskHandle_t task, BaseType_t* higherPriorityTaskWoken) { + uint32_t notificationValue; + xTaskNotifyAndQueryFromISR(task, 0, eNoAction, ¬ificationValue, higherPriorityTaskWoken); + return notificationValue; } -uint8_t CountingSemaphoreUsingTask::getMaxCount() const { - return maxCount; -} +uint8_t CountingSemaphoreUsingTask::getMaxCount() const { return maxCount; } #endif diff --git a/src/fsfw/osal/freertos/CountingSemaphUsingTask.h b/src/fsfw/osal/freertos/CountingSemaphUsingTask.h index eb2fc67b..86b27267 100644 --- a/src/fsfw/osal/freertos/CountingSemaphUsingTask.h +++ b/src/fsfw/osal/freertos/CountingSemaphUsingTask.h @@ -2,13 +2,11 @@ #define FSFW_OSAL_FREERTOS_COUNTINGSEMAPHUSINGTASK_H_ #include "CountingSemaphUsingTask.h" -#include "fsfw/tasks/SemaphoreIF.h" - #include "FreeRTOS.h" +#include "fsfw/tasks/SemaphoreIF.h" #include "task.h" -#if (tskKERNEL_VERSION_MAJOR == 8 && tskKERNEL_VERSION_MINOR > 2) || \ - tskKERNEL_VERSION_MAJOR > 8 +#if (tskKERNEL_VERSION_MAJOR == 8 && tskKERNEL_VERSION_MINOR > 2) || tskKERNEL_VERSION_MAJOR > 8 /** * @brief Couting Semaphore implementation which uses the notification value @@ -21,86 +19,84 @@ * Take care of calling this function with the correct executing task, * (for example in the initializeAfterTaskCreation() function). */ -class CountingSemaphoreUsingTask: public SemaphoreIF { -public: - CountingSemaphoreUsingTask(const uint8_t maxCount, uint8_t initCount); - virtual ~CountingSemaphoreUsingTask(); +class CountingSemaphoreUsingTask : public SemaphoreIF { + public: + CountingSemaphoreUsingTask(const uint8_t maxCount, uint8_t initCount); + virtual ~CountingSemaphoreUsingTask(); - /** - * Acquire the counting semaphore. - * If no semaphores are available, the task will be blocked - * for a maximum of #timeoutMs or until one is given back, - * for example by an ISR or another task. - * @param timeoutMs - * @return -@c RETURN_OK on success - * -@c SemaphoreIF::SEMAPHORE_TIMEOUT on timeout - */ - ReturnValue_t acquire(TimeoutType timeoutType = TimeoutType::BLOCKING, - uint32_t timeoutMs = portMAX_DELAY) override; + /** + * Acquire the counting semaphore. + * If no semaphores are available, the task will be blocked + * for a maximum of #timeoutMs or until one is given back, + * for example by an ISR or another task. + * @param timeoutMs + * @return -@c RETURN_OK on success + * -@c SemaphoreIF::SEMAPHORE_TIMEOUT on timeout + */ + ReturnValue_t acquire(TimeoutType timeoutType = TimeoutType::BLOCKING, + uint32_t timeoutMs = portMAX_DELAY) override; - /** - * Release a semaphore, increasing the number of available counting - * semaphores up to the #maxCount value. - * @return -@c RETURN_OK on success - * -@c SemaphoreIF::SEMAPHORE_NOT_OWNED if #maxCount semaphores are - * already available. - */ - ReturnValue_t release() override; + /** + * Release a semaphore, increasing the number of available counting + * semaphores up to the #maxCount value. + * @return -@c RETURN_OK on success + * -@c SemaphoreIF::SEMAPHORE_NOT_OWNED if #maxCount semaphores are + * already available. + */ + ReturnValue_t release() override; - uint8_t getSemaphoreCounter() const override; - /** - * Get the semaphore counter from an ISR. - * @param task - * @param higherPriorityTaskWoken This will be set to pdPASS if a task with - * a higher priority was unblocked. A context switch should be requested - * from an ISR if this is the case (see TaskManagement functions) - * @return - */ - static uint8_t getSemaphoreCounterFromISR(TaskHandle_t task, - BaseType_t* higherPriorityTaskWoken); + uint8_t getSemaphoreCounter() const override; + /** + * Get the semaphore counter from an ISR. + * @param task + * @param higherPriorityTaskWoken This will be set to pdPASS if a task with + * a higher priority was unblocked. A context switch should be requested + * from an ISR if this is the case (see TaskManagement functions) + * @return + */ + static uint8_t getSemaphoreCounterFromISR(TaskHandle_t task, BaseType_t* higherPriorityTaskWoken); - /** - * Acquire with a timeout value in ticks - * @param timeoutTicks - * @return -@c RETURN_OK on success - * -@c SemaphoreIF::SEMAPHORE_TIMEOUT on timeout - */ - ReturnValue_t acquireWithTickTimeout( - TimeoutType timeoutType = TimeoutType::BLOCKING, - TickType_t timeoutTicks = portMAX_DELAY); + /** + * Acquire with a timeout value in ticks + * @param timeoutTicks + * @return -@c RETURN_OK on success + * -@c SemaphoreIF::SEMAPHORE_TIMEOUT on timeout + */ + ReturnValue_t acquireWithTickTimeout(TimeoutType timeoutType = TimeoutType::BLOCKING, + TickType_t timeoutTicks = portMAX_DELAY); - /** - * Get handle to the task related to the semaphore. - * @return - */ - TaskHandle_t getTaskHandle(); + /** + * Get handle to the task related to the semaphore. + * @return + */ + TaskHandle_t getTaskHandle(); - /** - * Release semaphore of task by supplying task handle - * @param taskToNotify - * @return -@c RETURN_OK on success - * -@c SemaphoreIF::SEMAPHORE_NOT_OWNED if #maxCount semaphores are - * already available. - */ - static ReturnValue_t release(TaskHandle_t taskToNotify); - /** - * Release seamphore of a task from an ISR. - * @param taskToNotify - * @param higherPriorityTaskWoken This will be set to pdPASS if a task with - * a higher priority was unblocked. A context switch should be requested - * from an ISR if this is the case (see TaskManagement functions) - * @return -@c RETURN_OK on success - * -@c SemaphoreIF::SEMAPHORE_NOT_OWNED if #maxCount semaphores are - * already available. - */ - static ReturnValue_t releaseFromISR(TaskHandle_t taskToNotify, - BaseType_t* higherPriorityTaskWoken); + /** + * Release semaphore of task by supplying task handle + * @param taskToNotify + * @return -@c RETURN_OK on success + * -@c SemaphoreIF::SEMAPHORE_NOT_OWNED if #maxCount semaphores are + * already available. + */ + static ReturnValue_t release(TaskHandle_t taskToNotify); + /** + * Release seamphore of a task from an ISR. + * @param taskToNotify + * @param higherPriorityTaskWoken This will be set to pdPASS if a task with + * a higher priority was unblocked. A context switch should be requested + * from an ISR if this is the case (see TaskManagement functions) + * @return -@c RETURN_OK on success + * -@c SemaphoreIF::SEMAPHORE_NOT_OWNED if #maxCount semaphores are + * already available. + */ + static ReturnValue_t releaseFromISR(TaskHandle_t taskToNotify, + BaseType_t* higherPriorityTaskWoken); - uint8_t getMaxCount() const; + uint8_t getMaxCount() const; -private: - TaskHandle_t handle; - const uint8_t maxCount; + private: + TaskHandle_t handle; + const uint8_t maxCount; }; #endif /* (tskKERNEL_VERSION_MAJOR == 8 && tskKERNEL_VERSION_MINOR > 2) || \ diff --git a/src/fsfw/osal/freertos/CountingSemaphore.cpp b/src/fsfw/osal/freertos/CountingSemaphore.cpp index 90dc771f..3137166a 100644 --- a/src/fsfw/osal/freertos/CountingSemaphore.cpp +++ b/src/fsfw/osal/freertos/CountingSemaphore.cpp @@ -1,53 +1,49 @@ #include "fsfw/osal/freertos/CountingSemaphore.h" -#include "fsfw/osal/freertos/TaskManagement.h" - -#include "fsfw/serviceinterface/ServiceInterface.h" #include "FreeRTOS.h" +#include "fsfw/osal/freertos/TaskManagement.h" +#include "fsfw/serviceinterface/ServiceInterface.h" #include "semphr.h" // Make sure #define configUSE_COUNTING_SEMAPHORES 1 is set in // free FreeRTOSConfig.h file. -CountingSemaphore::CountingSemaphore(const uint8_t maxCount, uint8_t initCount): - maxCount(maxCount), initCount(initCount) { - if(initCount > maxCount) { +CountingSemaphore::CountingSemaphore(const uint8_t maxCount, uint8_t initCount) + : maxCount(maxCount), initCount(initCount) { + if (initCount > maxCount) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "CountingSemaphoreUsingTask: Max count bigger than " - "intial cout. Setting initial count to max count." << std::endl; + sif::error << "CountingSemaphoreUsingTask: Max count bigger than " + "intial cout. Setting initial count to max count." + << std::endl; #endif - initCount = maxCount; - } + initCount = maxCount; + } - handle = xSemaphoreCreateCounting(maxCount, initCount); - if(handle == nullptr) { + handle = xSemaphoreCreateCounting(maxCount, initCount); + if (handle == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "CountingSemaphore: Creation failure" << std::endl; + sif::error << "CountingSemaphore: Creation failure" << std::endl; #endif - } + } } -CountingSemaphore::CountingSemaphore(CountingSemaphore&& other): - maxCount(other.maxCount), initCount(other.initCount) { - handle = xSemaphoreCreateCounting(other.maxCount, other.initCount); - if(handle == nullptr) { +CountingSemaphore::CountingSemaphore(CountingSemaphore&& other) + : maxCount(other.maxCount), initCount(other.initCount) { + handle = xSemaphoreCreateCounting(other.maxCount, other.initCount); + if (handle == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "CountingSemaphore: Creation failure" << std::endl; + sif::error << "CountingSemaphore: Creation failure" << std::endl; #endif - } + } } -CountingSemaphore& CountingSemaphore::operator =( - CountingSemaphore&& other) { - handle = xSemaphoreCreateCounting(other.maxCount, other.initCount); - if(handle == nullptr) { +CountingSemaphore& CountingSemaphore::operator=(CountingSemaphore&& other) { + handle = xSemaphoreCreateCounting(other.maxCount, other.initCount); + if (handle == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "CountingSemaphore: Creation failure" << std::endl; + sif::error << "CountingSemaphore: Creation failure" << std::endl; #endif - } - return * this; + } + return *this; } - -uint8_t CountingSemaphore::getMaxCount() const { - return maxCount; -} +uint8_t CountingSemaphore::getMaxCount() const { return maxCount; } diff --git a/src/fsfw/osal/freertos/CountingSemaphore.h b/src/fsfw/osal/freertos/CountingSemaphore.h index 6af1d6d2..e0e89ee2 100644 --- a/src/fsfw/osal/freertos/CountingSemaphore.h +++ b/src/fsfw/osal/freertos/CountingSemaphore.h @@ -11,25 +11,26 @@ * so we just inherit from binary semaphore and provide the respective * constructors. */ -class CountingSemaphore: public BinarySemaphore { -public: - CountingSemaphore(const uint8_t maxCount, uint8_t initCount); - //! @brief Copy ctor, disabled - CountingSemaphore(const CountingSemaphore&) = delete; - //! @brief Copy assignment, disabled - CountingSemaphore& operator=(const CountingSemaphore&) = delete; - //! @brief Move ctor - CountingSemaphore (CountingSemaphore &&); - //! @brief Move assignment - CountingSemaphore & operator=(CountingSemaphore &&); +class CountingSemaphore : public BinarySemaphore { + public: + CountingSemaphore(const uint8_t maxCount, uint8_t initCount); + //! @brief Copy ctor, disabled + CountingSemaphore(const CountingSemaphore &) = delete; + //! @brief Copy assignment, disabled + CountingSemaphore &operator=(const CountingSemaphore &) = delete; + //! @brief Move ctor + CountingSemaphore(CountingSemaphore &&); + //! @brief Move assignment + CountingSemaphore &operator=(CountingSemaphore &&); - /* Same API as binary semaphore otherwise. acquire() can be called - * until there are not semaphores left and release() can be called - * until maxCount is reached. */ - uint8_t getMaxCount() const; -private: - const uint8_t maxCount; - uint8_t initCount = 0; + /* Same API as binary semaphore otherwise. acquire() can be called + * until there are not semaphores left and release() can be called + * until maxCount is reached. */ + uint8_t getMaxCount() const; + + private: + const uint8_t maxCount; + uint8_t initCount = 0; }; #endif /* FRAMEWORK_OSAL_FREERTOS_COUNTINGSEMAPHORE_H_ */ diff --git a/src/fsfw/osal/freertos/FixedTimeslotTask.cpp b/src/fsfw/osal/freertos/FixedTimeslotTask.cpp index 9690991d..e0e3779e 100644 --- a/src/fsfw/osal/freertos/FixedTimeslotTask.cpp +++ b/src/fsfw/osal/freertos/FixedTimeslotTask.cpp @@ -7,148 +7,139 @@ uint32_t FixedTimeslotTask::deadlineMissedCount = 0; const size_t PeriodicTaskIF::MINIMUM_STACK_SIZE = configMINIMAL_STACK_SIZE; FixedTimeslotTask::FixedTimeslotTask(TaskName name, TaskPriority setPriority, - TaskStackSize setStack, TaskPeriod overallPeriod, - void (*setDeadlineMissedFunc)()) : - started(false), handle(nullptr), pst(overallPeriod * 1000) { - configSTACK_DEPTH_TYPE stackSize = setStack / sizeof(configSTACK_DEPTH_TYPE); - xTaskCreate(taskEntryPoint, name, stackSize, this, setPriority, &handle); - // All additional attributes are applied to the object. - this->deadlineMissedFunc = setDeadlineMissedFunc; + TaskStackSize setStack, TaskPeriod overallPeriod, + void (*setDeadlineMissedFunc)()) + : started(false), handle(nullptr), pst(overallPeriod * 1000) { + configSTACK_DEPTH_TYPE stackSize = setStack / sizeof(configSTACK_DEPTH_TYPE); + xTaskCreate(taskEntryPoint, name, stackSize, this, setPriority, &handle); + // All additional attributes are applied to the object. + this->deadlineMissedFunc = setDeadlineMissedFunc; } -FixedTimeslotTask::~FixedTimeslotTask() { -} +FixedTimeslotTask::~FixedTimeslotTask() {} void FixedTimeslotTask::taskEntryPoint(void* argument) { + // The argument is re-interpreted as FixedTimeslotTask. The Task object is + // global, so it is found from any place. + FixedTimeslotTask* originalTask(reinterpret_cast(argument)); + /* Task should not start until explicitly requested, + * but in FreeRTOS, tasks start as soon as they are created if the scheduler + * is running but not if the scheduler is not running. + * To be able to accommodate both cases we check a member which is set in + * #startTask(). If it is not set and we get here, the scheduler was started + * before #startTask() was called and we need to suspend if it is set, + * the scheduler was not running before #startTask() was called and we + * can continue */ - // The argument is re-interpreted as FixedTimeslotTask. The Task object is - // global, so it is found from any place. - FixedTimeslotTask *originalTask(reinterpret_cast(argument)); - /* Task should not start until explicitly requested, - * but in FreeRTOS, tasks start as soon as they are created if the scheduler - * is running but not if the scheduler is not running. - * To be able to accommodate both cases we check a member which is set in - * #startTask(). If it is not set and we get here, the scheduler was started - * before #startTask() was called and we need to suspend if it is set, - * the scheduler was not running before #startTask() was called and we - * can continue */ + if (not originalTask->started) { + vTaskSuspend(NULL); + } - if (not originalTask->started) { - vTaskSuspend(NULL); - } - - originalTask->taskFunctionality(); + originalTask->taskFunctionality(); #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "Polling task " << originalTask->handle - << " returned from taskFunctionality." << std::endl; + sif::debug << "Polling task " << originalTask->handle << " returned from taskFunctionality." + << std::endl; #endif } void FixedTimeslotTask::missedDeadlineCounter() { - FixedTimeslotTask::deadlineMissedCount++; - if (FixedTimeslotTask::deadlineMissedCount % 10 == 0) { + FixedTimeslotTask::deadlineMissedCount++; + if (FixedTimeslotTask::deadlineMissedCount % 10 == 0) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "PST missed " << FixedTimeslotTask::deadlineMissedCount - << " deadlines." << std::endl; + sif::error << "PST missed " << FixedTimeslotTask::deadlineMissedCount << " deadlines." + << std::endl; #endif - } + } } ReturnValue_t FixedTimeslotTask::startTask() { - started = true; + started = true; - // We must not call resume if scheduler is not started yet - if (xTaskGetSchedulerState() != taskSCHEDULER_NOT_STARTED) { - vTaskResume(handle); - } + // We must not call resume if scheduler is not started yet + if (xTaskGetSchedulerState() != taskSCHEDULER_NOT_STARTED) { + vTaskResume(handle); + } - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t FixedTimeslotTask::addSlot(object_id_t componentId, - uint32_t slotTimeMs, int8_t executionStep) { - ExecutableObjectIF* handler = ObjectManager::instance()->get(componentId); - if (handler != nullptr) { - pst.addSlot(componentId, slotTimeMs, executionStep, handler, this); - return HasReturnvaluesIF::RETURN_OK; - } +ReturnValue_t FixedTimeslotTask::addSlot(object_id_t componentId, uint32_t slotTimeMs, + int8_t executionStep) { + ExecutableObjectIF* handler = ObjectManager::instance()->get(componentId); + if (handler != nullptr) { + pst.addSlot(componentId, slotTimeMs, executionStep, handler, this); + return HasReturnvaluesIF::RETURN_OK; + } #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Component " << std::hex << componentId << - " not found, not adding it to pst" << std::endl; + sif::error << "Component " << std::hex << componentId << " not found, not adding it to pst" + << std::endl; #endif - return HasReturnvaluesIF::RETURN_FAILED; + return HasReturnvaluesIF::RETURN_FAILED; } -uint32_t FixedTimeslotTask::getPeriodMs() const { - return pst.getLengthMs(); -} +uint32_t FixedTimeslotTask::getPeriodMs() const { return pst.getLengthMs(); } -ReturnValue_t FixedTimeslotTask::checkSequence() const { - return pst.checkSequence(); -} +ReturnValue_t FixedTimeslotTask::checkSequence() const { return pst.checkSequence(); } void FixedTimeslotTask::taskFunctionality() { - // A local iterator for the Polling Sequence Table is created to find the - // start time for the first entry. - auto slotListIter = pst.current; + // A local iterator for the Polling Sequence Table is created to find the + // start time for the first entry. + auto slotListIter = pst.current; - pst.intializeSequenceAfterTaskCreation(); + pst.intializeSequenceAfterTaskCreation(); - //The start time for the first entry is read. - uint32_t intervalMs = slotListIter->pollingTimeMs; - TickType_t interval = pdMS_TO_TICKS(intervalMs); + // The start time for the first entry is read. + uint32_t intervalMs = slotListIter->pollingTimeMs; + TickType_t interval = pdMS_TO_TICKS(intervalMs); - TickType_t xLastWakeTime; - /* The xLastWakeTime variable needs to be initialized with the current tick - count. Note that this is the only time the variable is written to - explicitly. After this assignment, xLastWakeTime is updated automatically - internally within vTaskDelayUntil(). */ - xLastWakeTime = xTaskGetTickCount(); + TickType_t xLastWakeTime; + /* The xLastWakeTime variable needs to be initialized with the current tick + count. Note that this is the only time the variable is written to + explicitly. After this assignment, xLastWakeTime is updated automatically + internally within vTaskDelayUntil(). */ + xLastWakeTime = xTaskGetTickCount(); - // wait for first entry's start time - if(interval > 0) { - vTaskDelayUntil(&xLastWakeTime, interval); - } + // wait for first entry's start time + if (interval > 0) { + vTaskDelayUntil(&xLastWakeTime, interval); + } - /* Enter the loop that defines the task behavior. */ - for (;;) { - //The component for this slot is executed and the next one is chosen. - this->pst.executeAndAdvance(); - if (not pst.slotFollowsImmediately()) { - // Get the interval till execution of the next slot. - intervalMs = this->pst.getIntervalToPreviousSlotMs(); - interval = pdMS_TO_TICKS(intervalMs); + /* Enter the loop that defines the task behavior. */ + for (;;) { + // The component for this slot is executed and the next one is chosen. + this->pst.executeAndAdvance(); + if (not pst.slotFollowsImmediately()) { + // Get the interval till execution of the next slot. + intervalMs = this->pst.getIntervalToPreviousSlotMs(); + interval = pdMS_TO_TICKS(intervalMs); -#if (tskKERNEL_VERSION_MAJOR == 10 && tskKERNEL_VERSION_MINOR >= 4) || \ - tskKERNEL_VERSION_MAJOR > 10 - BaseType_t wasDelayed = xTaskDelayUntil(&xLastWakeTime, interval); - if(wasDelayed == pdFALSE) { - handleMissedDeadline(); - } +#if (tskKERNEL_VERSION_MAJOR == 10 && tskKERNEL_VERSION_MINOR >= 4) || tskKERNEL_VERSION_MAJOR > 10 + BaseType_t wasDelayed = xTaskDelayUntil(&xLastWakeTime, interval); + if (wasDelayed == pdFALSE) { + handleMissedDeadline(); + } #else - if(checkMissedDeadline(xLastWakeTime, interval)) { - handleMissedDeadline(); - } - // Wait for the interval. This exits immediately if a deadline was - // missed while also updating the last wake time. - vTaskDelayUntil(&xLastWakeTime, interval); + if (checkMissedDeadline(xLastWakeTime, interval)) { + handleMissedDeadline(); + } + // Wait for the interval. This exits immediately if a deadline was + // missed while also updating the last wake time. + vTaskDelayUntil(&xLastWakeTime, interval); #endif - } - } + } + } } void FixedTimeslotTask::handleMissedDeadline() { - if(deadlineMissedFunc != nullptr) { - this->deadlineMissedFunc(); - } + if (deadlineMissedFunc != nullptr) { + this->deadlineMissedFunc(); + } } ReturnValue_t FixedTimeslotTask::sleepFor(uint32_t ms) { - vTaskDelay(pdMS_TO_TICKS(ms)); - return HasReturnvaluesIF::RETURN_OK; + vTaskDelay(pdMS_TO_TICKS(ms)); + return HasReturnvaluesIF::RETURN_OK; } -TaskHandle_t FixedTimeslotTask::getTaskHandle() { - return handle; -} +TaskHandle_t FixedTimeslotTask::getTaskHandle() { return handle; } diff --git a/src/fsfw/osal/freertos/FixedTimeslotTask.h b/src/fsfw/osal/freertos/FixedTimeslotTask.h index ebd902cc..77999d71 100644 --- a/src/fsfw/osal/freertos/FixedTimeslotTask.h +++ b/src/fsfw/osal/freertos/FixedTimeslotTask.h @@ -1,99 +1,96 @@ #ifndef FSFW_OSAL_FREERTOS_FIXEDTIMESLOTTASK_H_ #define FSFW_OSAL_FREERTOS_FIXEDTIMESLOTTASK_H_ +#include "FreeRTOS.h" #include "FreeRTOSTaskIF.h" #include "fsfw/tasks/FixedSlotSequence.h" #include "fsfw/tasks/FixedTimeslotTaskIF.h" #include "fsfw/tasks/Typedef.h" - -#include "FreeRTOS.h" #include "task.h" -class FixedTimeslotTask: public FixedTimeslotTaskIF, public FreeRTOSTaskIF { -public: +class FixedTimeslotTask : public FixedTimeslotTaskIF, public FreeRTOSTaskIF { + public: + /** + * Keep in mind that you need to call before vTaskStartScheduler()! + * A lot of task parameters are set in "FreeRTOSConfig.h". + * @param name Name of the task, lenght limited by configMAX_TASK_NAME_LEN + * @param setPriority Number of priorities specified by + * configMAX_PRIORITIES. High taskPriority_ number means high priority. + * @param setStack Stack size in words (not bytes!). + * Lower limit specified by configMINIMAL_STACK_SIZE + * @param overallPeriod Period in seconds. + * @param setDeadlineMissedFunc Callback if a deadline was missed. + * @return Pointer to the newly created task. + */ + FixedTimeslotTask(TaskName name, TaskPriority setPriority, TaskStackSize setStack, + TaskPeriod overallPeriod, void (*setDeadlineMissedFunc)()); - /** - * Keep in mind that you need to call before vTaskStartScheduler()! - * A lot of task parameters are set in "FreeRTOSConfig.h". - * @param name Name of the task, lenght limited by configMAX_TASK_NAME_LEN - * @param setPriority Number of priorities specified by - * configMAX_PRIORITIES. High taskPriority_ number means high priority. - * @param setStack Stack size in words (not bytes!). - * Lower limit specified by configMINIMAL_STACK_SIZE - * @param overallPeriod Period in seconds. - * @param setDeadlineMissedFunc Callback if a deadline was missed. - * @return Pointer to the newly created task. - */ - FixedTimeslotTask(TaskName name, TaskPriority setPriority, - TaskStackSize setStack, TaskPeriod overallPeriod, - void (*setDeadlineMissedFunc)()); + /** + * @brief The destructor of the class. + * @details + * The destructor frees all heap memory that was allocated on thread + * initialization for the PST and the device handlers. This is done by + * calling the PST's destructor. + */ + virtual ~FixedTimeslotTask(void); - /** - * @brief The destructor of the class. - * @details - * The destructor frees all heap memory that was allocated on thread - * initialization for the PST and the device handlers. This is done by - * calling the PST's destructor. - */ - virtual ~FixedTimeslotTask(void); + ReturnValue_t startTask(void); + /** + * This static function can be used as #deadlineMissedFunc. + * It counts missedDeadlines and prints the number of missed deadlines + * every 10th time. + */ + static void missedDeadlineCounter(); + /** + * A helper variable to count missed deadlines. + */ + static uint32_t deadlineMissedCount; - ReturnValue_t startTask(void); - /** - * This static function can be used as #deadlineMissedFunc. - * It counts missedDeadlines and prints the number of missed deadlines - * every 10th time. - */ - static void missedDeadlineCounter(); - /** - * A helper variable to count missed deadlines. - */ - static uint32_t deadlineMissedCount; + ReturnValue_t addSlot(object_id_t componentId, uint32_t slotTimeMs, + int8_t executionStep) override; - ReturnValue_t addSlot(object_id_t componentId, uint32_t slotTimeMs, - int8_t executionStep) override; + uint32_t getPeriodMs() const override; - uint32_t getPeriodMs() const override; + ReturnValue_t checkSequence() const override; - ReturnValue_t checkSequence() const override; + ReturnValue_t sleepFor(uint32_t ms) override; - ReturnValue_t sleepFor(uint32_t ms) override; + TaskHandle_t getTaskHandle() override; - TaskHandle_t getTaskHandle() override; + protected: + bool started; + TaskHandle_t handle; -protected: - bool started; - TaskHandle_t handle; + FixedSlotSequence pst; - FixedSlotSequence pst; + /** + * @brief This attribute holds a function pointer that is executed when + * a deadline was missed. + * @details + * Another function may be announced to determine the actions to perform + * when a deadline was missed. Currently, only one function for missing + * any deadline is allowed. If not used, it shall be declared NULL. + */ + void (*deadlineMissedFunc)(void); + /** + * @brief This is the entry point for a new task. + * @details + * This method starts the task by calling taskFunctionality(), as soon as + * all requirements (task scheduler has started and startTask() + * has been called) are met. + */ + static void taskEntryPoint(void* argument); - /** - * @brief This attribute holds a function pointer that is executed when - * a deadline was missed. - * @details - * Another function may be announced to determine the actions to perform - * when a deadline was missed. Currently, only one function for missing - * any deadline is allowed. If not used, it shall be declared NULL. - */ - void (*deadlineMissedFunc)(void); - /** - * @brief This is the entry point for a new task. - * @details - * This method starts the task by calling taskFunctionality(), as soon as - * all requirements (task scheduler has started and startTask() - * has been called) are met. - */ - static void taskEntryPoint(void* argument); + /** + * @brief This function holds the main functionality of the thread. + * @details + * Core function holding the main functionality of the task + * It links the functionalities provided by FixedSlotSequence with the + * OS's System Calls to keep the timing of the periods. + */ + void taskFunctionality(void); - /** - * @brief This function holds the main functionality of the thread. - * @details - * Core function holding the main functionality of the task - * It links the functionalities provided by FixedSlotSequence with the - * OS's System Calls to keep the timing of the periods. - */ - void taskFunctionality(void); - - void handleMissedDeadline(); + void handleMissedDeadline(); }; #endif /* FSFW_OSAL_FREERTOS_FIXEDTIMESLOTTASK_H_ */ diff --git a/src/fsfw/osal/freertos/FreeRTOSTaskIF.h b/src/fsfw/osal/freertos/FreeRTOSTaskIF.h index 08f0df25..ad5c9f7f 100644 --- a/src/fsfw/osal/freertos/FreeRTOSTaskIF.h +++ b/src/fsfw/osal/freertos/FreeRTOSTaskIF.h @@ -5,37 +5,33 @@ #include "task.h" class FreeRTOSTaskIF { -public: - virtual~ FreeRTOSTaskIF() {} - virtual TaskHandle_t getTaskHandle() = 0; + public: + virtual ~FreeRTOSTaskIF() {} + virtual TaskHandle_t getTaskHandle() = 0; -protected: - - bool checkMissedDeadline(const TickType_t xLastWakeTime, - const TickType_t interval) { - /* Check whether deadline was missed while also taking overflows - * into account. Drawing this on paper with a timeline helps to understand - * it. */ - TickType_t currentTickCount = xTaskGetTickCount(); - TickType_t timeToWake = xLastWakeTime + interval; - // Time to wake has not overflown. - if(timeToWake > xLastWakeTime) { - /* If the current time has overflown exclusively or the current - * tick count is simply larger than the time to wake, a deadline was - * missed */ - if((currentTickCount < xLastWakeTime) or - (currentTickCount > timeToWake)) { - return true; - } - } - /* Time to wake has overflown. A deadline was missed if the current time - * is larger than the time to wake */ - else if((timeToWake < xLastWakeTime) and - (currentTickCount > timeToWake)) { - return true; - } - return false; + protected: + bool checkMissedDeadline(const TickType_t xLastWakeTime, const TickType_t interval) { + /* Check whether deadline was missed while also taking overflows + * into account. Drawing this on paper with a timeline helps to understand + * it. */ + TickType_t currentTickCount = xTaskGetTickCount(); + TickType_t timeToWake = xLastWakeTime + interval; + // Time to wake has not overflown. + if (timeToWake > xLastWakeTime) { + /* If the current time has overflown exclusively or the current + * tick count is simply larger than the time to wake, a deadline was + * missed */ + if ((currentTickCount < xLastWakeTime) or (currentTickCount > timeToWake)) { + return true; + } } + /* Time to wake has overflown. A deadline was missed if the current time + * is larger than the time to wake */ + else if ((timeToWake < xLastWakeTime) and (currentTickCount > timeToWake)) { + return true; + } + return false; + } }; #endif /* FSFW_OSAL_FREERTOS_FREERTOSTASKIF_H_ */ diff --git a/src/fsfw/osal/freertos/MessageQueue.cpp b/src/fsfw/osal/freertos/MessageQueue.cpp index 487fa864..a8333fe5 100644 --- a/src/fsfw/osal/freertos/MessageQueue.cpp +++ b/src/fsfw/osal/freertos/MessageQueue.cpp @@ -1,159 +1,143 @@ #include "fsfw/osal/freertos/MessageQueue.h" -#include "fsfw/osal/freertos/QueueMapManager.h" #include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/osal/freertos/QueueMapManager.h" #include "fsfw/serviceinterface/ServiceInterface.h" -MessageQueue::MessageQueue(size_t messageDepth, size_t maxMessageSize): - maxMessageSize(maxMessageSize) { - handle = xQueueCreate(messageDepth, maxMessageSize); - if (handle == nullptr) { +MessageQueue::MessageQueue(size_t messageDepth, size_t maxMessageSize) + : maxMessageSize(maxMessageSize) { + handle = xQueueCreate(messageDepth, maxMessageSize); + if (handle == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "MessageQueue::MessageQueue: Creation failed" << std::endl; - sif::error << "Specified Message Depth: " << messageDepth << std::endl; - sif::error << "Specified Maximum Message Size: " << maxMessageSize << std::endl; + sif::error << "MessageQueue::MessageQueue: Creation failed" << std::endl; + sif::error << "Specified Message Depth: " << messageDepth << std::endl; + sif::error << "Specified Maximum Message Size: " << maxMessageSize << std::endl; #else - sif::printError("MessageQueue::MessageQueue: Creation failed\n"); - sif::printError("Specified Message Depth: %d\n", messageDepth); - sif::printError("Specified MAximum Message Size: %d\n", maxMessageSize); + sif::printError("MessageQueue::MessageQueue: Creation failed\n"); + sif::printError("Specified Message Depth: %d\n", messageDepth); + sif::printError("Specified MAximum Message Size: %d\n", maxMessageSize); #endif - } - QueueMapManager::instance()->addMessageQueue(handle, &queueId); + } + QueueMapManager::instance()->addMessageQueue(handle, &queueId); } MessageQueue::~MessageQueue() { - if (handle != nullptr) { - vQueueDelete(handle); - } + if (handle != nullptr) { + vQueueDelete(handle); + } } -void MessageQueue::switchSystemContext(CallContext callContext) { - this->callContext = callContext; -} +void MessageQueue::switchSystemContext(CallContext callContext) { this->callContext = callContext; } -ReturnValue_t MessageQueue::sendMessage(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, bool ignoreFault) { - return sendMessageFrom(sendTo, message, this->getId(), ignoreFault); +ReturnValue_t MessageQueue::sendMessage(MessageQueueId_t sendTo, MessageQueueMessageIF* message, + bool ignoreFault) { + return sendMessageFrom(sendTo, message, this->getId(), ignoreFault); } ReturnValue_t MessageQueue::sendToDefault(MessageQueueMessageIF* message) { - return sendToDefaultFrom(message, this->getId()); + return sendToDefaultFrom(message, this->getId()); } ReturnValue_t MessageQueue::sendToDefaultFrom(MessageQueueMessageIF* message, - MessageQueueId_t sentFrom, bool ignoreFault) { - return sendMessageFrom(defaultDestination,message,sentFrom,ignoreFault); + MessageQueueId_t sentFrom, bool ignoreFault) { + return sendMessageFrom(defaultDestination, message, sentFrom, ignoreFault); } ReturnValue_t MessageQueue::reply(MessageQueueMessageIF* message) { - if (this->lastPartner != MessageQueueIF::NO_QUEUE) { - return sendMessageFrom(this->lastPartner, message, this->getId()); - } else { - return NO_REPLY_PARTNER; - } + if (this->lastPartner != MessageQueueIF::NO_QUEUE) { + return sendMessageFrom(this->lastPartner, message, this->getId()); + } else { + return NO_REPLY_PARTNER; + } } -ReturnValue_t MessageQueue::sendMessageFrom(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, MessageQueueId_t sentFrom, - bool ignoreFault) { - return sendMessageFromMessageQueue(sendTo, message, sentFrom, ignoreFault, - callContext); +ReturnValue_t MessageQueue::sendMessageFrom(MessageQueueId_t sendTo, MessageQueueMessageIF* message, + MessageQueueId_t sentFrom, bool ignoreFault) { + return sendMessageFromMessageQueue(sendTo, message, sentFrom, ignoreFault, callContext); } -QueueHandle_t MessageQueue::getNativeQueueHandle() { - return handle; -} +QueueHandle_t MessageQueue::getNativeQueueHandle() { return handle; } ReturnValue_t MessageQueue::handleSendResult(BaseType_t result, bool ignoreFault) { - if (result != pdPASS) { - if (not ignoreFault) { - InternalErrorReporterIF* internalErrorReporter = ObjectManager::instance()-> - get(objects::INTERNAL_ERROR_REPORTER); - if (internalErrorReporter != nullptr) { - internalErrorReporter->queueMessageNotSent(); - } - } - return MessageQueueIF::FULL; - } - return HasReturnvaluesIF::RETURN_OK; + if (result != pdPASS) { + if (not ignoreFault) { + InternalErrorReporterIF* internalErrorReporter = + ObjectManager::instance()->get(objects::INTERNAL_ERROR_REPORTER); + if (internalErrorReporter != nullptr) { + internalErrorReporter->queueMessageNotSent(); + } + } + return MessageQueueIF::FULL; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t MessageQueue::receiveMessage(MessageQueueMessageIF* message, - MessageQueueId_t* receivedFrom) { - ReturnValue_t status = this->receiveMessage(message); - if(status == HasReturnvaluesIF::RETURN_OK) { - *receivedFrom = this->lastPartner; - } - return status; + MessageQueueId_t* receivedFrom) { + ReturnValue_t status = this->receiveMessage(message); + if (status == HasReturnvaluesIF::RETURN_OK) { + *receivedFrom = this->lastPartner; + } + return status; } ReturnValue_t MessageQueue::receiveMessage(MessageQueueMessageIF* message) { - BaseType_t result = xQueueReceive(handle,reinterpret_cast( - message->getBuffer()), 0); - if (result == pdPASS){ - this->lastPartner = message->getSender(); - return HasReturnvaluesIF::RETURN_OK; - } else { - return MessageQueueIF::EMPTY; - } + BaseType_t result = xQueueReceive(handle, reinterpret_cast(message->getBuffer()), 0); + if (result == pdPASS) { + this->lastPartner = message->getSender(); + return HasReturnvaluesIF::RETURN_OK; + } else { + return MessageQueueIF::EMPTY; + } } -MessageQueueId_t MessageQueue::getLastPartner() const { - return lastPartner; -} +MessageQueueId_t MessageQueue::getLastPartner() const { return lastPartner; } ReturnValue_t MessageQueue::flush(uint32_t* count) { - //TODO FreeRTOS does not support flushing partially - //Is always successful - xQueueReset(handle); - return HasReturnvaluesIF::RETURN_OK; + // TODO FreeRTOS does not support flushing partially + // Is always successful + xQueueReset(handle); + return HasReturnvaluesIF::RETURN_OK; } -MessageQueueId_t MessageQueue::getId() const { - return queueId; -} +MessageQueueId_t MessageQueue::getId() const { return queueId; } void MessageQueue::setDefaultDestination(MessageQueueId_t defaultDestination) { - defaultDestinationSet = true; - this->defaultDestination = defaultDestination; + defaultDestinationSet = true; + this->defaultDestination = defaultDestination; } -MessageQueueId_t MessageQueue::getDefaultDestination() const { - return defaultDestination; -} - -bool MessageQueue::isDefaultDestinationSet() const { - return defaultDestinationSet; -} +MessageQueueId_t MessageQueue::getDefaultDestination() const { return defaultDestination; } +bool MessageQueue::isDefaultDestinationSet() const { return defaultDestinationSet; } // static core function to send messages. ReturnValue_t MessageQueue::sendMessageFromMessageQueue(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, MessageQueueId_t sentFrom, - bool ignoreFault, CallContext callContext) { - BaseType_t result = pdFALSE; - if(sendTo == MessageQueueIF::NO_QUEUE) { - return MessageQueueIF::DESTINATION_INVALID; - } + MessageQueueMessageIF* message, + MessageQueueId_t sentFrom, bool ignoreFault, + CallContext callContext) { + BaseType_t result = pdFALSE; + if (sendTo == MessageQueueIF::NO_QUEUE) { + return MessageQueueIF::DESTINATION_INVALID; + } - QueueHandle_t destination = QueueMapManager::instance()->getMessageQueue(sendTo); - if(destination == nullptr) { - return MessageQueueIF::DESTINATION_INVALID; - } + QueueHandle_t destination = QueueMapManager::instance()->getMessageQueue(sendTo); + if (destination == nullptr) { + return MessageQueueIF::DESTINATION_INVALID; + } - message->setSender(sentFrom); - if(callContext == CallContext::TASK) { - result = xQueueSendToBack(destination, static_cast(message->getBuffer()), 0); + message->setSender(sentFrom); + if (callContext == CallContext::TASK) { + result = xQueueSendToBack(destination, static_cast(message->getBuffer()), 0); + } else { + /* If the call context is from an interrupt, request a context switch if a higher priority + task was blocked by the interrupt. */ + BaseType_t xHigherPriorityTaskWoken = pdFALSE; + result = xQueueSendFromISR(destination, static_cast(message->getBuffer()), + &xHigherPriorityTaskWoken); + if (xHigherPriorityTaskWoken == pdTRUE) { + TaskManagement::requestContextSwitch(callContext); } - else { - /* If the call context is from an interrupt, request a context switch if a higher priority - task was blocked by the interrupt. */ - BaseType_t xHigherPriorityTaskWoken = pdFALSE; - result = xQueueSendFromISR(destination, static_cast(message->getBuffer()), - &xHigherPriorityTaskWoken); - if(xHigherPriorityTaskWoken == pdTRUE) { - TaskManagement::requestContextSwitch(callContext); - } - } - return handleSendResult(result, ignoreFault); + } + return handleSendResult(result, ignoreFault); } diff --git a/src/fsfw/osal/freertos/MessageQueue.h b/src/fsfw/osal/freertos/MessageQueue.h index debb3034..1cb343d1 100644 --- a/src/fsfw/osal/freertos/MessageQueue.h +++ b/src/fsfw/osal/freertos/MessageQueue.h @@ -1,14 +1,12 @@ #ifndef FSFW_OSAL_FREERTOS_MESSAGEQUEUE_H_ #define FSFW_OSAL_FREERTOS_MESSAGEQUEUE_H_ +#include "FreeRTOS.h" #include "TaskManagement.h" - #include "fsfw/internalerror/InternalErrorReporterIF.h" #include "fsfw/ipc/MessageQueueIF.h" -#include "fsfw/ipc/MessageQueueMessageIF.h" #include "fsfw/ipc/MessageQueueMessage.h" - -#include "FreeRTOS.h" +#include "fsfw/ipc/MessageQueueMessageIF.h" #include "queue.h" /** @@ -35,116 +33,118 @@ * @ingroup message_queue */ class MessageQueue : public MessageQueueIF { - friend class MessageQueueSenderIF; -public: - /** - * @brief The constructor initializes and configures the message queue. - * @details - * By making use of the according operating system call, a message queue - * is created and initialized. The message depth - the maximum number of - * messages to be buffered - may be set with the help of a parameter, - * whereas the message size is automatically set to the maximum message - * queue message size. The operating system sets the message queue id, or - * in case of failure, it is set to zero. - * @param message_depth - * The number of messages to be buffered before passing an error to the - * sender. Default is three. - * @param max_message_size - * With this parameter, the maximum message size can be adjusted. - * This should be left default. - */ - MessageQueue( size_t messageDepth = 3, - size_t maxMessageSize = MessageQueueMessage::MAX_MESSAGE_SIZE ); + friend class MessageQueueSenderIF; - /** Copying message queues forbidden */ - MessageQueue(const MessageQueue&) = delete; - MessageQueue& operator=(const MessageQueue&) = delete; + public: + /** + * @brief The constructor initializes and configures the message queue. + * @details + * By making use of the according operating system call, a message queue + * is created and initialized. The message depth - the maximum number of + * messages to be buffered - may be set with the help of a parameter, + * whereas the message size is automatically set to the maximum message + * queue message size. The operating system sets the message queue id, or + * in case of failure, it is set to zero. + * @param message_depth + * The number of messages to be buffered before passing an error to the + * sender. Default is three. + * @param max_message_size + * With this parameter, the maximum message size can be adjusted. + * This should be left default. + */ + MessageQueue(size_t messageDepth = 3, + size_t maxMessageSize = MessageQueueMessage::MAX_MESSAGE_SIZE); - /** - * @brief The destructor deletes the formerly created message queue. - * @details This is accomplished by using the delete call provided - * by the operating system. - */ - virtual ~MessageQueue(); + /** Copying message queues forbidden */ + MessageQueue(const MessageQueue&) = delete; + MessageQueue& operator=(const MessageQueue&) = delete; - /** - * This function is used to switch the call context. This has to be called - * if a message is sent or received from an ISR! - * @param callContext - */ - void switchSystemContext(CallContext callContext); + /** + * @brief The destructor deletes the formerly created message queue. + * @details This is accomplished by using the delete call provided + * by the operating system. + */ + virtual ~MessageQueue(); - /** MessageQueueIF implementation */ - ReturnValue_t sendMessage(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, bool ignoreFault = false) override; + /** + * This function is used to switch the call context. This has to be called + * if a message is sent or received from an ISR! + * @param callContext + */ + void switchSystemContext(CallContext callContext); - ReturnValue_t sendToDefault(MessageQueueMessageIF* message) override; + /** MessageQueueIF implementation */ + ReturnValue_t sendMessage(MessageQueueId_t sendTo, MessageQueueMessageIF* message, + bool ignoreFault = false) override; - ReturnValue_t reply(MessageQueueMessageIF* message) override; - virtual ReturnValue_t sendMessageFrom(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, - MessageQueueId_t sentFrom = NO_QUEUE, - bool ignoreFault = false) override; + ReturnValue_t sendToDefault(MessageQueueMessageIF* message) override; - virtual ReturnValue_t sendToDefaultFrom( MessageQueueMessageIF* message, - MessageQueueId_t sentFrom = NO_QUEUE, - bool ignoreFault = false) override; + ReturnValue_t reply(MessageQueueMessageIF* message) override; + virtual ReturnValue_t sendMessageFrom(MessageQueueId_t sendTo, MessageQueueMessageIF* message, + MessageQueueId_t sentFrom = NO_QUEUE, + bool ignoreFault = false) override; - ReturnValue_t receiveMessage(MessageQueueMessageIF* message, - MessageQueueId_t *receivedFrom) override; + virtual ReturnValue_t sendToDefaultFrom(MessageQueueMessageIF* message, + MessageQueueId_t sentFrom = NO_QUEUE, + bool ignoreFault = false) override; - ReturnValue_t receiveMessage(MessageQueueMessageIF* message) override; + ReturnValue_t receiveMessage(MessageQueueMessageIF* message, + MessageQueueId_t* receivedFrom) override; - ReturnValue_t flush(uint32_t* count) override; + ReturnValue_t receiveMessage(MessageQueueMessageIF* message) override; - MessageQueueId_t getLastPartner() const override; + ReturnValue_t flush(uint32_t* count) override; - MessageQueueId_t getId() const override; + MessageQueueId_t getLastPartner() const override; - void setDefaultDestination(MessageQueueId_t defaultDestination) override; + MessageQueueId_t getId() const override; - MessageQueueId_t getDefaultDestination() const override; + void setDefaultDestination(MessageQueueId_t defaultDestination) override; - bool isDefaultDestinationSet() const override; + MessageQueueId_t getDefaultDestination() const override; - QueueHandle_t getNativeQueueHandle(); + bool isDefaultDestinationSet() const override; -protected: - /** - * @brief Implementation to be called from any send Call within - * MessageQueue and MessageQueueSenderIF. - * @details - * This method takes the message provided, adds the sentFrom information and - * passes it on to the destination provided with an operating system call. - * The OS's return value is returned. - * @param sendTo - * This parameter specifies the message queue id to send the message to. - * @param message - * This is a pointer to a previously created message, which is sent. - * @param sentFrom - * The sentFrom information can be set to inject the sender's queue id into - * the message. This variable is set to zero by default. - * @param ignoreFault - * If set to true, the internal software fault counter is not incremented - * if queue is full. - * @param context Specify whether call is made from task or from an ISR. - */ - static ReturnValue_t sendMessageFromMessageQueue(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, MessageQueueId_t sentFrom = NO_QUEUE, - bool ignoreFault=false, CallContext callContext = CallContext::TASK); + QueueHandle_t getNativeQueueHandle(); - static ReturnValue_t handleSendResult(BaseType_t result, bool ignoreFault); + protected: + /** + * @brief Implementation to be called from any send Call within + * MessageQueue and MessageQueueSenderIF. + * @details + * This method takes the message provided, adds the sentFrom information and + * passes it on to the destination provided with an operating system call. + * The OS's return value is returned. + * @param sendTo + * This parameter specifies the message queue id to send the message to. + * @param message + * This is a pointer to a previously created message, which is sent. + * @param sentFrom + * The sentFrom information can be set to inject the sender's queue id into + * the message. This variable is set to zero by default. + * @param ignoreFault + * If set to true, the internal software fault counter is not incremented + * if queue is full. + * @param context Specify whether call is made from task or from an ISR. + */ + static ReturnValue_t sendMessageFromMessageQueue(MessageQueueId_t sendTo, + MessageQueueMessageIF* message, + MessageQueueId_t sentFrom = NO_QUEUE, + bool ignoreFault = false, + CallContext callContext = CallContext::TASK); -private: - bool defaultDestinationSet = false; - QueueHandle_t handle; - MessageQueueId_t queueId = MessageQueueIF::NO_QUEUE; + static ReturnValue_t handleSendResult(BaseType_t result, bool ignoreFault); - MessageQueueId_t defaultDestination = MessageQueueIF::NO_QUEUE; - MessageQueueId_t lastPartner = MessageQueueIF::NO_QUEUE; - const size_t maxMessageSize; - //! Stores the current system context - CallContext callContext = CallContext::TASK; + private: + bool defaultDestinationSet = false; + QueueHandle_t handle; + MessageQueueId_t queueId = MessageQueueIF::NO_QUEUE; + + MessageQueueId_t defaultDestination = MessageQueueIF::NO_QUEUE; + MessageQueueId_t lastPartner = MessageQueueIF::NO_QUEUE; + const size_t maxMessageSize; + //! Stores the current system context + CallContext callContext = CallContext::TASK; }; #endif /* FSFW_OSAL_FREERTOS_MESSAGEQUEUE_H_ */ diff --git a/src/fsfw/osal/freertos/Mutex.cpp b/src/fsfw/osal/freertos/Mutex.cpp index 8d1313e6..1995e1ea 100644 --- a/src/fsfw/osal/freertos/Mutex.cpp +++ b/src/fsfw/osal/freertos/Mutex.cpp @@ -3,51 +3,48 @@ #include "fsfw/serviceinterface/ServiceInterface.h" Mutex::Mutex() { - handle = xSemaphoreCreateMutex(); - if(handle == nullptr) { + handle = xSemaphoreCreateMutex(); + if (handle == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Mutex::Mutex(FreeRTOS): Creation failure" << std::endl; + sif::error << "Mutex::Mutex(FreeRTOS): Creation failure" << std::endl; #endif - } + } } Mutex::~Mutex() { - if (handle != nullptr) { - vSemaphoreDelete(handle); - } - + if (handle != nullptr) { + vSemaphoreDelete(handle); + } } -ReturnValue_t Mutex::lockMutex(TimeoutType timeoutType, - uint32_t timeoutMs) { - if (handle == nullptr) { - return MutexIF::MUTEX_NOT_FOUND; - } - // If the timeout type is BLOCKING, this will be the correct value. - uint32_t timeout = portMAX_DELAY; - if(timeoutType == TimeoutType::POLLING) { - timeout = 0; - } - else if(timeoutType == TimeoutType::WAITING){ - timeout = pdMS_TO_TICKS(timeoutMs); - } +ReturnValue_t Mutex::lockMutex(TimeoutType timeoutType, uint32_t timeoutMs) { + if (handle == nullptr) { + return MutexIF::MUTEX_NOT_FOUND; + } + // If the timeout type is BLOCKING, this will be the correct value. + uint32_t timeout = portMAX_DELAY; + if (timeoutType == TimeoutType::POLLING) { + timeout = 0; + } else if (timeoutType == TimeoutType::WAITING) { + timeout = pdMS_TO_TICKS(timeoutMs); + } - BaseType_t returncode = xSemaphoreTake(handle, timeout); - if (returncode == pdPASS) { - return HasReturnvaluesIF::RETURN_OK; - } else { - return MutexIF::MUTEX_TIMEOUT; - } + BaseType_t returncode = xSemaphoreTake(handle, timeout); + if (returncode == pdPASS) { + return HasReturnvaluesIF::RETURN_OK; + } else { + return MutexIF::MUTEX_TIMEOUT; + } } ReturnValue_t Mutex::unlockMutex() { - if (handle == nullptr) { - return MutexIF::MUTEX_NOT_FOUND; - } - BaseType_t returncode = xSemaphoreGive(handle); - if (returncode == pdPASS) { - return HasReturnvaluesIF::RETURN_OK; - } else { - return MutexIF::CURR_THREAD_DOES_NOT_OWN_MUTEX; - } + if (handle == nullptr) { + return MutexIF::MUTEX_NOT_FOUND; + } + BaseType_t returncode = xSemaphoreGive(handle); + if (returncode == pdPASS) { + return HasReturnvaluesIF::RETURN_OK; + } else { + return MutexIF::CURR_THREAD_DOES_NOT_OWN_MUTEX; + } } diff --git a/src/fsfw/osal/freertos/Mutex.h b/src/fsfw/osal/freertos/Mutex.h index 082679c7..320ca901 100644 --- a/src/fsfw/osal/freertos/Mutex.h +++ b/src/fsfw/osal/freertos/Mutex.h @@ -1,9 +1,8 @@ #ifndef FRAMEWORK_FREERTOS_MUTEX_H_ #define FRAMEWORK_FREERTOS_MUTEX_H_ -#include "fsfw/ipc/MutexIF.h" - #include "FreeRTOS.h" +#include "fsfw/ipc/MutexIF.h" #include "semphr.h" /** @@ -15,15 +14,14 @@ * @ingroup osal */ class Mutex : public MutexIF { -public: - Mutex(); - ~Mutex(); - ReturnValue_t lockMutex(TimeoutType timeoutType, - uint32_t timeoutMs) override; - ReturnValue_t unlockMutex() override; + public: + Mutex(); + ~Mutex(); + ReturnValue_t lockMutex(TimeoutType timeoutType, uint32_t timeoutMs) override; + ReturnValue_t unlockMutex() override; -private: - SemaphoreHandle_t handle; + private: + SemaphoreHandle_t handle; }; #endif /* FRAMEWORK_FREERTOS_MUTEX_H_ */ diff --git a/src/fsfw/osal/freertos/MutexFactory.cpp b/src/fsfw/osal/freertos/MutexFactory.cpp index f8b48c7d..24587a89 100644 --- a/src/fsfw/osal/freertos/MutexFactory.cpp +++ b/src/fsfw/osal/freertos/MutexFactory.cpp @@ -1,30 +1,23 @@ -#include "fsfw/osal/freertos/Mutex.h" - #include "fsfw/ipc/MutexFactory.h" +#include "fsfw/osal/freertos/Mutex.h" -//TODO: Different variant than the lazy loading in QueueFactory. -//What's better and why? -> one is on heap the other on bss/data -//MutexFactory* MutexFactory::factoryInstance = new MutexFactory(); +// TODO: Different variant than the lazy loading in QueueFactory. +// What's better and why? -> one is on heap the other on bss/data +// MutexFactory* MutexFactory::factoryInstance = new MutexFactory(); MutexFactory* MutexFactory::factoryInstance = nullptr; -MutexFactory::MutexFactory() { -} +MutexFactory::MutexFactory() {} -MutexFactory::~MutexFactory() { -} +MutexFactory::~MutexFactory() {} MutexFactory* MutexFactory::instance() { - if (factoryInstance == nullptr){ - factoryInstance = new MutexFactory(); - } - return MutexFactory::factoryInstance; + if (factoryInstance == nullptr) { + factoryInstance = new MutexFactory(); + } + return MutexFactory::factoryInstance; } -MutexIF* MutexFactory::createMutex() { - return new Mutex(); -} +MutexIF* MutexFactory::createMutex() { return new Mutex(); } -void MutexFactory::deleteMutex(MutexIF* mutex) { - delete mutex; -} +void MutexFactory::deleteMutex(MutexIF* mutex) { delete mutex; } diff --git a/src/fsfw/osal/freertos/PeriodicTask.cpp b/src/fsfw/osal/freertos/PeriodicTask.cpp index 7ef1c837..8dfa0290 100644 --- a/src/fsfw/osal/freertos/PeriodicTask.cpp +++ b/src/fsfw/osal/freertos/PeriodicTask.cpp @@ -4,128 +4,119 @@ #include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/tasks/ExecutableObjectIF.h" -PeriodicTask::PeriodicTask(const char *name, TaskPriority setPriority, - TaskStackSize setStack, TaskPeriod setPeriod, - TaskDeadlineMissedFunction deadlineMissedFunc) : - started(false), handle(NULL), period(setPeriod), deadlineMissedFunc( - deadlineMissedFunc) -{ - configSTACK_DEPTH_TYPE stackSize = setStack / sizeof(configSTACK_DEPTH_TYPE); - BaseType_t status = xTaskCreate(taskEntryPoint, name, - stackSize, this, setPriority, &handle); - if(status != pdPASS){ +PeriodicTask::PeriodicTask(const char* name, TaskPriority setPriority, TaskStackSize setStack, + TaskPeriod setPeriod, TaskDeadlineMissedFunction deadlineMissedFunc) + : started(false), handle(NULL), period(setPeriod), deadlineMissedFunc(deadlineMissedFunc) { + configSTACK_DEPTH_TYPE stackSize = setStack / sizeof(configSTACK_DEPTH_TYPE); + BaseType_t status = xTaskCreate(taskEntryPoint, name, stackSize, this, setPriority, &handle); + if (status != pdPASS) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "PeriodicTask Insufficient heap memory remaining. " - "Status: " << status << std::endl; + sif::debug << "PeriodicTask Insufficient heap memory remaining. " + "Status: " + << status << std::endl; #endif - } - + } } PeriodicTask::~PeriodicTask(void) { - //Do not delete objects, we were responsible for ptrs only. + // Do not delete objects, we were responsible for ptrs only. } void PeriodicTask::taskEntryPoint(void* argument) { - // The argument is re-interpreted as PeriodicTask. The Task object is - // global, so it is found from any place. - PeriodicTask *originalTask(reinterpret_cast(argument)); - /* Task should not start until explicitly requested, - * but in FreeRTOS, tasks start as soon as they are created if the scheduler - * is running but not if the scheduler is not running. - * To be able to accommodate both cases we check a member which is set in - * #startTask(). If it is not set and we get here, the scheduler was started - * before #startTask() was called and we need to suspend if it is set, - * the scheduler was not running before #startTask() was called and we - * can continue */ + // The argument is re-interpreted as PeriodicTask. The Task object is + // global, so it is found from any place. + PeriodicTask* originalTask(reinterpret_cast(argument)); + /* Task should not start until explicitly requested, + * but in FreeRTOS, tasks start as soon as they are created if the scheduler + * is running but not if the scheduler is not running. + * To be able to accommodate both cases we check a member which is set in + * #startTask(). If it is not set and we get here, the scheduler was started + * before #startTask() was called and we need to suspend if it is set, + * the scheduler was not running before #startTask() was called and we + * can continue */ - if (not originalTask->started) { - vTaskSuspend(NULL); - } + if (not originalTask->started) { + vTaskSuspend(NULL); + } - originalTask->taskFunctionality(); + originalTask->taskFunctionality(); #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "Polling task " << originalTask->handle - << " returned from taskFunctionality." << std::endl; + sif::debug << "Polling task " << originalTask->handle << " returned from taskFunctionality." + << std::endl; #endif } ReturnValue_t PeriodicTask::startTask() { - started = true; + started = true; - // We must not call resume if scheduler is not started yet - if (xTaskGetSchedulerState() != taskSCHEDULER_NOT_STARTED) { - vTaskResume(handle); - } + // We must not call resume if scheduler is not started yet + if (xTaskGetSchedulerState() != taskSCHEDULER_NOT_STARTED) { + vTaskResume(handle); + } - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t PeriodicTask::sleepFor(uint32_t ms) { - vTaskDelay(pdMS_TO_TICKS(ms)); - return HasReturnvaluesIF::RETURN_OK; + vTaskDelay(pdMS_TO_TICKS(ms)); + return HasReturnvaluesIF::RETURN_OK; } void PeriodicTask::taskFunctionality() { - TickType_t xLastWakeTime; - const TickType_t xPeriod = pdMS_TO_TICKS(this->period * 1000.); - - for (auto const &object: objectList) { - object->initializeAfterTaskCreation(); - } + TickType_t xLastWakeTime; + const TickType_t xPeriod = pdMS_TO_TICKS(this->period * 1000.); - /* The xLastWakeTime variable needs to be initialized with the current tick - count. Note that this is the only time the variable is written to - explicitly. After this assignment, xLastWakeTime is updated automatically - internally within vTaskDelayUntil(). */ - xLastWakeTime = xTaskGetTickCount(); - /* Enter the loop that defines the task behavior. */ - for (;;) { - for (auto const& object: objectList) { - object->performOperation(); - } + for (auto const& object : objectList) { + object->initializeAfterTaskCreation(); + } -#if (tskKERNEL_VERSION_MAJOR == 10 && tskKERNEL_VERSION_MINOR >= 4) || \ - tskKERNEL_VERSION_MAJOR > 10 - BaseType_t wasDelayed = xTaskDelayUntil(&xLastWakeTime, xPeriod); - if(wasDelayed == pdFALSE) { - handleMissedDeadline(); - } + /* The xLastWakeTime variable needs to be initialized with the current tick + count. Note that this is the only time the variable is written to + explicitly. After this assignment, xLastWakeTime is updated automatically + internally within vTaskDelayUntil(). */ + xLastWakeTime = xTaskGetTickCount(); + /* Enter the loop that defines the task behavior. */ + for (;;) { + for (auto const& object : objectList) { + object->performOperation(); + } + +#if (tskKERNEL_VERSION_MAJOR == 10 && tskKERNEL_VERSION_MINOR >= 4) || tskKERNEL_VERSION_MAJOR > 10 + BaseType_t wasDelayed = xTaskDelayUntil(&xLastWakeTime, xPeriod); + if (wasDelayed == pdFALSE) { + handleMissedDeadline(); + } #else - if(checkMissedDeadline(xLastWakeTime, xPeriod)) { - handleMissedDeadline(); - } - vTaskDelayUntil(&xLastWakeTime, xPeriod); + if (checkMissedDeadline(xLastWakeTime, xPeriod)) { + handleMissedDeadline(); + } + vTaskDelayUntil(&xLastWakeTime, xPeriod); #endif - } + } } ReturnValue_t PeriodicTask::addComponent(object_id_t object) { - ExecutableObjectIF* newObject = ObjectManager::instance()->get( - object); - if (newObject == nullptr) { + ExecutableObjectIF* newObject = ObjectManager::instance()->get(object); + if (newObject == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "PeriodicTask::addComponent: Invalid object. Make sure" - "it implement ExecutableObjectIF" << std::endl; + sif::error << "PeriodicTask::addComponent: Invalid object. Make sure" + "it implement ExecutableObjectIF" + << std::endl; #endif - return HasReturnvaluesIF::RETURN_FAILED; - } - objectList.push_back(newObject); - newObject->setTaskIF(this); + return HasReturnvaluesIF::RETURN_FAILED; + } + objectList.push_back(newObject); + newObject->setTaskIF(this); - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } -uint32_t PeriodicTask::getPeriodMs() const { - return period * 1000; -} +uint32_t PeriodicTask::getPeriodMs() const { return period * 1000; } -TaskHandle_t PeriodicTask::getTaskHandle() { - return handle; -} +TaskHandle_t PeriodicTask::getTaskHandle() { return handle; } void PeriodicTask::handleMissedDeadline() { - if(deadlineMissedFunc != nullptr) { - this->deadlineMissedFunc(); - } + if (deadlineMissedFunc != nullptr) { + this->deadlineMissedFunc(); + } } diff --git a/src/fsfw/osal/freertos/PeriodicTask.h b/src/fsfw/osal/freertos/PeriodicTask.h index e910a0c6..cc395176 100644 --- a/src/fsfw/osal/freertos/PeriodicTask.h +++ b/src/fsfw/osal/freertos/PeriodicTask.h @@ -1,16 +1,15 @@ #ifndef FSFW_OSAL_FREERTOS_PERIODICTASK_H_ #define FSFW_OSAL_FREERTOS_PERIODICTASK_H_ +#include + +#include "FreeRTOS.h" #include "FreeRTOSTaskIF.h" #include "fsfw/objectmanager/ObjectManagerIF.h" #include "fsfw/tasks/PeriodicTaskIF.h" #include "fsfw/tasks/Typedef.h" - -#include "FreeRTOS.h" #include "task.h" -#include - class ExecutableObjectIF; /** @@ -18,108 +17,107 @@ class ExecutableObjectIF; * periodic activities of multiple objects. * @ingroup task_handling */ -class PeriodicTask: public PeriodicTaskIF, public FreeRTOSTaskIF { -public: - /** - * Keep in Mind that you need to call before this vTaskStartScheduler()! - * A lot of task parameters are set in "FreeRTOSConfig.h". - * @details - * The class is initialized without allocated objects. - * These need to be added with #addComponent. - * @param priority - * Sets the priority of a task. Values depend on freeRTOS configuration, - * high number means high priority. - * @param stack_size - * The stack size reserved by the operating system for the task. - * @param setPeriod - * The length of the period with which the task's - * functionality will be executed. It is expressed in clock ticks. - * @param setDeadlineMissedFunc - * The function pointer to the deadline missed function that shall - * be assigned. - */ - PeriodicTask(TaskName name, TaskPriority setPriority, - TaskStackSize setStack, TaskPeriod setPeriod, - TaskDeadlineMissedFunction deadlineMissedFunc); - /** - * @brief Currently, the executed object's lifetime is not coupled with - * the task object's lifetime, so the destructor is empty. - */ - virtual ~PeriodicTask(void); +class PeriodicTask : public PeriodicTaskIF, public FreeRTOSTaskIF { + public: + /** + * Keep in Mind that you need to call before this vTaskStartScheduler()! + * A lot of task parameters are set in "FreeRTOSConfig.h". + * @details + * The class is initialized without allocated objects. + * These need to be added with #addComponent. + * @param priority + * Sets the priority of a task. Values depend on freeRTOS configuration, + * high number means high priority. + * @param stack_size + * The stack size reserved by the operating system for the task. + * @param setPeriod + * The length of the period with which the task's + * functionality will be executed. It is expressed in clock ticks. + * @param setDeadlineMissedFunc + * The function pointer to the deadline missed function that shall + * be assigned. + */ + PeriodicTask(TaskName name, TaskPriority setPriority, TaskStackSize setStack, + TaskPeriod setPeriod, TaskDeadlineMissedFunction deadlineMissedFunc); + /** + * @brief Currently, the executed object's lifetime is not coupled with + * the task object's lifetime, so the destructor is empty. + */ + virtual ~PeriodicTask(void); - /** - * @brief The method to start the task. - * @details The method starts the task with the respective system call. - * Entry point is the taskEntryPoint method described below. - * The address of the task object is passed as an argument - * to the system call. - */ - ReturnValue_t startTask() override; - /** - * Adds an object to the list of objects to be executed. - * The objects are executed in the order added. - * @param object Id of the object to add. - * @return - * -@c RETURN_OK on success - * -@c RETURN_FAILED if the object could not be added. - */ - ReturnValue_t addComponent(object_id_t object) override; + /** + * @brief The method to start the task. + * @details The method starts the task with the respective system call. + * Entry point is the taskEntryPoint method described below. + * The address of the task object is passed as an argument + * to the system call. + */ + ReturnValue_t startTask() override; + /** + * Adds an object to the list of objects to be executed. + * The objects are executed in the order added. + * @param object Id of the object to add. + * @return + * -@c RETURN_OK on success + * -@c RETURN_FAILED if the object could not be added. + */ + ReturnValue_t addComponent(object_id_t object) override; - uint32_t getPeriodMs() const override; + uint32_t getPeriodMs() const override; - ReturnValue_t sleepFor(uint32_t ms) override; + ReturnValue_t sleepFor(uint32_t ms) override; - TaskHandle_t getTaskHandle() override; -protected: + TaskHandle_t getTaskHandle() override; - bool started; - TaskHandle_t handle; + protected: + bool started; + TaskHandle_t handle; - //! Typedef for the List of objects. - typedef std::vector ObjectList; - /** - * @brief This attribute holds a list of objects to be executed. - */ - ObjectList objectList; - /** - * @brief The period of the task. - * @details - * The period determines the frequency of the task's execution. - * It is expressed in clock ticks. - */ - TaskPeriod period; - /** - * @brief The pointer to the deadline-missed function. - * @details - * This pointer stores the function that is executed if the task's deadline - * is missed so each may react individually on a timing failure. - * The pointer may be NULL, then nothing happens on missing the deadline. - * The deadline is equal to the next execution of the periodic task. - */ - void (*deadlineMissedFunc)(void); - /** - * @brief This is the function executed in the new task's context. - * @details - * It converts the argument back to the thread object type and copies the - * class instance to the task context. The taskFunctionality method is - * called afterwards. - * @param A pointer to the task object itself is passed as argument. - */ + //! Typedef for the List of objects. + typedef std::vector ObjectList; + /** + * @brief This attribute holds a list of objects to be executed. + */ + ObjectList objectList; + /** + * @brief The period of the task. + * @details + * The period determines the frequency of the task's execution. + * It is expressed in clock ticks. + */ + TaskPeriod period; + /** + * @brief The pointer to the deadline-missed function. + * @details + * This pointer stores the function that is executed if the task's deadline + * is missed so each may react individually on a timing failure. + * The pointer may be NULL, then nothing happens on missing the deadline. + * The deadline is equal to the next execution of the periodic task. + */ + void (*deadlineMissedFunc)(void); + /** + * @brief This is the function executed in the new task's context. + * @details + * It converts the argument back to the thread object type and copies the + * class instance to the task context. The taskFunctionality method is + * called afterwards. + * @param A pointer to the task object itself is passed as argument. + */ - static void taskEntryPoint(void* argument); - /** - * @brief The function containing the actual functionality of the task. - * @details - * The method sets and starts the task's period, then enters a loop that is - * repeated as long as the isRunning attribute is true. Within the loop, - * all performOperation methods of the added objects are called. - * Afterwards the checkAndRestartPeriod system call blocks the task until - * the next period. - * On missing the deadline, the deadlineMissedFunction is executed. - */ - void taskFunctionality(void); + static void taskEntryPoint(void* argument); + /** + * @brief The function containing the actual functionality of the task. + * @details + * The method sets and starts the task's period, then enters a loop that is + * repeated as long as the isRunning attribute is true. Within the loop, + * all performOperation methods of the added objects are called. + * Afterwards the checkAndRestartPeriod system call blocks the task until + * the next period. + * On missing the deadline, the deadlineMissedFunction is executed. + */ + void taskFunctionality(void); - void handleMissedDeadline(); + void handleMissedDeadline(); }; #endif /* FSFW_OSAL_FREERTOS_PERIODICTASK_H_ */ diff --git a/src/fsfw/osal/freertos/QueueFactory.cpp b/src/fsfw/osal/freertos/QueueFactory.cpp index 536c16c0..f4941481 100644 --- a/src/fsfw/osal/freertos/QueueFactory.cpp +++ b/src/fsfw/osal/freertos/QueueFactory.cpp @@ -1,37 +1,29 @@ -#include "fsfw/osal/freertos/MessageQueue.h" - -#include "fsfw/ipc/MessageQueueSenderIF.h" #include "fsfw/ipc/QueueFactory.h" +#include "fsfw/ipc/MessageQueueSenderIF.h" +#include "fsfw/osal/freertos/MessageQueue.h" QueueFactory* QueueFactory::factoryInstance = nullptr; - ReturnValue_t MessageQueueSenderIF::sendMessage(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, MessageQueueId_t sentFrom, - bool ignoreFault) { - return MessageQueue::sendMessageFromMessageQueue(sendTo,message, - sentFrom,ignoreFault); + MessageQueueMessageIF* message, + MessageQueueId_t sentFrom, bool ignoreFault) { + return MessageQueue::sendMessageFromMessageQueue(sendTo, message, sentFrom, ignoreFault); } QueueFactory* QueueFactory::instance() { - if (factoryInstance == nullptr) { - factoryInstance = new QueueFactory; - } - return factoryInstance; + if (factoryInstance == nullptr) { + factoryInstance = new QueueFactory; + } + return factoryInstance; } -QueueFactory::QueueFactory() { +QueueFactory::QueueFactory() {} + +QueueFactory::~QueueFactory() {} + +MessageQueueIF* QueueFactory::createMessageQueue(uint32_t messageDepth, size_t maxMessageSize) { + return new MessageQueue(messageDepth, maxMessageSize); } -QueueFactory::~QueueFactory() { -} - -MessageQueueIF* QueueFactory::createMessageQueue(uint32_t messageDepth, - size_t maxMessageSize) { - return new MessageQueue(messageDepth, maxMessageSize); -} - -void QueueFactory::deleteMessageQueue(MessageQueueIF* queue) { - delete queue; -} +void QueueFactory::deleteMessageQueue(MessageQueueIF* queue) { delete queue; } diff --git a/src/fsfw/osal/freertos/QueueMapManager.cpp b/src/fsfw/osal/freertos/QueueMapManager.cpp index 7d6b2f12..cb3afb1c 100644 --- a/src/fsfw/osal/freertos/QueueMapManager.cpp +++ b/src/fsfw/osal/freertos/QueueMapManager.cpp @@ -1,64 +1,61 @@ #include "fsfw/osal/freertos/QueueMapManager.h" + #include "fsfw/ipc/MutexFactory.h" #include "fsfw/ipc/MutexGuard.h" QueueMapManager* QueueMapManager::mqManagerInstance = nullptr; -QueueMapManager::QueueMapManager() { - mapLock = MutexFactory::instance()->createMutex(); -} +QueueMapManager::QueueMapManager() { mapLock = MutexFactory::instance()->createMutex(); } QueueMapManager* QueueMapManager::instance() { - if (mqManagerInstance == nullptr){ - mqManagerInstance = new QueueMapManager(); - } - return QueueMapManager::mqManagerInstance; + if (mqManagerInstance == nullptr) { + mqManagerInstance = new QueueMapManager(); + } + return QueueMapManager::mqManagerInstance; } ReturnValue_t QueueMapManager::addMessageQueue(QueueHandle_t queue, MessageQueueId_t* id) { - MutexGuard lock(mapLock); - uint32_t currentId = queueCounter; + MutexGuard lock(mapLock); + uint32_t currentId = queueCounter; + queueCounter++; + if (currentId == MessageQueueIF::NO_QUEUE) { + // Skip the NO_QUEUE value + currentId = queueCounter; queueCounter++; - if(currentId == MessageQueueIF::NO_QUEUE) { - // Skip the NO_QUEUE value - currentId = queueCounter; - queueCounter++; - } - auto returnPair = queueMap.emplace(currentId, queue); - if(not returnPair.second) { + } + auto returnPair = queueMap.emplace(currentId, queue); + if (not returnPair.second) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "QueueMapManager::addMessageQueue This ID is already " - "inside the map!" << std::endl; + sif::error << "QueueMapManager::addMessageQueue This ID is already " + "inside the map!" + << std::endl; #else - sif::printError("QueueMapManager::addMessageQueue This ID is already " - "inside the map!\n"); + sif::printError( + "QueueMapManager::addMessageQueue This ID is already " + "inside the map!\n"); #endif - return HasReturnvaluesIF::RETURN_FAILED; - } - if (id != nullptr) { - *id = currentId; - } - return HasReturnvaluesIF::RETURN_OK; - + return HasReturnvaluesIF::RETURN_FAILED; + } + if (id != nullptr) { + *id = currentId; + } + return HasReturnvaluesIF::RETURN_OK; } QueueHandle_t QueueMapManager::getMessageQueue(MessageQueueId_t messageQueueId) const { - auto queueIter = queueMap.find(messageQueueId); - if(queueIter != queueMap.end()) { - return queueIter->second; - } - else { + auto queueIter = queueMap.find(messageQueueId); + if (queueIter != queueMap.end()) { + return queueIter->second; + } else { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "QueueMapManager::getQueueHandle: The ID " << messageQueueId << - " does not exists in the map!" << std::endl; + sif::warning << "QueueMapManager::getQueueHandle: The ID " << messageQueueId + << " does not exists in the map!" << std::endl; #else - sif::printWarning("QueueMapManager::getQueueHandle: The ID %d does not exist in the map!\n", - messageQueueId); + sif::printWarning("QueueMapManager::getQueueHandle: The ID %d does not exist in the map!\n", + messageQueueId); #endif - } - return nullptr; + } + return nullptr; } -QueueMapManager::~QueueMapManager() { - MutexFactory::instance()->deleteMutex(mapLock); -} +QueueMapManager::~QueueMapManager() { MutexFactory::instance()->deleteMutex(mapLock); } diff --git a/src/fsfw/osal/freertos/QueueMapManager.h b/src/fsfw/osal/freertos/QueueMapManager.h index dbe0526b..92722352 100644 --- a/src/fsfw/osal/freertos/QueueMapManager.h +++ b/src/fsfw/osal/freertos/QueueMapManager.h @@ -1,50 +1,46 @@ #ifndef FSFW_OSAL_FREERTOS_QUEUEMAPMANAGER_H_ #define FSFW_OSAL_FREERTOS_QUEUEMAPMANAGER_H_ -#include "fsfw/ipc/MutexIF.h" -#include "fsfw/ipc/messageQueueDefinitions.h" -#include "fsfw/ipc/MessageQueueIF.h" +#include #include "FreeRTOS.h" +#include "fsfw/ipc/MessageQueueIF.h" +#include "fsfw/ipc/MutexIF.h" +#include "fsfw/ipc/messageQueueDefinitions.h" #include "queue.h" -#include - using QueueMap = std::map; class QueueMapManager { -public: + public: + //! Returns the single instance of QueueMapManager + static QueueMapManager* instance(); - //! Returns the single instance of QueueMapManager - static QueueMapManager* instance(); + /** + * Insert a message queue and the corresponding QueueHandle into the map + * @param queue The message queue to insert. + * @param id The passed value will be set unless a nullptr is passed + * @return + */ + ReturnValue_t addMessageQueue(QueueHandle_t queue, MessageQueueId_t* id); - /** - * Insert a message queue and the corresponding QueueHandle into the map - * @param queue The message queue to insert. - * @param id The passed value will be set unless a nullptr is passed - * @return - */ - ReturnValue_t addMessageQueue(QueueHandle_t queue, MessageQueueId_t* id); + /** + * Get the message queue handle by providing a message queue ID. Returns nullptr + * if the queue ID does not exist in the internal map. + * @param messageQueueId + * @return + */ + QueueHandle_t getMessageQueue(MessageQueueId_t messageQueueId) const; - /** - * Get the message queue handle by providing a message queue ID. Returns nullptr - * if the queue ID does not exist in the internal map. - * @param messageQueueId - * @return - */ - QueueHandle_t getMessageQueue(MessageQueueId_t messageQueueId) const; + private: + //! External instantiation forbidden. Constructor still required for singleton instantiation. + QueueMapManager(); + ~QueueMapManager(); -private: - //! External instantiation forbidden. Constructor still required for singleton instantiation. - QueueMapManager(); - ~QueueMapManager(); - - uint32_t queueCounter = MessageQueueIF::NO_QUEUE + 1; - MutexIF* mapLock; - QueueMap queueMap; - static QueueMapManager* mqManagerInstance; + uint32_t queueCounter = MessageQueueIF::NO_QUEUE + 1; + MutexIF* mapLock; + QueueMap queueMap; + static QueueMapManager* mqManagerInstance; }; - - #endif /* FSFW_OSAL_FREERTOS_QUEUEMAPMANAGER_H_ */ diff --git a/src/fsfw/osal/freertos/SemaphoreFactory.cpp b/src/fsfw/osal/freertos/SemaphoreFactory.cpp index b6e8f86e..4224386e 100644 --- a/src/fsfw/osal/freertos/SemaphoreFactory.cpp +++ b/src/fsfw/osal/freertos/SemaphoreFactory.cpp @@ -1,9 +1,9 @@ -#include "fsfw/osal/freertos/BinarySemaphore.h" -#include "fsfw/osal/freertos/BinSemaphUsingTask.h" -#include "fsfw/osal/freertos/CountingSemaphore.h" -#include "fsfw/osal/freertos/CountingSemaphUsingTask.h" - #include "fsfw/tasks/SemaphoreFactory.h" + +#include "fsfw/osal/freertos/BinSemaphUsingTask.h" +#include "fsfw/osal/freertos/BinarySemaphore.h" +#include "fsfw/osal/freertos/CountingSemaphUsingTask.h" +#include "fsfw/osal/freertos/CountingSemaphore.h" #include "fsfw/serviceinterface/ServiceInterface.h" SemaphoreFactory* SemaphoreFactory::factoryInstance = nullptr; @@ -11,54 +11,46 @@ SemaphoreFactory* SemaphoreFactory::factoryInstance = nullptr; static const uint32_t USE_REGULAR_SEMAPHORES = 0; static const uint32_t USE_TASK_NOTIFICATIONS = 1; -SemaphoreFactory::SemaphoreFactory() { -} +SemaphoreFactory::SemaphoreFactory() {} -SemaphoreFactory::~SemaphoreFactory() { - delete factoryInstance; -} +SemaphoreFactory::~SemaphoreFactory() { delete factoryInstance; } SemaphoreFactory* SemaphoreFactory::instance() { - if (factoryInstance == nullptr){ - factoryInstance = new SemaphoreFactory(); - } - return SemaphoreFactory::factoryInstance; + if (factoryInstance == nullptr) { + factoryInstance = new SemaphoreFactory(); + } + return SemaphoreFactory::factoryInstance; } SemaphoreIF* SemaphoreFactory::createBinarySemaphore(uint32_t argument) { - if(argument == USE_REGULAR_SEMAPHORES) { - return new BinarySemaphore(); - } - else if(argument == USE_TASK_NOTIFICATIONS) { - return new BinarySemaphoreUsingTask(); - } - else { + if (argument == USE_REGULAR_SEMAPHORES) { + return new BinarySemaphore(); + } else if (argument == USE_TASK_NOTIFICATIONS) { + return new BinarySemaphoreUsingTask(); + } else { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "SemaphoreFactory: Invalid argument, return regular" - "binary semaphore" << std::endl; + sif::warning << "SemaphoreFactory: Invalid argument, return regular" + "binary semaphore" + << std::endl; #endif - return new BinarySemaphore(); - } + return new BinarySemaphore(); + } } -SemaphoreIF* SemaphoreFactory::createCountingSemaphore(uint8_t maxCount, - uint8_t initCount, uint32_t argument) { - if(argument == USE_REGULAR_SEMAPHORES) { - return new CountingSemaphore(maxCount, initCount); - } - else if(argument == USE_TASK_NOTIFICATIONS) { - return new CountingSemaphoreUsingTask(maxCount, initCount); - } - else { +SemaphoreIF* SemaphoreFactory::createCountingSemaphore(uint8_t maxCount, uint8_t initCount, + uint32_t argument) { + if (argument == USE_REGULAR_SEMAPHORES) { + return new CountingSemaphore(maxCount, initCount); + } else if (argument == USE_TASK_NOTIFICATIONS) { + return new CountingSemaphoreUsingTask(maxCount, initCount); + } else { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "SemaphoreFactory: Invalid argument, return regular" - "binary semaphore" << std::endl; + sif::warning << "SemaphoreFactory: Invalid argument, return regular" + "binary semaphore" + << std::endl; #endif - return new CountingSemaphore(maxCount, initCount); - } - + return new CountingSemaphore(maxCount, initCount); + } } -void SemaphoreFactory::deleteSemaphore(SemaphoreIF* semaphore) { - delete semaphore; -} +void SemaphoreFactory::deleteSemaphore(SemaphoreIF* semaphore) { delete semaphore; } diff --git a/src/fsfw/osal/freertos/TaskFactory.cpp b/src/fsfw/osal/freertos/TaskFactory.cpp index 21ca80cb..7acd812f 100644 --- a/src/fsfw/osal/freertos/TaskFactory.cpp +++ b/src/fsfw/osal/freertos/TaskFactory.cpp @@ -1,58 +1,51 @@ #include "fsfw/tasks/TaskFactory.h" -#include "fsfw/osal/freertos/PeriodicTask.h" -#include "fsfw/osal/freertos/FixedTimeslotTask.h" +#include "fsfw/osal/freertos/FixedTimeslotTask.h" +#include "fsfw/osal/freertos/PeriodicTask.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" TaskFactory* TaskFactory::factoryInstance = new TaskFactory(); -TaskFactory::~TaskFactory() { -} +TaskFactory::~TaskFactory() {} -TaskFactory* TaskFactory::instance() { - return TaskFactory::factoryInstance; -} +TaskFactory* TaskFactory::instance() { return TaskFactory::factoryInstance; } -PeriodicTaskIF* TaskFactory::createPeriodicTask(TaskName name_, - TaskPriority taskPriority_, TaskStackSize stackSize_, - TaskPeriod period_, - TaskDeadlineMissedFunction deadLineMissedFunction_) { - return dynamic_cast(new PeriodicTask(name_, taskPriority_, - stackSize_, period_, deadLineMissedFunction_)); +PeriodicTaskIF* TaskFactory::createPeriodicTask( + TaskName name_, TaskPriority taskPriority_, TaskStackSize stackSize_, TaskPeriod period_, + TaskDeadlineMissedFunction deadLineMissedFunction_) { + return dynamic_cast( + new PeriodicTask(name_, taskPriority_, stackSize_, period_, deadLineMissedFunction_)); } /** * Keep in Mind that you need to call before this vTaskStartScheduler()! */ -FixedTimeslotTaskIF* TaskFactory::createFixedTimeslotTask(TaskName name_, - TaskPriority taskPriority_, TaskStackSize stackSize_, - TaskPeriod period_, - TaskDeadlineMissedFunction deadLineMissedFunction_) { - return dynamic_cast(new FixedTimeslotTask(name_, - taskPriority_,stackSize_, period_, deadLineMissedFunction_)); +FixedTimeslotTaskIF* TaskFactory::createFixedTimeslotTask( + TaskName name_, TaskPriority taskPriority_, TaskStackSize stackSize_, TaskPeriod period_, + TaskDeadlineMissedFunction deadLineMissedFunction_) { + return dynamic_cast( + new FixedTimeslotTask(name_, taskPriority_, stackSize_, period_, deadLineMissedFunction_)); } ReturnValue_t TaskFactory::deleteTask(PeriodicTaskIF* task) { - if (task == nullptr) { - //delete self - vTaskDelete(nullptr); - return HasReturnvaluesIF::RETURN_OK; - } else { - //TODO not implemented - return HasReturnvaluesIF::RETURN_FAILED; - } + if (task == nullptr) { + // delete self + vTaskDelete(nullptr); + return HasReturnvaluesIF::RETURN_OK; + } else { + // TODO not implemented + return HasReturnvaluesIF::RETURN_FAILED; + } } ReturnValue_t TaskFactory::delayTask(uint32_t delayMs) { - vTaskDelay(pdMS_TO_TICKS(delayMs)); - return HasReturnvaluesIF::RETURN_OK; + vTaskDelay(pdMS_TO_TICKS(delayMs)); + return HasReturnvaluesIF::RETURN_OK; } void TaskFactory::printMissedDeadline() { - /* TODO: Implement */ - return; + /* TODO: Implement */ + return; } - -TaskFactory::TaskFactory() { -} +TaskFactory::TaskFactory() {} diff --git a/src/fsfw/osal/freertos/TaskManagement.cpp b/src/fsfw/osal/freertos/TaskManagement.cpp index f19aa4fd..1879976c 100644 --- a/src/fsfw/osal/freertos/TaskManagement.cpp +++ b/src/fsfw/osal/freertos/TaskManagement.cpp @@ -1,25 +1,18 @@ #include "fsfw/osal/freertos/TaskManagement.h" -void TaskManagement::vRequestContextSwitchFromTask() { - vTaskDelay(0); +void TaskManagement::vRequestContextSwitchFromTask() { vTaskDelay(0); } + +void TaskManagement::requestContextSwitch(CallContext callContext = CallContext::TASK) { + if (callContext == CallContext::ISR) { + // This function depends on the partmacro.h definition for the specific device + vRequestContextSwitchFromISR(); + } else { + vRequestContextSwitchFromTask(); + } } -void TaskManagement::requestContextSwitch( - CallContext callContext = CallContext::TASK) { - if(callContext == CallContext::ISR) { - // This function depends on the partmacro.h definition for the specific device - vRequestContextSwitchFromISR(); - } else { - vRequestContextSwitchFromTask(); - } -} +TaskHandle_t TaskManagement::getCurrentTaskHandle() { return xTaskGetCurrentTaskHandle(); } -TaskHandle_t TaskManagement::getCurrentTaskHandle() { - return xTaskGetCurrentTaskHandle(); +size_t TaskManagement::getTaskStackHighWatermark(TaskHandle_t task) { + return uxTaskGetStackHighWaterMark(task) * sizeof(StackType_t); } - -size_t TaskManagement::getTaskStackHighWatermark( - TaskHandle_t task) { - return uxTaskGetStackHighWaterMark(task) * sizeof(StackType_t); -} - diff --git a/src/fsfw/osal/freertos/TaskManagement.h b/src/fsfw/osal/freertos/TaskManagement.h index 9aa10797..825d8865 100644 --- a/src/fsfw/osal/freertos/TaskManagement.h +++ b/src/fsfw/osal/freertos/TaskManagement.h @@ -1,13 +1,12 @@ #ifndef FSFW_OSAL_FREERTOS_TASKMANAGEMENT_H_ #define FSFW_OSAL_FREERTOS_TASKMANAGEMENT_H_ -#include "../../returnvalues/HasReturnvaluesIF.h" +#include +#include "../../returnvalues/HasReturnvaluesIF.h" #include "FreeRTOS.h" #include "task.h" -#include - /** * Architecture dependant portmacro.h function call. * Should be implemented in bsp. @@ -21,11 +20,10 @@ extern "C" void vRequestContextSwitchFromISR(); * an ISR and task. */ enum class CallContext { - TASK = 0x00,//!< task_context - ISR = 0xFF //!< isr_context + TASK = 0x00, //!< task_context + ISR = 0xFF //!< isr_context }; - namespace TaskManagement { /** * @brief In this function, a function dependant on the portmacro.h header @@ -57,6 +55,6 @@ TaskHandle_t getCurrentTaskHandle(); */ size_t getTaskStackHighWatermark(TaskHandle_t task = nullptr); -}; +}; // namespace TaskManagement #endif /* FRAMEWORK_OSAL_FREERTOS_TASKMANAGEMENT_H_ */ diff --git a/src/fsfw/osal/freertos/Timekeeper.cpp b/src/fsfw/osal/freertos/Timekeeper.cpp index 1b7dc741..6649e099 100644 --- a/src/fsfw/osal/freertos/Timekeeper.cpp +++ b/src/fsfw/osal/freertos/Timekeeper.cpp @@ -2,40 +2,34 @@ #include "FreeRTOSConfig.h" -Timekeeper * Timekeeper::myinstance = nullptr; +Timekeeper* Timekeeper::myinstance = nullptr; -Timekeeper::Timekeeper() : offset( { 0, 0 } ) {} +Timekeeper::Timekeeper() : offset({0, 0}) {} Timekeeper::~Timekeeper() {} -const timeval& Timekeeper::getOffset() const { - return offset; -} +const timeval& Timekeeper::getOffset() const { return offset; } Timekeeper* Timekeeper::instance() { - if (myinstance == nullptr) { - myinstance = new Timekeeper(); - } - return myinstance; + if (myinstance == nullptr) { + myinstance = new Timekeeper(); + } + return myinstance; } -void Timekeeper::setOffset(const timeval& offset) { - this->offset = offset; -} +void Timekeeper::setOffset(const timeval& offset) { this->offset = offset; } timeval Timekeeper::ticksToTimeval(TickType_t ticks) { - timeval uptime; - uptime.tv_sec = ticks / configTICK_RATE_HZ; + timeval uptime; + uptime.tv_sec = ticks / configTICK_RATE_HZ; - //TODO explain, think about overflow - uint32_t subsecondTicks = ticks % configTICK_RATE_HZ; - uint64_t usecondTicks = subsecondTicks * 1000000; + // TODO explain, think about overflow + uint32_t subsecondTicks = ticks % configTICK_RATE_HZ; + uint64_t usecondTicks = subsecondTicks * 1000000; - uptime.tv_usec = usecondTicks / configTICK_RATE_HZ; + uptime.tv_usec = usecondTicks / configTICK_RATE_HZ; - return uptime; + return uptime; } -TickType_t Timekeeper::getTicks() { - return xTaskGetTickCount(); -} +TickType_t Timekeeper::getTicks() { return xTaskGetTickCount(); } diff --git a/src/fsfw/osal/freertos/Timekeeper.h b/src/fsfw/osal/freertos/Timekeeper.h index d4d0bc07..9068b902 100644 --- a/src/fsfw/osal/freertos/Timekeeper.h +++ b/src/fsfw/osal/freertos/Timekeeper.h @@ -2,11 +2,9 @@ #define FRAMEWORK_OSAL_FREERTOS_TIMEKEEPER_H_ #include "../../timemanager/Clock.h" - #include "FreeRTOS.h" #include "task.h" - /** * A Class to basically store the time difference between uptime and UTC * so the "time-agnostic" FreeRTOS can keep an UTC Time @@ -16,25 +14,26 @@ */ class Timekeeper { -private: - Timekeeper(); + private: + Timekeeper(); - timeval offset; + timeval offset; - static Timekeeper * myinstance; -public: - static Timekeeper * instance(); - virtual ~Timekeeper(); + static Timekeeper* myinstance; - static timeval ticksToTimeval(TickType_t ticks); - /** - * Get elapsed time in system ticks. - * @return - */ - static TickType_t getTicks(); + public: + static Timekeeper* instance(); + virtual ~Timekeeper(); - const timeval& getOffset() const; - void setOffset(const timeval& offset); + static timeval ticksToTimeval(TickType_t ticks); + /** + * Get elapsed time in system ticks. + * @return + */ + static TickType_t getTicks(); + + const timeval& getOffset() const; + void setOffset(const timeval& offset); }; #endif /* FRAMEWORK_OSAL_FREERTOS_TIMEKEEPER_H_ */ diff --git a/src/fsfw/osal/host/Clock.cpp b/src/fsfw/osal/host/Clock.cpp index 0bdcd8f5..62f9d9d5 100644 --- a/src/fsfw/osal/host/Clock.cpp +++ b/src/fsfw/osal/host/Clock.cpp @@ -1,9 +1,10 @@ -#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/timemanager/Clock.h" -#include "fsfw/platform.h" #include +#include "fsfw/platform.h" +#include "fsfw/serviceinterface/ServiceInterface.h" + #if defined(PLATFORM_WIN) #include #elif defined(PLATFORM_UNIX) @@ -15,159 +16,154 @@ MutexIF* Clock::timeMutex = NULL; using SystemClock = std::chrono::system_clock; -uint32_t Clock::getTicksPerSecond(void){ +uint32_t Clock::getTicksPerSecond(void) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "Clock::getTicksPerSecond: Not implemented for host OSAL" << std::endl; + sif::warning << "Clock::getTicksPerSecond: Not implemented for host OSAL" << std::endl; #else - sif::printWarning("Clock::getTicksPerSecond: Not implemented for host OSAL\n"); + sif::printWarning("Clock::getTicksPerSecond: Not implemented for host OSAL\n"); #endif - /* To avoid division by zero */ - return 1; + /* To avoid division by zero */ + return 1; } ReturnValue_t Clock::setClock(const TimeOfDay_t* time) { - /* I don't know why someone would need to set a clock which is probably perfectly fine on a - host system with internet access so this is not implemented for now. */ + /* I don't know why someone would need to set a clock which is probably perfectly fine on a + host system with internet access so this is not implemented for now. */ #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "Clock::setClock: Not implemented for host OSAL" << std::endl; + sif::warning << "Clock::setClock: Not implemented for host OSAL" << std::endl; #else - sif::printWarning("Clock::setClock: Not implemented for host OSAL\n"); + sif::printWarning("Clock::setClock: Not implemented for host OSAL\n"); #endif - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t Clock::setClock(const timeval* time) { - /* I don't know why someone would need to set a clock which is probably perfectly fine on a - host system with internet access so this is not implemented for now. */ + /* I don't know why someone would need to set a clock which is probably perfectly fine on a + host system with internet access so this is not implemented for now. */ #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "Clock::setClock: Not implemented for host OSAL" << std::endl; + sif::warning << "Clock::setClock: Not implemented for host OSAL" << std::endl; #else - sif::printWarning("Clock::setClock: Not implemented for host OSAL\n"); + sif::printWarning("Clock::setClock: Not implemented for host OSAL\n"); #endif - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t Clock::getClock_timeval(timeval* time) { #if defined(PLATFORM_WIN) - auto now = std::chrono::system_clock::now(); - auto secondsChrono = std::chrono::time_point_cast(now); - auto epoch = now.time_since_epoch(); - time->tv_sec = std::chrono::duration_cast(epoch).count(); - auto fraction = now - secondsChrono; - time->tv_usec = std::chrono::duration_cast(fraction).count(); - return HasReturnvaluesIF::RETURN_OK; + auto now = std::chrono::system_clock::now(); + auto secondsChrono = std::chrono::time_point_cast(now); + auto epoch = now.time_since_epoch(); + time->tv_sec = std::chrono::duration_cast(epoch).count(); + auto fraction = now - secondsChrono; + time->tv_usec = std::chrono::duration_cast(fraction).count(); + return HasReturnvaluesIF::RETURN_OK; #elif defined(PLATFORM_UNIX) - timespec timeUnix; - int status = clock_gettime(CLOCK_REALTIME,&timeUnix); - if(status!=0){ - return HasReturnvaluesIF::RETURN_FAILED; - } - time->tv_sec = timeUnix.tv_sec; - time->tv_usec = timeUnix.tv_nsec / 1000.0; - return HasReturnvaluesIF::RETURN_OK; + timespec timeUnix; + int status = clock_gettime(CLOCK_REALTIME, &timeUnix); + if (status != 0) { + return HasReturnvaluesIF::RETURN_FAILED; + } + time->tv_sec = timeUnix.tv_sec; + time->tv_usec = timeUnix.tv_nsec / 1000.0; + return HasReturnvaluesIF::RETURN_OK; #else #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "Clock::getUptime: Not implemented for found OS!" << std::endl; + sif::warning << "Clock::getUptime: Not implemented for found OS!" << std::endl; #else - sif::printWarning("Clock::getUptime: Not implemented for found OS!\n"); + sif::printWarning("Clock::getUptime: Not implemented for found OS!\n"); #endif - return HasReturnvaluesIF::RETURN_FAILED; + return HasReturnvaluesIF::RETURN_FAILED; #endif - } ReturnValue_t Clock::getClock_usecs(uint64_t* time) { - if(time == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - using namespace std::chrono; - *time = duration_cast(system_clock::now().time_since_epoch()).count(); - return HasReturnvaluesIF::RETURN_OK; + if (time == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + using namespace std::chrono; + *time = duration_cast(system_clock::now().time_since_epoch()).count(); + return HasReturnvaluesIF::RETURN_OK; } timeval Clock::getUptime() { - timeval timeval; + timeval timeval; #if defined(PLATFORM_WIN) - auto uptime = std::chrono::milliseconds(GetTickCount64()); - auto secondsChrono = std::chrono::duration_cast(uptime); - timeval.tv_sec = secondsChrono.count(); - auto fraction = uptime - secondsChrono; - timeval.tv_usec = std::chrono::duration_cast( - fraction).count(); + auto uptime = std::chrono::milliseconds(GetTickCount64()); + auto secondsChrono = std::chrono::duration_cast(uptime); + timeval.tv_sec = secondsChrono.count(); + auto fraction = uptime - secondsChrono; + timeval.tv_usec = std::chrono::duration_cast(fraction).count(); #elif defined(PLATFORM_UNIX) - double uptimeSeconds; - if (std::ifstream("/proc/uptime", std::ios::in) >> uptimeSeconds) - { - // value is rounded down automatically - timeval.tv_sec = uptimeSeconds; - timeval.tv_usec = uptimeSeconds *(double) 1e6 - (timeval.tv_sec *1e6); - } + double uptimeSeconds; + if (std::ifstream("/proc/uptime", std::ios::in) >> uptimeSeconds) { + // value is rounded down automatically + timeval.tv_sec = uptimeSeconds; + timeval.tv_usec = uptimeSeconds * (double)1e6 - (timeval.tv_sec * 1e6); + } #else #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "Clock::getUptime: Not implemented for found OS" << std::endl; + sif::warning << "Clock::getUptime: Not implemented for found OS" << std::endl; #endif #endif - return timeval; + return timeval; } ReturnValue_t Clock::getUptime(timeval* uptime) { - *uptime = getUptime(); - return HasReturnvaluesIF::RETURN_OK; + *uptime = getUptime(); + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t Clock::getUptime(uint32_t* uptimeMs) { - timeval uptime = getUptime(); - *uptimeMs = uptime.tv_sec * 1000 + uptime.tv_usec / 1000; - return HasReturnvaluesIF::RETURN_OK; + timeval uptime = getUptime(); + *uptimeMs = uptime.tv_sec * 1000 + uptime.tv_usec / 1000; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t Clock::getDateAndTime(TimeOfDay_t* time) { - /* Do some magic with chrono (C++20!) */ - /* Right now, the library doesn't have the new features to get the required values yet. - so we work around that for now. */ - auto now = SystemClock::now(); - auto seconds = std::chrono::time_point_cast(now); - auto fraction = now - seconds; - time_t tt = SystemClock::to_time_t(now); - struct tm* timeInfo; - timeInfo = gmtime(&tt); - time->year = timeInfo->tm_year + 1900; - time->month = timeInfo->tm_mon+1; - time->day = timeInfo->tm_mday; - time->hour = timeInfo->tm_hour; - time->minute = timeInfo->tm_min; - time->second = timeInfo->tm_sec; - auto usecond = std::chrono::duration_cast(fraction); - time->usecond = usecond.count(); - return HasReturnvaluesIF::RETURN_OK; + /* Do some magic with chrono (C++20!) */ + /* Right now, the library doesn't have the new features to get the required values yet. + so we work around that for now. */ + auto now = SystemClock::now(); + auto seconds = std::chrono::time_point_cast(now); + auto fraction = now - seconds; + time_t tt = SystemClock::to_time_t(now); + struct tm* timeInfo; + timeInfo = gmtime(&tt); + time->year = timeInfo->tm_year + 1900; + time->month = timeInfo->tm_mon + 1; + time->day = timeInfo->tm_mday; + time->hour = timeInfo->tm_hour; + time->minute = timeInfo->tm_min; + time->second = timeInfo->tm_sec; + auto usecond = std::chrono::duration_cast(fraction); + time->usecond = usecond.count(); + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t Clock::convertTimeOfDayToTimeval(const TimeOfDay_t* from, - timeval* to) { - struct tm time_tm; +ReturnValue_t Clock::convertTimeOfDayToTimeval(const TimeOfDay_t* from, timeval* to) { + struct tm time_tm; - time_tm.tm_year = from->year - 1900; - time_tm.tm_mon = from->month - 1; - time_tm.tm_mday = from->day; + time_tm.tm_year = from->year - 1900; + time_tm.tm_mon = from->month - 1; + time_tm.tm_mday = from->day; - time_tm.tm_hour = from->hour; - time_tm.tm_min = from->minute; - time_tm.tm_sec = from->second; + time_tm.tm_hour = from->hour; + time_tm.tm_min = from->minute; + time_tm.tm_sec = from->second; - time_t seconds = mktime(&time_tm); + time_t seconds = mktime(&time_tm); - to->tv_sec = seconds; - to->tv_usec = from->usecond; - //Fails in 2038.. - return HasReturnvaluesIF::RETURN_OK; + to->tv_sec = seconds; + to->tv_usec = from->usecond; + // Fails in 2038.. + return HasReturnvaluesIF::RETURN_OK; #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "Clock::convertTimeBla: not implemented yet" << std::endl; + sif::warning << "Clock::convertTimeBla: not implemented yet" << std::endl; #endif - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t Clock::convertTimevalToJD2000(timeval time, double* JD2000) { - *JD2000 = (time.tv_sec - 946728000. + time.tv_usec / 1000000.) / 24. - / 3600.; - return HasReturnvaluesIF::RETURN_OK; + *JD2000 = (time.tv_sec - 946728000. + time.tv_usec / 1000000.) / 24. / 3600.; + return HasReturnvaluesIF::RETURN_OK; } diff --git a/src/fsfw/osal/host/FixedTimeslotTask.cpp b/src/fsfw/osal/host/FixedTimeslotTask.cpp index f9a0588c..07853938 100644 --- a/src/fsfw/osal/host/FixedTimeslotTask.cpp +++ b/src/fsfw/osal/host/FixedTimeslotTask.cpp @@ -1,189 +1,178 @@ -#include "fsfw/osal/host/taskHelpers.h" -#include "fsfw/osal/host/FixedTimeslotTask.h" #include "fsfw/osal/host/FixedTimeslotTask.h" -#include "fsfw/platform.h" +#include +#include + #include "fsfw/ipc/MutexFactory.h" -#include "fsfw/osal/host/Mutex.h" #include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/osal/host/FixedTimeslotTask.h" +#include "fsfw/osal/host/Mutex.h" +#include "fsfw/osal/host/taskHelpers.h" +#include "fsfw/platform.h" #include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/tasks/ExecutableObjectIF.h" -#include -#include - #if defined(PLATFORM_WIN) #include + #include "fsfw/osal/windows/winTaskHelpers.h" #elif defined(PLATFORM_UNIX) #include #endif -FixedTimeslotTask::FixedTimeslotTask(const char *name, TaskPriority setPriority, - TaskStackSize setStack, TaskPeriod setPeriod, - void (*setDeadlineMissedFunc)()) : - started(false), pollingSeqTable(setPeriod*1000), taskName(name), - period(setPeriod), deadlineMissedFunc(setDeadlineMissedFunc) { - // It is propably possible to set task priorities by using the native - // task handles for Windows / Linux - mainThread = std::thread(&FixedTimeslotTask::taskEntryPoint, this, this); +FixedTimeslotTask::FixedTimeslotTask(const char* name, TaskPriority setPriority, + TaskStackSize setStack, TaskPeriod setPeriod, + void (*setDeadlineMissedFunc)()) + : started(false), + pollingSeqTable(setPeriod * 1000), + taskName(name), + period(setPeriod), + deadlineMissedFunc(setDeadlineMissedFunc) { + // It is propably possible to set task priorities by using the native + // task handles for Windows / Linux + mainThread = std::thread(&FixedTimeslotTask::taskEntryPoint, this, this); #if defined(_WIN32) - tasks::setTaskPriority(reinterpret_cast(mainThread.native_handle()), setPriority); + tasks::setTaskPriority(reinterpret_cast(mainThread.native_handle()), setPriority); #elif defined(__unix__) - // TODO: We could reuse existing code here. + // TODO: We could reuse existing code here. #endif - tasks::insertTaskName(mainThread.get_id(), taskName); + tasks::insertTaskName(mainThread.get_id(), taskName); } FixedTimeslotTask::~FixedTimeslotTask(void) { - //Do not delete objects, we were responsible for ptrs only. - terminateThread = true; - if(mainThread.joinable()) { - mainThread.join(); - } + // Do not delete objects, we were responsible for ptrs only. + terminateThread = true; + if (mainThread.joinable()) { + mainThread.join(); + } } void FixedTimeslotTask::taskEntryPoint(void* argument) { - FixedTimeslotTask *originalTask(reinterpret_cast(argument)); + FixedTimeslotTask* originalTask(reinterpret_cast(argument)); - if (not originalTask->started) { - // we have to suspend/block here until the task is started. - // if semaphores are implemented, use them here. - std::unique_lock lock(initMutex); - initCondition.wait(lock); - } + if (not originalTask->started) { + // we have to suspend/block here until the task is started. + // if semaphores are implemented, use them here. + std::unique_lock lock(initMutex); + initCondition.wait(lock); + } - this->taskFunctionality(); + this->taskFunctionality(); #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "FixedTimeslotTask::taskEntryPoint: " - "Returned from taskFunctionality." << std::endl; + sif::debug << "FixedTimeslotTask::taskEntryPoint: " + "Returned from taskFunctionality." + << std::endl; #endif } ReturnValue_t FixedTimeslotTask::startTask() { - started = true; + started = true; - // Notify task to start. - std::lock_guard lock(initMutex); - initCondition.notify_one(); + // Notify task to start. + std::lock_guard lock(initMutex); + initCondition.notify_one(); - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t FixedTimeslotTask::sleepFor(uint32_t ms) { - std::this_thread::sleep_for(std::chrono::milliseconds(ms)); - return HasReturnvaluesIF::RETURN_OK; + std::this_thread::sleep_for(std::chrono::milliseconds(ms)); + return HasReturnvaluesIF::RETURN_OK; } void FixedTimeslotTask::taskFunctionality() { - pollingSeqTable.intializeSequenceAfterTaskCreation(); + pollingSeqTable.intializeSequenceAfterTaskCreation(); - // A local iterator for the Polling Sequence Table is created to - // find the start time for the first entry. - auto slotListIter = pollingSeqTable.current; + // A local iterator for the Polling Sequence Table is created to + // find the start time for the first entry. + auto slotListIter = pollingSeqTable.current; - // Get start time for first entry. - chron_ms interval(slotListIter->pollingTimeMs); - auto currentStartTime { - std::chrono::duration_cast( - std::chrono::system_clock::now().time_since_epoch()) - }; - if(interval.count() > 0) { - delayForInterval(¤tStartTime, interval); + // Get start time for first entry. + chron_ms interval(slotListIter->pollingTimeMs); + auto currentStartTime{ + std::chrono::duration_cast(std::chrono::system_clock::now().time_since_epoch())}; + if (interval.count() > 0) { + delayForInterval(¤tStartTime, interval); + } + + /* Enter the loop that defines the task behavior. */ + for (;;) { + if (terminateThread.load()) { + break; } - - /* Enter the loop that defines the task behavior. */ - for (;;) { - if(terminateThread.load()) { - break; - } - //The component for this slot is executed and the next one is chosen. - this->pollingSeqTable.executeAndAdvance(); - if (not pollingSeqTable.slotFollowsImmediately()) { - // we need to wait before executing the current slot - // this gives us the time to wait: - interval = chron_ms( - this->pollingSeqTable.getIntervalToPreviousSlotMs()); - delayForInterval(¤tStartTime, interval); - //TODO deadline missed check - } + // The component for this slot is executed and the next one is chosen. + this->pollingSeqTable.executeAndAdvance(); + if (not pollingSeqTable.slotFollowsImmediately()) { + // we need to wait before executing the current slot + // this gives us the time to wait: + interval = chron_ms(this->pollingSeqTable.getIntervalToPreviousSlotMs()); + delayForInterval(¤tStartTime, interval); + // TODO deadline missed check } + } } -ReturnValue_t FixedTimeslotTask::addSlot(object_id_t componentId, - uint32_t slotTimeMs, int8_t executionStep) { - ExecutableObjectIF* executableObject = ObjectManager::instance()-> - get(componentId); - if (executableObject != nullptr) { - pollingSeqTable.addSlot(componentId, slotTimeMs, executionStep, - executableObject, this); - return HasReturnvaluesIF::RETURN_OK; - } +ReturnValue_t FixedTimeslotTask::addSlot(object_id_t componentId, uint32_t slotTimeMs, + int8_t executionStep) { + ExecutableObjectIF* executableObject = + ObjectManager::instance()->get(componentId); + if (executableObject != nullptr) { + pollingSeqTable.addSlot(componentId, slotTimeMs, executionStep, executableObject, this); + return HasReturnvaluesIF::RETURN_OK; + } #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Component " << std::hex << "0x" << componentId << "not found, " - "not adding it to PST.." << std::dec << std::endl; + sif::error << "Component " << std::hex << "0x" << componentId + << "not found, " + "not adding it to PST.." + << std::dec << std::endl; #else - sif::printError("Component 0x%08x not found, not adding it to PST..\n", - static_cast(componentId)); + sif::printError("Component 0x%08x not found, not adding it to PST..\n", + static_cast(componentId)); #endif - return HasReturnvaluesIF::RETURN_FAILED; + return HasReturnvaluesIF::RETURN_FAILED; } -ReturnValue_t FixedTimeslotTask::checkSequence() const { - return pollingSeqTable.checkSequence(); -} +ReturnValue_t FixedTimeslotTask::checkSequence() const { return pollingSeqTable.checkSequence(); } -uint32_t FixedTimeslotTask::getPeriodMs() const { - return period * 1000; -} +uint32_t FixedTimeslotTask::getPeriodMs() const { return period * 1000; } -bool FixedTimeslotTask::delayForInterval(chron_ms * previousWakeTimeMs, - const chron_ms interval) { - bool shouldDelay = false; - //Get current wakeup time - auto currentStartTime = - std::chrono::duration_cast( - std::chrono::system_clock::now().time_since_epoch()); - /* Generate the tick time at which the task wants to wake. */ - auto nextTimeToWake_ms = (*previousWakeTimeMs) + interval; +bool FixedTimeslotTask::delayForInterval(chron_ms* previousWakeTimeMs, const chron_ms interval) { + bool shouldDelay = false; + // Get current wakeup time + auto currentStartTime = + std::chrono::duration_cast(std::chrono::system_clock::now().time_since_epoch()); + /* Generate the tick time at which the task wants to wake. */ + auto nextTimeToWake_ms = (*previousWakeTimeMs) + interval; - if (currentStartTime < *previousWakeTimeMs) { - /* The tick count has overflowed since this function was - lasted called. In this case the only time we should ever - actually delay is if the wake time has also overflowed, - and the wake time is greater than the tick time. When this - is the case it is as if neither time had overflowed. */ - if ((nextTimeToWake_ms < *previousWakeTimeMs) - && (nextTimeToWake_ms > currentStartTime)) { - shouldDelay = true; - } - } else { - /* The tick time has not overflowed. In this case we will - delay if either the wake time has overflowed, and/or the - tick time is less than the wake time. */ - if ((nextTimeToWake_ms < *previousWakeTimeMs) - || (nextTimeToWake_ms > currentStartTime)) { - shouldDelay = true; - } + if (currentStartTime < *previousWakeTimeMs) { + /* The tick count has overflowed since this function was + lasted called. In this case the only time we should ever + actually delay is if the wake time has also overflowed, + and the wake time is greater than the tick time. When this + is the case it is as if neither time had overflowed. */ + if ((nextTimeToWake_ms < *previousWakeTimeMs) && (nextTimeToWake_ms > currentStartTime)) { + shouldDelay = true; } - - /* Update the wake time ready for the next call. */ - - (*previousWakeTimeMs) = nextTimeToWake_ms; - - if (shouldDelay) { - auto sleepTime = std::chrono::duration_cast( - nextTimeToWake_ms - currentStartTime); - std::this_thread::sleep_for(sleepTime); - return true; + } else { + /* The tick time has not overflowed. In this case we will + delay if either the wake time has overflowed, and/or the + tick time is less than the wake time. */ + if ((nextTimeToWake_ms < *previousWakeTimeMs) || (nextTimeToWake_ms > currentStartTime)) { + shouldDelay = true; } - //We are shifting the time in case the deadline was missed like rtems - (*previousWakeTimeMs) = currentStartTime; - return false; + } + /* Update the wake time ready for the next call. */ + + (*previousWakeTimeMs) = nextTimeToWake_ms; + + if (shouldDelay) { + auto sleepTime = std::chrono::duration_cast(nextTimeToWake_ms - currentStartTime); + std::this_thread::sleep_for(sleepTime); + return true; + } + // We are shifting the time in case the deadline was missed like rtems + (*previousWakeTimeMs) = currentStartTime; + return false; } - - - - diff --git a/src/fsfw/osal/host/FixedTimeslotTask.h b/src/fsfw/osal/host/FixedTimeslotTask.h index f3fffd0f..cdbc6f23 100644 --- a/src/fsfw/osal/host/FixedTimeslotTask.h +++ b/src/fsfw/osal/host/FixedTimeslotTask.h @@ -1,16 +1,16 @@ #ifndef FRAMEWORK_OSAL_HOST_FIXEDTIMESLOTTASK_H_ #define FRAMEWORK_OSAL_HOST_FIXEDTIMESLOTTASK_H_ +#include +#include +#include +#include + #include "../../objectmanager/ObjectManagerIF.h" #include "../../tasks/FixedSlotSequence.h" #include "../../tasks/FixedTimeslotTaskIF.h" #include "../../tasks/Typedef.h" -#include -#include -#include -#include - class ExecutableObjectIF; /** @@ -19,112 +19,107 @@ class ExecutableObjectIF; * @details * @ingroup task_handling */ -class FixedTimeslotTask: public FixedTimeslotTaskIF { -public: - /** - * @brief Standard constructor of the class. - * @details - * The class is initialized without allocated objects. These need to be - * added with #addComponent. - * @param priority - * @param stack_size - * @param setPeriod - * @param setDeadlineMissedFunc - * The function pointer to the deadline missed function that shall be - * assigned. - */ - FixedTimeslotTask(const char *name, TaskPriority setPriority, - TaskStackSize setStack, TaskPeriod setPeriod, - void (*setDeadlineMissedFunc)()); - /** - * @brief Currently, the executed object's lifetime is not coupled with - * the task object's lifetime, so the destructor is empty. - */ - virtual ~FixedTimeslotTask(void); +class FixedTimeslotTask : public FixedTimeslotTaskIF { + public: + /** + * @brief Standard constructor of the class. + * @details + * The class is initialized without allocated objects. These need to be + * added with #addComponent. + * @param priority + * @param stack_size + * @param setPeriod + * @param setDeadlineMissedFunc + * The function pointer to the deadline missed function that shall be + * assigned. + */ + FixedTimeslotTask(const char* name, TaskPriority setPriority, TaskStackSize setStack, + TaskPeriod setPeriod, void (*setDeadlineMissedFunc)()); + /** + * @brief Currently, the executed object's lifetime is not coupled with + * the task object's lifetime, so the destructor is empty. + */ + virtual ~FixedTimeslotTask(void); - /** - * @brief The method to start the task. - * @details The method starts the task with the respective system call. - * Entry point is the taskEntryPoint method described below. - * The address of the task object is passed as an argument - * to the system call. - */ - ReturnValue_t startTask(void); + /** + * @brief The method to start the task. + * @details The method starts the task with the respective system call. + * Entry point is the taskEntryPoint method described below. + * The address of the task object is passed as an argument + * to the system call. + */ + ReturnValue_t startTask(void); - /** - * Add timeslot to the polling sequence table. - * @param componentId - * @param slotTimeMs - * @param executionStep - * @return - */ - ReturnValue_t addSlot(object_id_t componentId, - uint32_t slotTimeMs, int8_t executionStep); + /** + * Add timeslot to the polling sequence table. + * @param componentId + * @param slotTimeMs + * @param executionStep + * @return + */ + ReturnValue_t addSlot(object_id_t componentId, uint32_t slotTimeMs, int8_t executionStep); - ReturnValue_t checkSequence() const override; + ReturnValue_t checkSequence() const override; - uint32_t getPeriodMs() const; + uint32_t getPeriodMs() const; - ReturnValue_t sleepFor(uint32_t ms); + ReturnValue_t sleepFor(uint32_t ms); -protected: - using chron_ms = std::chrono::milliseconds; + protected: + using chron_ms = std::chrono::milliseconds; - bool started; - //!< Typedef for the List of objects. - typedef std::vector ObjectList; - std::thread mainThread; - std::atomic terminateThread { false }; + bool started; + //!< Typedef for the List of objects. + typedef std::vector ObjectList; + std::thread mainThread; + std::atomic terminateThread{false}; - //! Polling sequence table which contains the object to execute - //! and information like the timeslots and the passed execution step. - FixedSlotSequence pollingSeqTable; + //! Polling sequence table which contains the object to execute + //! and information like the timeslots and the passed execution step. + FixedSlotSequence pollingSeqTable; - std::condition_variable initCondition; - std::mutex initMutex; - std::string taskName; - /** - * @brief The period of the task. - * @details - * The period determines the frequency of the task's execution. - * It is expressed in clock ticks. - */ - TaskPeriod period; + std::condition_variable initCondition; + std::mutex initMutex; + std::string taskName; + /** + * @brief The period of the task. + * @details + * The period determines the frequency of the task's execution. + * It is expressed in clock ticks. + */ + TaskPeriod period; - /** - * @brief The pointer to the deadline-missed function. - * @details - * This pointer stores the function that is executed if the task's deadline - * is missed. So, each may react individually on a timing failure. - * The pointer may be NULL, then nothing happens on missing the deadline. - * The deadline is equal to the next execution of the periodic task. - */ - void (*deadlineMissedFunc)(void); - /** - * @brief This is the function executed in the new task's context. - * @details - * It converts the argument back to the thread object type and copies the - * class instance to the task context. - * The taskFunctionality method is called afterwards. - * @param A pointer to the task object itself is passed as argument. - */ + /** + * @brief The pointer to the deadline-missed function. + * @details + * This pointer stores the function that is executed if the task's deadline + * is missed. So, each may react individually on a timing failure. + * The pointer may be NULL, then nothing happens on missing the deadline. + * The deadline is equal to the next execution of the periodic task. + */ + void (*deadlineMissedFunc)(void); + /** + * @brief This is the function executed in the new task's context. + * @details + * It converts the argument back to the thread object type and copies the + * class instance to the task context. + * The taskFunctionality method is called afterwards. + * @param A pointer to the task object itself is passed as argument. + */ - void taskEntryPoint(void* argument); - /** - * @brief The function containing the actual functionality of the task. - * @details - * The method sets and starts the task's period, then enters a loop that is - * repeated as long as the isRunning attribute is true. Within the loop, - * all performOperation methods of the added objects are called. Afterwards - * the checkAndRestartPeriod system call blocks the task until the next - * period. On missing the deadline, the deadlineMissedFunction is executed. - */ - void taskFunctionality(void); + void taskEntryPoint(void* argument); + /** + * @brief The function containing the actual functionality of the task. + * @details + * The method sets and starts the task's period, then enters a loop that is + * repeated as long as the isRunning attribute is true. Within the loop, + * all performOperation methods of the added objects are called. Afterwards + * the checkAndRestartPeriod system call blocks the task until the next + * period. On missing the deadline, the deadlineMissedFunction is executed. + */ + void taskFunctionality(void); - bool delayForInterval(chron_ms * previousWakeTimeMs, - const chron_ms interval); + bool delayForInterval(chron_ms* previousWakeTimeMs, const chron_ms interval); }; - - #endif /* FRAMEWORK_OSAL_HOST_FIXEDTIMESLOTTASK_H_ */ diff --git a/src/fsfw/osal/host/MessageQueue.cpp b/src/fsfw/osal/host/MessageQueue.cpp index c7bcb042..db66b671 100644 --- a/src/fsfw/osal/host/MessageQueue.cpp +++ b/src/fsfw/osal/host/MessageQueue.cpp @@ -1,153 +1,137 @@ #include "fsfw/osal/host/MessageQueue.h" -#include "fsfw/osal/host/QueueMapManager.h" - -#include "fsfw/serviceinterface/ServiceInterface.h" -#include "fsfw/objectmanager/ObjectManager.h" -#include "fsfw/ipc/MutexFactory.h" -#include "fsfw/ipc/MutexGuard.h" #include -MessageQueue::MessageQueue(size_t messageDepth, size_t maxMessageSize): - messageSize(maxMessageSize), messageDepth(messageDepth) { - queueLock = MutexFactory::instance()->createMutex(); - auto result = QueueMapManager::instance()->addMessageQueue(this, &mqId); - if(result != HasReturnvaluesIF::RETURN_OK) { +#include "fsfw/ipc/MutexFactory.h" +#include "fsfw/ipc/MutexGuard.h" +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/osal/host/QueueMapManager.h" +#include "fsfw/serviceinterface/ServiceInterface.h" + +MessageQueue::MessageQueue(size_t messageDepth, size_t maxMessageSize) + : messageSize(maxMessageSize), messageDepth(messageDepth) { + queueLock = MutexFactory::instance()->createMutex(); + auto result = QueueMapManager::instance()->addMessageQueue(this, &mqId); + if (result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "MessageQueue::MessageQueue: Could not be created" << std::endl; + sif::error << "MessageQueue::MessageQueue: Could not be created" << std::endl; #else - sif::printError("MessageQueue::MessageQueue: Could not be created\n"); + sif::printError("MessageQueue::MessageQueue: Could not be created\n"); #endif - } + } } -MessageQueue::~MessageQueue() { - MutexFactory::instance()->deleteMutex(queueLock); -} +MessageQueue::~MessageQueue() { MutexFactory::instance()->deleteMutex(queueLock); } -ReturnValue_t MessageQueue::sendMessage(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, bool ignoreFault) { - return sendMessageFrom(sendTo, message, this->getId(), ignoreFault); +ReturnValue_t MessageQueue::sendMessage(MessageQueueId_t sendTo, MessageQueueMessageIF* message, + bool ignoreFault) { + return sendMessageFrom(sendTo, message, this->getId(), ignoreFault); } ReturnValue_t MessageQueue::sendToDefault(MessageQueueMessageIF* message) { - return sendToDefaultFrom(message, this->getId()); + return sendToDefaultFrom(message, this->getId()); } ReturnValue_t MessageQueue::sendToDefaultFrom(MessageQueueMessageIF* message, - MessageQueueId_t sentFrom, bool ignoreFault) { - return sendMessageFrom(defaultDestination,message,sentFrom,ignoreFault); + MessageQueueId_t sentFrom, bool ignoreFault) { + return sendMessageFrom(defaultDestination, message, sentFrom, ignoreFault); } ReturnValue_t MessageQueue::reply(MessageQueueMessageIF* message) { - if (this->lastPartner != MessageQueueIF::NO_QUEUE) { - return sendMessageFrom(this->lastPartner, message, this->getId()); - } else { - return MessageQueueIF::NO_REPLY_PARTNER; - } + if (this->lastPartner != MessageQueueIF::NO_QUEUE) { + return sendMessageFrom(this->lastPartner, message, this->getId()); + } else { + return MessageQueueIF::NO_REPLY_PARTNER; + } } -ReturnValue_t MessageQueue::sendMessageFrom(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, MessageQueueId_t sentFrom, - bool ignoreFault) { - return sendMessageFromMessageQueue(sendTo, message, sentFrom, - ignoreFault); +ReturnValue_t MessageQueue::sendMessageFrom(MessageQueueId_t sendTo, MessageQueueMessageIF* message, + MessageQueueId_t sentFrom, bool ignoreFault) { + return sendMessageFromMessageQueue(sendTo, message, sentFrom, ignoreFault); } ReturnValue_t MessageQueue::receiveMessage(MessageQueueMessageIF* message, - MessageQueueId_t* receivedFrom) { - ReturnValue_t status = this->receiveMessage(message); - if(status == HasReturnvaluesIF::RETURN_OK) { - *receivedFrom = this->lastPartner; - } - return status; + MessageQueueId_t* receivedFrom) { + ReturnValue_t status = this->receiveMessage(message); + if (status == HasReturnvaluesIF::RETURN_OK) { + *receivedFrom = this->lastPartner; + } + return status; } ReturnValue_t MessageQueue::receiveMessage(MessageQueueMessageIF* message) { - if(messageQueue.empty()) { - return MessageQueueIF::EMPTY; - } - MutexGuard mutexLock(queueLock, MutexIF::TimeoutType::WAITING, 20); - std::copy(messageQueue.front().data(), messageQueue.front().data() + messageSize, - message->getBuffer()); - messageQueue.pop(); - // The last partner is the first uint32_t field in the message - this->lastPartner = message->getSender(); - return HasReturnvaluesIF::RETURN_OK; + if (messageQueue.empty()) { + return MessageQueueIF::EMPTY; + } + MutexGuard mutexLock(queueLock, MutexIF::TimeoutType::WAITING, 20); + std::copy(messageQueue.front().data(), messageQueue.front().data() + messageSize, + message->getBuffer()); + messageQueue.pop(); + // The last partner is the first uint32_t field in the message + this->lastPartner = message->getSender(); + return HasReturnvaluesIF::RETURN_OK; } -MessageQueueId_t MessageQueue::getLastPartner() const { - return lastPartner; -} +MessageQueueId_t MessageQueue::getLastPartner() const { return lastPartner; } ReturnValue_t MessageQueue::flush(uint32_t* count) { - *count = messageQueue.size(); - // Clears the queue. - messageQueue = std::queue>(); - return HasReturnvaluesIF::RETURN_OK; + *count = messageQueue.size(); + // Clears the queue. + messageQueue = std::queue>(); + return HasReturnvaluesIF::RETURN_OK; } -MessageQueueId_t MessageQueue::getId() const { - return mqId; -} +MessageQueueId_t MessageQueue::getId() const { return mqId; } void MessageQueue::setDefaultDestination(MessageQueueId_t defaultDestination) { - defaultDestinationSet = true; - this->defaultDestination = defaultDestination; + defaultDestinationSet = true; + this->defaultDestination = defaultDestination; } -MessageQueueId_t MessageQueue::getDefaultDestination() const { - return defaultDestination; -} - -bool MessageQueue::isDefaultDestinationSet() const { - return defaultDestinationSet; -} +MessageQueueId_t MessageQueue::getDefaultDestination() const { return defaultDestination; } +bool MessageQueue::isDefaultDestinationSet() const { return defaultDestinationSet; } // static core function to send messages. ReturnValue_t MessageQueue::sendMessageFromMessageQueue(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, MessageQueueId_t sentFrom, - bool ignoreFault) { - if(message == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; + MessageQueueMessageIF* message, + MessageQueueId_t sentFrom, + bool ignoreFault) { + if (message == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + message->setSender(sentFrom); + if (message->getMessageSize() > message->getMaximumMessageSize()) { + // Actually, this should never happen or an error will be emitted + // in MessageQueueMessage. + // But I will still return a failure here. + return HasReturnvaluesIF::RETURN_FAILED; + } + MessageQueue* targetQueue = + dynamic_cast(QueueMapManager::instance()->getMessageQueue(sendTo)); + if (targetQueue == nullptr) { + if (not ignoreFault) { + InternalErrorReporterIF* internalErrorReporter = + ObjectManager::instance()->get(objects::INTERNAL_ERROR_REPORTER); + if (internalErrorReporter != nullptr) { + internalErrorReporter->queueMessageNotSent(); + } } - message->setSender(sentFrom); - if(message->getMessageSize() > message->getMaximumMessageSize()) { - // Actually, this should never happen or an error will be emitted - // in MessageQueueMessage. - // But I will still return a failure here. - return HasReturnvaluesIF::RETURN_FAILED; - } - MessageQueue* targetQueue = dynamic_cast( - QueueMapManager::instance()->getMessageQueue(sendTo)); - if(targetQueue == nullptr) { - if(not ignoreFault) { - InternalErrorReporterIF* internalErrorReporter = ObjectManager::instance()-> - get(objects::INTERNAL_ERROR_REPORTER); - if (internalErrorReporter != nullptr) { - internalErrorReporter->queueMessageNotSent(); - } - } - return MessageQueueIF::DESTINATION_INVALID; - } - if(targetQueue->messageQueue.size() < targetQueue->messageDepth) { - MutexGuard mutexLock(targetQueue->queueLock, MutexIF::TimeoutType::WAITING, 20); - targetQueue->messageQueue.push(std::vector(message->getMaximumMessageSize())); - memcpy(targetQueue->messageQueue.back().data(), message->getBuffer(), - message->getMaximumMessageSize()); - } - else { - return MessageQueueIF::FULL; - } - return HasReturnvaluesIF::RETURN_OK; + return MessageQueueIF::DESTINATION_INVALID; + } + if (targetQueue->messageQueue.size() < targetQueue->messageDepth) { + MutexGuard mutexLock(targetQueue->queueLock, MutexIF::TimeoutType::WAITING, 20); + targetQueue->messageQueue.push(std::vector(message->getMaximumMessageSize())); + memcpy(targetQueue->messageQueue.back().data(), message->getBuffer(), + message->getMaximumMessageSize()); + } else { + return MessageQueueIF::FULL; + } + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t MessageQueue::lockQueue(MutexIF::TimeoutType timeoutType, - dur_millis_t lockTimeout) { - return queueLock->lockMutex(timeoutType, lockTimeout); +ReturnValue_t MessageQueue::lockQueue(MutexIF::TimeoutType timeoutType, dur_millis_t lockTimeout) { + return queueLock->lockMutex(timeoutType, lockTimeout); } -ReturnValue_t MessageQueue::unlockQueue() { - return queueLock->unlockMutex(); -} +ReturnValue_t MessageQueue::unlockQueue() { return queueLock->unlockMutex(); } diff --git a/src/fsfw/osal/host/MessageQueue.h b/src/fsfw/osal/host/MessageQueue.h index 0bdfd8fc..49375bb5 100644 --- a/src/fsfw/osal/host/MessageQueue.h +++ b/src/fsfw/osal/host/MessageQueue.h @@ -1,15 +1,15 @@ #ifndef FRAMEWORK_OSAL_HOST_MESSAGEQUEUE_H_ #define FRAMEWORK_OSAL_HOST_MESSAGEQUEUE_H_ +#include +#include + #include "fsfw/internalerror/InternalErrorReporterIF.h" #include "fsfw/ipc/MessageQueueIF.h" #include "fsfw/ipc/MessageQueueMessage.h" #include "fsfw/ipc/MutexIF.h" #include "fsfw/timemanager/Clock.h" -#include -#include - /** * @brief This class manages sending and receiving of * message queue messages. @@ -34,198 +34,200 @@ * @ingroup message_queue */ class MessageQueue : public MessageQueueIF { - friend class MessageQueueSenderIF; -public: - /** - * @brief The constructor initializes and configures the message queue. - * @details - * By making use of the according operating system call, a message queue is - * created and initialized. The message depth - the maximum number of - * messages to be buffered - may be set with the help of a parameter, - * whereas the message size is automatically set to the maximum message - * queue message size. The operating system sets the message queue id, or - * in case of failure, it is set to zero. - * @param message_depth - * The number of messages to be buffered before passing an error to the - * sender. Default is three. - * @param max_message_size - * With this parameter, the maximum message size can be adjusted. - * This should be left default. - */ - MessageQueue(size_t messageDepth = 3, - size_t maxMessageSize = MessageQueueMessage::MAX_MESSAGE_SIZE); + friend class MessageQueueSenderIF; - /** Copying message queues forbidden */ - MessageQueue(const MessageQueue&) = delete; - MessageQueue& operator=(const MessageQueue&) = delete; + public: + /** + * @brief The constructor initializes and configures the message queue. + * @details + * By making use of the according operating system call, a message queue is + * created and initialized. The message depth - the maximum number of + * messages to be buffered - may be set with the help of a parameter, + * whereas the message size is automatically set to the maximum message + * queue message size. The operating system sets the message queue id, or + * in case of failure, it is set to zero. + * @param message_depth + * The number of messages to be buffered before passing an error to the + * sender. Default is three. + * @param max_message_size + * With this parameter, the maximum message size can be adjusted. + * This should be left default. + */ + MessageQueue(size_t messageDepth = 3, + size_t maxMessageSize = MessageQueueMessage::MAX_MESSAGE_SIZE); - /** - * @brief The destructor deletes the formerly created message queue. - * @details This is accomplished by using the delete call provided - * by the operating system. - */ - virtual ~MessageQueue(); + /** Copying message queues forbidden */ + MessageQueue(const MessageQueue&) = delete; + MessageQueue& operator=(const MessageQueue&) = delete; - /** - * @brief This operation sends a message to the given destination. - * @details It directly uses the sendMessage call of the MessageQueueSender - * parent, but passes its queue id as "sentFrom" parameter. - * @param sendTo This parameter specifies the message queue id of the - * destination message queue. - * @param message A pointer to a previously created message, which is sent. - * @param ignoreFault If set to true, the internal software fault counter - * is not incremented if queue is full. - */ - ReturnValue_t sendMessage(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, bool ignoreFault = false) override; - /** - * @brief This operation sends a message to the default destination. - * @details As in the sendMessage method, this function uses the - * sendToDefault call of the MessageQueueSender parent class and adds its - * queue id as "sentFrom" information. - * @param message A pointer to a previously created message, which is sent. - */ - ReturnValue_t sendToDefault(MessageQueueMessageIF* message) override; - /** - * @brief This operation sends a message to the last communication partner. - * @details This operation simplifies answering an incoming message by using - * the stored lastPartner information as destination. If there was no - * message received yet (i.e. lastPartner is zero), an error code is returned. - * @param message A pointer to a previously created message, which is sent. - */ - ReturnValue_t reply(MessageQueueMessageIF* message) override; + /** + * @brief The destructor deletes the formerly created message queue. + * @details This is accomplished by using the delete call provided + * by the operating system. + */ + virtual ~MessageQueue(); - /** - * @brief With the sendMessage call, a queue message is sent to a - * receiving queue. - * @details - * This method takes the message provided, adds the sentFrom information and - * passes it on to the destination provided with an operating system call. - * The OS's return value is returned. - * @param sendTo This parameter specifies the message queue id to send - * the message to. - * @param message This is a pointer to a previously created message, - * which is sent. - * @param sentFrom The sentFrom information can be set to inject the - * sender's queue id into the message. This variable is set to zero by - * default. - * @param ignoreFault If set to true, the internal software fault counter - * is not incremented if queue is full. - */ - virtual ReturnValue_t sendMessageFrom( MessageQueueId_t sendTo, - MessageQueueMessageIF* message, MessageQueueId_t sentFrom = NO_QUEUE, - bool ignoreFault = false) override; + /** + * @brief This operation sends a message to the given destination. + * @details It directly uses the sendMessage call of the MessageQueueSender + * parent, but passes its queue id as "sentFrom" parameter. + * @param sendTo This parameter specifies the message queue id of the + * destination message queue. + * @param message A pointer to a previously created message, which is sent. + * @param ignoreFault If set to true, the internal software fault counter + * is not incremented if queue is full. + */ + ReturnValue_t sendMessage(MessageQueueId_t sendTo, MessageQueueMessageIF* message, + bool ignoreFault = false) override; + /** + * @brief This operation sends a message to the default destination. + * @details As in the sendMessage method, this function uses the + * sendToDefault call of the MessageQueueSender parent class and adds its + * queue id as "sentFrom" information. + * @param message A pointer to a previously created message, which is sent. + */ + ReturnValue_t sendToDefault(MessageQueueMessageIF* message) override; + /** + * @brief This operation sends a message to the last communication partner. + * @details This operation simplifies answering an incoming message by using + * the stored lastPartner information as destination. If there was no + * message received yet (i.e. lastPartner is zero), an error code is returned. + * @param message A pointer to a previously created message, which is sent. + */ + ReturnValue_t reply(MessageQueueMessageIF* message) override; - /** - * @brief The sendToDefault method sends a queue message to the default - * destination. - * @details - * In all other aspects, it works identical to the sendMessage method. - * @param message This is a pointer to a previously created message, - * which is sent. - * @param sentFrom The sentFrom information can be set to inject the - * sender's queue id into the message. This variable is set to zero by - * default. - */ - virtual ReturnValue_t sendToDefaultFrom( MessageQueueMessageIF* message, - MessageQueueId_t sentFrom = NO_QUEUE, - bool ignoreFault = false) override; + /** + * @brief With the sendMessage call, a queue message is sent to a + * receiving queue. + * @details + * This method takes the message provided, adds the sentFrom information and + * passes it on to the destination provided with an operating system call. + * The OS's return value is returned. + * @param sendTo This parameter specifies the message queue id to send + * the message to. + * @param message This is a pointer to a previously created message, + * which is sent. + * @param sentFrom The sentFrom information can be set to inject the + * sender's queue id into the message. This variable is set to zero by + * default. + * @param ignoreFault If set to true, the internal software fault counter + * is not incremented if queue is full. + */ + virtual ReturnValue_t sendMessageFrom(MessageQueueId_t sendTo, MessageQueueMessageIF* message, + MessageQueueId_t sentFrom = NO_QUEUE, + bool ignoreFault = false) override; - /** - * @brief This function reads available messages from the message queue - * and returns the sender. - * @details - * It works identically to the other receiveMessage call, but in addition - * returns the sender's queue id. - * @param message A pointer to a message in which the received data is stored. - * @param receivedFrom A pointer to a queue id in which the sender's id is stored. - */ - ReturnValue_t receiveMessage(MessageQueueMessageIF* message, - MessageQueueId_t *receivedFrom) override; + /** + * @brief The sendToDefault method sends a queue message to the default + * destination. + * @details + * In all other aspects, it works identical to the sendMessage method. + * @param message This is a pointer to a previously created message, + * which is sent. + * @param sentFrom The sentFrom information can be set to inject the + * sender's queue id into the message. This variable is set to zero by + * default. + */ + virtual ReturnValue_t sendToDefaultFrom(MessageQueueMessageIF* message, + MessageQueueId_t sentFrom = NO_QUEUE, + bool ignoreFault = false) override; - /** - * @brief This function reads available messages from the message queue. - * @details - * If data is available it is stored in the passed message pointer. - * The message's original content is overwritten and the sendFrom - * information is stored in the lastPartner attribute. Else, the lastPartner - * information remains untouched, the message's content is cleared and the - * function returns immediately. - * @param message A pointer to a message in which the received data is stored. - */ - ReturnValue_t receiveMessage(MessageQueueMessageIF* message) override; - /** - * Deletes all pending messages in the queue. - * @param count The number of flushed messages. - * @return RETURN_OK on success. - */ - ReturnValue_t flush(uint32_t* count) override; - /** - * @brief This method returns the message queue id of the last - * communication partner. - */ - MessageQueueId_t getLastPartner() const override; - /** - * @brief This method returns the message queue id of this class's - * message queue. - */ - MessageQueueId_t getId() const override; + /** + * @brief This function reads available messages from the message queue + * and returns the sender. + * @details + * It works identically to the other receiveMessage call, but in addition + * returns the sender's queue id. + * @param message A pointer to a message in which the received data is stored. + * @param receivedFrom A pointer to a queue id in which the sender's id is stored. + */ + ReturnValue_t receiveMessage(MessageQueueMessageIF* message, + MessageQueueId_t* receivedFrom) override; - /** - * @brief This method is a simple setter for the default destination. - */ - void setDefaultDestination(MessageQueueId_t defaultDestination) override; - /** - * @brief This method is a simple getter for the default destination. - */ - MessageQueueId_t getDefaultDestination() const override; + /** + * @brief This function reads available messages from the message queue. + * @details + * If data is available it is stored in the passed message pointer. + * The message's original content is overwritten and the sendFrom + * information is stored in the lastPartner attribute. Else, the lastPartner + * information remains untouched, the message's content is cleared and the + * function returns immediately. + * @param message A pointer to a message in which the received data is stored. + */ + ReturnValue_t receiveMessage(MessageQueueMessageIF* message) override; + /** + * Deletes all pending messages in the queue. + * @param count The number of flushed messages. + * @return RETURN_OK on success. + */ + ReturnValue_t flush(uint32_t* count) override; + /** + * @brief This method returns the message queue id of the last + * communication partner. + */ + MessageQueueId_t getLastPartner() const override; + /** + * @brief This method returns the message queue id of this class's + * message queue. + */ + MessageQueueId_t getId() const override; - bool isDefaultDestinationSet() const override; + /** + * @brief This method is a simple setter for the default destination. + */ + void setDefaultDestination(MessageQueueId_t defaultDestination) override; + /** + * @brief This method is a simple getter for the default destination. + */ + MessageQueueId_t getDefaultDestination() const override; - ReturnValue_t lockQueue(MutexIF::TimeoutType timeoutType, - dur_millis_t lockTimeout); - ReturnValue_t unlockQueue(); -protected: - /** - * @brief Implementation to be called from any send Call within - * MessageQueue and MessageQueueSenderIF. - * @details - * This method takes the message provided, adds the sentFrom information and - * passes it on to the destination provided with an operating system call. - * The OS's return value is returned. - * @param sendTo - * This parameter specifies the message queue id to send the message to. - * @param message - * This is a pointer to a previously created message, which is sent. - * @param sentFrom - * The sentFrom information can be set to inject the sender's queue id into - * the message. This variable is set to zero by default. - * @param ignoreFault - * If set to true, the internal software fault counter is not incremented - * if queue is full. - * @param context Specify whether call is made from task or from an ISR. - */ - static ReturnValue_t sendMessageFromMessageQueue(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, MessageQueueId_t sentFrom = NO_QUEUE, - bool ignoreFault=false); + bool isDefaultDestinationSet() const override; - //static ReturnValue_t handleSendResult(BaseType_t result, bool ignoreFault); + ReturnValue_t lockQueue(MutexIF::TimeoutType timeoutType, dur_millis_t lockTimeout); + ReturnValue_t unlockQueue(); -private: - std::queue> messageQueue; - /** - * @brief The class stores the queue id it got assigned. - * If initialization fails, the queue id is set to zero. - */ - MessageQueueId_t mqId = MessageQueueIF::NO_QUEUE; - size_t messageSize = 0; - size_t messageDepth = 0; + protected: + /** + * @brief Implementation to be called from any send Call within + * MessageQueue and MessageQueueSenderIF. + * @details + * This method takes the message provided, adds the sentFrom information and + * passes it on to the destination provided with an operating system call. + * The OS's return value is returned. + * @param sendTo + * This parameter specifies the message queue id to send the message to. + * @param message + * This is a pointer to a previously created message, which is sent. + * @param sentFrom + * The sentFrom information can be set to inject the sender's queue id into + * the message. This variable is set to zero by default. + * @param ignoreFault + * If set to true, the internal software fault counter is not incremented + * if queue is full. + * @param context Specify whether call is made from task or from an ISR. + */ + static ReturnValue_t sendMessageFromMessageQueue(MessageQueueId_t sendTo, + MessageQueueMessageIF* message, + MessageQueueId_t sentFrom = NO_QUEUE, + bool ignoreFault = false); - MutexIF* queueLock; + // static ReturnValue_t handleSendResult(BaseType_t result, bool ignoreFault); - bool defaultDestinationSet = false; - MessageQueueId_t defaultDestination = MessageQueueIF::NO_QUEUE; - MessageQueueId_t lastPartner = MessageQueueIF::NO_QUEUE; + private: + std::queue> messageQueue; + /** + * @brief The class stores the queue id it got assigned. + * If initialization fails, the queue id is set to zero. + */ + MessageQueueId_t mqId = MessageQueueIF::NO_QUEUE; + size_t messageSize = 0; + size_t messageDepth = 0; + + MutexIF* queueLock; + + bool defaultDestinationSet = false; + MessageQueueId_t defaultDestination = MessageQueueIF::NO_QUEUE; + MessageQueueId_t lastPartner = MessageQueueIF::NO_QUEUE; }; #endif /* FRAMEWORK_OSAL_HOST_MESSAGEQUEUE_H_ */ diff --git a/src/fsfw/osal/host/Mutex.cpp b/src/fsfw/osal/host/Mutex.cpp index e423ea93..4b7a9582 100644 --- a/src/fsfw/osal/host/Mutex.cpp +++ b/src/fsfw/osal/host/Mutex.cpp @@ -1,32 +1,29 @@ #include "fsfw/osal/host/Mutex.h" + #include "fsfw/serviceinterface/ServiceInterface.h" Mutex::Mutex() {} ReturnValue_t Mutex::lockMutex(TimeoutType timeoutType, uint32_t timeoutMs) { - if(timeoutType == TimeoutType::BLOCKING) { - mutex.lock(); - return HasReturnvaluesIF::RETURN_OK; - } - else if(timeoutType == TimeoutType::POLLING) { - if(mutex.try_lock()) { - return HasReturnvaluesIF::RETURN_OK; - } - } - else if(timeoutType == TimeoutType::WAITING){ - auto chronoMs = std::chrono::milliseconds(timeoutMs); - if(mutex.try_lock_for(chronoMs)) { - return HasReturnvaluesIF::RETURN_OK; - } - } - return MutexIF::MUTEX_TIMEOUT; + if (timeoutType == TimeoutType::BLOCKING) { + mutex.lock(); + return HasReturnvaluesIF::RETURN_OK; + } else if (timeoutType == TimeoutType::POLLING) { + if (mutex.try_lock()) { + return HasReturnvaluesIF::RETURN_OK; + } + } else if (timeoutType == TimeoutType::WAITING) { + auto chronoMs = std::chrono::milliseconds(timeoutMs); + if (mutex.try_lock_for(chronoMs)) { + return HasReturnvaluesIF::RETURN_OK; + } + } + return MutexIF::MUTEX_TIMEOUT; } ReturnValue_t Mutex::unlockMutex() { - mutex.unlock(); - return HasReturnvaluesIF::RETURN_OK; + mutex.unlock(); + return HasReturnvaluesIF::RETURN_OK; } -std::timed_mutex* Mutex::getMutexHandle() { - return &mutex; -} +std::timed_mutex* Mutex::getMutexHandle() { return &mutex; } diff --git a/src/fsfw/osal/host/Mutex.h b/src/fsfw/osal/host/Mutex.h index e90ce932..458f8a17 100644 --- a/src/fsfw/osal/host/Mutex.h +++ b/src/fsfw/osal/host/Mutex.h @@ -1,10 +1,10 @@ #ifndef FSFW_OSAL_HOSTED_MUTEX_H_ #define FSFW_OSAL_HOSTED_MUTEX_H_ -#include "fsfw/ipc/MutexIF.h" - #include +#include "fsfw/ipc/MutexIF.h" + /** * @brief OS component to implement MUTual EXclusion * @@ -14,15 +14,16 @@ * @ingroup osal */ class Mutex : public MutexIF { -public: - Mutex(); - ReturnValue_t lockMutex(TimeoutType timeoutType = - TimeoutType::BLOCKING, uint32_t timeoutMs = 0) override; - ReturnValue_t unlockMutex() override; + public: + Mutex(); + ReturnValue_t lockMutex(TimeoutType timeoutType = TimeoutType::BLOCKING, + uint32_t timeoutMs = 0) override; + ReturnValue_t unlockMutex() override; - std::timed_mutex* getMutexHandle(); -private: - std::timed_mutex mutex; + std::timed_mutex* getMutexHandle(); + + private: + std::timed_mutex mutex; }; #endif /* FSFW_OSAL_HOSTED_MUTEX_H_ */ diff --git a/src/fsfw/osal/host/MutexFactory.cpp b/src/fsfw/osal/host/MutexFactory.cpp index 87287906..335d8048 100644 --- a/src/fsfw/osal/host/MutexFactory.cpp +++ b/src/fsfw/osal/host/MutexFactory.cpp @@ -1,30 +1,27 @@ -#include "fsfw/osal/host/Mutex.h" #include "fsfw/ipc/MutexFactory.h" -//TODO: Different variant than the lazy loading in QueueFactory. -//What's better and why? -> one is on heap the other on bss/data -//MutexFactory* MutexFactory::factoryInstance = new MutexFactory(); +#include "fsfw/osal/host/Mutex.h" + +// TODO: Different variant than the lazy loading in QueueFactory. +// What's better and why? -> one is on heap the other on bss/data +// MutexFactory* MutexFactory::factoryInstance = new MutexFactory(); MutexFactory* MutexFactory::factoryInstance = nullptr; -MutexFactory::MutexFactory() { -} +MutexFactory::MutexFactory() {} -MutexFactory::~MutexFactory() { -} +MutexFactory::~MutexFactory() {} MutexFactory* MutexFactory::instance() { - if (factoryInstance == nullptr){ - factoryInstance = new MutexFactory(); - } - return MutexFactory::factoryInstance; + if (factoryInstance == nullptr) { + factoryInstance = new MutexFactory(); + } + return MutexFactory::factoryInstance; } -MutexIF* MutexFactory::createMutex() { - return new Mutex(); -} +MutexIF* MutexFactory::createMutex() { return new Mutex(); } void MutexFactory::deleteMutex(MutexIF* mutex) { - if(mutex != nullptr) { - delete mutex; - } + if (mutex != nullptr) { + delete mutex; + } } diff --git a/src/fsfw/osal/host/PeriodicTask.cpp b/src/fsfw/osal/host/PeriodicTask.cpp index def3a6cb..1de4aedf 100644 --- a/src/fsfw/osal/host/PeriodicTask.cpp +++ b/src/fsfw/osal/host/PeriodicTask.cpp @@ -1,165 +1,154 @@ -#include "fsfw/osal/host/Mutex.h" #include "fsfw/osal/host/PeriodicTask.h" -#include "fsfw/osal/host/taskHelpers.h" -#include "fsfw/platform.h" +#include +#include + #include "fsfw/ipc/MutexFactory.h" #include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/osal/host/Mutex.h" +#include "fsfw/osal/host/taskHelpers.h" +#include "fsfw/platform.h" #include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/tasks/ExecutableObjectIF.h" -#include -#include - #if defined(PLATFORM_WIN) #include + #include "fsfw/osal/windows/winTaskHelpers.h" #elif defined(PLATFORM_UNIX) #include #endif -PeriodicTask::PeriodicTask(const char *name, TaskPriority setPriority, - TaskStackSize setStack, TaskPeriod setPeriod, - void (*setDeadlineMissedFunc)()) : - started(false), taskName(name), period(setPeriod), - deadlineMissedFunc(setDeadlineMissedFunc) { - // It is probably possible to set task priorities by using the native - // task handles for Windows / Linux - mainThread = std::thread(&PeriodicTask::taskEntryPoint, this, this); +PeriodicTask::PeriodicTask(const char* name, TaskPriority setPriority, TaskStackSize setStack, + TaskPeriod setPeriod, void (*setDeadlineMissedFunc)()) + : started(false), taskName(name), period(setPeriod), deadlineMissedFunc(setDeadlineMissedFunc) { + // It is probably possible to set task priorities by using the native + // task handles for Windows / Linux + mainThread = std::thread(&PeriodicTask::taskEntryPoint, this, this); #if defined(PLATFORM_WIN) - tasks::setTaskPriority(reinterpret_cast(mainThread.native_handle()), setPriority); + tasks::setTaskPriority(reinterpret_cast(mainThread.native_handle()), setPriority); #elif defined(PLATFORM_UNIX) - // TODO: We could reuse existing code here. + // TODO: We could reuse existing code here. #endif - tasks::insertTaskName(mainThread.get_id(), taskName); + tasks::insertTaskName(mainThread.get_id(), taskName); } PeriodicTask::~PeriodicTask(void) { - //Do not delete objects, we were responsible for ptrs only. - terminateThread = true; - if(mainThread.joinable()) { - mainThread.join(); - } + // Do not delete objects, we were responsible for ptrs only. + terminateThread = true; + if (mainThread.joinable()) { + mainThread.join(); + } } void PeriodicTask::taskEntryPoint(void* argument) { - PeriodicTask *originalTask(reinterpret_cast(argument)); + PeriodicTask* originalTask(reinterpret_cast(argument)); + if (not originalTask->started) { + // we have to suspend/block here until the task is started. + // if semaphores are implemented, use them here. + std::unique_lock lock(initMutex); + initCondition.wait(lock); + } - if (not originalTask->started) { - // we have to suspend/block here until the task is started. - // if semaphores are implemented, use them here. - std::unique_lock lock(initMutex); - initCondition.wait(lock); - } - - this->taskFunctionality(); + this->taskFunctionality(); #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "PeriodicTask::taskEntryPoint: " - "Returned from taskFunctionality." << std::endl; + sif::debug << "PeriodicTask::taskEntryPoint: " + "Returned from taskFunctionality." + << std::endl; #endif } ReturnValue_t PeriodicTask::startTask() { - started = true; + started = true; - // Notify task to start. - std::lock_guard lock(initMutex); - initCondition.notify_one(); + // Notify task to start. + std::lock_guard lock(initMutex); + initCondition.notify_one(); - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t PeriodicTask::sleepFor(uint32_t ms) { - std::this_thread::sleep_for(std::chrono::milliseconds(ms)); - return HasReturnvaluesIF::RETURN_OK; + std::this_thread::sleep_for(std::chrono::milliseconds(ms)); + return HasReturnvaluesIF::RETURN_OK; } void PeriodicTask::taskFunctionality() { - for (const auto& object: objectList) { - object->initializeAfterTaskCreation(); + for (const auto& object : objectList) { + object->initializeAfterTaskCreation(); + } + + std::chrono::milliseconds periodChrono(static_cast(period * 1000)); + auto currentStartTime{std::chrono::duration_cast( + std::chrono::system_clock::now().time_since_epoch())}; + auto nextStartTime{currentStartTime}; + + /* Enter the loop that defines the task behavior. */ + for (;;) { + if (terminateThread.load()) { + break; } - - std::chrono::milliseconds periodChrono(static_cast(period*1000)); - auto currentStartTime { - std::chrono::duration_cast( - std::chrono::system_clock::now().time_since_epoch()) - }; - auto nextStartTime { currentStartTime }; - - /* Enter the loop that defines the task behavior. */ - for (;;) { - if(terminateThread.load()) { - break; - } - for (const auto& object: objectList) { - object->performOperation(); - } - if(not delayForInterval(¤tStartTime, periodChrono)) { - if(deadlineMissedFunc != nullptr) { - this->deadlineMissedFunc(); - } - } - } + for (const auto& object : objectList) { + object->performOperation(); + } + if (not delayForInterval(¤tStartTime, periodChrono)) { + if (deadlineMissedFunc != nullptr) { + this->deadlineMissedFunc(); + } + } + } } ReturnValue_t PeriodicTask::addComponent(object_id_t object) { - ExecutableObjectIF* newObject = ObjectManager::instance()->get( - object); - if (newObject == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - newObject->setTaskIF(this); - objectList.push_back(newObject); - return HasReturnvaluesIF::RETURN_OK; + ExecutableObjectIF* newObject = ObjectManager::instance()->get(object); + if (newObject == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + newObject->setTaskIF(this); + objectList.push_back(newObject); + return HasReturnvaluesIF::RETURN_OK; } -uint32_t PeriodicTask::getPeriodMs() const { - return period * 1000; -} +uint32_t PeriodicTask::getPeriodMs() const { return period * 1000; } -bool PeriodicTask::delayForInterval(chron_ms* previousWakeTimeMs, - const chron_ms interval) { - bool shouldDelay = false; - //Get current wakeup time - auto currentStartTime = - std::chrono::duration_cast( - std::chrono::system_clock::now().time_since_epoch()); - /* Generate the tick time at which the task wants to wake. */ - auto nextTimeToWake_ms = (*previousWakeTimeMs) + interval; +bool PeriodicTask::delayForInterval(chron_ms* previousWakeTimeMs, const chron_ms interval) { + bool shouldDelay = false; + // Get current wakeup time + auto currentStartTime = std::chrono::duration_cast( + std::chrono::system_clock::now().time_since_epoch()); + /* Generate the tick time at which the task wants to wake. */ + auto nextTimeToWake_ms = (*previousWakeTimeMs) + interval; - if (currentStartTime < *previousWakeTimeMs) { - /* The tick count has overflowed since this function was - lasted called. In this case the only time we should ever - actually delay is if the wake time has also overflowed, - and the wake time is greater than the tick time. When this - is the case it is as if neither time had overflowed. */ - if ((nextTimeToWake_ms < *previousWakeTimeMs) - && (nextTimeToWake_ms > currentStartTime)) { - shouldDelay = true; - } - } else { - /* The tick time has not overflowed. In this case we will - delay if either the wake time has overflowed, and/or the - tick time is less than the wake time. */ - if ((nextTimeToWake_ms < *previousWakeTimeMs) - || (nextTimeToWake_ms > currentStartTime)) { - shouldDelay = true; - } + if (currentStartTime < *previousWakeTimeMs) { + /* The tick count has overflowed since this function was + lasted called. In this case the only time we should ever + actually delay is if the wake time has also overflowed, + and the wake time is greater than the tick time. When this + is the case it is as if neither time had overflowed. */ + if ((nextTimeToWake_ms < *previousWakeTimeMs) && (nextTimeToWake_ms > currentStartTime)) { + shouldDelay = true; } - - /* Update the wake time ready for the next call. */ - - (*previousWakeTimeMs) = nextTimeToWake_ms; - - if (shouldDelay) { - auto sleepTime = std::chrono::duration_cast( - nextTimeToWake_ms - currentStartTime); - std::this_thread::sleep_for(sleepTime); - return true; + } else { + /* The tick time has not overflowed. In this case we will + delay if either the wake time has overflowed, and/or the + tick time is less than the wake time. */ + if ((nextTimeToWake_ms < *previousWakeTimeMs) || (nextTimeToWake_ms > currentStartTime)) { + shouldDelay = true; } - //We are shifting the time in case the deadline was missed like rtems - (*previousWakeTimeMs) = currentStartTime; - return false; + } + /* Update the wake time ready for the next call. */ + + (*previousWakeTimeMs) = nextTimeToWake_ms; + + if (shouldDelay) { + auto sleepTime = + std::chrono::duration_cast(nextTimeToWake_ms - currentStartTime); + std::this_thread::sleep_for(sleepTime); + return true; + } + // We are shifting the time in case the deadline was missed like rtems + (*previousWakeTimeMs) = currentStartTime; + return false; } diff --git a/src/fsfw/osal/host/PeriodicTask.h b/src/fsfw/osal/host/PeriodicTask.h index 00cb6a24..0c41c0f7 100644 --- a/src/fsfw/osal/host/PeriodicTask.h +++ b/src/fsfw/osal/host/PeriodicTask.h @@ -1,15 +1,15 @@ #ifndef FRAMEWORK_OSAL_HOST_PERIODICTASK_H_ #define FRAMEWORK_OSAL_HOST_PERIODICTASK_H_ +#include +#include +#include +#include + #include "../../objectmanager/ObjectManagerIF.h" #include "../../tasks/PeriodicTaskIF.h" #include "../../tasks/Typedef.h" -#include -#include -#include -#include - class ExecutableObjectIF; /** @@ -19,105 +19,104 @@ class ExecutableObjectIF; * * @ingroup task_handling */ -class PeriodicTask: public PeriodicTaskIF { -public: - /** - * @brief Standard constructor of the class. - * @details - * The class is initialized without allocated objects. These need to be - * added with #addComponent. - * @param priority - * @param stack_size - * @param setPeriod - * @param setDeadlineMissedFunc - * The function pointer to the deadline missed function that shall be - * assigned. - */ - PeriodicTask(const char *name, TaskPriority setPriority, TaskStackSize setStack, - TaskPeriod setPeriod,void (*setDeadlineMissedFunc)()); - /** - * @brief Currently, the executed object's lifetime is not coupled with - * the task object's lifetime, so the destructor is empty. - */ - virtual ~PeriodicTask(void); +class PeriodicTask : public PeriodicTaskIF { + public: + /** + * @brief Standard constructor of the class. + * @details + * The class is initialized without allocated objects. These need to be + * added with #addComponent. + * @param priority + * @param stack_size + * @param setPeriod + * @param setDeadlineMissedFunc + * The function pointer to the deadline missed function that shall be + * assigned. + */ + PeriodicTask(const char* name, TaskPriority setPriority, TaskStackSize setStack, + TaskPeriod setPeriod, void (*setDeadlineMissedFunc)()); + /** + * @brief Currently, the executed object's lifetime is not coupled with + * the task object's lifetime, so the destructor is empty. + */ + virtual ~PeriodicTask(void); - /** - * @brief The method to start the task. - * @details The method starts the task with the respective system call. - * Entry point is the taskEntryPoint method described below. - * The address of the task object is passed as an argument - * to the system call. - */ - ReturnValue_t startTask(void); - /** - * Adds an object to the list of objects to be executed. - * The objects are executed in the order added. - * @param object Id of the object to add. - * @return - * -@c RETURN_OK on success - * -@c RETURN_FAILED if the object could not be added. - */ - ReturnValue_t addComponent(object_id_t object); + /** + * @brief The method to start the task. + * @details The method starts the task with the respective system call. + * Entry point is the taskEntryPoint method described below. + * The address of the task object is passed as an argument + * to the system call. + */ + ReturnValue_t startTask(void); + /** + * Adds an object to the list of objects to be executed. + * The objects are executed in the order added. + * @param object Id of the object to add. + * @return + * -@c RETURN_OK on success + * -@c RETURN_FAILED if the object could not be added. + */ + ReturnValue_t addComponent(object_id_t object); - uint32_t getPeriodMs() const; + uint32_t getPeriodMs() const; - ReturnValue_t sleepFor(uint32_t ms); + ReturnValue_t sleepFor(uint32_t ms); -protected: - using chron_ms = std::chrono::milliseconds; - bool started; - //!< Typedef for the List of objects. - typedef std::vector ObjectList; - std::thread mainThread; - std::atomic terminateThread { false }; + protected: + using chron_ms = std::chrono::milliseconds; + bool started; + //!< Typedef for the List of objects. + typedef std::vector ObjectList; + std::thread mainThread; + std::atomic terminateThread{false}; - /** - * @brief This attribute holds a list of objects to be executed. - */ - ObjectList objectList; + /** + * @brief This attribute holds a list of objects to be executed. + */ + ObjectList objectList; - std::condition_variable initCondition; - std::mutex initMutex; - std::string taskName; - /** - * @brief The period of the task. - * @details - * The period determines the frequency of the task's execution. - * It is expressed in clock ticks. - */ - TaskPeriod period; - /** - * @brief The pointer to the deadline-missed function. - * @details - * This pointer stores the function that is executed if the task's deadline - * is missed. So, each may react individually on a timing failure. - * The pointer may be NULL, then nothing happens on missing the deadline. - * The deadline is equal to the next execution of the periodic task. - */ - void (*deadlineMissedFunc)(void); - /** - * @brief This is the function executed in the new task's context. - * @details - * It converts the argument back to the thread object type and copies the - * class instance to the task context. - * The taskFunctionality method is called afterwards. - * @param A pointer to the task object itself is passed as argument. - */ + std::condition_variable initCondition; + std::mutex initMutex; + std::string taskName; + /** + * @brief The period of the task. + * @details + * The period determines the frequency of the task's execution. + * It is expressed in clock ticks. + */ + TaskPeriod period; + /** + * @brief The pointer to the deadline-missed function. + * @details + * This pointer stores the function that is executed if the task's deadline + * is missed. So, each may react individually on a timing failure. + * The pointer may be NULL, then nothing happens on missing the deadline. + * The deadline is equal to the next execution of the periodic task. + */ + void (*deadlineMissedFunc)(void); + /** + * @brief This is the function executed in the new task's context. + * @details + * It converts the argument back to the thread object type and copies the + * class instance to the task context. + * The taskFunctionality method is called afterwards. + * @param A pointer to the task object itself is passed as argument. + */ - void taskEntryPoint(void* argument); - /** - * @brief The function containing the actual functionality of the task. - * @details - * The method sets and starts the task's period, then enters a loop that is - * repeated as long as the isRunning attribute is true. Within the loop, - * all performOperation methods of the added objects are called. Afterwards - * the checkAndRestartPeriod system call blocks the task until the next - * period. On missing the deadline, the deadlineMissedFunction is executed. - */ - void taskFunctionality(void); + void taskEntryPoint(void* argument); + /** + * @brief The function containing the actual functionality of the task. + * @details + * The method sets and starts the task's period, then enters a loop that is + * repeated as long as the isRunning attribute is true. Within the loop, + * all performOperation methods of the added objects are called. Afterwards + * the checkAndRestartPeriod system call blocks the task until the next + * period. On missing the deadline, the deadlineMissedFunction is executed. + */ + void taskFunctionality(void); - bool delayForInterval(chron_ms * previousWakeTimeMs, - const chron_ms interval); + bool delayForInterval(chron_ms* previousWakeTimeMs, const chron_ms interval); }; #endif /* PERIODICTASK_H_ */ diff --git a/src/fsfw/osal/host/QueueFactory.cpp b/src/fsfw/osal/host/QueueFactory.cpp index 466bb33b..3c63e6c9 100644 --- a/src/fsfw/osal/host/QueueFactory.cpp +++ b/src/fsfw/osal/host/QueueFactory.cpp @@ -1,45 +1,38 @@ -#include "fsfw/osal/host/MessageQueue.h" - -#include "fsfw/ipc/MessageQueueSenderIF.h" -#include "fsfw/ipc/MessageQueueMessageIF.h" #include "fsfw/ipc/QueueFactory.h" -#include "fsfw/serviceinterface/ServiceInterface.h" #include +#include "fsfw/ipc/MessageQueueMessageIF.h" +#include "fsfw/ipc/MessageQueueSenderIF.h" +#include "fsfw/osal/host/MessageQueue.h" +#include "fsfw/serviceinterface/ServiceInterface.h" + QueueFactory* QueueFactory::factoryInstance = nullptr; - ReturnValue_t MessageQueueSenderIF::sendMessage(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, MessageQueueId_t sentFrom, - bool ignoreFault) { - return MessageQueue::sendMessageFromMessageQueue(sendTo,message, - sentFrom,ignoreFault); - return HasReturnvaluesIF::RETURN_OK; + MessageQueueMessageIF* message, + MessageQueueId_t sentFrom, bool ignoreFault) { + return MessageQueue::sendMessageFromMessageQueue(sendTo, message, sentFrom, ignoreFault); + return HasReturnvaluesIF::RETURN_OK; } QueueFactory* QueueFactory::instance() { - if (factoryInstance == nullptr) { - factoryInstance = new QueueFactory; - } - return factoryInstance; + if (factoryInstance == nullptr) { + factoryInstance = new QueueFactory; + } + return factoryInstance; } -QueueFactory::QueueFactory() { +QueueFactory::QueueFactory() {} + +QueueFactory::~QueueFactory() {} + +MessageQueueIF* QueueFactory::createMessageQueue(uint32_t messageDepth, size_t maxMessageSize) { + // A thread-safe queue can be implemented by using a combination + // of std::queue and std::mutex. This uses dynamic memory allocation + // which could be alleviated by using a custom allocator, external library + // (etl::queue) or simply using std::queue, we're on a host machine anyway. + return new MessageQueue(messageDepth, maxMessageSize); } -QueueFactory::~QueueFactory() { -} - -MessageQueueIF* QueueFactory::createMessageQueue(uint32_t messageDepth, - size_t maxMessageSize) { - // A thread-safe queue can be implemented by using a combination - // of std::queue and std::mutex. This uses dynamic memory allocation - // which could be alleviated by using a custom allocator, external library - // (etl::queue) or simply using std::queue, we're on a host machine anyway. - return new MessageQueue(messageDepth, maxMessageSize); -} - -void QueueFactory::deleteMessageQueue(MessageQueueIF* queue) { - delete queue; -} +void QueueFactory::deleteMessageQueue(MessageQueueIF* queue) { delete queue; } diff --git a/src/fsfw/osal/host/QueueMapManager.cpp b/src/fsfw/osal/host/QueueMapManager.cpp index 58575cf6..72c70baa 100644 --- a/src/fsfw/osal/host/QueueMapManager.cpp +++ b/src/fsfw/osal/host/QueueMapManager.cpp @@ -1,69 +1,64 @@ #include "fsfw/osal/host/QueueMapManager.h" -#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/ipc/MutexFactory.h" #include "fsfw/ipc/MutexGuard.h" +#include "fsfw/serviceinterface/ServiceInterface.h" QueueMapManager* QueueMapManager::mqManagerInstance = nullptr; -QueueMapManager::QueueMapManager() { - mapLock = MutexFactory::instance()->createMutex(); -} +QueueMapManager::QueueMapManager() { mapLock = MutexFactory::instance()->createMutex(); } -QueueMapManager::~QueueMapManager() { - MutexFactory::instance()->deleteMutex(mapLock); -} +QueueMapManager::~QueueMapManager() { MutexFactory::instance()->deleteMutex(mapLock); } QueueMapManager* QueueMapManager::instance() { - if (mqManagerInstance == nullptr){ - mqManagerInstance = new QueueMapManager(); - } - return QueueMapManager::mqManagerInstance; + if (mqManagerInstance == nullptr) { + mqManagerInstance = new QueueMapManager(); + } + return QueueMapManager::mqManagerInstance; } -ReturnValue_t QueueMapManager::addMessageQueue( - MessageQueueIF* queueToInsert, MessageQueueId_t* id) { - MutexGuard lock(mapLock); - uint32_t currentId = queueCounter; +ReturnValue_t QueueMapManager::addMessageQueue(MessageQueueIF* queueToInsert, + MessageQueueId_t* id) { + MutexGuard lock(mapLock); + uint32_t currentId = queueCounter; + queueCounter++; + if (currentId == MessageQueueIF::NO_QUEUE) { + // Skip the NO_QUEUE value + currentId = queueCounter; queueCounter++; - if(currentId == MessageQueueIF::NO_QUEUE) { - // Skip the NO_QUEUE value - currentId = queueCounter; - queueCounter++; - } - auto returnPair = queueMap.emplace(currentId, queueToInsert); - if(not returnPair.second) { - /* This should never happen for the atomic variable. */ + } + auto returnPair = queueMap.emplace(currentId, queueToInsert); + if (not returnPair.second) { + /* This should never happen for the atomic variable. */ #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "QueueMapManager::addMessageQueue This ID is already " - "inside the map!" << std::endl; + sif::error << "QueueMapManager::addMessageQueue This ID is already " + "inside the map!" + << std::endl; #else - sif::printError("QueueMapManager::addMessageQueue This ID is already " - "inside the map!\n"); + sif::printError( + "QueueMapManager::addMessageQueue This ID is already " + "inside the map!\n"); #endif - return HasReturnvaluesIF::RETURN_FAILED; - } - if (id != nullptr) { - *id = currentId; - } - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_FAILED; + } + if (id != nullptr) { + *id = currentId; + } + return HasReturnvaluesIF::RETURN_OK; } -MessageQueueIF* QueueMapManager::getMessageQueue( - MessageQueueId_t messageQueueId) const { - auto queueIter = queueMap.find(messageQueueId); - if(queueIter != queueMap.end()) { - return queueIter->second; - } - else { +MessageQueueIF* QueueMapManager::getMessageQueue(MessageQueueId_t messageQueueId) const { + auto queueIter = queueMap.find(messageQueueId); + if (queueIter != queueMap.end()) { + return queueIter->second; + } else { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "QueueMapManager::getQueueHandle: The ID " << messageQueueId << - " does not exists in the map!" << std::endl; + sif::warning << "QueueMapManager::getQueueHandle: The ID " << messageQueueId + << " does not exists in the map!" << std::endl; #else - sif::printWarning("QueueMapManager::getQueueHandle: The ID %d does not exist in the map!\n", - messageQueueId); + sif::printWarning("QueueMapManager::getQueueHandle: The ID %d does not exist in the map!\n", + messageQueueId); #endif - } - return nullptr; + } + return nullptr; } - diff --git a/src/fsfw/osal/host/QueueMapManager.h b/src/fsfw/osal/host/QueueMapManager.h index 2dd2a01d..b290b566 100644 --- a/src/fsfw/osal/host/QueueMapManager.h +++ b/src/fsfw/osal/host/QueueMapManager.h @@ -1,52 +1,47 @@ #ifndef FSFW_OSAL_HOST_QUEUEMAPMANAGER_H_ #define FSFW_OSAL_HOST_QUEUEMAPMANAGER_H_ +#include +#include + #include "../../ipc/MessageQueueSenderIF.h" #include "../../osal/host/MessageQueue.h" -#include -#include using QueueMap = std::unordered_map; - /** * An internal map to map message queue IDs to message queues. * This propably should be a singleton.. */ class QueueMapManager { -public: + public: + //! Returns the single instance of QueueMapManager. + static QueueMapManager* instance(); + /** + * Insert a message queue into the map and returns a message queue ID + * @param queue The message queue to insert. + * @param id The passed value will be set unless a nullptr is passed + * @return + */ + ReturnValue_t addMessageQueue(MessageQueueIF* queue, MessageQueueId_t* id = nullptr); + /** + * Get the message queue handle by providing a message queue ID. Returns nullptr + * if the queue ID is not contained inside the internal map. + * @param messageQueueId + * @return + */ + MessageQueueIF* getMessageQueue(MessageQueueId_t messageQueueId) const; - //! Returns the single instance of QueueMapManager. - static QueueMapManager* instance(); + private: + //! External instantiation is forbidden. Constructor still required for singleton instantiation. + QueueMapManager(); + ~QueueMapManager(); - /** - * Insert a message queue into the map and returns a message queue ID - * @param queue The message queue to insert. - * @param id The passed value will be set unless a nullptr is passed - * @return - */ - ReturnValue_t addMessageQueue(MessageQueueIF* queue, MessageQueueId_t* - id = nullptr); - /** - * Get the message queue handle by providing a message queue ID. Returns nullptr - * if the queue ID is not contained inside the internal map. - * @param messageQueueId - * @return - */ - MessageQueueIF* getMessageQueue(MessageQueueId_t messageQueueId) const; - -private: - //! External instantiation is forbidden. Constructor still required for singleton instantiation. - QueueMapManager(); - ~QueueMapManager(); - - uint32_t queueCounter = MessageQueueIF::NO_QUEUE + 1; - MutexIF* mapLock; - QueueMap queueMap; - static QueueMapManager* mqManagerInstance; + uint32_t queueCounter = MessageQueueIF::NO_QUEUE + 1; + MutexIF* mapLock; + QueueMap queueMap; + static QueueMapManager* mqManagerInstance; }; - - #endif /* FSFW_OSAL_HOST_QUEUEMAPMANAGER_H_ */ diff --git a/src/fsfw/osal/host/SemaphoreFactory.cpp b/src/fsfw/osal/host/SemaphoreFactory.cpp index 3ea12877..cead3c3d 100644 --- a/src/fsfw/osal/host/SemaphoreFactory.cpp +++ b/src/fsfw/osal/host/SemaphoreFactory.cpp @@ -1,41 +1,39 @@ #include "fsfw/tasks/SemaphoreFactory.h" + #include "fsfw/serviceinterface/ServiceInterface.h" SemaphoreFactory* SemaphoreFactory::factoryInstance = nullptr; -SemaphoreFactory::SemaphoreFactory() { -} +SemaphoreFactory::SemaphoreFactory() {} -SemaphoreFactory::~SemaphoreFactory() { - delete factoryInstance; -} +SemaphoreFactory::~SemaphoreFactory() { delete factoryInstance; } SemaphoreFactory* SemaphoreFactory::instance() { - if (factoryInstance == nullptr){ - factoryInstance = new SemaphoreFactory(); - } - return SemaphoreFactory::factoryInstance; + if (factoryInstance == nullptr) { + factoryInstance = new SemaphoreFactory(); + } + return SemaphoreFactory::factoryInstance; } SemaphoreIF* SemaphoreFactory::createBinarySemaphore(uint32_t arguments) { - // Just gonna wait for full C++20 for now. + // Just gonna wait for full C++20 for now. #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "SemaphoreFactory: Binary Semaphore not implemented yet." - " Returning nullptr!\n" << std::flush; + sif::error << "SemaphoreFactory: Binary Semaphore not implemented yet." + " Returning nullptr!\n" + << std::flush; #endif - return nullptr; + return nullptr; } -SemaphoreIF* SemaphoreFactory::createCountingSemaphore(const uint8_t maxCount, - uint8_t initCount, uint32_t arguments) { - // Just gonna wait for full C++20 for now. +SemaphoreIF* SemaphoreFactory::createCountingSemaphore(const uint8_t maxCount, uint8_t initCount, + uint32_t arguments) { + // Just gonna wait for full C++20 for now. #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "SemaphoreFactory: Counting Semaphore not implemented yet." - " Returning nullptr!\n" << std::flush; + sif::error << "SemaphoreFactory: Counting Semaphore not implemented yet." + " Returning nullptr!\n" + << std::flush; #endif - return nullptr; + return nullptr; } -void SemaphoreFactory::deleteSemaphore(SemaphoreIF* semaphore) { - delete semaphore; -} +void SemaphoreFactory::deleteSemaphore(SemaphoreIF* semaphore) { delete semaphore; } diff --git a/src/fsfw/osal/host/TaskFactory.cpp b/src/fsfw/osal/host/TaskFactory.cpp index ad59bd1a..6e74fd57 100644 --- a/src/fsfw/osal/host/TaskFactory.cpp +++ b/src/fsfw/osal/host/TaskFactory.cpp @@ -1,63 +1,55 @@ +#include "fsfw/tasks/TaskFactory.h" + +#include + #include "fsfw/osal/host/FixedTimeslotTask.h" #include "fsfw/osal/host/PeriodicTask.h" #include "fsfw/osal/host/taskHelpers.h" - -#include "fsfw/tasks/TaskFactory.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" -#include "fsfw/tasks/PeriodicTaskIF.h" #include "fsfw/serviceinterface/ServiceInterface.h" - -#include +#include "fsfw/tasks/PeriodicTaskIF.h" TaskFactory* TaskFactory::factoryInstance = new TaskFactory(); // Not used for the host implementation for now because C++ thread abstraction is used const size_t PeriodicTaskIF::MINIMUM_STACK_SIZE = 0; -TaskFactory::TaskFactory() { +TaskFactory::TaskFactory() {} + +TaskFactory::~TaskFactory() {} + +TaskFactory* TaskFactory::instance() { return TaskFactory::factoryInstance; } + +PeriodicTaskIF* TaskFactory::createPeriodicTask( + TaskName name_, TaskPriority taskPriority_, TaskStackSize stackSize_, + TaskPeriod periodInSeconds_, TaskDeadlineMissedFunction deadLineMissedFunction_) { + return new PeriodicTask(name_, taskPriority_, stackSize_, periodInSeconds_, + deadLineMissedFunction_); } -TaskFactory::~TaskFactory() { -} - -TaskFactory* TaskFactory::instance() { - return TaskFactory::factoryInstance; -} - -PeriodicTaskIF* TaskFactory::createPeriodicTask(TaskName name_, - TaskPriority taskPriority_,TaskStackSize stackSize_, - TaskPeriod periodInSeconds_, - TaskDeadlineMissedFunction deadLineMissedFunction_) { - return new PeriodicTask(name_, taskPriority_, stackSize_, periodInSeconds_, - deadLineMissedFunction_); -} - -FixedTimeslotTaskIF* TaskFactory::createFixedTimeslotTask(TaskName name_, - TaskPriority taskPriority_,TaskStackSize stackSize_, - TaskPeriod periodInSeconds_, - TaskDeadlineMissedFunction deadLineMissedFunction_) { - return new FixedTimeslotTask(name_, taskPriority_, stackSize_, - periodInSeconds_, deadLineMissedFunction_); +FixedTimeslotTaskIF* TaskFactory::createFixedTimeslotTask( + TaskName name_, TaskPriority taskPriority_, TaskStackSize stackSize_, + TaskPeriod periodInSeconds_, TaskDeadlineMissedFunction deadLineMissedFunction_) { + return new FixedTimeslotTask(name_, taskPriority_, stackSize_, periodInSeconds_, + deadLineMissedFunction_); } ReturnValue_t TaskFactory::deleteTask(PeriodicTaskIF* task) { - // This might block for some time! - delete task; - return HasReturnvaluesIF::RETURN_FAILED; + // This might block for some time! + delete task; + return HasReturnvaluesIF::RETURN_FAILED; } -ReturnValue_t TaskFactory::delayTask(uint32_t delayMs){ - std::this_thread::sleep_for(std::chrono::milliseconds(delayMs)); - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t TaskFactory::delayTask(uint32_t delayMs) { + std::this_thread::sleep_for(std::chrono::milliseconds(delayMs)); + return HasReturnvaluesIF::RETURN_OK; } void TaskFactory::printMissedDeadline() { - std::string name = tasks::getTaskName(std::this_thread::get_id()); + std::string name = tasks::getTaskName(std::this_thread::get_id()); #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "TaskFactory::printMissedDeadline: " << name << std::endl; + sif::warning << "TaskFactory::printMissedDeadline: " << name << std::endl; #else - sif::printWarning("TaskFactory::printMissedDeadline: %s\n", name); + sif::printWarning("TaskFactory::printMissedDeadline: %s\n", name); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ } - - diff --git a/src/fsfw/osal/host/taskHelpers.cpp b/src/fsfw/osal/host/taskHelpers.cpp index a7de76d9..aba2948a 100644 --- a/src/fsfw/osal/host/taskHelpers.cpp +++ b/src/fsfw/osal/host/taskHelpers.cpp @@ -1,4 +1,5 @@ #include "fsfw/osal/host/taskHelpers.h" + #include #include @@ -6,22 +7,20 @@ std::mutex nameMapLock; std::map taskNameMap; ReturnValue_t tasks::insertTaskName(std::thread::id threadId, std::string taskName) { - std::lock_guard lg(nameMapLock); - auto returnPair = taskNameMap.emplace(threadId, taskName); - if(not returnPair.second) { - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + std::lock_guard lg(nameMapLock); + auto returnPair = taskNameMap.emplace(threadId, taskName); + if (not returnPair.second) { + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } std::string tasks::getTaskName(std::thread::id threadId) { - std::lock_guard lg(nameMapLock); - auto resultIter = taskNameMap.find(threadId); - if(resultIter != taskNameMap.end()) { - return resultIter->second; - } - else { - return "Unknown task"; - } + std::lock_guard lg(nameMapLock); + auto resultIter = taskNameMap.find(threadId); + if (resultIter != taskNameMap.end()) { + return resultIter->second; + } else { + return "Unknown task"; + } } - diff --git a/src/fsfw/osal/host/taskHelpers.h b/src/fsfw/osal/host/taskHelpers.h index fa00490f..cf553011 100644 --- a/src/fsfw/osal/host/taskHelpers.h +++ b/src/fsfw/osal/host/taskHelpers.h @@ -2,6 +2,7 @@ #define FSFW_OSAL_HOST_TASKHELPERS_H_ #include + #include namespace tasks { @@ -9,8 +10,6 @@ namespace tasks { ReturnValue_t insertTaskName(std::thread::id threadId, std::string taskName); std::string getTaskName(std::thread::id threadId); -} - - +} // namespace tasks #endif /* FSFW_OSAL_HOST_TASKHELPERS_H_ */ diff --git a/src/fsfw/osal/linux/BinarySemaphore.cpp b/src/fsfw/osal/linux/BinarySemaphore.cpp index 3ef04cf0..ffe0e3a8 100644 --- a/src/fsfw/osal/linux/BinarySemaphore.cpp +++ b/src/fsfw/osal/linux/BinarySemaphore.cpp @@ -1,162 +1,152 @@ #include "fsfw/osal/linux/BinarySemaphore.h" + +#include +#include + +#include + #include "fsfw/osal/linux/unixUtility.h" #include "fsfw/serviceinterface/ServiceInterfacePrinter.h" #include "fsfw/serviceinterface/ServiceInterfaceStream.h" -#include -#include -#include - - BinarySemaphore::BinarySemaphore() { - // Using unnamed semaphores for now - initSemaphore(); + // Using unnamed semaphores for now + initSemaphore(); } -BinarySemaphore::~BinarySemaphore() { - sem_destroy(&handle); +BinarySemaphore::~BinarySemaphore() { sem_destroy(&handle); } + +BinarySemaphore::BinarySemaphore(BinarySemaphore&& s) { initSemaphore(); } + +BinarySemaphore& BinarySemaphore::operator=(BinarySemaphore&& s) { + initSemaphore(); + return *this; } -BinarySemaphore::BinarySemaphore(BinarySemaphore&& s) { - initSemaphore(); -} +ReturnValue_t BinarySemaphore::acquire(TimeoutType timeoutType, uint32_t timeoutMs) { + int result = 0; + if (timeoutType == TimeoutType::POLLING) { + result = sem_trywait(&handle); + } else if (timeoutType == TimeoutType::BLOCKING) { + result = sem_wait(&handle); + } else if (timeoutType == TimeoutType::WAITING) { + timespec timeOut; + clock_gettime(CLOCK_REALTIME, &timeOut); + uint64_t nseconds = timeOut.tv_sec * 1000000000 + timeOut.tv_nsec; + nseconds += timeoutMs * 1000000; + timeOut.tv_sec = nseconds / 1000000000; + timeOut.tv_nsec = nseconds - timeOut.tv_sec * 1000000000; + result = sem_timedwait(&handle, &timeOut); + if (result != 0 and errno == EINVAL) { + utility::printUnixErrorGeneric(CLASS_NAME, "acquire", "sem_timedwait"); + } + } + if (result == 0) { + return HasReturnvaluesIF::RETURN_OK; + } -BinarySemaphore& BinarySemaphore::operator =( - BinarySemaphore&& s) { - initSemaphore(); - return * this; -} - -ReturnValue_t BinarySemaphore::acquire(TimeoutType timeoutType, - uint32_t timeoutMs) { - int result = 0; - if(timeoutType == TimeoutType::POLLING) { - result = sem_trywait(&handle); + switch (errno) { + case (EAGAIN): + // Operation could not be performed without blocking (for sem_trywait) + case (ETIMEDOUT): { + // Semaphore is 0 + utility::printUnixErrorGeneric(CLASS_NAME, "acquire", "ETIMEDOUT"); + return SemaphoreIF::SEMAPHORE_TIMEOUT; } - else if(timeoutType == TimeoutType::BLOCKING) { - result = sem_wait(&handle); + case (EINVAL): { + // Semaphore invalid + utility::printUnixErrorGeneric(CLASS_NAME, "acquire", "EINVAL"); + return SemaphoreIF::SEMAPHORE_INVALID; } - else if(timeoutType == TimeoutType::WAITING){ - timespec timeOut; - clock_gettime(CLOCK_REALTIME, &timeOut); - uint64_t nseconds = timeOut.tv_sec * 1000000000 + timeOut.tv_nsec; - nseconds += timeoutMs * 1000000; - timeOut.tv_sec = nseconds / 1000000000; - timeOut.tv_nsec = nseconds - timeOut.tv_sec * 1000000000; - result = sem_timedwait(&handle, &timeOut); - if(result != 0 and errno == EINVAL) { - utility::printUnixErrorGeneric(CLASS_NAME, "acquire", "sem_timedwait"); - } - } - if(result == 0) { - return HasReturnvaluesIF::RETURN_OK; - } - - switch(errno) { - case(EAGAIN): - // Operation could not be performed without blocking (for sem_trywait) - case(ETIMEDOUT): { - // Semaphore is 0 - utility::printUnixErrorGeneric(CLASS_NAME, "acquire", "ETIMEDOUT"); - return SemaphoreIF::SEMAPHORE_TIMEOUT; - } - case(EINVAL): { - // Semaphore invalid - utility::printUnixErrorGeneric(CLASS_NAME, "acquire", "EINVAL"); - return SemaphoreIF::SEMAPHORE_INVALID; - } - case(EINTR): { - // Call was interrupted by signal handler - utility::printUnixErrorGeneric(CLASS_NAME, "acquire", "EINTR"); - return HasReturnvaluesIF::RETURN_FAILED; + case (EINTR): { + // Call was interrupted by signal handler + utility::printUnixErrorGeneric(CLASS_NAME, "acquire", "EINTR"); + return HasReturnvaluesIF::RETURN_FAILED; } default: - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; + } } -ReturnValue_t BinarySemaphore::release() { - return BinarySemaphore::release(&this->handle); -} +ReturnValue_t BinarySemaphore::release() { return BinarySemaphore::release(&this->handle); } -ReturnValue_t BinarySemaphore::release(sem_t *handle) { - ReturnValue_t countResult = checkCount(handle, 1); - if(countResult != HasReturnvaluesIF::RETURN_OK) { - return countResult; - } +ReturnValue_t BinarySemaphore::release(sem_t* handle) { + ReturnValue_t countResult = checkCount(handle, 1); + if (countResult != HasReturnvaluesIF::RETURN_OK) { + return countResult; + } - int result = sem_post(handle); - if(result == 0) { - return HasReturnvaluesIF::RETURN_OK; - } + int result = sem_post(handle); + if (result == 0) { + return HasReturnvaluesIF::RETURN_OK; + } - switch(errno) { - case(EINVAL): { - // Semaphore invalid - utility::printUnixErrorGeneric(CLASS_NAME, "release", "EINVAL"); - return SemaphoreIF::SEMAPHORE_INVALID; + switch (errno) { + case (EINVAL): { + // Semaphore invalid + utility::printUnixErrorGeneric(CLASS_NAME, "release", "EINVAL"); + return SemaphoreIF::SEMAPHORE_INVALID; } - case(EOVERFLOW): { - // SEM_MAX_VALUE overflow. This should never happen - utility::printUnixErrorGeneric(CLASS_NAME, "release", "EOVERFLOW"); - return HasReturnvaluesIF::RETURN_FAILED; + case (EOVERFLOW): { + // SEM_MAX_VALUE overflow. This should never happen + utility::printUnixErrorGeneric(CLASS_NAME, "release", "EOVERFLOW"); + return HasReturnvaluesIF::RETURN_FAILED; } default: - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; + } } uint8_t BinarySemaphore::getSemaphoreCounter() const { - // And another ugly cast :-D - return getSemaphoreCounter(const_cast(&this->handle)); + // And another ugly cast :-D + return getSemaphoreCounter(const_cast(&this->handle)); } -uint8_t BinarySemaphore::getSemaphoreCounter(sem_t *handle) { - int value = 0; - int result = sem_getvalue(handle, &value); - if (result == 0) { - return value; - } - else if(result != 0 and errno == EINVAL) { - // Could be called from interrupt, use lightweight printf - sif::printError("BinarySemaphore::getSemaphoreCounter: " - "Invalid semaphore\n"); - return 0; - } - else { - // This should never happen. - return 0; - } +uint8_t BinarySemaphore::getSemaphoreCounter(sem_t* handle) { + int value = 0; + int result = sem_getvalue(handle, &value); + if (result == 0) { + return value; + } else if (result != 0 and errno == EINVAL) { + // Could be called from interrupt, use lightweight printf + sif::printError( + "BinarySemaphore::getSemaphoreCounter: " + "Invalid semaphore\n"); + return 0; + } else { + // This should never happen. + return 0; + } } void BinarySemaphore::initSemaphore(uint8_t initCount) { - auto result = sem_init(&handle, true, initCount); - if(result == -1) { - switch(errno) { - case(EINVAL): { - utility::printUnixErrorGeneric(CLASS_NAME, "initSemaphore", "EINVAL"); - break; - } - case(ENOSYS): { - // System does not support process-shared semaphores - utility::printUnixErrorGeneric(CLASS_NAME, "initSemaphore", "ENOSYS"); - break; - } - } + auto result = sem_init(&handle, true, initCount); + if (result == -1) { + switch (errno) { + case (EINVAL): { + utility::printUnixErrorGeneric(CLASS_NAME, "initSemaphore", "EINVAL"); + break; + } + case (ENOSYS): { + // System does not support process-shared semaphores + utility::printUnixErrorGeneric(CLASS_NAME, "initSemaphore", "ENOSYS"); + break; + } } + } } ReturnValue_t BinarySemaphore::checkCount(sem_t* handle, uint8_t maxCount) { - int value = getSemaphoreCounter(handle); - if(value >= maxCount) { - if(maxCount == 1 and value > 1) { - // Binary Semaphore special case. - // This is a config error use lightweight printf is this is called - // from an interrupt - printf("BinarySemaphore::release: Value of binary semaphore greater than 1!\n"); - return HasReturnvaluesIF::RETURN_FAILED; - } - return SemaphoreIF::SEMAPHORE_NOT_OWNED; + int value = getSemaphoreCounter(handle); + if (value >= maxCount) { + if (maxCount == 1 and value > 1) { + // Binary Semaphore special case. + // This is a config error use lightweight printf is this is called + // from an interrupt + printf("BinarySemaphore::release: Value of binary semaphore greater than 1!\n"); + return HasReturnvaluesIF::RETURN_FAILED; } - return HasReturnvaluesIF::RETURN_OK; + return SemaphoreIF::SEMAPHORE_NOT_OWNED; + } + return HasReturnvaluesIF::RETURN_OK; } diff --git a/src/fsfw/osal/linux/BinarySemaphore.h b/src/fsfw/osal/linux/BinarySemaphore.h index 2e6ded15..f75618a6 100644 --- a/src/fsfw/osal/linux/BinarySemaphore.h +++ b/src/fsfw/osal/linux/BinarySemaphore.h @@ -17,66 +17,66 @@ extern "C" { * @author R. Mueller * @ingroup osal */ -class BinarySemaphore: public SemaphoreIF, - public HasReturnvaluesIF { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::SEMAPHORE_IF; +class BinarySemaphore : public SemaphoreIF, public HasReturnvaluesIF { + public: + static const uint8_t INTERFACE_ID = CLASS_ID::SEMAPHORE_IF; - //! @brief Default ctor - BinarySemaphore(); - //! @brief Copy ctor, deleted explicitely. - BinarySemaphore(const BinarySemaphore&) = delete; - //! @brief Copy assignment, deleted explicitely. - BinarySemaphore& operator=(const BinarySemaphore&) = delete; - //! @brief Move ctor - BinarySemaphore (BinarySemaphore &&); - //! @brief Move assignment - BinarySemaphore & operator=(BinarySemaphore &&); - //! @brief Destructor - virtual ~BinarySemaphore(); + //! @brief Default ctor + BinarySemaphore(); + //! @brief Copy ctor, deleted explicitely. + BinarySemaphore(const BinarySemaphore&) = delete; + //! @brief Copy assignment, deleted explicitely. + BinarySemaphore& operator=(const BinarySemaphore&) = delete; + //! @brief Move ctor + BinarySemaphore(BinarySemaphore&&); + //! @brief Move assignment + BinarySemaphore& operator=(BinarySemaphore&&); + //! @brief Destructor + virtual ~BinarySemaphore(); - void initSemaphore(uint8_t initCount = 1); + void initSemaphore(uint8_t initCount = 1); - uint8_t getSemaphoreCounter() const override; - static uint8_t getSemaphoreCounter(sem_t* handle); + uint8_t getSemaphoreCounter() const override; + static uint8_t getSemaphoreCounter(sem_t* handle); - /** - * Take the binary semaphore. - * If the semaphore has already been taken, the task will be blocked - * for a maximum of #timeoutMs or until the semaphore is given back, - * for example by an ISR or another task. - * @param timeoutMs - * @return -@c RETURN_OK on success - * -@c SemaphoreIF::SEMAPHORE_TIMEOUT on timeout - */ - ReturnValue_t acquire(TimeoutType timeoutType = TimeoutType::BLOCKING, - uint32_t timeoutMs = 0) override; + /** + * Take the binary semaphore. + * If the semaphore has already been taken, the task will be blocked + * for a maximum of #timeoutMs or until the semaphore is given back, + * for example by an ISR or another task. + * @param timeoutMs + * @return -@c RETURN_OK on success + * -@c SemaphoreIF::SEMAPHORE_TIMEOUT on timeout + */ + ReturnValue_t acquire(TimeoutType timeoutType = TimeoutType::BLOCKING, + uint32_t timeoutMs = 0) override; - /** - * Release the binary semaphore. - * @return -@c RETURN_OK on success - * -@c SemaphoreIF::SEMAPHORE_NOT_OWNED if the semaphores is - * already available. - */ - virtual ReturnValue_t release() override; - /** - * This static function can be used to release a semaphore by providing - * its handle. - * @param handle - * @return - */ - static ReturnValue_t release(sem_t* handle); + /** + * Release the binary semaphore. + * @return -@c RETURN_OK on success + * -@c SemaphoreIF::SEMAPHORE_NOT_OWNED if the semaphores is + * already available. + */ + virtual ReturnValue_t release() override; + /** + * This static function can be used to release a semaphore by providing + * its handle. + * @param handle + * @return + */ + static ReturnValue_t release(sem_t* handle); - /** Checks the validity of the semaphore count against a specified - * known maxCount - * @param handle - * @param maxCount - * @return - */ - static ReturnValue_t checkCount(sem_t* handle, uint8_t maxCount); -protected: - sem_t handle; - static constexpr const char* CLASS_NAME = "BinarySemaphore"; + /** Checks the validity of the semaphore count against a specified + * known maxCount + * @param handle + * @param maxCount + * @return + */ + static ReturnValue_t checkCount(sem_t* handle, uint8_t maxCount); + + protected: + sem_t handle; + static constexpr const char* CLASS_NAME = "BinarySemaphore"; }; #endif /* FRAMEWORK_OSAL_FREERTOS_BINARYSEMPAHORE_H_ */ diff --git a/src/fsfw/osal/linux/Clock.cpp b/src/fsfw/osal/linux/Clock.cpp index d79c72be..7092e6b2 100644 --- a/src/fsfw/osal/linux/Clock.cpp +++ b/src/fsfw/osal/linux/Clock.cpp @@ -1,94 +1,96 @@ -#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/timemanager/Clock.h" -#include -#include #include +#include +#include #include #include + #include +#include "fsfw/serviceinterface/ServiceInterface.h" + uint16_t Clock::leapSeconds = 0; MutexIF* Clock::timeMutex = NULL; -uint32_t Clock::getTicksPerSecond(void){ - uint32_t ticks = sysconf(_SC_CLK_TCK); - return ticks; +uint32_t Clock::getTicksPerSecond(void) { + uint32_t ticks = sysconf(_SC_CLK_TCK); + return ticks; } ReturnValue_t Clock::setClock(const TimeOfDay_t* time) { - timespec timeUnix; - timeval timeTimeval; - convertTimeOfDayToTimeval(time,&timeTimeval); - timeUnix.tv_sec = timeTimeval.tv_sec; - timeUnix.tv_nsec = (__syscall_slong_t) timeTimeval.tv_usec * 1000; + timespec timeUnix; + timeval timeTimeval; + convertTimeOfDayToTimeval(time, &timeTimeval); + timeUnix.tv_sec = timeTimeval.tv_sec; + timeUnix.tv_nsec = (__syscall_slong_t)timeTimeval.tv_usec * 1000; - int status = clock_settime(CLOCK_REALTIME,&timeUnix); - if(status!=0){ - //TODO errno - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + int status = clock_settime(CLOCK_REALTIME, &timeUnix); + if (status != 0) { + // TODO errno + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t Clock::setClock(const timeval* time) { - timespec timeUnix; - timeUnix.tv_sec = time->tv_sec; - timeUnix.tv_nsec = (__syscall_slong_t) time->tv_usec * 1000; - int status = clock_settime(CLOCK_REALTIME,&timeUnix); - if(status!=0){ - //TODO errno - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + timespec timeUnix; + timeUnix.tv_sec = time->tv_sec; + timeUnix.tv_nsec = (__syscall_slong_t)time->tv_usec * 1000; + int status = clock_settime(CLOCK_REALTIME, &timeUnix); + if (status != 0) { + // TODO errno + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t Clock::getClock_timeval(timeval* time) { - timespec timeUnix; - int status = clock_gettime(CLOCK_REALTIME,&timeUnix); - if(status!=0){ - return HasReturnvaluesIF::RETURN_FAILED; - } - time->tv_sec = timeUnix.tv_sec; - time->tv_usec = timeUnix.tv_nsec / 1000.0; - return HasReturnvaluesIF::RETURN_OK; + timespec timeUnix; + int status = clock_gettime(CLOCK_REALTIME, &timeUnix); + if (status != 0) { + return HasReturnvaluesIF::RETURN_FAILED; + } + time->tv_sec = timeUnix.tv_sec; + time->tv_usec = timeUnix.tv_nsec / 1000.0; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t Clock::getClock_usecs(uint64_t* time) { - timeval timeVal; - ReturnValue_t result = getClock_timeval(&timeVal); - if(result != HasReturnvaluesIF::RETURN_OK){ - return result; - } - *time = (uint64_t)timeVal.tv_sec*1e6 + timeVal.tv_usec; + timeval timeVal; + ReturnValue_t result = getClock_timeval(&timeVal); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + *time = (uint64_t)timeVal.tv_sec * 1e6 + timeVal.tv_usec; - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } timeval Clock::getUptime() { - timeval uptime; - auto result = getUptime(&uptime); - if(result != HasReturnvaluesIF::RETURN_OK) { + timeval uptime; + auto result = getUptime(&uptime); + if (result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Clock::getUptime: Error getting uptime" << std::endl; + sif::error << "Clock::getUptime: Error getting uptime" << std::endl; #endif - } - return uptime; + } + return uptime; } ReturnValue_t Clock::getUptime(timeval* uptime) { - //TODO This is not posix compatible and delivers only seconds precision - // Linux specific file read but more precise. - double uptimeSeconds; - if(std::ifstream("/proc/uptime",std::ios::in) >> uptimeSeconds){ - uptime->tv_sec = uptimeSeconds; - uptime->tv_usec = uptimeSeconds *(double) 1e6 - (uptime->tv_sec *1e6); - } - return HasReturnvaluesIF::RETURN_OK; + // TODO This is not posix compatible and delivers only seconds precision + // Linux specific file read but more precise. + double uptimeSeconds; + if (std::ifstream("/proc/uptime", std::ios::in) >> uptimeSeconds) { + uptime->tv_sec = uptimeSeconds; + uptime->tv_usec = uptimeSeconds * (double)1e6 - (uptime->tv_sec * 1e6); + } + return HasReturnvaluesIF::RETURN_OK; } // Wait for new FSFW Clock function delivering seconds uptime. -//uint32_t Clock::getUptimeSeconds() { +// uint32_t Clock::getUptimeSeconds() { // //TODO This is not posix compatible and delivers only seconds precision // struct sysinfo sysInfo; // int result = sysinfo(&sysInfo); @@ -99,57 +101,52 @@ ReturnValue_t Clock::getUptime(timeval* uptime) { //} ReturnValue_t Clock::getUptime(uint32_t* uptimeMs) { - timeval uptime; - ReturnValue_t result = getUptime(&uptime); - if(result != HasReturnvaluesIF::RETURN_OK){ - return result; - } - *uptimeMs = uptime.tv_sec * 1e3 + uptime.tv_usec / 1e3; - return HasReturnvaluesIF::RETURN_OK; + timeval uptime; + ReturnValue_t result = getUptime(&uptime); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + *uptimeMs = uptime.tv_sec * 1e3 + uptime.tv_usec / 1e3; + return HasReturnvaluesIF::RETURN_OK; } - - ReturnValue_t Clock::getDateAndTime(TimeOfDay_t* time) { - timespec timeUnix; - int status = clock_gettime(CLOCK_REALTIME,&timeUnix); - if(status != 0){ - //TODO errno - return HasReturnvaluesIF::RETURN_FAILED; - } + timespec timeUnix; + int status = clock_gettime(CLOCK_REALTIME, &timeUnix); + if (status != 0) { + // TODO errno + return HasReturnvaluesIF::RETURN_FAILED; + } - struct tm* timeInfo; - timeInfo = gmtime(&timeUnix.tv_sec); - time->year = timeInfo->tm_year + 1900; - time->month = timeInfo->tm_mon+1; - time->day = timeInfo->tm_mday; - time->hour = timeInfo->tm_hour; - time->minute = timeInfo->tm_min; - time->second = timeInfo->tm_sec; - time->usecond = timeUnix.tv_nsec / 1000.0; + struct tm* timeInfo; + timeInfo = gmtime(&timeUnix.tv_sec); + time->year = timeInfo->tm_year + 1900; + time->month = timeInfo->tm_mon + 1; + time->day = timeInfo->tm_mday; + time->hour = timeInfo->tm_hour; + time->minute = timeInfo->tm_min; + time->second = timeInfo->tm_sec; + time->usecond = timeUnix.tv_nsec / 1000.0; - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t Clock::convertTimeOfDayToTimeval(const TimeOfDay_t* from, - timeval* to) { +ReturnValue_t Clock::convertTimeOfDayToTimeval(const TimeOfDay_t* from, timeval* to) { + tm fromTm; + // Note: Fails for years before AD + fromTm.tm_year = from->year - 1900; + fromTm.tm_mon = from->month - 1; + fromTm.tm_mday = from->day; + fromTm.tm_hour = from->hour; + fromTm.tm_min = from->minute; + fromTm.tm_sec = from->second; - tm fromTm; - //Note: Fails for years before AD - fromTm.tm_year = from->year - 1900; - fromTm.tm_mon = from->month - 1; - fromTm.tm_mday = from->day; - fromTm.tm_hour = from->hour; - fromTm.tm_min = from->minute; - fromTm.tm_sec = from->second; - - to->tv_sec = mktime(&fromTm); - to->tv_usec = from->usecond; - return HasReturnvaluesIF::RETURN_OK; + to->tv_sec = mktime(&fromTm); + to->tv_usec = from->usecond; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t Clock::convertTimevalToJD2000(timeval time, double* JD2000) { - *JD2000 = (time.tv_sec - 946728000. + time.tv_usec / 1000000.) / 24. - / 3600.; - return HasReturnvaluesIF::RETURN_OK; + *JD2000 = (time.tv_sec - 946728000. + time.tv_usec / 1000000.) / 24. / 3600.; + return HasReturnvaluesIF::RETURN_OK; } diff --git a/src/fsfw/osal/linux/CountingSemaphore.cpp b/src/fsfw/osal/linux/CountingSemaphore.cpp index cc2117f3..78210996 100644 --- a/src/fsfw/osal/linux/CountingSemaphore.cpp +++ b/src/fsfw/osal/linux/CountingSemaphore.cpp @@ -1,70 +1,68 @@ #include "fsfw/osal/linux/CountingSemaphore.h" -#include "fsfw/osal/linux/unixUtility.h" - -#include "fsfw/serviceinterface/ServiceInterface.h" #include -CountingSemaphore::CountingSemaphore(const uint8_t maxCount, uint8_t initCount): - maxCount(maxCount), initCount(initCount) { - if(initCount > maxCount) { +#include "fsfw/osal/linux/unixUtility.h" +#include "fsfw/serviceinterface/ServiceInterface.h" + +CountingSemaphore::CountingSemaphore(const uint8_t maxCount, uint8_t initCount) + : maxCount(maxCount), initCount(initCount) { + if (initCount > maxCount) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "CountingSemaphoreUsingTask: Max count bigger than " - "intial cout. Setting initial count to max count" << std::endl; + sif::warning << "CountingSemaphoreUsingTask: Max count bigger than " + "intial cout. Setting initial count to max count" + << std::endl; #else - sif::printWarning("CountingSemaphoreUsingTask: Max count bigger than " - "intial cout. Setting initial count to max count\n"); + sif::printWarning( + "CountingSemaphoreUsingTask: Max count bigger than " + "intial cout. Setting initial count to max count\n"); #endif - initCount = maxCount; - } + initCount = maxCount; + } - initSemaphore(initCount); + initSemaphore(initCount); } -CountingSemaphore::CountingSemaphore(CountingSemaphore&& other): - maxCount(other.maxCount), initCount(other.initCount) { - initSemaphore(initCount); +CountingSemaphore::CountingSemaphore(CountingSemaphore&& other) + : maxCount(other.maxCount), initCount(other.initCount) { + initSemaphore(initCount); } -CountingSemaphore& CountingSemaphore::operator =( - CountingSemaphore&& other) { - initSemaphore(other.initCount); - return * this; +CountingSemaphore& CountingSemaphore::operator=(CountingSemaphore&& other) { + initSemaphore(other.initCount); + return *this; } ReturnValue_t CountingSemaphore::release() { - ReturnValue_t result = checkCount(&handle, maxCount); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return CountingSemaphore::release(&this->handle); + ReturnValue_t result = checkCount(&handle, maxCount); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return CountingSemaphore::release(&this->handle); } ReturnValue_t CountingSemaphore::release(sem_t* handle) { - int result = sem_post(handle); - if(result == 0) { - return HasReturnvaluesIF::RETURN_OK; + int result = sem_post(handle); + if (result == 0) { + return HasReturnvaluesIF::RETURN_OK; + } + + switch (errno) { + case (EINVAL): { + // Semaphore invalid + utility::printUnixErrorGeneric("CountingSemaphore", "release", "EINVAL"); + return SemaphoreIF::SEMAPHORE_INVALID; } - switch(errno) { - case(EINVAL): { - // Semaphore invalid - utility::printUnixErrorGeneric("CountingSemaphore", "release", "EINVAL"); - return SemaphoreIF::SEMAPHORE_INVALID; - } - - case(EOVERFLOW): { - // SEM_MAX_VALUE overflow. This should never happen - utility::printUnixErrorGeneric("CountingSemaphore", "release", "EOVERFLOW"); - return SemaphoreIF::SEMAPHORE_INVALID; + case (EOVERFLOW): { + // SEM_MAX_VALUE overflow. This should never happen + utility::printUnixErrorGeneric("CountingSemaphore", "release", "EOVERFLOW"); + return SemaphoreIF::SEMAPHORE_INVALID; } default: - return HasReturnvaluesIF::RETURN_FAILED; - } -} - -uint8_t CountingSemaphore::getMaxCount() const { - return maxCount; + return HasReturnvaluesIF::RETURN_FAILED; + } } +uint8_t CountingSemaphore::getMaxCount() const { return maxCount; } diff --git a/src/fsfw/osal/linux/CountingSemaphore.h b/src/fsfw/osal/linux/CountingSemaphore.h index e0fbb992..136e3549 100644 --- a/src/fsfw/osal/linux/CountingSemaphore.h +++ b/src/fsfw/osal/linux/CountingSemaphore.h @@ -10,28 +10,29 @@ * so we just inherit from binary semaphore and provide the respective * constructors. */ -class CountingSemaphore: public BinarySemaphore { -public: - CountingSemaphore(const uint8_t maxCount, uint8_t initCount); - //! @brief Copy ctor, disabled - CountingSemaphore(const CountingSemaphore&) = delete; - //! @brief Copy assignment, disabled - CountingSemaphore& operator=(const CountingSemaphore&) = delete; - //! @brief Move ctor - CountingSemaphore (CountingSemaphore &&); - //! @brief Move assignment - CountingSemaphore & operator=(CountingSemaphore &&); +class CountingSemaphore : public BinarySemaphore { + public: + CountingSemaphore(const uint8_t maxCount, uint8_t initCount); + //! @brief Copy ctor, disabled + CountingSemaphore(const CountingSemaphore&) = delete; + //! @brief Copy assignment, disabled + CountingSemaphore& operator=(const CountingSemaphore&) = delete; + //! @brief Move ctor + CountingSemaphore(CountingSemaphore&&); + //! @brief Move assignment + CountingSemaphore& operator=(CountingSemaphore&&); - ReturnValue_t release() override; - static ReturnValue_t release(sem_t* sem); - /* Same API as binary semaphore otherwise. acquire() can be called - * until there are not semaphores left and release() can be called - * until maxCount is reached. */ + ReturnValue_t release() override; + static ReturnValue_t release(sem_t* sem); + /* Same API as binary semaphore otherwise. acquire() can be called + * until there are not semaphores left and release() can be called + * until maxCount is reached. */ - uint8_t getMaxCount() const; -private: - const uint8_t maxCount; - uint8_t initCount = 0; + uint8_t getMaxCount() const; + + private: + const uint8_t maxCount; + uint8_t initCount = 0; }; #endif /* FRAMEWORK_OSAL_FREERTOS_COUNTINGSEMAPHORE_H_ */ diff --git a/src/fsfw/osal/linux/FixedTimeslotTask.cpp b/src/fsfw/osal/linux/FixedTimeslotTask.cpp index f6648299..1f4d6e23 100644 --- a/src/fsfw/osal/linux/FixedTimeslotTask.cpp +++ b/src/fsfw/osal/linux/FixedTimeslotTask.cpp @@ -1,103 +1,94 @@ #include "fsfw/osal/linux/FixedTimeslotTask.h" +#include + #include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/serviceinterface/ServiceInterface.h" -#include - uint32_t FixedTimeslotTask::deadlineMissedCount = 0; const size_t PeriodicTaskIF::MINIMUM_STACK_SIZE = PTHREAD_STACK_MIN; -FixedTimeslotTask::FixedTimeslotTask(const char* name_, int priority_, - size_t stackSize_, uint32_t periodMs_): - PosixThread(name_,priority_,stackSize_),pst(periodMs_),started(false) { -} +FixedTimeslotTask::FixedTimeslotTask(const char* name_, int priority_, size_t stackSize_, + uint32_t periodMs_) + : PosixThread(name_, priority_, stackSize_), pst(periodMs_), started(false) {} -FixedTimeslotTask::~FixedTimeslotTask() { - -} +FixedTimeslotTask::~FixedTimeslotTask() {} void* FixedTimeslotTask::taskEntryPoint(void* arg) { - //The argument is re-interpreted as PollingTask. - FixedTimeslotTask *originalTask(reinterpret_cast(arg)); - //The task's functionality is called. - originalTask->taskFunctionality(); - return nullptr; + // The argument is re-interpreted as PollingTask. + FixedTimeslotTask* originalTask(reinterpret_cast(arg)); + // The task's functionality is called. + originalTask->taskFunctionality(); + return nullptr; } ReturnValue_t FixedTimeslotTask::startTask() { - started = true; - createTask(&taskEntryPoint,this); - return HasReturnvaluesIF::RETURN_OK; + started = true; + createTask(&taskEntryPoint, this); + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t FixedTimeslotTask::sleepFor(uint32_t ms) { - return PosixThread::sleep((uint64_t)ms*1000000); + return PosixThread::sleep((uint64_t)ms * 1000000); } -uint32_t FixedTimeslotTask::getPeriodMs() const { - return pst.getLengthMs(); -} +uint32_t FixedTimeslotTask::getPeriodMs() const { return pst.getLengthMs(); } -ReturnValue_t FixedTimeslotTask::addSlot(object_id_t componentId, - uint32_t slotTimeMs, int8_t executionStep) { - ExecutableObjectIF* executableObject = - ObjectManager::instance()->get(componentId); - if (executableObject != nullptr) { - pst.addSlot(componentId, slotTimeMs, executionStep, - executableObject,this); - return HasReturnvaluesIF::RETURN_OK; - } +ReturnValue_t FixedTimeslotTask::addSlot(object_id_t componentId, uint32_t slotTimeMs, + int8_t executionStep) { + ExecutableObjectIF* executableObject = + ObjectManager::instance()->get(componentId); + if (executableObject != nullptr) { + pst.addSlot(componentId, slotTimeMs, executionStep, executableObject, this); + return HasReturnvaluesIF::RETURN_OK; + } #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Component " << std::hex << componentId << - " not found, not adding it to pst" << std::dec << std::endl; + sif::error << "Component " << std::hex << componentId << " not found, not adding it to pst" + << std::dec << std::endl; #endif - return HasReturnvaluesIF::RETURN_FAILED; + return HasReturnvaluesIF::RETURN_FAILED; } -ReturnValue_t FixedTimeslotTask::checkSequence() const { - return pst.checkSequence(); -} +ReturnValue_t FixedTimeslotTask::checkSequence() const { return pst.checkSequence(); } void FixedTimeslotTask::taskFunctionality() { - //Like FreeRTOS pthreads are running as soon as they are created - if (!started) { - suspend(); - } + // Like FreeRTOS pthreads are running as soon as they are created + if (!started) { + suspend(); + } - pst.intializeSequenceAfterTaskCreation(); + pst.intializeSequenceAfterTaskCreation(); - //The start time for the first entry is read. - uint64_t lastWakeTime = getCurrentMonotonicTimeMs(); - uint64_t interval = pst.getIntervalToNextSlotMs(); + // The start time for the first entry is read. + uint64_t lastWakeTime = getCurrentMonotonicTimeMs(); + uint64_t interval = pst.getIntervalToNextSlotMs(); - - //The task's "infinite" inner loop is entered. - while (1) { - if (pst.slotFollowsImmediately()) { - //Do nothing - } else { - //The interval for the next polling slot is selected. - interval = this->pst.getIntervalToPreviousSlotMs(); - //The period is checked and restarted with the new interval. - //If the deadline was missed, the deadlineMissedFunc is called. - if(!PosixThread::delayUntil(&lastWakeTime,interval)) { - //No time left on timer -> we missed the deadline - missedDeadlineCounter(); - } - } - //The device handler for this slot is executed and the next one is chosen. - this->pst.executeAndAdvance(); - } + // The task's "infinite" inner loop is entered. + while (1) { + if (pst.slotFollowsImmediately()) { + // Do nothing + } else { + // The interval for the next polling slot is selected. + interval = this->pst.getIntervalToPreviousSlotMs(); + // The period is checked and restarted with the new interval. + // If the deadline was missed, the deadlineMissedFunc is called. + if (!PosixThread::delayUntil(&lastWakeTime, interval)) { + // No time left on timer -> we missed the deadline + missedDeadlineCounter(); + } + } + // The device handler for this slot is executed and the next one is chosen. + this->pst.executeAndAdvance(); + } } void FixedTimeslotTask::missedDeadlineCounter() { - FixedTimeslotTask::deadlineMissedCount++; - if (FixedTimeslotTask::deadlineMissedCount % 10 == 0) { + FixedTimeslotTask::deadlineMissedCount++; + if (FixedTimeslotTask::deadlineMissedCount % 10 == 0) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "PST missed " << FixedTimeslotTask::deadlineMissedCount - << " deadlines." << std::endl; + sif::error << "PST missed " << FixedTimeslotTask::deadlineMissedCount << " deadlines." + << std::endl; #endif - } + } } diff --git a/src/fsfw/osal/linux/FixedTimeslotTask.h b/src/fsfw/osal/linux/FixedTimeslotTask.h index 5c5c1814..76b92db3 100644 --- a/src/fsfw/osal/linux/FixedTimeslotTask.h +++ b/src/fsfw/osal/linux/FixedTimeslotTask.h @@ -1,77 +1,76 @@ #ifndef FSFW_OSAL_LINUX_FIXEDTIMESLOTTASK_H_ #define FSFW_OSAL_LINUX_FIXEDTIMESLOTTASK_H_ -#include "PosixThread.h" -#include "../../tasks/FixedTimeslotTaskIF.h" -#include "../../tasks/FixedSlotSequence.h" #include -class FixedTimeslotTask: public FixedTimeslotTaskIF, public PosixThread { -public: - /** - * Create a generic periodic task. - * @param name_ - * Name, maximum allowed size of linux is 16 chars, everything else will - * be truncated. - * @param priority_ - * Real-time priority, ranges from 1 to 99 for Linux. - * See: https://man7.org/linux/man-pages/man7/sched.7.html - * @param stackSize_ - * @param period_ - * @param deadlineMissedFunc_ - */ - FixedTimeslotTask(const char* name_, int priority_, size_t stackSize_, - uint32_t periodMs_); - virtual ~FixedTimeslotTask(); +#include "../../tasks/FixedSlotSequence.h" +#include "../../tasks/FixedTimeslotTaskIF.h" +#include "PosixThread.h" - virtual ReturnValue_t startTask(); +class FixedTimeslotTask : public FixedTimeslotTaskIF, public PosixThread { + public: + /** + * Create a generic periodic task. + * @param name_ + * Name, maximum allowed size of linux is 16 chars, everything else will + * be truncated. + * @param priority_ + * Real-time priority, ranges from 1 to 99 for Linux. + * See: https://man7.org/linux/man-pages/man7/sched.7.html + * @param stackSize_ + * @param period_ + * @param deadlineMissedFunc_ + */ + FixedTimeslotTask(const char* name_, int priority_, size_t stackSize_, uint32_t periodMs_); + virtual ~FixedTimeslotTask(); - virtual ReturnValue_t sleepFor(uint32_t ms); + virtual ReturnValue_t startTask(); - virtual uint32_t getPeriodMs() const; + virtual ReturnValue_t sleepFor(uint32_t ms); - virtual ReturnValue_t addSlot(object_id_t componentId, uint32_t slotTimeMs, - int8_t executionStep); + virtual uint32_t getPeriodMs() const; - virtual ReturnValue_t checkSequence() const; + virtual ReturnValue_t addSlot(object_id_t componentId, uint32_t slotTimeMs, int8_t executionStep); - /** - * This static function can be used as #deadlineMissedFunc. - * It counts missedDeadlines and prints the number of missed deadlines every 10th time. - */ - static void missedDeadlineCounter(); + virtual ReturnValue_t checkSequence() const; - /** - * A helper variable to count missed deadlines. - */ - static uint32_t deadlineMissedCount; + /** + * This static function can be used as #deadlineMissedFunc. + * It counts missedDeadlines and prints the number of missed deadlines every 10th time. + */ + static void missedDeadlineCounter(); -protected: - /** - * @brief This function holds the main functionality of the thread. - * @details - * Holding the main functionality of the task, this method is most important. - * It links the functionalities provided by FixedSlotSequence with the - * OS's System Calls to keep the timing of the periods. - */ - virtual void taskFunctionality(); + /** + * A helper variable to count missed deadlines. + */ + static uint32_t deadlineMissedCount; -private: - /** - * @brief This is the entry point in a new thread. - * - * @details - * This method, that is the entry point in the new thread and calls - * taskFunctionality of the child class. Needs a valid pointer to the - * derived class. - * - * The void* returnvalue is not used yet but could be used to return - * arbitrary data. - */ - static void* taskEntryPoint(void* arg); - FixedSlotSequence pst; + protected: + /** + * @brief This function holds the main functionality of the thread. + * @details + * Holding the main functionality of the task, this method is most important. + * It links the functionalities provided by FixedSlotSequence with the + * OS's System Calls to keep the timing of the periods. + */ + virtual void taskFunctionality(); - bool started; + private: + /** + * @brief This is the entry point in a new thread. + * + * @details + * This method, that is the entry point in the new thread and calls + * taskFunctionality of the child class. Needs a valid pointer to the + * derived class. + * + * The void* returnvalue is not used yet but could be used to return + * arbitrary data. + */ + static void* taskEntryPoint(void* arg); + FixedSlotSequence pst; + + bool started; }; #endif /* FSFW_OSAL_LINUX_FIXEDTIMESLOTTASK_H_ */ diff --git a/src/fsfw/osal/linux/InternalErrorCodes.cpp b/src/fsfw/osal/linux/InternalErrorCodes.cpp index 14274535..11913906 100644 --- a/src/fsfw/osal/linux/InternalErrorCodes.cpp +++ b/src/fsfw/osal/linux/InternalErrorCodes.cpp @@ -1,14 +1,10 @@ #include "fsfw/osal/InternalErrorCodes.h" ReturnValue_t InternalErrorCodes::translate(uint8_t code) { - //TODO This class can be removed - return HasReturnvaluesIF::RETURN_FAILED; + // TODO This class can be removed + return HasReturnvaluesIF::RETURN_FAILED; } -InternalErrorCodes::InternalErrorCodes() { -} - -InternalErrorCodes::~InternalErrorCodes() { - -} +InternalErrorCodes::InternalErrorCodes() {} +InternalErrorCodes::~InternalErrorCodes() {} diff --git a/src/fsfw/osal/linux/MessageQueue.cpp b/src/fsfw/osal/linux/MessageQueue.cpp index d028f9f7..f876ec6e 100644 --- a/src/fsfw/osal/linux/MessageQueue.cpp +++ b/src/fsfw/osal/linux/MessageQueue.cpp @@ -1,392 +1,379 @@ #include "fsfw/osal/linux/MessageQueue.h" -#include "fsfw/osal/linux/unixUtility.h" -#include "fsfw/serviceinterface/ServiceInterface.h" -#include "fsfw/objectmanager/ObjectManager.h" +#include +#include /* For O_* constants */ +#include /* For mode constants */ +#include #include -#include /* For O_* constants */ -#include /* For mode constants */ -#include -#include +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/osal/linux/unixUtility.h" +#include "fsfw/serviceinterface/ServiceInterface.h" +MessageQueue::MessageQueue(uint32_t messageDepth, size_t maxMessageSize) + : id(MessageQueueIF::NO_QUEUE), + lastPartner(MessageQueueIF::NO_QUEUE), + defaultDestination(MessageQueueIF::NO_QUEUE), + maxMessageSize(maxMessageSize) { + mq_attr attributes; + this->id = 0; + // Set attributes + attributes.mq_curmsgs = 0; + attributes.mq_maxmsg = messageDepth; + attributes.mq_msgsize = maxMessageSize; + attributes.mq_flags = 0; // Flags are ignored on Linux during mq_open + // Set the name of the queue. The slash is mandatory! + sprintf(name, "/FSFW_MQ%u\n", queueCounter++); -MessageQueue::MessageQueue(uint32_t messageDepth, size_t maxMessageSize): - id(MessageQueueIF::NO_QUEUE),lastPartner(MessageQueueIF::NO_QUEUE), - defaultDestination(MessageQueueIF::NO_QUEUE), maxMessageSize(maxMessageSize) { - mq_attr attributes; - this->id = 0; - //Set attributes - attributes.mq_curmsgs = 0; - attributes.mq_maxmsg = messageDepth; - attributes.mq_msgsize = maxMessageSize; - attributes.mq_flags = 0; //Flags are ignored on Linux during mq_open - //Set the name of the queue. The slash is mandatory! - sprintf(name, "/FSFW_MQ%u\n", queueCounter++); - - // Create a nonblocking queue if the name is available (the queue is read - // and writable for the owner as well as the group) - int oflag = O_NONBLOCK | O_RDWR | O_CREAT | O_EXCL; - mode_t mode = S_IWUSR | S_IREAD | S_IWGRP | S_IRGRP | S_IROTH | S_IWOTH; - mqd_t tempId = mq_open(name, oflag, mode, &attributes); - if (tempId == -1) { - handleOpenError(&attributes, messageDepth); - } - else { - //Successful mq_open call - this->id = tempId; - } + // Create a nonblocking queue if the name is available (the queue is read + // and writable for the owner as well as the group) + int oflag = O_NONBLOCK | O_RDWR | O_CREAT | O_EXCL; + mode_t mode = S_IWUSR | S_IREAD | S_IWGRP | S_IRGRP | S_IROTH | S_IWOTH; + mqd_t tempId = mq_open(name, oflag, mode, &attributes); + if (tempId == -1) { + handleOpenError(&attributes, messageDepth); + } else { + // Successful mq_open call + this->id = tempId; + } } MessageQueue::~MessageQueue() { - int status = mq_close(this->id); - if(status != 0){ - utility::printUnixErrorGeneric(CLASS_NAME, "~MessageQueue", "close"); - } - status = mq_unlink(name); - if(status != 0){ - utility::printUnixErrorGeneric(CLASS_NAME, "~MessageQueue", "unlink"); - } + int status = mq_close(this->id); + if (status != 0) { + utility::printUnixErrorGeneric(CLASS_NAME, "~MessageQueue", "close"); + } + status = mq_unlink(name); + if (status != 0) { + utility::printUnixErrorGeneric(CLASS_NAME, "~MessageQueue", "unlink"); + } } -ReturnValue_t MessageQueue::sendMessage(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, bool ignoreFault) { - return sendMessageFrom(sendTo, message, this->getId(), false); +ReturnValue_t MessageQueue::sendMessage(MessageQueueId_t sendTo, MessageQueueMessageIF* message, + bool ignoreFault) { + return sendMessageFrom(sendTo, message, this->getId(), false); } ReturnValue_t MessageQueue::sendToDefault(MessageQueueMessageIF* message) { - return sendToDefaultFrom(message, this->getId()); + return sendToDefaultFrom(message, this->getId()); } ReturnValue_t MessageQueue::reply(MessageQueueMessageIF* message) { - if (this->lastPartner != 0) { - return sendMessageFrom(this->lastPartner, message, this->getId()); - } else { - return NO_REPLY_PARTNER; - } + if (this->lastPartner != 0) { + return sendMessageFrom(this->lastPartner, message, this->getId()); + } else { + return NO_REPLY_PARTNER; + } } ReturnValue_t MessageQueue::receiveMessage(MessageQueueMessageIF* message, - MessageQueueId_t* receivedFrom) { - ReturnValue_t status = this->receiveMessage(message); - *receivedFrom = this->lastPartner; - return status; + MessageQueueId_t* receivedFrom) { + ReturnValue_t status = this->receiveMessage(message); + *receivedFrom = this->lastPartner; + return status; } ReturnValue_t MessageQueue::receiveMessage(MessageQueueMessageIF* message) { - if(message == nullptr) { + if (message == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "MessageQueue::receiveMessage: Message is " - "nullptr!" << std::endl; + sif::error << "MessageQueue::receiveMessage: Message is " + "nullptr!" + << std::endl; #endif - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; + } - if(message->getMaximumMessageSize() < maxMessageSize) { + if (message->getMaximumMessageSize() < maxMessageSize) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "MessageQueue::receiveMessage: Message size " - << message->getMaximumMessageSize() - << " too small to receive data!" << std::endl; + sif::error << "MessageQueue::receiveMessage: Message size " << message->getMaximumMessageSize() + << " too small to receive data!" << std::endl; #endif - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; + } - unsigned int messagePriority = 0; - int status = mq_receive(id,reinterpret_cast(message->getBuffer()), - message->getMaximumMessageSize(),&messagePriority); - if (status > 0) { - this->lastPartner = message->getSender(); - //Check size of incoming message. - if (message->getMessageSize() < message->getMinimumMessageSize()) { - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; - } - else if (status==0) { - //Success but no message received - return MessageQueueIF::EMPTY; - } - else { - //No message was received. Keep lastPartner anyway, I might send - //something later. But still, delete packet content. - memset(message->getData(), 0, message->getMaximumDataSize()); - switch(errno){ - case EAGAIN: - //O_NONBLOCK or MQ_NONBLOCK was set and there are no messages - //currently on the specified queue. - return MessageQueueIF::EMPTY; - case EBADF: { - //mqdes doesn't represent a valid queue open for reading. - utility::printUnixErrorGeneric(CLASS_NAME, "receiveMessage", "EBADF"); - break; - } - case EINVAL: { - /* - * This value indicates one of the following: - * - The pointer to the buffer for storing the received message, - * msg_ptr, is NULL. - * - The number of bytes requested, msg_len is less than zero. - * - msg_len is anything other than the mq_msgsize of the specified - * queue, and the QNX extended option MQ_READBUF_DYNAMIC hasn't - * been set in the queue's mq_flags. - */ - utility::printUnixErrorGeneric(CLASS_NAME, "receiveMessage", "EINVAL"); - break; - } - case EMSGSIZE: { - /* - * This value indicates one of the following: - * - the QNX extended option MQ_READBUF_DYNAMIC hasn't been set, - * and the given msg_len is shorter than the mq_msgsize for - * the given queue. - * - the extended option MQ_READBUF_DYNAMIC has been set, but the - * given msg_len is too short for the message that would have - * been received. - */ - utility::printUnixErrorGeneric(CLASS_NAME, "receiveMessage", "EMSGSIZE"); - break; - } - - case EINTR: { - //The operation was interrupted by a signal. - utility::printUnixErrorGeneric(CLASS_NAME, "receiveMessage", "EINTR"); - break; - } - case ETIMEDOUT: { - //The operation was interrupted by a signal. - utility::printUnixErrorGeneric(CLASS_NAME, "receiveMessage", "ETIMEDOUT"); - break; - } - - default: - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_FAILED; - } -} - -MessageQueueId_t MessageQueue::getLastPartner() const { - return this->lastPartner; -} - -ReturnValue_t MessageQueue::flush(uint32_t* count) { - mq_attr attrib; - int status = mq_getattr(id,&attrib); - if(status != 0){ - switch(errno){ - case EBADF: - //mqdes doesn't represent a valid message queue. - utility::printUnixErrorGeneric(CLASS_NAME, "flush", "EBADF"); - break; - /*NO BREAK*/ - case EINVAL: - //mq_attr is NULL - utility::printUnixErrorGeneric(CLASS_NAME, "flush", "EINVAL"); - break; - default: - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_FAILED; - } - *count = attrib.mq_curmsgs; - attrib.mq_curmsgs = 0; - status = mq_setattr(id,&attrib,NULL); - if(status != 0){ - switch(errno) { - case EBADF: - //mqdes doesn't represent a valid message queue. - utility::printUnixErrorGeneric(CLASS_NAME, "flush", "EBADF"); - break; - case EINVAL: - /* - * This value indicates one of the following: - * - mq_attr is NULL. - * - MQ_MULT_NOTIFY had been set for this queue, and the given - * mq_flags includes a 0 in the MQ_MULT_NOTIFY bit. Once - * MQ_MULT_NOTIFY has been turned on, it may never be turned off. - */ - utility::printUnixErrorGeneric(CLASS_NAME, "flush", "EINVAL"); - break; - default: - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_FAILED; + unsigned int messagePriority = 0; + int status = mq_receive(id, reinterpret_cast(message->getBuffer()), + message->getMaximumMessageSize(), &messagePriority); + if (status > 0) { + this->lastPartner = message->getSender(); + // Check size of incoming message. + if (message->getMessageSize() < message->getMinimumMessageSize()) { + return HasReturnvaluesIF::RETURN_FAILED; } return HasReturnvaluesIF::RETURN_OK; + } else if (status == 0) { + // Success but no message received + return MessageQueueIF::EMPTY; + } else { + // No message was received. Keep lastPartner anyway, I might send + // something later. But still, delete packet content. + memset(message->getData(), 0, message->getMaximumDataSize()); + switch (errno) { + case EAGAIN: + // O_NONBLOCK or MQ_NONBLOCK was set and there are no messages + // currently on the specified queue. + return MessageQueueIF::EMPTY; + case EBADF: { + // mqdes doesn't represent a valid queue open for reading. + utility::printUnixErrorGeneric(CLASS_NAME, "receiveMessage", "EBADF"); + break; + } + case EINVAL: { + /* + * This value indicates one of the following: + * - The pointer to the buffer for storing the received message, + * msg_ptr, is NULL. + * - The number of bytes requested, msg_len is less than zero. + * - msg_len is anything other than the mq_msgsize of the specified + * queue, and the QNX extended option MQ_READBUF_DYNAMIC hasn't + * been set in the queue's mq_flags. + */ + utility::printUnixErrorGeneric(CLASS_NAME, "receiveMessage", "EINVAL"); + break; + } + case EMSGSIZE: { + /* + * This value indicates one of the following: + * - the QNX extended option MQ_READBUF_DYNAMIC hasn't been set, + * and the given msg_len is shorter than the mq_msgsize for + * the given queue. + * - the extended option MQ_READBUF_DYNAMIC has been set, but the + * given msg_len is too short for the message that would have + * been received. + */ + utility::printUnixErrorGeneric(CLASS_NAME, "receiveMessage", "EMSGSIZE"); + break; + } + + case EINTR: { + // The operation was interrupted by a signal. + utility::printUnixErrorGeneric(CLASS_NAME, "receiveMessage", "EINTR"); + break; + } + case ETIMEDOUT: { + // The operation was interrupted by a signal. + utility::printUnixErrorGeneric(CLASS_NAME, "receiveMessage", "ETIMEDOUT"); + break; + } + + default: + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_FAILED; + } } -MessageQueueId_t MessageQueue::getId() const { - return this->id; +MessageQueueId_t MessageQueue::getLastPartner() const { return this->lastPartner; } + +ReturnValue_t MessageQueue::flush(uint32_t* count) { + mq_attr attrib; + int status = mq_getattr(id, &attrib); + if (status != 0) { + switch (errno) { + case EBADF: + // mqdes doesn't represent a valid message queue. + utility::printUnixErrorGeneric(CLASS_NAME, "flush", "EBADF"); + break; + /*NO BREAK*/ + case EINVAL: + // mq_attr is NULL + utility::printUnixErrorGeneric(CLASS_NAME, "flush", "EINVAL"); + break; + default: + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_FAILED; + } + *count = attrib.mq_curmsgs; + attrib.mq_curmsgs = 0; + status = mq_setattr(id, &attrib, NULL); + if (status != 0) { + switch (errno) { + case EBADF: + // mqdes doesn't represent a valid message queue. + utility::printUnixErrorGeneric(CLASS_NAME, "flush", "EBADF"); + break; + case EINVAL: + /* + * This value indicates one of the following: + * - mq_attr is NULL. + * - MQ_MULT_NOTIFY had been set for this queue, and the given + * mq_flags includes a 0 in the MQ_MULT_NOTIFY bit. Once + * MQ_MULT_NOTIFY has been turned on, it may never be turned off. + */ + utility::printUnixErrorGeneric(CLASS_NAME, "flush", "EINVAL"); + break; + default: + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } +MessageQueueId_t MessageQueue::getId() const { return this->id; } + void MessageQueue::setDefaultDestination(MessageQueueId_t defaultDestination) { - this->defaultDestination = defaultDestination; + this->defaultDestination = defaultDestination; } ReturnValue_t MessageQueue::sendToDefaultFrom(MessageQueueMessageIF* message, - MessageQueueId_t sentFrom, bool ignoreFault) { - return sendMessageFrom(defaultDestination, message, sentFrom, ignoreFault); + MessageQueueId_t sentFrom, bool ignoreFault) { + return sendMessageFrom(defaultDestination, message, sentFrom, ignoreFault); } - -ReturnValue_t MessageQueue::sendMessageFrom(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, MessageQueueId_t sentFrom, - bool ignoreFault) { - return sendMessageFromMessageQueue(sendTo,message, sentFrom,ignoreFault); - +ReturnValue_t MessageQueue::sendMessageFrom(MessageQueueId_t sendTo, MessageQueueMessageIF* message, + MessageQueueId_t sentFrom, bool ignoreFault) { + return sendMessageFromMessageQueue(sendTo, message, sentFrom, ignoreFault); } -MessageQueueId_t MessageQueue::getDefaultDestination() const { - return this->defaultDestination; -} +MessageQueueId_t MessageQueue::getDefaultDestination() const { return this->defaultDestination; } -bool MessageQueue::isDefaultDestinationSet() const { - return (defaultDestination != NO_QUEUE); -} +bool MessageQueue::isDefaultDestinationSet() const { return (defaultDestination != NO_QUEUE); } uint16_t MessageQueue::queueCounter = 0; ReturnValue_t MessageQueue::sendMessageFromMessageQueue(MessageQueueId_t sendTo, - MessageQueueMessageIF *message, MessageQueueId_t sentFrom, - bool ignoreFault) { - if(message == nullptr) { + MessageQueueMessageIF* message, + MessageQueueId_t sentFrom, + bool ignoreFault) { + if (message == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "MessageQueue::sendMessageFromMessageQueue: Message is nullptr!" << std::endl; + sif::error << "MessageQueue::sendMessageFromMessageQueue: Message is nullptr!" << std::endl; #else - sif::printError("MessageQueue::sendMessageFromMessageQueue: Message is nullptr!\n"); + sif::printError("MessageQueue::sendMessageFromMessageQueue: Message is nullptr!\n"); #endif + return HasReturnvaluesIF::RETURN_FAILED; + } + + message->setSender(sentFrom); + int result = mq_send(sendTo, reinterpret_cast(message->getBuffer()), + message->getMessageSize(), 0); + + // TODO: Check if we're in ISR. + if (result != 0) { + if (!ignoreFault) { + InternalErrorReporterIF* internalErrorReporter = + ObjectManager::instance()->get(objects::INTERNAL_ERROR_REPORTER); + if (internalErrorReporter != NULL) { + internalErrorReporter->queueMessageNotSent(); + } + } + switch (errno) { + case EAGAIN: + // The O_NONBLOCK flag was set when opening the queue, or the + // MQ_NONBLOCK flag was set in its attributes, and the + // specified queue is full. + return MessageQueueIF::FULL; + case EBADF: { + // mq_des doesn't represent a valid message queue descriptor, + // or mq_des wasn't opened for writing. + + utility::printUnixErrorGeneric(CLASS_NAME, "sendMessageFromMessageQueue", "EBADF"); +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "mq_send to " << sendTo << " sent from " << sentFrom << " failed" + << std::endl; +#else + sif::printWarning("mq_send to %d sent from %d failed\n", sendTo, sentFrom); +#endif + return DESTINATION_INVALID; + } + case EINTR: + // The call was interrupted by a signal. + utility::printUnixErrorGeneric(CLASS_NAME, "sendMessageFromMessageQueue", "EINTR"); + break; + case EINVAL: + /* + * This value indicates one of the following: + * - msg_ptr is NULL. + * - msg_len is negative. + * - msg_prio is greater than MQ_PRIO_MAX. + * - msg_prio is less than 0. + * - MQ_PRIO_RESTRICT is set in the mq_attr of mq_des, and + * msg_prio is greater than the priority of the calling process. + */ + utility::printUnixErrorGeneric(CLASS_NAME, "sendMessageFromMessageQueue", "EINVAL"); + break; + case EMSGSIZE: + // The msg_len is greater than the msgsize associated with + // the specified queue. + utility::printUnixErrorGeneric(CLASS_NAME, "sendMessageFromMessageQueue", "EMSGSIZE"); + break; + default: return HasReturnvaluesIF::RETURN_FAILED; } - - message->setSender(sentFrom); - int result = mq_send(sendTo, - reinterpret_cast(message->getBuffer()), - message->getMessageSize(),0); - - //TODO: Check if we're in ISR. - if (result != 0) { - if(!ignoreFault){ - InternalErrorReporterIF* internalErrorReporter = ObjectManager::instance()-> - get(objects::INTERNAL_ERROR_REPORTER); - if (internalErrorReporter != NULL) { - internalErrorReporter->queueMessageNotSent(); - } - } - switch(errno){ - case EAGAIN: - //The O_NONBLOCK flag was set when opening the queue, or the - //MQ_NONBLOCK flag was set in its attributes, and the - //specified queue is full. - return MessageQueueIF::FULL; - case EBADF: { - //mq_des doesn't represent a valid message queue descriptor, - //or mq_des wasn't opened for writing. - - utility::printUnixErrorGeneric(CLASS_NAME, "sendMessageFromMessageQueue", "EBADF"); -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "mq_send to " << sendTo << " sent from " - << sentFrom << " failed" << std::endl; -#else - sif::printWarning("mq_send to %d sent from %d failed\n", sendTo, sentFrom); -#endif - return DESTINATION_INVALID; - } - case EINTR: - //The call was interrupted by a signal. - utility::printUnixErrorGeneric(CLASS_NAME, "sendMessageFromMessageQueue", "EINTR"); - break; - case EINVAL: - /* - * This value indicates one of the following: - * - msg_ptr is NULL. - * - msg_len is negative. - * - msg_prio is greater than MQ_PRIO_MAX. - * - msg_prio is less than 0. - * - MQ_PRIO_RESTRICT is set in the mq_attr of mq_des, and - * msg_prio is greater than the priority of the calling process. - */ - utility::printUnixErrorGeneric(CLASS_NAME, "sendMessageFromMessageQueue", "EINVAL"); - break; - case EMSGSIZE: - // The msg_len is greater than the msgsize associated with - //the specified queue. - utility::printUnixErrorGeneric(CLASS_NAME, "sendMessageFromMessageQueue", "EMSGSIZE"); - break; - default: - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t MessageQueue::handleOpenError(mq_attr* attributes, - uint32_t messageDepth) { - switch(errno) { - case(EINVAL): { - utility::printUnixErrorGeneric(CLASS_NAME, "MessageQueue", "EINVAL"); - size_t defaultMqMaxMsg = 0; - // Not POSIX conformant, but should work for all UNIX systems. - // Just an additional helpful printout :-) - if(std::ifstream("/proc/sys/fs/mqueue/msg_max",std::ios::in) >> - defaultMqMaxMsg and defaultMqMaxMsg < messageDepth) { - /* - See: https://www.man7.org/linux/man-pages/man3/mq_open.3.html - This happens if the msg_max value is not large enough - It is ignored if the executable is run in privileged mode. - Run the unlockRealtime script or grant the mode manually by using: - sudo setcap 'CAP_SYS_RESOURCE=+ep' +ReturnValue_t MessageQueue::handleOpenError(mq_attr* attributes, uint32_t messageDepth) { + switch (errno) { + case (EINVAL): { + utility::printUnixErrorGeneric(CLASS_NAME, "MessageQueue", "EINVAL"); + size_t defaultMqMaxMsg = 0; + // Not POSIX conformant, but should work for all UNIX systems. + // Just an additional helpful printout :-) + if (std::ifstream("/proc/sys/fs/mqueue/msg_max", std::ios::in) >> defaultMqMaxMsg and + defaultMqMaxMsg < messageDepth) { + /* + See: https://www.man7.org/linux/man-pages/man3/mq_open.3.html + This happens if the msg_max value is not large enough + It is ignored if the executable is run in privileged mode. + Run the unlockRealtime script or grant the mode manually by using: + sudo setcap 'CAP_SYS_RESOURCE=+ep' - Persistent solution for session: - echo | sudo tee /proc/sys/fs/mqueue/msg_max + Persistent solution for session: + echo | sudo tee /proc/sys/fs/mqueue/msg_max - Permanent solution: - sudo nano /etc/sysctl.conf - Append at end: fs/mqueue/msg_max = - Apply changes with: sudo sysctl -p - */ + Permanent solution: + sudo nano /etc/sysctl.conf + Append at end: fs/mqueue/msg_max = + Apply changes with: sudo sysctl -p + */ #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "MessageQueue::MessageQueue: Default MQ size " << defaultMqMaxMsg << - " is too small for requested size " << messageDepth << std::endl; - sif::error << "This error can be fixed by setting the maximum " - "allowed message size higher!" << std::endl; + sif::error << "MessageQueue::MessageQueue: Default MQ size " << defaultMqMaxMsg + << " is too small for requested size " << messageDepth << std::endl; + sif::error << "This error can be fixed by setting the maximum " + "allowed message size higher!" + << std::endl; #else - sif::printError("MessageQueue::MessageQueue: Default MQ size %d is too small for" - "requested size %d\n"); - sif::printError("This error can be fixes by setting the maximum allowed" - "message size higher!\n"); + sif::printError( + "MessageQueue::MessageQueue: Default MQ size %d is too small for" + "requested size %d\n"); + sif::printError( + "This error can be fixes by setting the maximum allowed" + "message size higher!\n"); #endif - } - break; + } + break; } - case(EEXIST): { - // An error occured during open. - // We need to distinguish if it is caused by an already created queue - // There's another queue with the same name - // We unlink the other queue - int status = mq_unlink(name); - if (status != 0) { - utility::printUnixErrorGeneric(CLASS_NAME, "MessageQueue", "EEXIST"); + case (EEXIST): { + // An error occured during open. + // We need to distinguish if it is caused by an already created queue + // There's another queue with the same name + // We unlink the other queue + int status = mq_unlink(name); + if (status != 0) { + utility::printUnixErrorGeneric(CLASS_NAME, "MessageQueue", "EEXIST"); + } else { + // Successful unlinking, try to open again + mqd_t tempId = mq_open(name, O_NONBLOCK | O_RDWR | O_CREAT | O_EXCL, + S_IWUSR | S_IREAD | S_IWGRP | S_IRGRP, attributes); + if (tempId != -1) { + // Successful mq_open + this->id = tempId; + return HasReturnvaluesIF::RETURN_OK; } - else { - // Successful unlinking, try to open again - mqd_t tempId = mq_open(name, - O_NONBLOCK | O_RDWR | O_CREAT | O_EXCL, - S_IWUSR | S_IREAD | S_IWGRP | S_IRGRP, attributes); - if (tempId != -1) { - //Successful mq_open - this->id = tempId; - return HasReturnvaluesIF::RETURN_OK; - } - } - break; + } + break; } default: { - // Failed either the first time or the second time - utility::printUnixErrorGeneric(CLASS_NAME, "MessageQueue", "Unknown"); + // Failed either the first time or the second time + utility::printUnixErrorGeneric(CLASS_NAME, "MessageQueue", "Unknown"); } - } - return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_FAILED; } diff --git a/src/fsfw/osal/linux/MessageQueue.h b/src/fsfw/osal/linux/MessageQueue.h index cf0ac10c..dbf6555e 100644 --- a/src/fsfw/osal/linux/MessageQueue.h +++ b/src/fsfw/osal/linux/MessageQueue.h @@ -1,11 +1,11 @@ #ifndef FSFW_OSAL_LINUX_MESSAGEQUEUE_H_ #define FSFW_OSAL_LINUX_MESSAGEQUEUE_H_ +#include + #include "fsfw/internalerror/InternalErrorReporterIF.h" #include "fsfw/ipc/MessageQueueIF.h" #include "fsfw/ipc/MessageQueueMessage.h" - -#include /** * @brief This class manages sending and receiving of message queue messages. * @@ -26,163 +26,169 @@ * @ingroup message_queue */ class MessageQueue : public MessageQueueIF { - friend class MessageQueueSenderIF; -public: - /** - * @brief The constructor initializes and configures the message queue. - * @details By making use of the according operating system call, a message queue is created - * and initialized. The message depth - the maximum number of messages to be - * buffered - may be set with the help of a parameter, whereas the message size is - * automatically set to the maximum message queue message size. The operating system - * sets the message queue id, or i case of failure, it is set to zero. - * @param message_depth The number of messages to be buffered before passing an error to the - * sender. Default is three. - * @param max_message_size With this parameter, the maximum message size can be adjusted. - * This should be left default. - */ - MessageQueue(uint32_t messageDepth = 3, - size_t maxMessageSize = MessageQueueMessage::MAX_MESSAGE_SIZE ); - /** - * @brief The destructor deletes the formerly created message queue. - * @details This is accomplished by using the delete call provided by the operating system. - */ - virtual ~MessageQueue(); - /** - * @brief This operation sends a message to the given destination. - * @details It directly uses the sendMessage call of the MessageQueueSender parent, but passes its - * queue id as "sentFrom" parameter. - * @param sendTo This parameter specifies the message queue id of the destination message queue. - * @param message A pointer to a previously created message, which is sent. - * @param ignoreFault If set to true, the internal software fault counter is not incremented if queue is full. - */ - virtual ReturnValue_t sendMessage(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, bool ignoreFault = false ); - /** - * @brief This operation sends a message to the default destination. - * @details As in the sendMessage method, this function uses the sendToDefault call of the - * MessageQueueSender parent class and adds its queue id as "sentFrom" information. - * @param message A pointer to a previously created message, which is sent. - */ - virtual ReturnValue_t sendToDefault( MessageQueueMessageIF* message ); - /** - * @brief This operation sends a message to the last communication partner. - * @details This operation simplifies answering an incoming message by using the stored - * lastParnter information as destination. If there was no message received yet - * (i.e. lastPartner is zero), an error code is returned. - * @param message A pointer to a previously created message, which is sent. - */ - ReturnValue_t reply( MessageQueueMessageIF* message ); + friend class MessageQueueSenderIF; - /** - * @brief This function reads available messages from the message queue and returns the sender. - * @details It works identically to the other receiveMessage call, but in addition returns the - * sender's queue id. - * @param message A pointer to a message in which the received data is stored. - * @param receivedFrom A pointer to a queue id in which the sender's id is stored. - */ - ReturnValue_t receiveMessage(MessageQueueMessageIF* message, - MessageQueueId_t *receivedFrom); + public: + /** + * @brief The constructor initializes and configures the message queue. + * @details By making use of the according operating system call, a message queue is created + * and initialized. The message depth - the maximum number of messages to be + * buffered - may be set with the help of a parameter, whereas the message size + * is automatically set to the maximum message queue message size. The operating system sets the + * message queue id, or i case of failure, it is set to zero. + * @param message_depth The number of messages to be buffered before passing an error to the + * sender. Default is three. + * @param max_message_size With this parameter, the maximum message size can be adjusted. + * This should be left default. + */ + MessageQueue(uint32_t messageDepth = 3, + size_t maxMessageSize = MessageQueueMessage::MAX_MESSAGE_SIZE); + /** + * @brief The destructor deletes the formerly created message queue. + * @details This is accomplished by using the delete call provided by the operating system. + */ + virtual ~MessageQueue(); + /** + * @brief This operation sends a message to the given destination. + * @details It directly uses the sendMessage call of the MessageQueueSender parent, but passes + * its queue id as "sentFrom" parameter. + * @param sendTo This parameter specifies the message queue id of the destination message + * queue. + * @param message A pointer to a previously created message, which is sent. + * @param ignoreFault If set to true, the internal software fault counter is not incremented if + * queue is full. + */ + virtual ReturnValue_t sendMessage(MessageQueueId_t sendTo, MessageQueueMessageIF* message, + bool ignoreFault = false); + /** + * @brief This operation sends a message to the default destination. + * @details As in the sendMessage method, this function uses the sendToDefault call of the + * MessageQueueSender parent class and adds its queue id as "sentFrom" + * information. + * @param message A pointer to a previously created message, which is sent. + */ + virtual ReturnValue_t sendToDefault(MessageQueueMessageIF* message); + /** + * @brief This operation sends a message to the last communication partner. + * @details This operation simplifies answering an incoming message by using the stored + * lastParnter information as destination. If there was no message received yet + * (i.e. lastPartner is zero), an error code is returned. + * @param message A pointer to a previously created message, which is sent. + */ + ReturnValue_t reply(MessageQueueMessageIF* message); - /** - * @brief This function reads available messages from the message queue. - * @details If data is available it is stored in the passed message pointer. The message's - * original content is overwritten and the sendFrom information is stored in the - * lastPartner attribute. Else, the lastPartner information remains untouched, the - * message's content is cleared and the function returns immediately. - * @param message A pointer to a message in which the received data is stored. - */ - ReturnValue_t receiveMessage(MessageQueueMessageIF* message); - /** - * Deletes all pending messages in the queue. - * @param count The number of flushed messages. - * @return RETURN_OK on success. - */ - ReturnValue_t flush(uint32_t* count); - /** - * @brief This method returns the message queue id of the last communication partner. - */ - MessageQueueId_t getLastPartner() const; - /** - * @brief This method returns the message queue id of this class's message queue. - */ - MessageQueueId_t getId() const; - /** - * \brief With the sendMessage call, a queue message is sent to a receiving queue. - * \param sendTo This parameter specifies the message queue id to send the message to. - * \param message This is a pointer to a previously created message, which is sent. - * \param sentFrom The sentFrom information can be set to inject the sender's queue id into the message. - * This variable is set to zero by default. - * \param ignoreFault If set to true, the internal software fault counter is not incremented if queue is full. - */ - virtual ReturnValue_t sendMessageFrom( MessageQueueId_t sendTo, - MessageQueueMessageIF* message, MessageQueueId_t sentFrom, - bool ignoreFault = false ); - /** - * \brief The sendToDefault method sends a queue message to the default destination. - * \details In all other aspects, it works identical to the sendMessage method. - * \param message This is a pointer to a previously created message, which is sent. - * \param sentFrom The sentFrom information can be set to inject the sender's queue id into the message. - * This variable is set to zero by default. - */ - virtual ReturnValue_t sendToDefaultFrom( MessageQueueMessageIF* message, - MessageQueueId_t sentFrom = NO_QUEUE, bool ignoreFault = false ); - /** - * \brief This method is a simple setter for the default destination. - */ - void setDefaultDestination(MessageQueueId_t defaultDestination); - /** - * \brief This method is a simple getter for the default destination. - */ - MessageQueueId_t getDefaultDestination() const; + /** + * @brief This function reads available messages from the message queue and returns the + * sender. + * @details It works identically to the other receiveMessage call, but in addition returns the + * sender's queue id. + * @param message A pointer to a message in which the received data is stored. + * @param receivedFrom A pointer to a queue id in which the sender's id is stored. + */ + ReturnValue_t receiveMessage(MessageQueueMessageIF* message, MessageQueueId_t* receivedFrom); - bool isDefaultDestinationSet() const; -protected: - /** - * Implementation to be called from any send Call within MessageQueue and MessageQueueSenderIF - * \details This method takes the message provided, adds the sentFrom information and passes - * it on to the destination provided with an operating system call. The OS's return - * value is returned. - * \param sendTo This parameter specifies the message queue id to send the message to. - * \param message This is a pointer to a previously created message, which is sent. - * \param sentFrom The sentFrom information can be set to inject the sender's queue id into the message. - * This variable is set to zero by default. - * \param ignoreFault If set to true, the internal software fault counter is not incremented if queue is full. - */ - static ReturnValue_t sendMessageFromMessageQueue(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, MessageQueueId_t sentFrom = NO_QUEUE, - bool ignoreFault=false); -private: - /** - * @brief The class stores the queue id it got assigned from the operating system in this attribute. - * If initialization fails, the queue id is set to zero. - */ - MessageQueueId_t id; - /** - * @brief In this attribute, the queue id of the last communication partner is stored - * to allow for replying. - */ - MessageQueueId_t lastPartner; - /** - * @brief The message queue's name -a user specific information for the operating system- is - * generated automatically with the help of this static counter. - */ - /** - * \brief This attribute stores a default destination to send messages to. - * \details It is stored to simplify sending to always-the-same receiver. The attribute may - * be set in the constructor or by a setter call to setDefaultDestination. - */ - MessageQueueId_t defaultDestination; + /** + * @brief This function reads available messages from the message queue. + * @details If data is available it is stored in the passed message pointer. The message's + * original content is overwritten and the sendFrom information is stored in + * the lastPartner attribute. Else, the lastPartner information remains untouched, the message's + * content is cleared and the function returns immediately. + * @param message A pointer to a message in which the received data is stored. + */ + ReturnValue_t receiveMessage(MessageQueueMessageIF* message); + /** + * Deletes all pending messages in the queue. + * @param count The number of flushed messages. + * @return RETURN_OK on success. + */ + ReturnValue_t flush(uint32_t* count); + /** + * @brief This method returns the message queue id of the last communication partner. + */ + MessageQueueId_t getLastPartner() const; + /** + * @brief This method returns the message queue id of this class's message queue. + */ + MessageQueueId_t getId() const; + /** + * \brief With the sendMessage call, a queue message is sent to a receiving queue. + * \param sendTo This parameter specifies the message queue id to send the message to. + * \param message This is a pointer to a previously created message, which is sent. + * \param sentFrom The sentFrom information can be set to inject the sender's queue id into the + * message. This variable is set to zero by default. \param ignoreFault If set to true, the + * internal software fault counter is not incremented if queue is full. + */ + virtual ReturnValue_t sendMessageFrom(MessageQueueId_t sendTo, MessageQueueMessageIF* message, + MessageQueueId_t sentFrom, bool ignoreFault = false); + /** + * \brief The sendToDefault method sends a queue message to the default destination. + * \details In all other aspects, it works identical to the sendMessage method. + * \param message This is a pointer to a previously created message, which is sent. + * \param sentFrom The sentFrom information can be set to inject the sender's queue id into the + * message. This variable is set to zero by default. + */ + virtual ReturnValue_t sendToDefaultFrom(MessageQueueMessageIF* message, + MessageQueueId_t sentFrom = NO_QUEUE, + bool ignoreFault = false); + /** + * \brief This method is a simple setter for the default destination. + */ + void setDefaultDestination(MessageQueueId_t defaultDestination); + /** + * \brief This method is a simple getter for the default destination. + */ + MessageQueueId_t getDefaultDestination() const; - /** - * The name of the message queue, stored for unlinking - */ - char name[16]; + bool isDefaultDestinationSet() const; - static uint16_t queueCounter; - const size_t maxMessageSize; + protected: + /** + * Implementation to be called from any send Call within MessageQueue and MessageQueueSenderIF + * \details This method takes the message provided, adds the sentFrom information and + * passes it on to the destination provided with an operating system call. The OS's return value + * is returned. \param sendTo This parameter specifies the message queue id to send the message + * to. \param message This is a pointer to a previously created message, which is sent. \param + * sentFrom The sentFrom information can be set to inject the sender's queue id into the + * message. This variable is set to zero by default. \param ignoreFault If set to true, the + * internal software fault counter is not incremented if queue is full. + */ + static ReturnValue_t sendMessageFromMessageQueue(MessageQueueId_t sendTo, + MessageQueueMessageIF* message, + MessageQueueId_t sentFrom = NO_QUEUE, + bool ignoreFault = false); - static constexpr const char* CLASS_NAME = "MessageQueue"; - ReturnValue_t handleOpenError(mq_attr* attributes, uint32_t messageDepth); + private: + /** + * @brief The class stores the queue id it got assigned from the operating system in this + * attribute. If initialization fails, the queue id is set to zero. + */ + MessageQueueId_t id; + /** + * @brief In this attribute, the queue id of the last communication partner is stored + * to allow for replying. + */ + MessageQueueId_t lastPartner; + /** + * @brief The message queue's name -a user specific information for the operating system- is + * generated automatically with the help of this static counter. + */ + /** + * \brief This attribute stores a default destination to send messages to. + * \details It is stored to simplify sending to always-the-same receiver. The attribute may + * be set in the constructor or by a setter call to setDefaultDestination. + */ + MessageQueueId_t defaultDestination; + + /** + * The name of the message queue, stored for unlinking + */ + char name[16]; + + static uint16_t queueCounter; + const size_t maxMessageSize; + + static constexpr const char* CLASS_NAME = "MessageQueue"; + ReturnValue_t handleOpenError(mq_attr* attributes, uint32_t messageDepth); }; #endif /* FSFW_OSAL_LINUX_MESSAGEQUEUE_H_ */ diff --git a/src/fsfw/osal/linux/Mutex.cpp b/src/fsfw/osal/linux/Mutex.cpp index 7391c6b5..2698fb54 100644 --- a/src/fsfw/osal/linux/Mutex.cpp +++ b/src/fsfw/osal/linux/Mutex.cpp @@ -1,110 +1,110 @@ #include "fsfw/osal/linux/Mutex.h" -#include "fsfw/osal/linux/unixUtility.h" -#include "fsfw/serviceinterface/ServiceInterface.h" -#include "fsfw/timemanager/Clock.h" +#include #include -#include + +#include "fsfw/osal/linux/unixUtility.h" +#include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/timemanager/Clock.h" uint8_t Mutex::count = 0; Mutex::Mutex() { - pthread_mutexattr_t mutexAttr; - int status = pthread_mutexattr_init(&mutexAttr); - if (status != 0) { - utility::printUnixErrorGeneric("Mutex", "Mutex", "pthread_mutexattr_init"); - } - status = pthread_mutexattr_setprotocol(&mutexAttr, PTHREAD_PRIO_INHERIT); - if (status != 0) { - utility::printUnixErrorGeneric("Mutex", "Mutex", "pthread_mutexattr_setprotocol"); - } - status = pthread_mutex_init(&mutex, &mutexAttr); - if (status != 0) { - utility::printUnixErrorGeneric("Mutex", "Mutex", "pthread_mutex_init"); - } - // After a mutex attributes object has been used to initialize one or more - // mutexes, any function affecting the attributes object - // (including destruction) shall not affect any previously initialized mutexes. - status = pthread_mutexattr_destroy(&mutexAttr); - if (status != 0) { - utility::printUnixErrorGeneric("Mutex", "Mutex", "pthread_mutexattr_destroy"); - } + pthread_mutexattr_t mutexAttr; + int status = pthread_mutexattr_init(&mutexAttr); + if (status != 0) { + utility::printUnixErrorGeneric("Mutex", "Mutex", "pthread_mutexattr_init"); + } + status = pthread_mutexattr_setprotocol(&mutexAttr, PTHREAD_PRIO_INHERIT); + if (status != 0) { + utility::printUnixErrorGeneric("Mutex", "Mutex", "pthread_mutexattr_setprotocol"); + } + status = pthread_mutex_init(&mutex, &mutexAttr); + if (status != 0) { + utility::printUnixErrorGeneric("Mutex", "Mutex", "pthread_mutex_init"); + } + // After a mutex attributes object has been used to initialize one or more + // mutexes, any function affecting the attributes object + // (including destruction) shall not affect any previously initialized mutexes. + status = pthread_mutexattr_destroy(&mutexAttr); + if (status != 0) { + utility::printUnixErrorGeneric("Mutex", "Mutex", "pthread_mutexattr_destroy"); + } } Mutex::~Mutex() { - //No Status check yet - pthread_mutex_destroy(&mutex); + // No Status check yet + pthread_mutex_destroy(&mutex); } ReturnValue_t Mutex::lockMutex(TimeoutType timeoutType, uint32_t timeoutMs) { - int status = 0; + int status = 0; - if(timeoutType == TimeoutType::POLLING) { - status = pthread_mutex_trylock(&mutex); - } - else if (timeoutType == TimeoutType::WAITING) { - timespec timeOut; - clock_gettime(CLOCK_REALTIME, &timeOut); - uint64_t nseconds = timeOut.tv_sec * 1000000000 + timeOut.tv_nsec; - nseconds += timeoutMs * 1000000; - timeOut.tv_sec = nseconds / 1000000000; - timeOut.tv_nsec = nseconds - timeOut.tv_sec * 1000000000; - status = pthread_mutex_timedlock(&mutex, &timeOut); - } - else if(timeoutType == TimeoutType::BLOCKING) { - status = pthread_mutex_lock(&mutex); - } + if (timeoutType == TimeoutType::POLLING) { + status = pthread_mutex_trylock(&mutex); + } else if (timeoutType == TimeoutType::WAITING) { + timespec timeOut; + clock_gettime(CLOCK_REALTIME, &timeOut); + uint64_t nseconds = timeOut.tv_sec * 1000000000 + timeOut.tv_nsec; + nseconds += timeoutMs * 1000000; + timeOut.tv_sec = nseconds / 1000000000; + timeOut.tv_nsec = nseconds - timeOut.tv_sec * 1000000000; + status = pthread_mutex_timedlock(&mutex, &timeOut); + } else if (timeoutType == TimeoutType::BLOCKING) { + status = pthread_mutex_lock(&mutex); + } - switch (status) { - case EINVAL: - // The mutex was created with the protocol attribute having the value - // PTHREAD_PRIO_PROTECT and the calling thread's priority is higher - // than the mutex's current priority ceiling. - return WRONG_ATTRIBUTE_SETTING; - // The process or thread would have blocked, and the abs_timeout - // parameter specified a nanoseconds field value less than zero or - // greater than or equal to 1000 million. - // The value specified by mutex does not refer to an initialized mutex object. - //return MUTEX_NOT_FOUND; - case EBUSY: - // The mutex could not be acquired because it was already locked. - return MUTEX_ALREADY_LOCKED; - case ETIMEDOUT: - // The mutex could not be locked before the specified timeout expired. - return MUTEX_TIMEOUT; - case EAGAIN: - // The mutex could not be acquired because the maximum number of - // recursive locks for mutex has been exceeded. - return MUTEX_MAX_LOCKS; - case EDEADLK: - // A deadlock condition was detected or the current thread - // already owns the mutex. - return CURR_THREAD_ALREADY_OWNS_MUTEX; - case 0: - //Success - return HasReturnvaluesIF::RETURN_OK; - default: - return HasReturnvaluesIF::RETURN_FAILED; - }; + switch (status) { + case EINVAL: + // The mutex was created with the protocol attribute having the value + // PTHREAD_PRIO_PROTECT and the calling thread's priority is higher + // than the mutex's current priority ceiling. + return WRONG_ATTRIBUTE_SETTING; + // The process or thread would have blocked, and the abs_timeout + // parameter specified a nanoseconds field value less than zero or + // greater than or equal to 1000 million. + // The value specified by mutex does not refer to an initialized mutex object. + // return MUTEX_NOT_FOUND; + case EBUSY: + // The mutex could not be acquired because it was already locked. + return MUTEX_ALREADY_LOCKED; + case ETIMEDOUT: + // The mutex could not be locked before the specified timeout expired. + return MUTEX_TIMEOUT; + case EAGAIN: + // The mutex could not be acquired because the maximum number of + // recursive locks for mutex has been exceeded. + return MUTEX_MAX_LOCKS; + case EDEADLK: + // A deadlock condition was detected or the current thread + // already owns the mutex. + return CURR_THREAD_ALREADY_OWNS_MUTEX; + case 0: + // Success + return HasReturnvaluesIF::RETURN_OK; + default: + return HasReturnvaluesIF::RETURN_FAILED; + }; } ReturnValue_t Mutex::unlockMutex() { - int status = pthread_mutex_unlock(&mutex); - switch (status) { - case EINVAL: - //The value specified by mutex does not refer to an initialized mutex object. - return MUTEX_NOT_FOUND; - case EAGAIN: - //The mutex could not be acquired because the maximum number of recursive locks for mutex has been exceeded. - return MUTEX_MAX_LOCKS; - case EPERM: - //The current thread does not own the mutex. - return CURR_THREAD_DOES_NOT_OWN_MUTEX; - case 0: - //Success - return HasReturnvaluesIF::RETURN_OK; - default: - return HasReturnvaluesIF::RETURN_FAILED; - }; + int status = pthread_mutex_unlock(&mutex); + switch (status) { + case EINVAL: + // The value specified by mutex does not refer to an initialized mutex object. + return MUTEX_NOT_FOUND; + case EAGAIN: + // The mutex could not be acquired because the maximum number of recursive locks for mutex has + // been exceeded. + return MUTEX_MAX_LOCKS; + case EPERM: + // The current thread does not own the mutex. + return CURR_THREAD_DOES_NOT_OWN_MUTEX; + case 0: + // Success + return HasReturnvaluesIF::RETURN_OK; + default: + return HasReturnvaluesIF::RETURN_FAILED; + }; } diff --git a/src/fsfw/osal/linux/Mutex.h b/src/fsfw/osal/linux/Mutex.h index cfce407f..69cd0705 100644 --- a/src/fsfw/osal/linux/Mutex.h +++ b/src/fsfw/osal/linux/Mutex.h @@ -1,18 +1,20 @@ #ifndef FSFW_OSAL_LINUX_MUTEX_H_ #define FSFW_OSAL_LINUX_MUTEX_H_ -#include "../../ipc/MutexIF.h" #include +#include "../../ipc/MutexIF.h" + class Mutex : public MutexIF { -public: - Mutex(); - virtual ~Mutex(); - virtual ReturnValue_t lockMutex(TimeoutType timeoutType, uint32_t timeoutMs); - virtual ReturnValue_t unlockMutex(); -private: - pthread_mutex_t mutex; - static uint8_t count; + public: + Mutex(); + virtual ~Mutex(); + virtual ReturnValue_t lockMutex(TimeoutType timeoutType, uint32_t timeoutMs); + virtual ReturnValue_t unlockMutex(); + + private: + pthread_mutex_t mutex; + static uint8_t count; }; #endif /* OS_RTEMS_MUTEX_H_ */ diff --git a/src/fsfw/osal/linux/MutexFactory.cpp b/src/fsfw/osal/linux/MutexFactory.cpp index 373ff7da..ea4692c5 100644 --- a/src/fsfw/osal/linux/MutexFactory.cpp +++ b/src/fsfw/osal/linux/MutexFactory.cpp @@ -1,24 +1,16 @@ -#include "fsfw/osal/linux/Mutex.h" - #include "fsfw/ipc/MutexFactory.h" -//TODO: Different variant than the lazy loading in QueueFactory. What's better and why? +#include "fsfw/osal/linux/Mutex.h" + +// TODO: Different variant than the lazy loading in QueueFactory. What's better and why? MutexFactory* MutexFactory::factoryInstance = new MutexFactory(); -MutexFactory::MutexFactory() { -} +MutexFactory::MutexFactory() {} -MutexFactory::~MutexFactory() { -} +MutexFactory::~MutexFactory() {} -MutexFactory* MutexFactory::instance() { - return MutexFactory::factoryInstance; -} +MutexFactory* MutexFactory::instance() { return MutexFactory::factoryInstance; } -MutexIF* MutexFactory::createMutex() { - return new Mutex(); -} +MutexIF* MutexFactory::createMutex() { return new Mutex(); } -void MutexFactory::deleteMutex(MutexIF* mutex) { - delete mutex; -} +void MutexFactory::deleteMutex(MutexIF* mutex) { delete mutex; } diff --git a/src/fsfw/osal/linux/PeriodicPosixTask.cpp b/src/fsfw/osal/linux/PeriodicPosixTask.cpp index 0603cf6a..ca346670 100644 --- a/src/fsfw/osal/linux/PeriodicPosixTask.cpp +++ b/src/fsfw/osal/linux/PeriodicPosixTask.cpp @@ -1,83 +1,82 @@ #include "fsfw/osal/linux/PeriodicPosixTask.h" -#include "fsfw/objectmanager/ObjectManager.h" -#include "fsfw/tasks/ExecutableObjectIF.h" -#include "fsfw/serviceinterface/ServiceInterface.h" - #include -PeriodicPosixTask::PeriodicPosixTask(const char* name_, int priority_, - size_t stackSize_, uint32_t period_, void(deadlineMissedFunc_)()): - PosixThread(name_, priority_, stackSize_), objectList(), started(false), - periodMs(period_), deadlineMissedFunc(deadlineMissedFunc_) { -} +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/tasks/ExecutableObjectIF.h" + +PeriodicPosixTask::PeriodicPosixTask(const char* name_, int priority_, size_t stackSize_, + uint32_t period_, void(deadlineMissedFunc_)()) + : PosixThread(name_, priority_, stackSize_), + objectList(), + started(false), + periodMs(period_), + deadlineMissedFunc(deadlineMissedFunc_) {} PeriodicPosixTask::~PeriodicPosixTask() { - //Not Implemented + // Not Implemented } void* PeriodicPosixTask::taskEntryPoint(void* arg) { - //The argument is re-interpreted as PollingTask. - PeriodicPosixTask *originalTask(reinterpret_cast(arg)); - //The task's functionality is called. - originalTask->taskFunctionality(); - return NULL; + // The argument is re-interpreted as PollingTask. + PeriodicPosixTask* originalTask(reinterpret_cast(arg)); + // The task's functionality is called. + originalTask->taskFunctionality(); + return NULL; } ReturnValue_t PeriodicPosixTask::addComponent(object_id_t object) { - ExecutableObjectIF* newObject = ObjectManager::instance()->get( - object); - if (newObject == nullptr) { + ExecutableObjectIF* newObject = ObjectManager::instance()->get(object); + if (newObject == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "PeriodicTask::addComponent: Invalid object. Make sure" - << " it implements ExecutableObjectIF!" << std::endl; + sif::error << "PeriodicTask::addComponent: Invalid object. Make sure" + << " it implements ExecutableObjectIF!" << std::endl; #else - sif::printError("PeriodicTask::addComponent: Invalid object. Make sure it " - "implements ExecutableObjectIF!\n"); + sif::printError( + "PeriodicTask::addComponent: Invalid object. Make sure it " + "implements ExecutableObjectIF!\n"); #endif - return HasReturnvaluesIF::RETURN_FAILED; - } - objectList.push_back(newObject); - newObject->setTaskIF(this); + return HasReturnvaluesIF::RETURN_FAILED; + } + objectList.push_back(newObject); + newObject->setTaskIF(this); - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t PeriodicPosixTask::sleepFor(uint32_t ms) { - return PosixThread::sleep((uint64_t)ms*1000000); + return PosixThread::sleep((uint64_t)ms * 1000000); } - ReturnValue_t PeriodicPosixTask::startTask(void) { - started = true; - PosixThread::createTask(&taskEntryPoint,this); - return HasReturnvaluesIF::RETURN_OK; + started = true; + PosixThread::createTask(&taskEntryPoint, this); + return HasReturnvaluesIF::RETURN_OK; } void PeriodicPosixTask::taskFunctionality(void) { - if(not started) { - suspend(); - } + if (not started) { + suspend(); + } - for (auto const &object: objectList) { - object->initializeAfterTaskCreation(); - } + for (auto const& object : objectList) { + object->initializeAfterTaskCreation(); + } - uint64_t lastWakeTime = getCurrentMonotonicTimeMs(); - //The task's "infinite" inner loop is entered. - while (1) { - for (auto const &object: objectList) { - object->performOperation(); - } + uint64_t lastWakeTime = getCurrentMonotonicTimeMs(); + // The task's "infinite" inner loop is entered. + while (1) { + for (auto const& object : objectList) { + object->performOperation(); + } - if(not PosixThread::delayUntil(&lastWakeTime, periodMs)){ - if (this->deadlineMissedFunc != nullptr) { - this->deadlineMissedFunc(); - } - } - } + if (not PosixThread::delayUntil(&lastWakeTime, periodMs)) { + if (this->deadlineMissedFunc != nullptr) { + this->deadlineMissedFunc(); + } + } + } } -uint32_t PeriodicPosixTask::getPeriodMs() const { - return periodMs; -} +uint32_t PeriodicPosixTask::getPeriodMs() const { return periodMs; } diff --git a/src/fsfw/osal/linux/PeriodicPosixTask.h b/src/fsfw/osal/linux/PeriodicPosixTask.h index ffee236b..e2db042d 100644 --- a/src/fsfw/osal/linux/PeriodicPosixTask.h +++ b/src/fsfw/osal/linux/PeriodicPosixTask.h @@ -1,90 +1,90 @@ #ifndef FRAMEWORK_OSAL_LINUX_PERIODICPOSIXTASK_H_ #define FRAMEWORK_OSAL_LINUX_PERIODICPOSIXTASK_H_ -#include "../../tasks/PeriodicTaskIF.h" -#include "../../objectmanager/ObjectManagerIF.h" -#include "PosixThread.h" -#include "../../tasks/ExecutableObjectIF.h" #include -class PeriodicPosixTask: public PosixThread, public PeriodicTaskIF { -public: - /** - * Create a generic periodic task. - * @param name_ - * Name, maximum allowed size of linux is 16 chars, everything else will - * be truncated. - * @param priority_ - * Real-time priority, ranges from 1 to 99 for Linux. - * See: https://man7.org/linux/man-pages/man7/sched.7.html - * @param stackSize_ - * @param period_ - * @param deadlineMissedFunc_ - */ - PeriodicPosixTask(const char* name_, int priority_, size_t stackSize_, - uint32_t period_, void(*deadlineMissedFunc_)()); - virtual ~PeriodicPosixTask(); +#include "../../objectmanager/ObjectManagerIF.h" +#include "../../tasks/ExecutableObjectIF.h" +#include "../../tasks/PeriodicTaskIF.h" +#include "PosixThread.h" - /** - * @brief The method to start the task. - * @details The method starts the task with the respective system call. - * Entry point is the taskEntryPoint method described below. - * The address of the task object is passed as an argument - * to the system call. - */ - ReturnValue_t startTask() override; - /** - * Adds an object to the list of objects to be executed. - * The objects are executed in the order added. - * @param object Id of the object to add. - * @return RETURN_OK on success, RETURN_FAILED if the object could not be added. - */ - ReturnValue_t addComponent(object_id_t object) override; +class PeriodicPosixTask : public PosixThread, public PeriodicTaskIF { + public: + /** + * Create a generic periodic task. + * @param name_ + * Name, maximum allowed size of linux is 16 chars, everything else will + * be truncated. + * @param priority_ + * Real-time priority, ranges from 1 to 99 for Linux. + * See: https://man7.org/linux/man-pages/man7/sched.7.html + * @param stackSize_ + * @param period_ + * @param deadlineMissedFunc_ + */ + PeriodicPosixTask(const char* name_, int priority_, size_t stackSize_, uint32_t period_, + void (*deadlineMissedFunc_)()); + virtual ~PeriodicPosixTask(); - uint32_t getPeriodMs() const override; + /** + * @brief The method to start the task. + * @details The method starts the task with the respective system call. + * Entry point is the taskEntryPoint method described below. + * The address of the task object is passed as an argument + * to the system call. + */ + ReturnValue_t startTask() override; + /** + * Adds an object to the list of objects to be executed. + * The objects are executed in the order added. + * @param object Id of the object to add. + * @return RETURN_OK on success, RETURN_FAILED if the object could not be added. + */ + ReturnValue_t addComponent(object_id_t object) override; - ReturnValue_t sleepFor(uint32_t ms) override; + uint32_t getPeriodMs() const override; -private: - typedef std::vector ObjectList; //!< Typedef for the List of objects. - /** - * @brief This attribute holds a list of objects to be executed. - */ - ObjectList objectList; + ReturnValue_t sleepFor(uint32_t ms) override; - /** - * @brief Flag to indicate that the task was started and is allowed to run - */ - bool started; + private: + typedef std::vector ObjectList; //!< Typedef for the List of objects. + /** + * @brief This attribute holds a list of objects to be executed. + */ + ObjectList objectList; + /** + * @brief Flag to indicate that the task was started and is allowed to run + */ + bool started; - /** - * @brief Period of the task in milliseconds - */ - uint32_t periodMs; - /** - * @brief The function containing the actual functionality of the task. - * @details The method sets and starts - * the task's period, then enters a loop that is repeated indefinitely. Within the loop, all performOperation methods of the added - * objects are called. Afterwards the task will be blocked until the next period. - * On missing the deadline, the deadlineMissedFunction is executed. - */ - virtual void taskFunctionality(void); - /** - * @brief This is the entry point in a new thread. - * - * @details This method, that is the entry point in the new thread and calls taskFunctionality of the child class. - * Needs a valid pointer to the derived class. - */ - static void* taskEntryPoint(void* arg); - /** - * @brief The pointer to the deadline-missed function. - * @details This pointer stores the function that is executed if the task's deadline is missed. - * So, each may react individually on a timing failure. The pointer may be NULL, - * then nothing happens on missing the deadline. The deadline is equal to the next execution - * of the periodic task. - */ - void (*deadlineMissedFunc)(); + /** + * @brief Period of the task in milliseconds + */ + uint32_t periodMs; + /** + * @brief The function containing the actual functionality of the task. + * @details The method sets and starts + * the task's period, then enters a loop that is repeated indefinitely. Within the loop, + * all performOperation methods of the added objects are called. Afterwards the task will be + * blocked until the next period. On missing the deadline, the deadlineMissedFunction is executed. + */ + virtual void taskFunctionality(void); + /** + * @brief This is the entry point in a new thread. + * + * @details This method, that is the entry point in the new thread and calls taskFunctionality + * of the child class. Needs a valid pointer to the derived class. + */ + static void* taskEntryPoint(void* arg); + /** + * @brief The pointer to the deadline-missed function. + * @details This pointer stores the function that is executed if the task's deadline is missed. + * So, each may react individually on a timing failure. The pointer may be + * NULL, then nothing happens on missing the deadline. The deadline is equal to the next execution + * of the periodic task. + */ + void (*deadlineMissedFunc)(); }; #endif /* FRAMEWORK_OSAL_LINUX_PERIODICPOSIXTASK_H_ */ diff --git a/src/fsfw/osal/linux/PosixThread.cpp b/src/fsfw/osal/linux/PosixThread.cpp index 5ca41d73..9fc088ae 100644 --- a/src/fsfw/osal/linux/PosixThread.cpp +++ b/src/fsfw/osal/linux/PosixThread.cpp @@ -1,246 +1,245 @@ #include "fsfw/osal/linux/PosixThread.h" -#include "fsfw/osal/linux/unixUtility.h" -#include "fsfw/serviceinterface/ServiceInterface.h" - -#include #include -PosixThread::PosixThread(const char* name_, int priority_, size_t stackSize_): - thread(0), priority(priority_), stackSize(stackSize_) { - name[0] = '\0'; - std::strncat(name, name_, PTHREAD_MAX_NAMELEN - 1); +#include + +#include "fsfw/osal/linux/unixUtility.h" +#include "fsfw/serviceinterface/ServiceInterface.h" + +PosixThread::PosixThread(const char* name_, int priority_, size_t stackSize_) + : thread(0), priority(priority_), stackSize(stackSize_) { + name[0] = '\0'; + std::strncat(name, name_, PTHREAD_MAX_NAMELEN - 1); } PosixThread::~PosixThread() { - //No deletion and no free of Stack Pointer + // No deletion and no free of Stack Pointer } ReturnValue_t PosixThread::sleep(uint64_t ns) { - //TODO sleep might be better with timer instead of sleep() - timespec time; - time.tv_sec = ns/1000000000; - time.tv_nsec = ns - time.tv_sec*1e9; - - //Remaining Time is not set here - int status = nanosleep(&time,NULL); - if(status != 0){ - switch(errno){ - case EINTR: - //The nanosleep() function was interrupted by a signal. - return HasReturnvaluesIF::RETURN_FAILED; - case EINVAL: - //The rqtp argument specified a nanosecond value less than zero or - // greater than or equal to 1000 million. - return HasReturnvaluesIF::RETURN_FAILED; - default: - return HasReturnvaluesIF::RETURN_FAILED; - } + // TODO sleep might be better with timer instead of sleep() + timespec time; + time.tv_sec = ns / 1000000000; + time.tv_nsec = ns - time.tv_sec * 1e9; + // Remaining Time is not set here + int status = nanosleep(&time, NULL); + if (status != 0) { + switch (errno) { + case EINTR: + // The nanosleep() function was interrupted by a signal. + return HasReturnvaluesIF::RETURN_FAILED; + case EINVAL: + // The rqtp argument specified a nanosecond value less than zero or + // greater than or equal to 1000 million. + return HasReturnvaluesIF::RETURN_FAILED; + default: + return HasReturnvaluesIF::RETURN_FAILED; } - return HasReturnvaluesIF::RETURN_OK; + } + return HasReturnvaluesIF::RETURN_OK; } void PosixThread::suspend() { - //Wait for SIGUSR1 - int caughtSig = 0; - sigset_t waitSignal; - sigemptyset(&waitSignal); - sigaddset(&waitSignal, SIGUSR1); - sigwait(&waitSignal, &caughtSig); - if (caughtSig != SIGUSR1) { + // Wait for SIGUSR1 + int caughtSig = 0; + sigset_t waitSignal; + sigemptyset(&waitSignal); + sigaddset(&waitSignal, SIGUSR1); + sigwait(&waitSignal, &caughtSig); + if (caughtSig != SIGUSR1) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "FixedTimeslotTask::suspend: Unknown Signal received: " << caughtSig << - std::endl; + sif::error << "FixedTimeslotTask::suspend: Unknown Signal received: " << caughtSig << std::endl; #else - sif::printError("FixedTimeslotTask::suspend: Unknown Signal received: %d\n", caughtSig); + sif::printError("FixedTimeslotTask::suspend: Unknown Signal received: %d\n", caughtSig); #endif + } +} + +void PosixThread::resume() { + /* Signal the thread to start. Makes sense to call kill to start or? ;) + * + * According to Posix raise(signal) will call pthread_kill(pthread_self(), sig), + * but as the call must be done from the thread itsself this is not possible here + */ + pthread_kill(thread, SIGUSR1); +} + +bool PosixThread::delayUntil(uint64_t* const prevoiusWakeTime_ms, const uint64_t delayTime_ms) { + uint64_t nextTimeToWake_ms; + bool shouldDelay = false; + // Get current Time + const uint64_t currentTime_ms = getCurrentMonotonicTimeMs(); + /* Generate the tick time at which the task wants to wake. */ + nextTimeToWake_ms = (*prevoiusWakeTime_ms) + delayTime_ms; + + if (currentTime_ms < *prevoiusWakeTime_ms) { + /* The tick count has overflowed since this function was + lasted called. In this case the only time we should ever + actually delay is if the wake time has also overflowed, + and the wake time is greater than the tick time. When this + is the case it is as if neither time had overflowed. */ + if ((nextTimeToWake_ms < *prevoiusWakeTime_ms) && (nextTimeToWake_ms > currentTime_ms)) { + shouldDelay = true; } -} - -void PosixThread::resume(){ - /* Signal the thread to start. Makes sense to call kill to start or? ;) - * - * According to Posix raise(signal) will call pthread_kill(pthread_self(), sig), - * but as the call must be done from the thread itsself this is not possible here - */ - pthread_kill(thread,SIGUSR1); -} - -bool PosixThread::delayUntil(uint64_t* const prevoiusWakeTime_ms, - const uint64_t delayTime_ms) { - uint64_t nextTimeToWake_ms; - bool shouldDelay = false; - //Get current Time - const uint64_t currentTime_ms = getCurrentMonotonicTimeMs(); - /* Generate the tick time at which the task wants to wake. */ - nextTimeToWake_ms = (*prevoiusWakeTime_ms) + delayTime_ms; - - if (currentTime_ms < *prevoiusWakeTime_ms) { - /* The tick count has overflowed since this function was - lasted called. In this case the only time we should ever - actually delay is if the wake time has also overflowed, - and the wake time is greater than the tick time. When this - is the case it is as if neither time had overflowed. */ - if ((nextTimeToWake_ms < *prevoiusWakeTime_ms) - && (nextTimeToWake_ms > currentTime_ms)) { - shouldDelay = true; - } - } else { - /* The tick time has not overflowed. In this case we will - delay if either the wake time has overflowed, and/or the - tick time is less than the wake time. */ - if ((nextTimeToWake_ms < *prevoiusWakeTime_ms) - || (nextTimeToWake_ms > currentTime_ms)) { - shouldDelay = true; - } + } else { + /* The tick time has not overflowed. In this case we will + delay if either the wake time has overflowed, and/or the + tick time is less than the wake time. */ + if ((nextTimeToWake_ms < *prevoiusWakeTime_ms) || (nextTimeToWake_ms > currentTime_ms)) { + shouldDelay = true; } + } - /* Update the wake time ready for the next call. */ + /* Update the wake time ready for the next call. */ - (*prevoiusWakeTime_ms) = nextTimeToWake_ms; - - if (shouldDelay) { - uint64_t sleepTime = nextTimeToWake_ms - currentTime_ms; - PosixThread::sleep(sleepTime * 1000000ull); - return true; - } - //We are shifting the time in case the deadline was missed like rtems - (*prevoiusWakeTime_ms) = currentTime_ms; - return false; + (*prevoiusWakeTime_ms) = nextTimeToWake_ms; + if (shouldDelay) { + uint64_t sleepTime = nextTimeToWake_ms - currentTime_ms; + PosixThread::sleep(sleepTime * 1000000ull); + return true; + } + // We are shifting the time in case the deadline was missed like rtems + (*prevoiusWakeTime_ms) = currentTime_ms; + return false; } +uint64_t PosixThread::getCurrentMonotonicTimeMs() { + timespec timeNow; + clock_gettime(CLOCK_MONOTONIC_RAW, &timeNow); + uint64_t currentTime_ms = (uint64_t)timeNow.tv_sec * 1000 + timeNow.tv_nsec / 1000000; -uint64_t PosixThread::getCurrentMonotonicTimeMs(){ - timespec timeNow; - clock_gettime(CLOCK_MONOTONIC_RAW, &timeNow); - uint64_t currentTime_ms = (uint64_t) timeNow.tv_sec * 1000 - + timeNow.tv_nsec / 1000000; - - return currentTime_ms; + return currentTime_ms; } - void PosixThread::createTask(void* (*fnc_)(void*), void* arg_) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - //sif::debug << "PosixThread::createTask" << std::endl; + // sif::debug << "PosixThread::createTask" << std::endl; #endif - /* - * The attr argument points to a pthread_attr_t structure whose contents - are used at thread creation time to determine attributes for the new - thread; this structure is initialized using pthread_attr_init(3) and - related functions. If attr is NULL, then the thread is created with - default attributes. - */ - pthread_attr_t attributes; - int status = pthread_attr_init(&attributes); - if(status != 0){ - utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_attr_init"); - } - void* stackPointer; - status = posix_memalign(&stackPointer, sysconf(_SC_PAGESIZE), stackSize); - if(status != 0) { - if(errno == ENOMEM) { - size_t stackMb = stackSize/10e6; + /* + * The attr argument points to a pthread_attr_t structure whose contents + are used at thread creation time to determine attributes for the new + thread; this structure is initialized using pthread_attr_init(3) and + related functions. If attr is NULL, then the thread is created with + default attributes. + */ + pthread_attr_t attributes; + int status = pthread_attr_init(&attributes); + if (status != 0) { + utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_attr_init"); + } + void* stackPointer; + status = posix_memalign(&stackPointer, sysconf(_SC_PAGESIZE), stackSize); + if (status != 0) { + if (errno == ENOMEM) { + size_t stackMb = stackSize / 10e6; #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "PosixThread::createTask: Insufficient memory for" - " the requested " << stackMb << " MB" << std::endl; + sif::error << "PosixThread::createTask: Insufficient memory for" + " the requested " + << stackMb << " MB" << std::endl; #else - sif::printError("PosixThread::createTask: Insufficient memory for " - "the requested %lu MB\n", static_cast(stackMb)); + sif::printError( + "PosixThread::createTask: Insufficient memory for " + "the requested %lu MB\n", + static_cast(stackMb)); #endif - utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "ENOMEM"); - } - else if(errno == EINVAL) { + utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "ENOMEM"); + } else if (errno == EINVAL) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "PosixThread::createTask: Wrong alignment argument!" - << std::endl; + sif::error << "PosixThread::createTask: Wrong alignment argument!" << std::endl; #else - sif::printError("PosixThread::createTask: Wrong alignment argument!\n"); + sif::printError("PosixThread::createTask: Wrong alignment argument!\n"); #endif - utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "EINVAL"); - } - return; + utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "EINVAL"); } + return; + } - status = pthread_attr_setstack(&attributes, stackPointer, stackSize); - if(status != 0) { - utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_attr_setstack"); + status = pthread_attr_setstack(&attributes, stackPointer, stackSize); + if (status != 0) { + utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_attr_setstack"); #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "Make sure the specified stack size is valid and is " - "larger than the minimum allowed stack size." << std::endl; + sif::warning << "Make sure the specified stack size is valid and is " + "larger than the minimum allowed stack size." + << std::endl; #else - sif::printWarning("Make sure the specified stack size is valid and is " - "larger than the minimum allowed stack size.\n"); + sif::printWarning( + "Make sure the specified stack size is valid and is " + "larger than the minimum allowed stack size.\n"); #endif - } + } - status = pthread_attr_setinheritsched(&attributes, PTHREAD_EXPLICIT_SCHED); - if(status != 0){ - utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_attr_setinheritsched"); - } + status = pthread_attr_setinheritsched(&attributes, PTHREAD_EXPLICIT_SCHED); + if (status != 0) { + utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_attr_setinheritsched"); + } #ifndef FSFW_USE_REALTIME_FOR_LINUX #error "Please define FSFW_USE_REALTIME_FOR_LINUX with either 0 or 1" #endif #if FSFW_USE_REALTIME_FOR_LINUX == 1 - // FIFO -> This needs root privileges for the process - status = pthread_attr_setschedpolicy(&attributes,SCHED_FIFO); - if(status != 0){ - utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_attr_setschedpolicy"); - } + // FIFO -> This needs root privileges for the process + status = pthread_attr_setschedpolicy(&attributes, SCHED_FIFO); + if (status != 0) { + utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_attr_setschedpolicy"); + } - sched_param scheduleParams; - scheduleParams.__sched_priority = priority; - status = pthread_attr_setschedparam(&attributes, &scheduleParams); - if(status != 0){ - utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_attr_setschedparam"); - } + 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 - sigset_t waitSignal; - sigemptyset(&waitSignal); - sigaddset(&waitSignal, SIGUSR1); - status = pthread_sigmask(SIG_BLOCK, &waitSignal, NULL); - if(status != 0){ - utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_sigmask"); - } + // Set Signal Mask for suspend until startTask is called + sigset_t waitSignal; + sigemptyset(&waitSignal); + sigaddset(&waitSignal, SIGUSR1); + status = pthread_sigmask(SIG_BLOCK, &waitSignal, NULL); + if (status != 0) { + utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_sigmask"); + } - status = pthread_create(&thread,&attributes,fnc_,arg_); - if(status != 0){ - utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_create"); + status = pthread_create(&thread, &attributes, fnc_, arg_); + if (status != 0) { + utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_create"); #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "For FSFW_USE_REALTIME_FOR_LINUX == 1 make sure to call " << - "\"all sudo setcap 'cap_sys_nice=eip'\" on the application or set " - "/etc/security/limit.conf" << std::endl; + sif::error << "For FSFW_USE_REALTIME_FOR_LINUX == 1 make sure to call " + << "\"all sudo setcap 'cap_sys_nice=eip'\" on the application or set " + "/etc/security/limit.conf" + << std::endl; #else - sif::printError("For FSFW_USE_REALTIME_FOR_LINUX == 1 make sure to call " - "\"all sudo setcap 'cap_sys_nice=eip'\" on the application or set " - "/etc/security/limit.conf\n"); + sif::printError( + "For FSFW_USE_REALTIME_FOR_LINUX == 1 make sure to call " + "\"all sudo setcap 'cap_sys_nice=eip'\" on the application or set " + "/etc/security/limit.conf\n"); #endif - } + } - status = pthread_setname_np(thread,name); - if(status != 0){ + status = pthread_setname_np(thread, name); + if (status != 0) { + utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_setname_np"); + if (status == ERANGE) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "PosixThread::createTask: Task name length longer" + " than 16 chars. Truncating.." + << std::endl; +#else + sif::printWarning( + "PosixThread::createTask: Task name length longer" + " than 16 chars. Truncating..\n"); +#endif + name[15] = '\0'; + status = pthread_setname_np(thread, name); + if (status != 0) { utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_setname_np"); - if(status == ERANGE) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "PosixThread::createTask: Task name length longer" - " than 16 chars. Truncating.." << std::endl; -#else - sif::printWarning("PosixThread::createTask: Task name length longer" - " than 16 chars. Truncating..\n"); -#endif - name[15] = '\0'; - status = pthread_setname_np(thread,name); - if(status != 0){ - utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_setname_np"); - } - } + } } + } - status = pthread_attr_destroy(&attributes); - if (status != 0) { - utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_attr_destroy"); - } + status = pthread_attr_destroy(&attributes); + if (status != 0) { + utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_attr_destroy"); + } } diff --git a/src/fsfw/osal/linux/PosixThread.h b/src/fsfw/osal/linux/PosixThread.h index 9c0ad39b..69c6c5b7 100644 --- a/src/fsfw/osal/linux/PosixThread.h +++ b/src/fsfw/osal/linux/PosixThread.h @@ -1,79 +1,81 @@ #ifndef FRAMEWORK_OSAL_LINUX_POSIXTHREAD_H_ #define FRAMEWORK_OSAL_LINUX_POSIXTHREAD_H_ -#include "../../returnvalues/HasReturnvaluesIF.h" #include #include -#include #include +#include + +#include "../../returnvalues/HasReturnvaluesIF.h" + class PosixThread { -public: - static constexpr uint8_t PTHREAD_MAX_NAMELEN = 16; - PosixThread(const char* name_, int priority_, size_t stackSize_); - virtual ~PosixThread(); - /** - * Set the Thread to sleep state - * @param ns Nanosecond sleep time - * @return Returns Failed if sleep fails - */ - static ReturnValue_t sleep(uint64_t ns); - /** - * @brief Function to suspend the task until SIGUSR1 was received - * - * @details Will be called in the beginning to suspend execution until startTask() is called explicitly. - */ - void suspend(); + public: + static constexpr uint8_t PTHREAD_MAX_NAMELEN = 16; + PosixThread(const char* name_, int priority_, size_t stackSize_); + virtual ~PosixThread(); + /** + * Set the Thread to sleep state + * @param ns Nanosecond sleep time + * @return Returns Failed if sleep fails + */ + static ReturnValue_t sleep(uint64_t ns); + /** + * @brief Function to suspend the task until SIGUSR1 was received + * + * @details Will be called in the beginning to suspend execution until startTask() is called + * explicitly. + */ + void suspend(); - /** - * @brief Function to allow a other thread to start the thread again from suspend state - * - * @details Restarts the Thread after suspend call - */ - void resume(); + /** + * @brief Function to allow a other thread to start the thread again from suspend state + * + * @details Restarts the Thread after suspend call + */ + void resume(); + /** + * Delay function similar to FreeRtos delayUntil function + * + * @param prevoiusWakeTime_ms Needs the previous wake time and returns the next wakeup time + * @param delayTime_ms Time period to delay + * + * @return False If deadline was missed; True if task was delayed + */ + static bool delayUntil(uint64_t* const prevoiusWakeTime_ms, const uint64_t delayTime_ms); - /** - * Delay function similar to FreeRtos delayUntil function - * - * @param prevoiusWakeTime_ms Needs the previous wake time and returns the next wakeup time - * @param delayTime_ms Time period to delay - * - * @return False If deadline was missed; True if task was delayed - */ - static bool delayUntil(uint64_t* const prevoiusWakeTime_ms, const uint64_t delayTime_ms); + /** + * Returns the current time in milliseconds from CLOCK_MONOTONIC + * + * @return current time in milliseconds from CLOCK_MONOTONIC + */ + static uint64_t getCurrentMonotonicTimeMs(); - /** - * Returns the current time in milliseconds from CLOCK_MONOTONIC - * - * @return current time in milliseconds from CLOCK_MONOTONIC - */ - static uint64_t getCurrentMonotonicTimeMs(); + protected: + pthread_t thread; -protected: - pthread_t thread; + /** + * @brief Function that has to be called by derived class because the + * derived class pointer has to be valid as argument. + * @details + * This function creates a pthread with the given parameters. As the + * function requires a pointer to the derived object it has to be called + * after the this pointer of the derived object is valid. + * Sets the taskEntryPoint as function to be called by new a thread. + * @param fnc_ Function which will be executed by the thread. + * @param arg_ + * argument of the taskEntryPoint function, needs to be this pointer + * of derived class + */ + void createTask(void* (*fnc_)(void*), void* arg_); - /** - * @brief Function that has to be called by derived class because the - * derived class pointer has to be valid as argument. - * @details - * This function creates a pthread with the given parameters. As the - * function requires a pointer to the derived object it has to be called - * after the this pointer of the derived object is valid. - * Sets the taskEntryPoint as function to be called by new a thread. - * @param fnc_ Function which will be executed by the thread. - * @param arg_ - * argument of the taskEntryPoint function, needs to be this pointer - * of derived class - */ - void createTask(void* (*fnc_)(void*),void* arg_); + private: + char name[PTHREAD_MAX_NAMELEN]; + int priority; + size_t stackSize = 0; -private: - char name[PTHREAD_MAX_NAMELEN]; - int priority; - size_t stackSize = 0; - - static constexpr const char* CLASS_NAME = "PosixThread"; + static constexpr const char* CLASS_NAME = "PosixThread"; }; #endif /* FRAMEWORK_OSAL_LINUX_POSIXTHREAD_H_ */ diff --git a/src/fsfw/osal/linux/QueueFactory.cpp b/src/fsfw/osal/linux/QueueFactory.cpp index 1df26ca9..d1b1cfdb 100644 --- a/src/fsfw/osal/linux/QueueFactory.cpp +++ b/src/fsfw/osal/linux/QueueFactory.cpp @@ -1,42 +1,35 @@ #include "fsfw/ipc/QueueFactory.h" -#include "fsfw/osal/linux/MessageQueue.h" -#include "fsfw/ipc/messageQueueDefinitions.h" -#include "fsfw/ipc/MessageQueueSenderIF.h" - -#include #include +#include #include +#include "fsfw/ipc/MessageQueueSenderIF.h" +#include "fsfw/ipc/messageQueueDefinitions.h" +#include "fsfw/osal/linux/MessageQueue.h" + QueueFactory* QueueFactory::factoryInstance = nullptr; - ReturnValue_t MessageQueueSenderIF::sendMessage(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, MessageQueueId_t sentFrom, - bool ignoreFault) { - return MessageQueue::sendMessageFromMessageQueue(sendTo,message, - sentFrom,ignoreFault); + MessageQueueMessageIF* message, + MessageQueueId_t sentFrom, bool ignoreFault) { + return MessageQueue::sendMessageFromMessageQueue(sendTo, message, sentFrom, ignoreFault); } QueueFactory* QueueFactory::instance() { - if (factoryInstance == nullptr) { - factoryInstance = new QueueFactory; - } - return factoryInstance; + if (factoryInstance == nullptr) { + factoryInstance = new QueueFactory; + } + return factoryInstance; } -QueueFactory::QueueFactory() { +QueueFactory::QueueFactory() {} + +QueueFactory::~QueueFactory() {} + +MessageQueueIF* QueueFactory::createMessageQueue(uint32_t messageDepth, size_t maxMessageSize) { + return new MessageQueue(messageDepth, maxMessageSize); } -QueueFactory::~QueueFactory() { -} - -MessageQueueIF* QueueFactory::createMessageQueue(uint32_t messageDepth, - size_t maxMessageSize) { - return new MessageQueue(messageDepth, maxMessageSize); -} - -void QueueFactory::deleteMessageQueue(MessageQueueIF* queue) { - delete queue; -} +void QueueFactory::deleteMessageQueue(MessageQueueIF* queue) { delete queue; } diff --git a/src/fsfw/osal/linux/SemaphoreFactory.cpp b/src/fsfw/osal/linux/SemaphoreFactory.cpp index 0a0974be..08fa0b2d 100644 --- a/src/fsfw/osal/linux/SemaphoreFactory.cpp +++ b/src/fsfw/osal/linux/SemaphoreFactory.cpp @@ -1,33 +1,28 @@ +#include "fsfw/tasks/SemaphoreFactory.h" + #include "fsfw/osal/linux/BinarySemaphore.h" #include "fsfw/osal/linux/CountingSemaphore.h" -#include "fsfw/tasks/SemaphoreFactory.h" - SemaphoreFactory* SemaphoreFactory::factoryInstance = nullptr; -SemaphoreFactory::SemaphoreFactory() { -} +SemaphoreFactory::SemaphoreFactory() {} -SemaphoreFactory::~SemaphoreFactory() { - delete factoryInstance; -} +SemaphoreFactory::~SemaphoreFactory() { delete factoryInstance; } SemaphoreFactory* SemaphoreFactory::instance() { - if (factoryInstance == nullptr){ - factoryInstance = new SemaphoreFactory(); - } - return SemaphoreFactory::factoryInstance; + if (factoryInstance == nullptr) { + factoryInstance = new SemaphoreFactory(); + } + return SemaphoreFactory::factoryInstance; } SemaphoreIF* SemaphoreFactory::createBinarySemaphore(uint32_t arguments) { - return new BinarySemaphore(); + return new BinarySemaphore(); } -SemaphoreIF* SemaphoreFactory::createCountingSemaphore(const uint8_t maxCount, - uint8_t initCount, uint32_t arguments) { - return new CountingSemaphore(maxCount, initCount); +SemaphoreIF* SemaphoreFactory::createCountingSemaphore(const uint8_t maxCount, uint8_t initCount, + uint32_t arguments) { + return new CountingSemaphore(maxCount, initCount); } -void SemaphoreFactory::deleteSemaphore(SemaphoreIF* semaphore) { - delete semaphore; -} +void SemaphoreFactory::deleteSemaphore(SemaphoreIF* semaphore) { delete semaphore; } diff --git a/src/fsfw/osal/linux/TaskFactory.cpp b/src/fsfw/osal/linux/TaskFactory.cpp index 53aea0ac..8503039f 100644 --- a/src/fsfw/osal/linux/TaskFactory.cpp +++ b/src/fsfw/osal/linux/TaskFactory.cpp @@ -1,65 +1,55 @@ +#include "fsfw/tasks/TaskFactory.h" + #include "fsfw/osal/linux/FixedTimeslotTask.h" #include "fsfw/osal/linux/PeriodicPosixTask.h" - -#include "fsfw/tasks/TaskFactory.h" -#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "fsfw/serviceinterface/ServiceInterface.h" -//TODO: Different variant than the lazy loading in QueueFactory. What's better and why? +// TODO: Different variant than the lazy loading in QueueFactory. What's better and why? TaskFactory* TaskFactory::factoryInstance = new TaskFactory(); -TaskFactory::~TaskFactory() { +TaskFactory::~TaskFactory() {} + +TaskFactory* TaskFactory::instance() { return TaskFactory::factoryInstance; } + +PeriodicTaskIF* TaskFactory::createPeriodicTask( + TaskName name_, TaskPriority taskPriority_, TaskStackSize stackSize_, + TaskPeriod periodInSeconds_, TaskDeadlineMissedFunction deadLineMissedFunction_) { + return new PeriodicPosixTask(name_, taskPriority_, stackSize_, periodInSeconds_ * 1000, + deadLineMissedFunction_); } -TaskFactory* TaskFactory::instance() { - return TaskFactory::factoryInstance; -} - -PeriodicTaskIF* TaskFactory::createPeriodicTask(TaskName name_, - TaskPriority taskPriority_,TaskStackSize stackSize_, - TaskPeriod periodInSeconds_, - TaskDeadlineMissedFunction deadLineMissedFunction_) { - return new PeriodicPosixTask(name_, taskPriority_,stackSize_, - periodInSeconds_ * 1000, deadLineMissedFunction_); -} - -FixedTimeslotTaskIF* TaskFactory::createFixedTimeslotTask(TaskName name_, - TaskPriority taskPriority_,TaskStackSize stackSize_, - TaskPeriod periodInSeconds_, - TaskDeadlineMissedFunction deadLineMissedFunction_) { - return new FixedTimeslotTask(name_, taskPriority_,stackSize_, - periodInSeconds_*1000); +FixedTimeslotTaskIF* TaskFactory::createFixedTimeslotTask( + TaskName name_, TaskPriority taskPriority_, TaskStackSize stackSize_, + TaskPeriod periodInSeconds_, TaskDeadlineMissedFunction deadLineMissedFunction_) { + return new FixedTimeslotTask(name_, taskPriority_, stackSize_, periodInSeconds_ * 1000); } ReturnValue_t TaskFactory::deleteTask(PeriodicTaskIF* task) { - //TODO not implemented - return HasReturnvaluesIF::RETURN_FAILED; + // TODO not implemented + return HasReturnvaluesIF::RETURN_FAILED; } -ReturnValue_t TaskFactory::delayTask(uint32_t delayMs){ - return PosixThread::sleep(delayMs*1000000ull); +ReturnValue_t TaskFactory::delayTask(uint32_t delayMs) { + return PosixThread::sleep(delayMs * 1000000ull); } void TaskFactory::printMissedDeadline() { - char name[20] = {0}; - int status = pthread_getname_np(pthread_self(), name, sizeof(name)); + char name[20] = {0}; + int status = pthread_getname_np(pthread_self(), name, sizeof(name)); #if FSFW_CPP_OSTREAM_ENABLED == 1 - if(status == 0) { - sif::warning << "task::printMissedDeadline: " << name << "" << std::endl; - } - else { - sif::warning << "task::printMissedDeadline: Unknown task name" << status << - std::endl; - } + if (status == 0) { + sif::warning << "task::printMissedDeadline: " << name << "" << std::endl; + } else { + sif::warning << "task::printMissedDeadline: Unknown task name" << status << std::endl; + } #else - if(status == 0) { - sif::printWarning("task::printMissedDeadline: %s\n", name); - } - else { - sif::printWarning("task::printMissedDeadline: Unknown task name\n", name); - } + if (status == 0) { + sif::printWarning("task::printMissedDeadline: %s\n", name); + } else { + sif::printWarning("task::printMissedDeadline: Unknown task name\n", name); + } #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ } -TaskFactory::TaskFactory() { -} +TaskFactory::TaskFactory() {} diff --git a/src/fsfw/osal/linux/tcpipHelpers.cpp b/src/fsfw/osal/linux/tcpipHelpers.cpp index 800c6fb7..2ae9bc8a 100644 --- a/src/fsfw/osal/linux/tcpipHelpers.cpp +++ b/src/fsfw/osal/linux/tcpipHelpers.cpp @@ -1,109 +1,110 @@ #include "fsfw/osal/common/tcpipHelpers.h" +#include + +#include + #include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/tasks/TaskFactory.h" -#include -#include - void tcpip::handleError(Protocol protocol, ErrorSources errorSrc, dur_millis_t sleepDuration) { - int errCode = errno; - std::string protocolString; - std::string errorSrcString; - determineErrorStrings(protocol, errorSrc, protocolString, errorSrcString); - std::string infoString; - switch(errCode) { - case(EACCES): { - infoString = "EACCES"; - break; + int errCode = errno; + std::string protocolString; + std::string errorSrcString; + determineErrorStrings(protocol, errorSrc, protocolString, errorSrcString); + std::string infoString; + switch (errCode) { + case (EACCES): { + infoString = "EACCES"; + break; } - case(EINVAL): { - infoString = "EINVAL"; - break; + case (EINVAL): { + infoString = "EINVAL"; + break; } - case(EAGAIN): { - infoString = "EAGAIN"; - break; + case (EAGAIN): { + infoString = "EAGAIN"; + break; } - case(EMFILE): { - infoString = "EMFILE"; - break; + case (EMFILE): { + infoString = "EMFILE"; + break; } - case(ENFILE): { - infoString = "ENFILE"; - break; + case (ENFILE): { + infoString = "ENFILE"; + break; } - case(EAFNOSUPPORT): { - infoString = "EAFNOSUPPORT"; - break; + case (EAFNOSUPPORT): { + infoString = "EAFNOSUPPORT"; + break; } - case(ENOBUFS): { - infoString = "ENOBUFS"; - break; + case (ENOBUFS): { + infoString = "ENOBUFS"; + break; } - case(ENOMEM): { - infoString = "ENOMEM"; - break; + case (ENOMEM): { + infoString = "ENOMEM"; + break; } - case(EPROTONOSUPPORT): { - infoString = "EPROTONOSUPPORT"; - break; + case (EPROTONOSUPPORT): { + infoString = "EPROTONOSUPPORT"; + break; } - case(EADDRINUSE): { - infoString = "EADDRINUSE"; - break; + case (EADDRINUSE): { + infoString = "EADDRINUSE"; + break; } - case(EBADF): { - infoString = "EBADF"; - break; + case (EBADF): { + infoString = "EBADF"; + break; } - case(ENOTSOCK): { - infoString = "ENOTSOCK"; - break; + case (ENOTSOCK): { + infoString = "ENOTSOCK"; + break; } - case(EADDRNOTAVAIL): { - infoString = "EADDRNOTAVAIL"; - break; + case (EADDRNOTAVAIL): { + infoString = "EADDRNOTAVAIL"; + break; } - case(EFAULT): { - infoString = "EFAULT"; - break; + case (EFAULT): { + infoString = "EFAULT"; + break; } - case(ELOOP): { - infoString = "ELOOP"; - break; + case (ELOOP): { + infoString = "ELOOP"; + break; } - case(ENAMETOOLONG): { - infoString = "ENAMETOOLONG"; - break; + case (ENAMETOOLONG): { + infoString = "ENAMETOOLONG"; + break; } - case(ENOENT): { - infoString = "ENOENT"; - break; + case (ENOENT): { + infoString = "ENOENT"; + break; } - case(ENOTDIR): { - infoString = "ENOTDIR"; - break; + case (ENOTDIR): { + infoString = "ENOTDIR"; + break; } - case(EROFS): { - infoString = "EROFS"; - break; + case (EROFS): { + infoString = "EROFS"; + break; } default: { - infoString = "Error code: " + std::to_string(errCode); - } + infoString = "Error code: " + std::to_string(errCode); } + } #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "tcpip::handleError: " << protocolString << " | " << errorSrcString << - " | " << infoString << std::endl; + sif::warning << "tcpip::handleError: " << protocolString << " | " << errorSrcString << " | " + << infoString << std::endl; #else - sif::printWarning("tcpip::handleError: %s | %s | %s\n", protocolString.c_str(), - errorSrcString.c_str(), infoString.c_str()); + sif::printWarning("tcpip::handleError: %s | %s | %s\n", protocolString.c_str(), + errorSrcString.c_str(), infoString.c_str()); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ - if(sleepDuration > 0) { - TaskFactory::instance()->delayTask(sleepDuration); - } + if (sleepDuration > 0) { + TaskFactory::instance()->delayTask(sleepDuration); + } } diff --git a/src/fsfw/osal/linux/unixUtility.cpp b/src/fsfw/osal/linux/unixUtility.cpp index 57e1f17a..e6fe42ed 100644 --- a/src/fsfw/osal/linux/unixUtility.cpp +++ b/src/fsfw/osal/linux/unixUtility.cpp @@ -1,32 +1,32 @@ -#include "fsfw/FSFW.h" #include "fsfw/osal/linux/unixUtility.h" -#include "fsfw/serviceinterface/ServiceInterface.h" -#include #include -void utility::printUnixErrorGeneric(const char* const className, - const char* const function, const char* const failString, - sif::OutputTypes outputType) { - if(className == nullptr or failString == nullptr or function == nullptr) { - return; - } +#include + +#include "fsfw/FSFW.h" +#include "fsfw/serviceinterface/ServiceInterface.h" + +void utility::printUnixErrorGeneric(const char* const className, const char* const function, + const char* const failString, sif::OutputTypes outputType) { + if (className == nullptr or failString == nullptr or function == nullptr) { + return; + } #if FSFW_VERBOSE_LEVEL >= 1 - if(outputType == sif::OutputTypes::OUT_ERROR) { + if (outputType == sif::OutputTypes::OUT_ERROR) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << className << "::" << function << ": " << failString << " error: " - << strerror(errno) << std::endl; + sif::error << className << "::" << function << ": " << failString + << " error: " << strerror(errno) << std::endl; #else sif::printError("%s::%s: %s error: %s\n", className, function, failString, strerror(errno)); #endif - } - else { + } else { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << className << "::" << function << ": " << failString << " error: " - << strerror(errno) << std::endl; + sif::warning << className << "::" << function << ": " << failString + << " error: " << strerror(errno) << std::endl; #else sif::printWarning("%s::%s: %s error: %s\n", className, function, failString, strerror(errno)); #endif - } + } #endif } diff --git a/src/fsfw/osal/linux/unixUtility.h b/src/fsfw/osal/linux/unixUtility.h index 8a964f3a..3334b8f5 100644 --- a/src/fsfw/osal/linux/unixUtility.h +++ b/src/fsfw/osal/linux/unixUtility.h @@ -6,7 +6,8 @@ namespace utility { void printUnixErrorGeneric(const char* const className, const char* const function, - const char* const failString, sif::OutputTypes outputType = sif::OutputTypes::OUT_ERROR); + const char* const failString, + sif::OutputTypes outputType = sif::OutputTypes::OUT_ERROR); } diff --git a/src/fsfw/osal/rtems/BinarySemaphore.cpp b/src/fsfw/osal/rtems/BinarySemaphore.cpp index 6d145d98..06b0bf77 100644 --- a/src/fsfw/osal/rtems/BinarySemaphore.cpp +++ b/src/fsfw/osal/rtems/BinarySemaphore.cpp @@ -2,22 +2,14 @@ #include -BinarySemaphore::BinarySemaphore() { -} +BinarySemaphore::BinarySemaphore() {} -BinarySemaphore::~BinarySemaphore() { - -} +BinarySemaphore::~BinarySemaphore() {} ReturnValue_t BinarySemaphore::acquire(TimeoutType timeoutType, uint32_t timeoutMs) { - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } +ReturnValue_t BinarySemaphore::release() { return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t BinarySemaphore::release() { - return HasReturnvaluesIF::RETURN_OK; -} - -uint8_t BinarySemaphore::getSemaphoreCounter() const { - return 0; -} +uint8_t BinarySemaphore::getSemaphoreCounter() const { return 0; } diff --git a/src/fsfw/osal/rtems/BinarySemaphore.h b/src/fsfw/osal/rtems/BinarySemaphore.h index a2796af1..5454671a 100644 --- a/src/fsfw/osal/rtems/BinarySemaphore.h +++ b/src/fsfw/osal/rtems/BinarySemaphore.h @@ -3,21 +3,18 @@ #include "fsfw/tasks/SemaphoreIF.h" -class BinarySemaphore: public SemaphoreIF { -public: - BinarySemaphore(); - virtual ~BinarySemaphore(); +class BinarySemaphore : public SemaphoreIF { + public: + BinarySemaphore(); + virtual ~BinarySemaphore(); - // Semaphore IF implementations - ReturnValue_t acquire(TimeoutType timeoutType = - TimeoutType::BLOCKING, uint32_t timeoutMs = 0) override; - ReturnValue_t release() override; - uint8_t getSemaphoreCounter() const override; - -private: + // Semaphore IF implementations + ReturnValue_t acquire(TimeoutType timeoutType = TimeoutType::BLOCKING, + uint32_t timeoutMs = 0) override; + ReturnValue_t release() override; + uint8_t getSemaphoreCounter() const override; + private: }; - - #endif /* FSFW_SRC_FSFW_OSAL_RTEMS_BINARYSEMAPHORE_H_ */ diff --git a/src/fsfw/osal/rtems/Clock.cpp b/src/fsfw/osal/rtems/Clock.cpp index 42f30dcc..06b0c1d8 100644 --- a/src/fsfw/osal/rtems/Clock.cpp +++ b/src/fsfw/osal/rtems/Clock.cpp @@ -1,156 +1,155 @@ -#include "fsfw/osal/rtems/RtemsBasic.h" - #include "fsfw/timemanager/Clock.h" -#include "fsfw/ipc/MutexGuard.h" -#include #include +#include + +#include "fsfw/ipc/MutexGuard.h" +#include "fsfw/osal/rtems/RtemsBasic.h" uint16_t Clock::leapSeconds = 0; MutexIF* Clock::timeMutex = nullptr; -uint32_t Clock::getTicksPerSecond(void){ - rtems_interval ticks_per_second = rtems_clock_get_ticks_per_second(); - return static_cast(ticks_per_second); +uint32_t Clock::getTicksPerSecond(void) { + rtems_interval ticks_per_second = rtems_clock_get_ticks_per_second(); + return static_cast(ticks_per_second); } ReturnValue_t Clock::setClock(const TimeOfDay_t* time) { - rtems_time_of_day timeRtems; - timeRtems.year = time->year; - timeRtems.month = time->month; - timeRtems.day = time->day; - timeRtems.hour = time->hour; - timeRtems.minute = time->minute; - timeRtems.second = time->second; - timeRtems.ticks = time->usecond * getTicksPerSecond() / 1e6; - rtems_status_code status = rtems_clock_set(&timeRtems); - switch(status){ + rtems_time_of_day timeRtems; + timeRtems.year = time->year; + timeRtems.month = time->month; + timeRtems.day = time->day; + timeRtems.hour = time->hour; + timeRtems.minute = time->minute; + timeRtems.second = time->second; + timeRtems.ticks = time->usecond * getTicksPerSecond() / 1e6; + rtems_status_code status = rtems_clock_set(&timeRtems); + switch (status) { case RTEMS_SUCCESSFUL: - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; case RTEMS_INVALID_ADDRESS: - return HasReturnvaluesIF::RETURN_FAILED; + return HasReturnvaluesIF::RETURN_FAILED; case RTEMS_INVALID_CLOCK: - return HasReturnvaluesIF::RETURN_FAILED; + return HasReturnvaluesIF::RETURN_FAILED; default: - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; + } } ReturnValue_t Clock::setClock(const timeval* time) { - timespec newTime; - newTime.tv_sec = time->tv_sec; - if(time->tv_usec < 0) { - // better returnvalue. - return HasReturnvaluesIF::RETURN_FAILED; - } - newTime.tv_nsec = time->tv_usec * TOD_NANOSECONDS_PER_MICROSECOND; - - ISR_lock_Context context; - _TOD_Lock(); - _TOD_Acquire(&context); - Status_Control status = _TOD_Set(&newTime, &context); - _TOD_Unlock(); - if(status == STATUS_SUCCESSFUL) { - return HasReturnvaluesIF::RETURN_OK; - } - // better returnvalue + timespec newTime; + newTime.tv_sec = time->tv_sec; + if (time->tv_usec < 0) { + // better returnvalue. return HasReturnvaluesIF::RETURN_FAILED; + } + newTime.tv_nsec = time->tv_usec * TOD_NANOSECONDS_PER_MICROSECOND; + + ISR_lock_Context context; + _TOD_Lock(); + _TOD_Acquire(&context); + Status_Control status = _TOD_Set(&newTime, &context); + _TOD_Unlock(); + if (status == STATUS_SUCCESSFUL) { + return HasReturnvaluesIF::RETURN_OK; + } + // better returnvalue + return HasReturnvaluesIF::RETURN_FAILED; } ReturnValue_t Clock::getClock_timeval(timeval* time) { - //Callable from ISR - rtems_status_code status = rtems_clock_get_tod_timeval(time); - switch(status){ + // Callable from ISR + rtems_status_code status = rtems_clock_get_tod_timeval(time); + switch (status) { case RTEMS_SUCCESSFUL: - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; case RTEMS_NOT_DEFINED: - return HasReturnvaluesIF::RETURN_FAILED; + return HasReturnvaluesIF::RETURN_FAILED; default: - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; + } } ReturnValue_t Clock::getUptime(timeval* uptime) { - //According to docs.rtems.org for rtems 5 this method is more accurate than rtems_clock_get_ticks_since_boot - timespec time; - rtems_status_code status = rtems_clock_get_uptime(&time); - uptime->tv_sec = time.tv_sec; - time.tv_nsec = time.tv_nsec / 1000; - uptime->tv_usec = time.tv_nsec; - switch(status){ + // According to docs.rtems.org for rtems 5 this method is more accurate than + // rtems_clock_get_ticks_since_boot + timespec time; + rtems_status_code status = rtems_clock_get_uptime(&time); + uptime->tv_sec = time.tv_sec; + time.tv_nsec = time.tv_nsec / 1000; + uptime->tv_usec = time.tv_nsec; + switch (status) { case RTEMS_SUCCESSFUL: - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; default: - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; + } } ReturnValue_t Clock::getUptime(uint32_t* uptimeMs) { - //This counter overflows after 50 days - *uptimeMs = rtems_clock_get_ticks_since_boot(); - return HasReturnvaluesIF::RETURN_OK; + // This counter overflows after 50 days + *uptimeMs = rtems_clock_get_ticks_since_boot(); + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t Clock::getClock_usecs(uint64_t* time) { - timeval temp_time; - rtems_status_code returnValue = rtems_clock_get_tod_timeval(&temp_time); - *time = ((uint64_t) temp_time.tv_sec * 1000000) + temp_time.tv_usec; - switch(returnValue){ + timeval temp_time; + rtems_status_code returnValue = rtems_clock_get_tod_timeval(&temp_time); + *time = ((uint64_t)temp_time.tv_sec * 1000000) + temp_time.tv_usec; + switch (returnValue) { case RTEMS_SUCCESSFUL: - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; default: - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; + } } ReturnValue_t Clock::getDateAndTime(TimeOfDay_t* time) { - /* For all but the last field, the struct will be filled with the correct values */ - rtems_time_of_day timeRtems; - rtems_status_code status = rtems_clock_get_tod(&timeRtems); - switch (status) { + /* For all but the last field, the struct will be filled with the correct values */ + rtems_time_of_day timeRtems; + rtems_status_code status = rtems_clock_get_tod(&timeRtems); + switch (status) { case RTEMS_SUCCESSFUL: { - /* The last field now contains the RTEMS ticks of the seconds from 0 - to rtems_clock_get_ticks_per_second() minus one. - We calculate the microseconds accordingly */ - time->day = timeRtems.day; - time->hour = timeRtems.hour; - time->minute = timeRtems.minute; - time->month = timeRtems.month; - time->second = timeRtems.second; - time->usecond = static_cast(timeRtems.ticks) / - rtems_clock_get_ticks_per_second() * 1e6; - time->year = timeRtems.year; - return HasReturnvaluesIF::RETURN_OK; + /* The last field now contains the RTEMS ticks of the seconds from 0 + to rtems_clock_get_ticks_per_second() minus one. + We calculate the microseconds accordingly */ + time->day = timeRtems.day; + time->hour = timeRtems.hour; + time->minute = timeRtems.minute; + time->month = timeRtems.month; + time->second = timeRtems.second; + time->usecond = + static_cast(timeRtems.ticks) / rtems_clock_get_ticks_per_second() * 1e6; + time->year = timeRtems.year; + return HasReturnvaluesIF::RETURN_OK; } case RTEMS_NOT_DEFINED: - /* System date and time is not set */ - return HasReturnvaluesIF::RETURN_FAILED; + /* System date and time is not set */ + return HasReturnvaluesIF::RETURN_FAILED; case RTEMS_INVALID_ADDRESS: - /* time_buffer is NULL */ - return HasReturnvaluesIF::RETURN_FAILED; + /* time_buffer is NULL */ + return HasReturnvaluesIF::RETURN_FAILED; default: - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; + } } -ReturnValue_t Clock::convertTimeOfDayToTimeval(const TimeOfDay_t* from, - timeval* to) { - //Fails in 2038.. - rtems_time_of_day timeRtems; - timeRtems.year = from->year; - timeRtems.month = from->month; - timeRtems.day = from->day; - timeRtems.hour = from->hour; - timeRtems.minute = from->minute; - timeRtems.second = from->second; - timeRtems.ticks = from->usecond * getTicksPerSecond() / 1e6; - to->tv_sec = _TOD_To_seconds(&timeRtems); - to->tv_usec = from->usecond; - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t Clock::convertTimeOfDayToTimeval(const TimeOfDay_t* from, timeval* to) { + // Fails in 2038.. + rtems_time_of_day timeRtems; + timeRtems.year = from->year; + timeRtems.month = from->month; + timeRtems.day = from->day; + timeRtems.hour = from->hour; + timeRtems.minute = from->minute; + timeRtems.second = from->second; + timeRtems.ticks = from->usecond * getTicksPerSecond() / 1e6; + to->tv_sec = _TOD_To_seconds(&timeRtems); + to->tv_usec = from->usecond; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t Clock::convertTimevalToJD2000(timeval time, double* JD2000) { - *JD2000 = (time.tv_sec - 946728000. + time.tv_usec / 1000000.) / 24. - / 3600.; - return HasReturnvaluesIF::RETURN_OK; + *JD2000 = (time.tv_sec - 946728000. + time.tv_usec / 1000000.) / 24. / 3600.; + return HasReturnvaluesIF::RETURN_OK; } diff --git a/src/fsfw/osal/rtems/CpuUsage.cpp b/src/fsfw/osal/rtems/CpuUsage.cpp index 771b52dc..2613a698 100644 --- a/src/fsfw/osal/rtems/CpuUsage.cpp +++ b/src/fsfw/osal/rtems/CpuUsage.cpp @@ -1,183 +1,170 @@ #include "fsfw/osal/rtems/CpuUsage.h" + +#include + #include "fsfw/serialize/SerialArrayListAdapter.h" #include "fsfw/serialize/SerializeAdapter.h" -#include extern "C" { #include } -int handlePrint(void * token, const char *format, ...) { - CpuUsage *cpuUsage = (CpuUsage *) token; +int handlePrint(void* token, const char* format, ...) { + CpuUsage* cpuUsage = (CpuUsage*)token; - if (cpuUsage->counter == 0) { - //header - cpuUsage->counter++; - return 0; - } + if (cpuUsage->counter == 0) { + // header + cpuUsage->counter++; + return 0; + } - if (cpuUsage->counter % 2 == 1) { - { - //we can not tell when the last call is so we assume it be every uneven time - va_list vl; - va_start(vl, format); - float timeSinceLastReset = va_arg(vl,uint32_t); - uint32_t timeSinceLastResetDecimals = va_arg(vl,uint32_t); + if (cpuUsage->counter % 2 == 1) { + { + // we can not tell when the last call is so we assume it be every uneven time + va_list vl; + va_start(vl, format); + float timeSinceLastReset = va_arg(vl, uint32_t); + uint32_t timeSinceLastResetDecimals = va_arg(vl, uint32_t); - timeSinceLastReset = timeSinceLastReset - + (timeSinceLastResetDecimals / 1000.); + timeSinceLastReset = timeSinceLastReset + (timeSinceLastResetDecimals / 1000.); - cpuUsage->timeSinceLastReset = timeSinceLastReset; + cpuUsage->timeSinceLastReset = timeSinceLastReset; - va_end(vl); - } - //task name and id - va_list vl; - va_start(vl, format); + va_end(vl); + } + // task name and id + va_list vl; + va_start(vl, format); - cpuUsage->cachedValue.id = va_arg(vl,uint32_t); - const char *name = va_arg(vl,const char *); - memcpy(cpuUsage->cachedValue.name, name, - CpuUsage::ThreadData::MAX_LENGTH_OF_THREAD_NAME); + cpuUsage->cachedValue.id = va_arg(vl, uint32_t); + const char* name = va_arg(vl, const char*); + memcpy(cpuUsage->cachedValue.name, name, CpuUsage::ThreadData::MAX_LENGTH_OF_THREAD_NAME); - va_end(vl); + va_end(vl); - } else { - //statistics - va_list vl; - va_start(vl, format); - float run = va_arg(vl,uint32_t); - uint32_t runDecimals = va_arg(vl,uint32_t); - float percent = va_arg(vl,uint32_t); - uint32_t percent_decimals = va_arg(vl,uint32_t); + } else { + // statistics + va_list vl; + va_start(vl, format); + float run = va_arg(vl, uint32_t); + uint32_t runDecimals = va_arg(vl, uint32_t); + float percent = va_arg(vl, uint32_t); + uint32_t percent_decimals = va_arg(vl, uint32_t); - run = run + (runDecimals / 1000.); - percent = percent + (percent_decimals / 1000.); + run = run + (runDecimals / 1000.); + percent = percent + (percent_decimals / 1000.); - cpuUsage->cachedValue.percentUsage = percent; - cpuUsage->cachedValue.timeRunning = run; + cpuUsage->cachedValue.percentUsage = percent; + cpuUsage->cachedValue.timeRunning = run; - cpuUsage->threadData.insert(cpuUsage->cachedValue); + cpuUsage->threadData.insert(cpuUsage->cachedValue); - va_end(vl); - } - cpuUsage->counter++; + va_end(vl); + } + cpuUsage->counter++; - return 0; + return 0; } -CpuUsage::CpuUsage() : - counter(0), timeSinceLastReset(0) { +CpuUsage::CpuUsage() : counter(0), timeSinceLastReset(0) {} -} +CpuUsage::~CpuUsage() {} -CpuUsage::~CpuUsage() { - -} - -void CpuUsage::resetCpuUsage() { - rtems_cpu_usage_reset(); -} +void CpuUsage::resetCpuUsage() { rtems_cpu_usage_reset(); } void CpuUsage::read() { - //rtems_cpu_usage_report_with_plugin(this, &handlePrint); + // rtems_cpu_usage_report_with_plugin(this, &handlePrint); } void CpuUsage::clear() { - counter = 0; - timeSinceLastReset = 0; - threadData.clear(); + counter = 0; + timeSinceLastReset = 0; + threadData.clear(); } -ReturnValue_t CpuUsage::serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const { - ReturnValue_t result = SerializeAdapter::serialize( - &timeSinceLastReset, buffer, size, maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return SerialArrayListAdapter::serialize(&threadData, buffer, - size, maxSize, streamEndianness); +ReturnValue_t CpuUsage::serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const { + ReturnValue_t result = + SerializeAdapter::serialize(&timeSinceLastReset, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return SerialArrayListAdapter::serialize(&threadData, buffer, size, maxSize, + streamEndianness); } uint32_t CpuUsage::getSerializedSize() const { - uint32_t size = 0; + uint32_t size = 0; - size += sizeof(timeSinceLastReset); - size += SerialArrayListAdapter::getSerializedSize(&threadData); + size += sizeof(timeSinceLastReset); + size += SerialArrayListAdapter::getSerializedSize(&threadData); - return size; + return size; } ReturnValue_t CpuUsage::deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) { - ReturnValue_t result = SerializeAdapter::deSerialize( - &timeSinceLastReset, buffer, size, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return SerialArrayListAdapter::deSerialize(&threadData, buffer, - size, streamEndianness); + Endianness streamEndianness) { + ReturnValue_t result = + SerializeAdapter::deSerialize(&timeSinceLastReset, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return SerialArrayListAdapter::deSerialize(&threadData, buffer, size, + streamEndianness); } -ReturnValue_t CpuUsage::ThreadData::serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const { - ReturnValue_t result = SerializeAdapter::serialize(&id, buffer, - size, maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if (*size + MAX_LENGTH_OF_THREAD_NAME > maxSize) { - return BUFFER_TOO_SHORT; - } - memcpy(*buffer, name, MAX_LENGTH_OF_THREAD_NAME); - *size += MAX_LENGTH_OF_THREAD_NAME; - *buffer += MAX_LENGTH_OF_THREAD_NAME; - result = SerializeAdapter::serialize(&timeRunning, - buffer, size, maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::serialize(&percentUsage, - buffer, size, maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t CpuUsage::ThreadData::serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const { + ReturnValue_t result = SerializeAdapter::serialize(&id, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (*size + MAX_LENGTH_OF_THREAD_NAME > maxSize) { + return BUFFER_TOO_SHORT; + } + memcpy(*buffer, name, MAX_LENGTH_OF_THREAD_NAME); + *size += MAX_LENGTH_OF_THREAD_NAME; + *buffer += MAX_LENGTH_OF_THREAD_NAME; + result = SerializeAdapter::serialize(&timeRunning, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::serialize(&percentUsage, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return HasReturnvaluesIF::RETURN_OK; } uint32_t CpuUsage::ThreadData::getSerializedSize() const { - uint32_t size = 0; + uint32_t size = 0; - size += sizeof(id); - size += MAX_LENGTH_OF_THREAD_NAME; - size += sizeof(timeRunning); - size += sizeof(percentUsage); + size += sizeof(id); + size += MAX_LENGTH_OF_THREAD_NAME; + size += sizeof(timeRunning); + size += sizeof(percentUsage); - return size; + return size; } -ReturnValue_t CpuUsage::ThreadData::deSerialize(const uint8_t** buffer, - size_t* size, Endianness streamEndianness) { - ReturnValue_t result = SerializeAdapter::deSerialize(&id, buffer, - size, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if (*size < MAX_LENGTH_OF_THREAD_NAME) { - return STREAM_TOO_SHORT; - } - memcpy(name, *buffer, MAX_LENGTH_OF_THREAD_NAME); - *buffer -= MAX_LENGTH_OF_THREAD_NAME; - result = SerializeAdapter::deSerialize(&timeRunning, - buffer, size, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::deSerialize(&percentUsage, - buffer, size, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t CpuUsage::ThreadData::deSerialize(const uint8_t** buffer, size_t* size, + Endianness streamEndianness) { + ReturnValue_t result = SerializeAdapter::deSerialize(&id, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (*size < MAX_LENGTH_OF_THREAD_NAME) { + return STREAM_TOO_SHORT; + } + memcpy(name, *buffer, MAX_LENGTH_OF_THREAD_NAME); + *buffer -= MAX_LENGTH_OF_THREAD_NAME; + result = SerializeAdapter::deSerialize(&timeRunning, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::deSerialize(&percentUsage, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return HasReturnvaluesIF::RETURN_OK; } diff --git a/src/fsfw/osal/rtems/CpuUsage.h b/src/fsfw/osal/rtems/CpuUsage.h index 6b6b9910..fdba689e 100644 --- a/src/fsfw/osal/rtems/CpuUsage.h +++ b/src/fsfw/osal/rtems/CpuUsage.h @@ -1,53 +1,54 @@ #ifndef CPUUSAGE_H_ #define CPUUSAGE_H_ -#include "fsfw/container/FixedArrayList.h" -#include "fsfw/serialize/SerializeIF.h" #include +#include "fsfw/container/FixedArrayList.h" +#include "fsfw/serialize/SerializeIF.h" + class CpuUsage : public SerializeIF { -public: - static const uint8_t MAXIMUM_NUMBER_OF_THREADS = 30; + public: + static const uint8_t MAXIMUM_NUMBER_OF_THREADS = 30; - class ThreadData: public SerializeIF { - public: - static const uint8_t MAX_LENGTH_OF_THREAD_NAME = 4; + class ThreadData : public SerializeIF { + public: + static const uint8_t MAX_LENGTH_OF_THREAD_NAME = 4; - uint32_t id; - char name[MAX_LENGTH_OF_THREAD_NAME]; - float timeRunning; - float percentUsage; + uint32_t id; + char name[MAX_LENGTH_OF_THREAD_NAME]; + float timeRunning; + float percentUsage; - virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const override; + virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; - virtual size_t getSerializedSize() const override; + virtual size_t getSerializedSize() const override; - virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) override; - }; + virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + Endianness streamEndianness) override; + }; - CpuUsage(); - virtual ~CpuUsage(); + CpuUsage(); + virtual ~CpuUsage(); - uint8_t counter; - float timeSinceLastReset; - FixedArrayList threadData; - ThreadData cachedValue; + uint8_t counter; + float timeSinceLastReset; + FixedArrayList threadData; + ThreadData cachedValue; - static void resetCpuUsage(); + static void resetCpuUsage(); - void read(); + void read(); - void clear(); + void clear(); - virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const override; + virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; - virtual size_t getSerializedSize() const override; + virtual size_t getSerializedSize() const override; - virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) override; + virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + Endianness streamEndianness) override; }; #endif /* CPUUSAGE_H_ */ diff --git a/src/fsfw/osal/rtems/FixedTimeslotTask.cpp b/src/fsfw/osal/rtems/FixedTimeslotTask.cpp index 8b313df6..3347739a 100644 --- a/src/fsfw/osal/rtems/FixedTimeslotTask.cpp +++ b/src/fsfw/osal/rtems/FixedTimeslotTask.cpp @@ -1,11 +1,4 @@ #include "fsfw/osal/rtems/FixedTimeslotTask.h" -#include "fsfw/osal/rtems/RtemsBasic.h" - -#include "fsfw/tasks/FixedSequenceSlot.h" -#include "fsfw/objectmanager/SystemObjectIF.h" -#include "fsfw/objectmanager/ObjectManager.h" -#include "fsfw/returnvalues/HasReturnvaluesIF.h" -#include "fsfw/serviceinterface/ServiceInterface.h" #include #include @@ -15,6 +8,13 @@ #include #include +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/objectmanager/SystemObjectIF.h" +#include "fsfw/osal/rtems/RtemsBasic.h" +#include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/tasks/FixedSequenceSlot.h" + #if FSFW_CPP_OSTREAM_ENABLED == 1 #include #endif @@ -25,116 +25,109 @@ uint32_t FixedTimeslotTask::deadlineMissedCount = 0; FixedTimeslotTask::FixedTimeslotTask(const char *name, rtems_task_priority setPriority, - size_t setStack, uint32_t setOverallPeriod, void (*setDeadlineMissedFunc)(void)): - RTEMSTaskBase(setPriority, setStack, name), periodId(0), pst(setOverallPeriod) { - // All additional attributes are applied to the object. - this->deadlineMissedFunc = setDeadlineMissedFunc; + size_t setStack, uint32_t setOverallPeriod, + void (*setDeadlineMissedFunc)(void)) + : RTEMSTaskBase(setPriority, setStack, name), periodId(0), pst(setOverallPeriod) { + // All additional attributes are applied to the object. + this->deadlineMissedFunc = setDeadlineMissedFunc; } -FixedTimeslotTask::~FixedTimeslotTask() { -} +FixedTimeslotTask::~FixedTimeslotTask() {} rtems_task FixedTimeslotTask::taskEntryPoint(rtems_task_argument argument) { - /* The argument is re-interpreted as a FixedTimeslotTask */ - FixedTimeslotTask *originalTask(reinterpret_cast(argument)); - /* The task's functionality is called. */ - return originalTask->taskFunctionality(); - /* Should never be reached */ + /* The argument is re-interpreted as a FixedTimeslotTask */ + FixedTimeslotTask *originalTask(reinterpret_cast(argument)); + /* The task's functionality is called. */ + return originalTask->taskFunctionality(); + /* Should never be reached */ #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Polling task " << originalTask->getId() << " returned from taskFunctionality." << - std::endl; + sif::error << "Polling task " << originalTask->getId() << " returned from taskFunctionality." + << std::endl; #endif } void FixedTimeslotTask::missedDeadlineCounter() { - FixedTimeslotTask::deadlineMissedCount++; - if (FixedTimeslotTask::deadlineMissedCount % 10 == 0) { + FixedTimeslotTask::deadlineMissedCount++; + if (FixedTimeslotTask::deadlineMissedCount % 10 == 0) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "PST missed " << FixedTimeslotTask::deadlineMissedCount - << " deadlines." << std::endl; + sif::error << "PST missed " << FixedTimeslotTask::deadlineMissedCount << " deadlines." + << std::endl; #endif - } + } } ReturnValue_t FixedTimeslotTask::startTask() { - rtems_status_code status = rtems_task_start(id, FixedTimeslotTask::taskEntryPoint, - rtems_task_argument((void *) this)); - if (status != RTEMS_SUCCESSFUL) { + rtems_status_code status = + rtems_task_start(id, FixedTimeslotTask::taskEntryPoint, rtems_task_argument((void *)this)); + if (status != RTEMS_SUCCESSFUL) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "PollingTask::startTask for " << std::hex << this->getId() - << std::dec << " failed." << std::endl; + sif::error << "PollingTask::startTask for " << std::hex << this->getId() << std::dec + << " failed." << std::endl; #endif - } - switch(status){ + } + switch (status) { case RTEMS_SUCCESSFUL: - //ask started successfully - return HasReturnvaluesIF::RETURN_OK; + // ask started successfully + return HasReturnvaluesIF::RETURN_OK; default: - /* - RTEMS_INVALID_ADDRESS - invalid task entry point - RTEMS_INVALID_ID - invalid task id - RTEMS_INCORRECT_STATE - task not in the dormant state - RTEMS_ILLEGAL_ON_REMOTE_OBJECT - cannot start remote task */ - return HasReturnvaluesIF::RETURN_FAILED; - } + /* + RTEMS_INVALID_ADDRESS - invalid task entry point + RTEMS_INVALID_ID - invalid task id + RTEMS_INCORRECT_STATE - task not in the dormant state + RTEMS_ILLEGAL_ON_REMOTE_OBJECT - cannot start remote task */ + return HasReturnvaluesIF::RETURN_FAILED; + } } -ReturnValue_t FixedTimeslotTask::addSlot(object_id_t componentId, - uint32_t slotTimeMs, int8_t executionStep) { - ExecutableObjectIF* object = ObjectManager::instance()->get(componentId); - if (object != nullptr) { - pst.addSlot(componentId, slotTimeMs, executionStep, object, this); - return HasReturnvaluesIF::RETURN_OK; - } +ReturnValue_t FixedTimeslotTask::addSlot(object_id_t componentId, uint32_t slotTimeMs, + int8_t executionStep) { + ExecutableObjectIF *object = ObjectManager::instance()->get(componentId); + if (object != nullptr) { + pst.addSlot(componentId, slotTimeMs, executionStep, object, this); + return HasReturnvaluesIF::RETURN_OK; + } #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Component " << std::hex << componentId << - " not found, not adding it to pst" << std::endl; + sif::error << "Component " << std::hex << componentId << " not found, not adding it to pst" + << std::endl; #endif - return HasReturnvaluesIF::RETURN_FAILED; + return HasReturnvaluesIF::RETURN_FAILED; } -uint32_t FixedTimeslotTask::getPeriodMs() const { - return pst.getLengthMs(); -} +uint32_t FixedTimeslotTask::getPeriodMs() const { return pst.getLengthMs(); } -ReturnValue_t FixedTimeslotTask::checkSequence() const { - return pst.checkSequence(); -} +ReturnValue_t FixedTimeslotTask::checkSequence() const { return pst.checkSequence(); } void FixedTimeslotTask::taskFunctionality() { - /* A local iterator for the Polling Sequence Table is created to find the start time for - the first entry. */ - FixedSlotSequence::SlotListIter it = pst.current; + /* A local iterator for the Polling Sequence Table is created to find the start time for + the first entry. */ + FixedSlotSequence::SlotListIter it = pst.current; - /* Initialize the PST with the correct calling task */ - pst.intializeSequenceAfterTaskCreation(); + /* Initialize the PST with the correct calling task */ + pst.intializeSequenceAfterTaskCreation(); - /* The start time for the first entry is read. */ - rtems_interval interval = RtemsBasic::convertMsToTicks(it->pollingTimeMs); - RTEMSTaskBase::setAndStartPeriod(interval,&periodId); - //The task's "infinite" inner loop is entered. - while (1) { - if (pst.slotFollowsImmediately()) { - /* Do nothing */ + /* The start time for the first entry is read. */ + rtems_interval interval = RtemsBasic::convertMsToTicks(it->pollingTimeMs); + RTEMSTaskBase::setAndStartPeriod(interval, &periodId); + // The task's "infinite" inner loop is entered. + while (1) { + if (pst.slotFollowsImmediately()) { + /* Do nothing */ + } else { + /* The interval for the next polling slot is selected. */ + interval = RtemsBasic::convertMsToTicks(this->pst.getIntervalToNextSlotMs()); + /* The period is checked and restarted with the new interval. + If the deadline was missed, the deadlineMissedFunc is called. */ + rtems_status_code status = RTEMSTaskBase::restartPeriod(interval, periodId); + if (status == RTEMS_TIMEOUT) { + if (this->deadlineMissedFunc != nullptr) { + this->deadlineMissedFunc(); } - else { - /* The interval for the next polling slot is selected. */ - interval = RtemsBasic::convertMsToTicks(this->pst.getIntervalToNextSlotMs()); - /* The period is checked and restarted with the new interval. - If the deadline was missed, the deadlineMissedFunc is called. */ - rtems_status_code status = RTEMSTaskBase::restartPeriod(interval,periodId); - if (status == RTEMS_TIMEOUT) { - if (this->deadlineMissedFunc != nullptr) { - this->deadlineMissedFunc(); - } - } - } - /* The device handler for this slot is executed and the next one is chosen. */ - this->pst.executeAndAdvance(); + } } + /* The device handler for this slot is executed and the next one is chosen. */ + this->pst.executeAndAdvance(); + } } -ReturnValue_t FixedTimeslotTask::sleepFor(uint32_t ms){ - return RTEMSTaskBase::sleepFor(ms); -}; +ReturnValue_t FixedTimeslotTask::sleepFor(uint32_t ms) { return RTEMSTaskBase::sleepFor(ms); }; diff --git a/src/fsfw/osal/rtems/FixedTimeslotTask.h b/src/fsfw/osal/rtems/FixedTimeslotTask.h index 0d78c474..6dedfa44 100644 --- a/src/fsfw/osal/rtems/FixedTimeslotTask.h +++ b/src/fsfw/osal/rtems/FixedTimeslotTask.h @@ -1,81 +1,82 @@ #ifndef FSFW_OSAL_RTEMS_FIXEDTIMESLOTTASK_H_ #define FSFW_OSAL_RTEMS_FIXEDTIMESLOTTASK_H_ -#include "RTEMSTaskBase.h" #include "../../tasks/FixedSlotSequence.h" #include "../../tasks/FixedTimeslotTaskIF.h" +#include "RTEMSTaskBase.h" -class FixedTimeslotTask: public RTEMSTaskBase, public FixedTimeslotTaskIF { -public: - /** - * @brief The standard constructor of the class. - * @details - * This is the general constructor of the class. In addition to the TaskBase parameters, - * the following variables are passed: - * @param setDeadlineMissedFunc The function pointer to the deadline missed function - * that shall be assigned. - * @param getPst The object id of the completely initialized polling sequence. - */ - FixedTimeslotTask( const char *name, rtems_task_priority setPriority, size_t setStackSize, - uint32_t overallPeriod, void (*setDeadlineMissedFunc)()); +class FixedTimeslotTask : public RTEMSTaskBase, public FixedTimeslotTaskIF { + public: + /** + * @brief The standard constructor of the class. + * @details + * This is the general constructor of the class. In addition to the TaskBase parameters, + * the following variables are passed: + * @param setDeadlineMissedFunc The function pointer to the deadline missed function + * that shall be assigned. + * @param getPst The object id of the completely initialized polling sequence. + */ + FixedTimeslotTask(const char *name, rtems_task_priority setPriority, size_t setStackSize, + uint32_t overallPeriod, void (*setDeadlineMissedFunc)()); - /** - * @brief The destructor of the class. - * @details - * The destructor frees all heap memory that was allocated on thread initialization - * for the PST andthe device handlers. This is done by calling the PST's destructor. - */ - virtual ~FixedTimeslotTask( void ); + /** + * @brief The destructor of the class. + * @details + * The destructor frees all heap memory that was allocated on thread initialization + * for the PST andthe device handlers. This is done by calling the PST's destructor. + */ + virtual ~FixedTimeslotTask(void); - ReturnValue_t startTask( void ); - /** - * This static function can be used as #deadlineMissedFunc. - * It counts missedDeadlines and prints the number of missed deadlines every 10th time. - */ - static void missedDeadlineCounter(); - /** - * A helper variable to count missed deadlines. - */ - static uint32_t deadlineMissedCount; + ReturnValue_t startTask(void); + /** + * This static function can be used as #deadlineMissedFunc. + * It counts missedDeadlines and prints the number of missed deadlines every 10th time. + */ + static void missedDeadlineCounter(); + /** + * A helper variable to count missed deadlines. + */ + static uint32_t deadlineMissedCount; - ReturnValue_t addSlot(object_id_t componentId, uint32_t slotTimeMs, int8_t executionStep); + ReturnValue_t addSlot(object_id_t componentId, uint32_t slotTimeMs, int8_t executionStep); - uint32_t getPeriodMs() const; + uint32_t getPeriodMs() const; - ReturnValue_t checkSequence() const; + ReturnValue_t checkSequence() const; - ReturnValue_t sleepFor(uint32_t ms); -protected: - /** - * @brief id of the associated OS period - */ - rtems_id periodId; + ReturnValue_t sleepFor(uint32_t ms); - FixedSlotSequence pst; + protected: + /** + * @brief id of the associated OS period + */ + rtems_id periodId; - /** - * @brief This attribute holds a function pointer that is executed when a deadline was missed. - * - * @details - * Another function may be announced to determine the actions to perform when a deadline - * was missed. Currently, only one function for missing any deadline is allowed. - * If not used, it shall be declared NULL. - */ - void ( *deadlineMissedFunc )( void ) = nullptr; - /** - * @brief This is the entry point in a new polling thread. - * @details This method is the entry point in the new thread - */ - static rtems_task taskEntryPoint( rtems_task_argument argument ); + FixedSlotSequence pst; - /** - * @brief This function holds the main functionality of the thread. - * @details - * Holding the main functionality of the task, this method is most important. - * It links the functionalities provided by FixedSlotSequence with the OS's system calls to - * keep the timing of the periods. - */ - void taskFunctionality( void ); + /** + * @brief This attribute holds a function pointer that is executed when a deadline was missed. + * + * @details + * Another function may be announced to determine the actions to perform when a deadline + * was missed. Currently, only one function for missing any deadline is allowed. + * If not used, it shall be declared NULL. + */ + void (*deadlineMissedFunc)(void) = nullptr; + /** + * @brief This is the entry point in a new polling thread. + * @details This method is the entry point in the new thread + */ + static rtems_task taskEntryPoint(rtems_task_argument argument); + + /** + * @brief This function holds the main functionality of the thread. + * @details + * Holding the main functionality of the task, this method is most important. + * It links the functionalities provided by FixedSlotSequence with the OS's system calls to + * keep the timing of the periods. + */ + void taskFunctionality(void); }; #endif /* FSFW_OSAL_RTEMS_FIXEDTIMESLOTTASK_H_ */ diff --git a/src/fsfw/osal/rtems/InitTask.cpp b/src/fsfw/osal/rtems/InitTask.cpp index 8a9bb9f6..7854203c 100644 --- a/src/fsfw/osal/rtems/InitTask.cpp +++ b/src/fsfw/osal/rtems/InitTask.cpp @@ -1,11 +1,7 @@ #include "fsfw/osal/rtems/InitTask.h" + #include "fsfw/osal/rtems/RtemsBasic.h" +InitTask::InitTask() {} - -InitTask::InitTask() { -} - -InitTask::~InitTask() { - rtems_task_delete(RTEMS_SELF); -} +InitTask::~InitTask() { rtems_task_delete(RTEMS_SELF); } diff --git a/src/fsfw/osal/rtems/InitTask.h b/src/fsfw/osal/rtems/InitTask.h index 2c8c0c6a..e880b022 100644 --- a/src/fsfw/osal/rtems/InitTask.h +++ b/src/fsfw/osal/rtems/InitTask.h @@ -1,7 +1,7 @@ #ifndef OS_RTEMS_INITTASK_H_ #define OS_RTEMS_INITTASK_H_ -//TODO move into static function in TaskIF +// TODO move into static function in TaskIF /** * The init task is created automatically by RTEMS. @@ -11,9 +11,9 @@ * calls rtems_task_delete(RTEMS_SELF) */ class InitTask { -public: - InitTask(); - virtual ~InitTask(); + public: + InitTask(); + virtual ~InitTask(); }; #endif /* OS_RTEMS_INITTASK_H_ */ diff --git a/src/fsfw/osal/rtems/InternalErrorCodes.cpp b/src/fsfw/osal/rtems/InternalErrorCodes.cpp index 049286d7..4d78186c 100644 --- a/src/fsfw/osal/rtems/InternalErrorCodes.cpp +++ b/src/fsfw/osal/rtems/InternalErrorCodes.cpp @@ -1,62 +1,59 @@ #include "fsfw/osal/InternalErrorCodes.h" + #include ReturnValue_t InternalErrorCodes::translate(uint8_t code) { - switch (code) { - //TODO It looks like RTEMS-5 does not provide the same error codes -// case INTERNAL_ERROR_NO_CONFIGURATION_TABLE: -// return NO_CONFIGURATION_TABLE; -// case INTERNAL_ERROR_NO_CPU_TABLE: -// return NO_CPU_TABLE; -// case INTERNAL_ERROR_INVALID_WORKSPACE_ADDRESS: -// return INVALID_WORKSPACE_ADDRESS; - case INTERNAL_ERROR_TOO_LITTLE_WORKSPACE: - return TOO_LITTLE_WORKSPACE; -// case INTERNAL_ERROR_WORKSPACE_ALLOCATION: -// return WORKSPACE_ALLOCATION; -// case INTERNAL_ERROR_INTERRUPT_STACK_TOO_SMALL: -// return INTERRUPT_STACK_TOO_SMALL; - case INTERNAL_ERROR_THREAD_EXITTED: - return THREAD_EXITTED; - case INTERNAL_ERROR_INCONSISTENT_MP_INFORMATION: - return INCONSISTENT_MP_INFORMATION; - case INTERNAL_ERROR_INVALID_NODE: - return INVALID_NODE; - case INTERNAL_ERROR_NO_MPCI: - return NO_MPCI; - case INTERNAL_ERROR_BAD_PACKET: - return BAD_PACKET; - case INTERNAL_ERROR_OUT_OF_PACKETS: - return OUT_OF_PACKETS; - case INTERNAL_ERROR_OUT_OF_GLOBAL_OBJECTS: - return OUT_OF_GLOBAL_OBJECTS; - case INTERNAL_ERROR_OUT_OF_PROXIES: - return OUT_OF_PROXIES; - case INTERNAL_ERROR_INVALID_GLOBAL_ID: - return INVALID_GLOBAL_ID; + switch (code) { + // TODO It looks like RTEMS-5 does not provide the same error codes + // case INTERNAL_ERROR_NO_CONFIGURATION_TABLE: + // return NO_CONFIGURATION_TABLE; + // case INTERNAL_ERROR_NO_CPU_TABLE: + // return NO_CPU_TABLE; + // case INTERNAL_ERROR_INVALID_WORKSPACE_ADDRESS: + // return INVALID_WORKSPACE_ADDRESS; + case INTERNAL_ERROR_TOO_LITTLE_WORKSPACE: + return TOO_LITTLE_WORKSPACE; + // case INTERNAL_ERROR_WORKSPACE_ALLOCATION: + // return WORKSPACE_ALLOCATION; + // case INTERNAL_ERROR_INTERRUPT_STACK_TOO_SMALL: + // return INTERRUPT_STACK_TOO_SMALL; + case INTERNAL_ERROR_THREAD_EXITTED: + return THREAD_EXITTED; + case INTERNAL_ERROR_INCONSISTENT_MP_INFORMATION: + return INCONSISTENT_MP_INFORMATION; + case INTERNAL_ERROR_INVALID_NODE: + return INVALID_NODE; + case INTERNAL_ERROR_NO_MPCI: + return NO_MPCI; + case INTERNAL_ERROR_BAD_PACKET: + return BAD_PACKET; + case INTERNAL_ERROR_OUT_OF_PACKETS: + return OUT_OF_PACKETS; + case INTERNAL_ERROR_OUT_OF_GLOBAL_OBJECTS: + return OUT_OF_GLOBAL_OBJECTS; + case INTERNAL_ERROR_OUT_OF_PROXIES: + return OUT_OF_PROXIES; + case INTERNAL_ERROR_INVALID_GLOBAL_ID: + return INVALID_GLOBAL_ID; #ifndef STM32H743ZI_NUCLEO - case INTERNAL_ERROR_BAD_STACK_HOOK: - return BAD_STACK_HOOK; + case INTERNAL_ERROR_BAD_STACK_HOOK: + return BAD_STACK_HOOK; #endif -// case INTERNAL_ERROR_BAD_ATTRIBUTES: -// return BAD_ATTRIBUTES; -// case INTERNAL_ERROR_IMPLEMENTATION_KEY_CREATE_INCONSISTENCY: -// return IMPLEMENTATION_KEY_CREATE_INCONSISTENCY; -// case INTERNAL_ERROR_IMPLEMENTATION_BLOCKING_OPERATION_CANCEL: -// return IMPLEMENTATION_BLOCKING_OPERATION_CANCEL; -// case INTERNAL_ERROR_MUTEX_OBTAIN_FROM_BAD_STATE: -// return MUTEX_OBTAIN_FROM_BAD_STATE; -// case INTERNAL_ERROR_UNLIMITED_AND_MAXIMUM_IS_0: -// return UNLIMITED_AND_MAXIMUM_IS_0; - default: - return HasReturnvaluesIF::RETURN_FAILED; - } + // case INTERNAL_ERROR_BAD_ATTRIBUTES: + // return BAD_ATTRIBUTES; + // case INTERNAL_ERROR_IMPLEMENTATION_KEY_CREATE_INCONSISTENCY: + // return IMPLEMENTATION_KEY_CREATE_INCONSISTENCY; + // case INTERNAL_ERROR_IMPLEMENTATION_BLOCKING_OPERATION_CANCEL: + // return IMPLEMENTATION_BLOCKING_OPERATION_CANCEL; + // case INTERNAL_ERROR_MUTEX_OBTAIN_FROM_BAD_STATE: + // return MUTEX_OBTAIN_FROM_BAD_STATE; + // case INTERNAL_ERROR_UNLIMITED_AND_MAXIMUM_IS_0: + // return UNLIMITED_AND_MAXIMUM_IS_0; + default: + return HasReturnvaluesIF::RETURN_FAILED; + } } -InternalErrorCodes::InternalErrorCodes() { -} - -InternalErrorCodes::~InternalErrorCodes() { - -} +InternalErrorCodes::InternalErrorCodes() {} +InternalErrorCodes::~InternalErrorCodes() {} diff --git a/src/fsfw/osal/rtems/MessageQueue.cpp b/src/fsfw/osal/rtems/MessageQueue.cpp index 65fe0946..e45679d5 100644 --- a/src/fsfw/osal/rtems/MessageQueue.cpp +++ b/src/fsfw/osal/rtems/MessageQueue.cpp @@ -1,155 +1,138 @@ #include "fsfw/osal/rtems/MessageQueue.h" -#include "fsfw/osal/rtems/RtemsBasic.h" - -#include "fsfw/serviceinterface/ServiceInterface.h" -#include "fsfw/objectmanager/ObjectManager.h" #include -MessageQueue::MessageQueue(size_t message_depth, size_t max_message_size) : - id(0), lastPartner(0), defaultDestination(NO_QUEUE), internalErrorReporter(nullptr) { - rtems_name name = ('Q' << 24) + (queueCounter++ << 8); - rtems_status_code status = rtems_message_queue_create(name, message_depth, - max_message_size, 0, &(this->id)); - if (status != RTEMS_SUCCESSFUL) { +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/osal/rtems/RtemsBasic.h" +#include "fsfw/serviceinterface/ServiceInterface.h" + +MessageQueue::MessageQueue(size_t message_depth, size_t max_message_size) + : id(0), lastPartner(0), defaultDestination(NO_QUEUE), internalErrorReporter(nullptr) { + rtems_name name = ('Q' << 24) + (queueCounter++ << 8); + rtems_status_code status = + rtems_message_queue_create(name, message_depth, max_message_size, 0, &(this->id)); + if (status != RTEMS_SUCCESSFUL) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "MessageQueue::MessageQueue: Creating Queue " << std::hex - << name << std::dec << " failed with status:" - << (uint32_t) status << std::endl; + sif::error << "MessageQueue::MessageQueue: Creating Queue " << std::hex << name << std::dec + << " failed with status:" << (uint32_t)status << std::endl; #endif - this->id = 0; - } + this->id = 0; + } } -MessageQueue::~MessageQueue() { - rtems_message_queue_delete(id); -} +MessageQueue::~MessageQueue() { rtems_message_queue_delete(id); } -ReturnValue_t MessageQueue::sendMessage(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, bool ignoreFault) { - return sendMessageFrom(sendTo, message, this->getId(), ignoreFault); +ReturnValue_t MessageQueue::sendMessage(MessageQueueId_t sendTo, MessageQueueMessageIF* message, + bool ignoreFault) { + return sendMessageFrom(sendTo, message, this->getId(), ignoreFault); } ReturnValue_t MessageQueue::sendToDefault(MessageQueueMessageIF* message) { - return sendToDefaultFrom(message, this->getId()); + return sendToDefaultFrom(message, this->getId()); } ReturnValue_t MessageQueue::reply(MessageQueueMessageIF* message) { - if (this->lastPartner != 0) { - return sendMessage(this->lastPartner, message, this->getId()); - } else { - return NO_REPLY_PARTNER; - } + if (this->lastPartner != 0) { + return sendMessage(this->lastPartner, message, this->getId()); + } else { + return NO_REPLY_PARTNER; + } } ReturnValue_t MessageQueue::receiveMessage(MessageQueueMessageIF* message, - MessageQueueId_t* receivedFrom) { - ReturnValue_t status = this->receiveMessage(message); - *receivedFrom = this->lastPartner; - return status; + MessageQueueId_t* receivedFrom) { + ReturnValue_t status = this->receiveMessage(message); + *receivedFrom = this->lastPartner; + return status; } ReturnValue_t MessageQueue::receiveMessage(MessageQueueMessageIF* message) { - size_t size = 0; - rtems_status_code status = rtems_message_queue_receive(id, - message->getBuffer(),&size, - RTEMS_NO_WAIT, 1); - if (status == RTEMS_SUCCESSFUL) { - message->setMessageSize(size); - this->lastPartner = message->getSender(); - //Check size of incoming message. - if (message->getMessageSize() < message->getMinimumMessageSize()) { - return HasReturnvaluesIF::RETURN_FAILED; - } - } else { - //No message was received. Keep lastPartner anyway, I might send something later. - //But still, delete packet content. - memset(message->getData(), 0, message->getMaximumDataSize()); - } - return convertReturnCode(status); + size_t size = 0; + rtems_status_code status = + rtems_message_queue_receive(id, message->getBuffer(), &size, RTEMS_NO_WAIT, 1); + if (status == RTEMS_SUCCESSFUL) { + message->setMessageSize(size); + this->lastPartner = message->getSender(); + // Check size of incoming message. + if (message->getMessageSize() < message->getMinimumMessageSize()) { + return HasReturnvaluesIF::RETURN_FAILED; + } + } else { + // No message was received. Keep lastPartner anyway, I might send something later. + // But still, delete packet content. + memset(message->getData(), 0, message->getMaximumDataSize()); + } + return convertReturnCode(status); } -MessageQueueId_t MessageQueue::getLastPartner() const { - return this->lastPartner; -} +MessageQueueId_t MessageQueue::getLastPartner() const { return this->lastPartner; } ReturnValue_t MessageQueue::flush(uint32_t* count) { - rtems_status_code status = rtems_message_queue_flush(id, count); - return convertReturnCode(status); + rtems_status_code status = rtems_message_queue_flush(id, count); + return convertReturnCode(status); } -MessageQueueId_t MessageQueue::getId() const { - return this->id; -} +MessageQueueId_t MessageQueue::getId() const { return this->id; } void MessageQueue::setDefaultDestination(MessageQueueId_t defaultDestination) { - this->defaultDestination = defaultDestination; + this->defaultDestination = defaultDestination; } -ReturnValue_t MessageQueue::sendMessageFrom(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, MessageQueueId_t sentFrom, - bool ignoreFault) { +ReturnValue_t MessageQueue::sendMessageFrom(MessageQueueId_t sendTo, MessageQueueMessageIF* message, + MessageQueueId_t sentFrom, bool ignoreFault) { + message->setSender(sentFrom); + rtems_status_code result = + rtems_message_queue_send(sendTo, message->getBuffer(), message->getMessageSize()); - message->setSender(sentFrom); - rtems_status_code result = rtems_message_queue_send(sendTo, - message->getBuffer(), message->getMessageSize()); + // TODO: Check if we're in ISR. + if (result != RTEMS_SUCCESSFUL && !ignoreFault) { + if (internalErrorReporter == nullptr) { + internalErrorReporter = + ObjectManager::instance()->get(objects::INTERNAL_ERROR_REPORTER); + } + if (internalErrorReporter != nullptr) { + internalErrorReporter->queueMessageNotSent(); + } + } - //TODO: Check if we're in ISR. - if (result != RTEMS_SUCCESSFUL && !ignoreFault) { - if (internalErrorReporter == nullptr) { - internalErrorReporter = ObjectManager::instance()->get( - objects::INTERNAL_ERROR_REPORTER); - } - if (internalErrorReporter != nullptr) { - internalErrorReporter->queueMessageNotSent(); - } - } + ReturnValue_t returnCode = convertReturnCode(result); + if (result == MessageQueueIF::EMPTY) { + return HasReturnvaluesIF::RETURN_FAILED; + } - ReturnValue_t returnCode = convertReturnCode(result); - if(result == MessageQueueIF::EMPTY){ - return HasReturnvaluesIF::RETURN_FAILED; - } - - return returnCode; + return returnCode; } ReturnValue_t MessageQueue::sendToDefaultFrom(MessageQueueMessageIF* message, - MessageQueueId_t sentFrom, bool ignoreFault) { - return sendMessageFrom(defaultDestination, message, sentFrom, ignoreFault); + MessageQueueId_t sentFrom, bool ignoreFault) { + return sendMessageFrom(defaultDestination, message, sentFrom, ignoreFault); } -MessageQueueId_t MessageQueue::getDefaultDestination() const { - return this->defaultDestination; +MessageQueueId_t MessageQueue::getDefaultDestination() const { return this->defaultDestination; } + +bool MessageQueue::isDefaultDestinationSet() const { return (defaultDestination != NO_QUEUE); } + +ReturnValue_t MessageQueue::convertReturnCode(rtems_status_code inValue) { + switch (inValue) { + case RTEMS_SUCCESSFUL: + return HasReturnvaluesIF::RETURN_OK; + case RTEMS_INVALID_ID: + return HasReturnvaluesIF::RETURN_FAILED; + case RTEMS_TIMEOUT: + return HasReturnvaluesIF::RETURN_FAILED; + case RTEMS_OBJECT_WAS_DELETED: + return HasReturnvaluesIF::RETURN_FAILED; + case RTEMS_INVALID_ADDRESS: + return HasReturnvaluesIF::RETURN_FAILED; + case RTEMS_INVALID_SIZE: + return HasReturnvaluesIF::RETURN_FAILED; + case RTEMS_TOO_MANY: + return MessageQueueIF::FULL; + case RTEMS_UNSATISFIED: + return MessageQueueIF::EMPTY; + default: + return HasReturnvaluesIF::RETURN_FAILED; + } } -bool MessageQueue::isDefaultDestinationSet() const { - return (defaultDestination != NO_QUEUE); -} - -ReturnValue_t MessageQueue::convertReturnCode(rtems_status_code inValue){ - switch(inValue){ - case RTEMS_SUCCESSFUL: - return HasReturnvaluesIF::RETURN_OK; - case RTEMS_INVALID_ID: - return HasReturnvaluesIF::RETURN_FAILED; - case RTEMS_TIMEOUT: - return HasReturnvaluesIF::RETURN_FAILED; - case RTEMS_OBJECT_WAS_DELETED: - return HasReturnvaluesIF::RETURN_FAILED; - case RTEMS_INVALID_ADDRESS: - return HasReturnvaluesIF::RETURN_FAILED; - case RTEMS_INVALID_SIZE: - return HasReturnvaluesIF::RETURN_FAILED; - case RTEMS_TOO_MANY: - return MessageQueueIF::FULL; - case RTEMS_UNSATISFIED: - return MessageQueueIF::EMPTY; - default: - return HasReturnvaluesIF::RETURN_FAILED; - } - -} - - - uint16_t MessageQueue::queueCounter = 0; diff --git a/src/fsfw/osal/rtems/MessageQueue.h b/src/fsfw/osal/rtems/MessageQueue.h index fa143ebe..89aae2ad 100644 --- a/src/fsfw/osal/rtems/MessageQueue.h +++ b/src/fsfw/osal/rtems/MessageQueue.h @@ -1,172 +1,178 @@ #ifndef FSFW_OSAL_RTEMS_MESSAGEQUEUE_H_ #define FSFW_OSAL_RTEMS_MESSAGEQUEUE_H_ +#include "RtemsBasic.h" #include "fsfw/internalerror/InternalErrorReporterIF.h" #include "fsfw/ipc/MessageQueueIF.h" #include "fsfw/ipc/MessageQueueMessage.h" -#include "RtemsBasic.h" /** * @brief This class manages sending and receiving of message queue messages. * * @details Message queues are used to pass asynchronous messages between processes. - * They work like post boxes, where all incoming messages are stored in FIFO - * order. This class creates a new receiving queue and provides methods to fetch - * received messages. Being a child of MessageQueueSender, this class also provides - * methods to send a message to a user-defined or a default destination. In addition - * it also provides a reply method to answer to the queue it received its last message - * from. - * The MessageQueue should be used as "post box" for a single owning object. So all - * message queue communication is "n-to-one". - * For creating the queue, as well as sending and receiving messages, the class makes - * use of the operating system calls provided. - * \ingroup message_queue + * They work like post boxes, where all incoming messages are stored in + *FIFO order. This class creates a new receiving queue and provides methods to fetch received + *messages. Being a child of MessageQueueSender, this class also provides methods to send a message + *to a user-defined or a default destination. In addition it also provides a reply method to answer + *to the queue it received its last message from. The MessageQueue should be used as "post box" for + *a single owning object. So all message queue communication is "n-to-one". For creating the queue, + *as well as sending and receiving messages, the class makes use of the operating system calls + *provided. \ingroup message_queue */ class MessageQueue : public MessageQueueIF { -public: - /** - * @brief The constructor initializes and configures the message queue. - * @details By making use of the according operating system call, a message queue is created - * and initialized. The message depth - the maximum number of messages to be - * buffered - may be set with the help of a parameter, whereas the message size is - * automatically set to the maximum message queue message size. The operating system - * sets the message queue id, or i case of failure, it is set to zero. - * @param message_depth The number of messages to be buffered before passing an error to the - * sender. Default is three. - * @param max_message_size With this parameter, the maximum message size can be adjusted. - * This should be left default. - */ - MessageQueue( size_t message_depth = 3, size_t max_message_size = MessageQueueMessage::MAX_MESSAGE_SIZE ); - /** - * @brief The destructor deletes the formerly created message queue. - * @details This is accomplished by using the delete call provided by the operating system. - */ - virtual ~MessageQueue(); - /** - * @brief This operation sends a message to the given destination. - * @details It directly uses the sendMessage call of the MessageQueueSender parent, but passes its - * queue id as "sentFrom" parameter. - * @param sendTo This parameter specifies the message queue id of the destination message queue. - * @param message A pointer to a previously created message, which is sent. - * @param ignoreFault If set to true, the internal software fault counter is not incremented if queue is full. - */ - ReturnValue_t sendMessage(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, bool ignoreFault = false ); - /** - * @brief This operation sends a message to the default destination. - * @details As in the sendMessage method, this function uses the sendToDefault call of the - * MessageQueueSender parent class and adds its queue id as "sentFrom" information. - * @param message A pointer to a previously created message, which is sent. - */ - ReturnValue_t sendToDefault( MessageQueueMessageIF* message ); - /** - * @brief This operation sends a message to the last communication partner. - * @details This operation simplifies answering an incoming message by using the stored - * lastParnter information as destination. If there was no message received yet - * (i.e. lastPartner is zero), an error code is returned. - * @param message A pointer to a previously created message, which is sent. - */ - ReturnValue_t reply( MessageQueueMessageIF* message ); + public: + /** + * @brief The constructor initializes and configures the message queue. + * @details By making use of the according operating system call, a message queue is created + * and initialized. The message depth - the maximum number of messages to be + * buffered - may be set with the help of a parameter, whereas the message size + * is automatically set to the maximum message queue message size. The operating system sets the + * message queue id, or i case of failure, it is set to zero. + * @param message_depth The number of messages to be buffered before passing an error to the + * sender. Default is three. + * @param max_message_size With this parameter, the maximum message size can be adjusted. + * This should be left default. + */ + MessageQueue(size_t message_depth = 3, + size_t max_message_size = MessageQueueMessage::MAX_MESSAGE_SIZE); + /** + * @brief The destructor deletes the formerly created message queue. + * @details This is accomplished by using the delete call provided by the operating system. + */ + virtual ~MessageQueue(); + /** + * @brief This operation sends a message to the given destination. + * @details It directly uses the sendMessage call of the MessageQueueSender parent, but passes + * its queue id as "sentFrom" parameter. + * @param sendTo This parameter specifies the message queue id of the destination message + * queue. + * @param message A pointer to a previously created message, which is sent. + * @param ignoreFault If set to true, the internal software fault counter is not incremented if + * queue is full. + */ + ReturnValue_t sendMessage(MessageQueueId_t sendTo, MessageQueueMessageIF* message, + bool ignoreFault = false); + /** + * @brief This operation sends a message to the default destination. + * @details As in the sendMessage method, this function uses the sendToDefault call of the + * MessageQueueSender parent class and adds its queue id as "sentFrom" + * information. + * @param message A pointer to a previously created message, which is sent. + */ + ReturnValue_t sendToDefault(MessageQueueMessageIF* message); + /** + * @brief This operation sends a message to the last communication partner. + * @details This operation simplifies answering an incoming message by using the stored + * lastParnter information as destination. If there was no message received yet + * (i.e. lastPartner is zero), an error code is returned. + * @param message A pointer to a previously created message, which is sent. + */ + ReturnValue_t reply(MessageQueueMessageIF* message); - /** - * @brief This function reads available messages from the message queue and returns the sender. - * @details It works identically to the other receiveMessage call, but in addition returns the - * sender's queue id. - * @param message A pointer to a message in which the received data is stored. - * @param receivedFrom A pointer to a queue id in which the sender's id is stored. - */ - ReturnValue_t receiveMessage(MessageQueueMessageIF* message, - MessageQueueId_t *receivedFrom); + /** + * @brief This function reads available messages from the message queue and returns the + * sender. + * @details It works identically to the other receiveMessage call, but in addition returns the + * sender's queue id. + * @param message A pointer to a message in which the received data is stored. + * @param receivedFrom A pointer to a queue id in which the sender's id is stored. + */ + ReturnValue_t receiveMessage(MessageQueueMessageIF* message, MessageQueueId_t* receivedFrom); - /** - * @brief This function reads available messages from the message queue. - * @details If data is available it is stored in the passed message pointer. The message's - * original content is overwritten and the sendFrom information is stored in the - * lastPartner attribute. Else, the lastPartner information remains untouched, the - * message's content is cleared and the function returns immediately. - * @param message A pointer to a message in which the received data is stored. - */ - ReturnValue_t receiveMessage(MessageQueueMessageIF* message); - /** - * Deletes all pending messages in the queue. - * @param count The number of flushed messages. - * @return RETURN_OK on success. - */ - ReturnValue_t flush(uint32_t* count); - /** - * @brief This method returns the message queue id of the last communication partner. - */ - MessageQueueId_t getLastPartner() const; - /** - * @brief This method returns the message queue id of this class's message queue. - */ - MessageQueueId_t getId() const; - /** - * \brief With the sendMessage call, a queue message is sent to a receiving queue. - * \details This method takes the message provided, adds the sentFrom information and passes - * it on to the destination provided with an operating system call. The OS's return - * value is returned. - * \param sendTo This parameter specifies the message queue id to send the message to. - * \param message This is a pointer to a previously created message, which is sent. - * \param sentFrom The sentFrom information can be set to inject the sender's queue id into the message. - * This variable is set to zero by default. - * \param ignoreFault If set to true, the internal software fault counter is not incremented if queue is full. - */ - virtual ReturnValue_t sendMessageFrom( MessageQueueId_t sendTo, MessageQueueMessageIF* message, MessageQueueId_t sentFrom = NO_QUEUE, bool ignoreFault = false ); - /** - * \brief The sendToDefault method sends a queue message to the default destination. - * \details In all other aspects, it works identical to the sendMessage method. - * \param message This is a pointer to a previously created message, which is sent. - * \param sentFrom The sentFrom information can be set to inject the sender's queue id into the message. - * This variable is set to zero by default. - */ - virtual ReturnValue_t sendToDefaultFrom( MessageQueueMessageIF* message, MessageQueueId_t sentFrom = NO_QUEUE, bool ignoreFault = false ); - /** - * \brief This method is a simple setter for the default destination. - */ - void setDefaultDestination(MessageQueueId_t defaultDestination); - /** - * \brief This method is a simple getter for the default destination. - */ - MessageQueueId_t getDefaultDestination() const; + /** + * @brief This function reads available messages from the message queue. + * @details If data is available it is stored in the passed message pointer. The message's + * original content is overwritten and the sendFrom information is stored in + * the lastPartner attribute. Else, the lastPartner information remains untouched, the message's + * content is cleared and the function returns immediately. + * @param message A pointer to a message in which the received data is stored. + */ + ReturnValue_t receiveMessage(MessageQueueMessageIF* message); + /** + * Deletes all pending messages in the queue. + * @param count The number of flushed messages. + * @return RETURN_OK on success. + */ + ReturnValue_t flush(uint32_t* count); + /** + * @brief This method returns the message queue id of the last communication partner. + */ + MessageQueueId_t getLastPartner() const; + /** + * @brief This method returns the message queue id of this class's message queue. + */ + MessageQueueId_t getId() const; + /** + * \brief With the sendMessage call, a queue message is sent to a receiving queue. + * \details This method takes the message provided, adds the sentFrom information and passes + * it on to the destination provided with an operating system call. The OS's + * return value is returned. + * \param sendTo This parameter specifies the message queue id to send the message to. + * \param message This is a pointer to a previously created message, which is sent. + * \param sentFrom The sentFrom information can be set to inject the sender's queue id into the + * message. This variable is set to zero by default. \param ignoreFault If set to true, the + * internal software fault counter is not incremented if queue is full. + */ + virtual ReturnValue_t sendMessageFrom(MessageQueueId_t sendTo, MessageQueueMessageIF* message, + MessageQueueId_t sentFrom = NO_QUEUE, + bool ignoreFault = false); + /** + * \brief The sendToDefault method sends a queue message to the default destination. + * \details In all other aspects, it works identical to the sendMessage method. + * \param message This is a pointer to a previously created message, which is sent. + * \param sentFrom The sentFrom information can be set to inject the sender's queue id into the + * message. This variable is set to zero by default. + */ + virtual ReturnValue_t sendToDefaultFrom(MessageQueueMessageIF* message, + MessageQueueId_t sentFrom = NO_QUEUE, + bool ignoreFault = false); + /** + * \brief This method is a simple setter for the default destination. + */ + void setDefaultDestination(MessageQueueId_t defaultDestination); + /** + * \brief This method is a simple getter for the default destination. + */ + MessageQueueId_t getDefaultDestination() const; - bool isDefaultDestinationSet() const; -private: - /** - * @brief The class stores the queue id it got assigned from the operating system in this attribute. - * If initialization fails, the queue id is set to zero. - */ - MessageQueueId_t id; - /** - * @brief In this attribute, the queue id of the last communication partner is stored - * to allow for replying. - */ - MessageQueueId_t lastPartner; - /** - * @brief The message queue's name -a user specific information for the operating system- is - * generated automatically with the help of this static counter. - */ - /** - * \brief This attribute stores a default destination to send messages to. - * \details It is stored to simplify sending to always-the-same receiver. The attribute may - * be set in the constructor or by a setter call to setDefaultDestination. - */ - MessageQueueId_t defaultDestination; + bool isDefaultDestinationSet() const; - /** - * \brief This attribute stores a reference to the internal error reporter for reporting full queues. - * \details In the event of a full destination queue, the reporter will be notified. The reference is set - * by lazy loading - */ - InternalErrorReporterIF *internalErrorReporter; + private: + /** + * @brief The class stores the queue id it got assigned from the operating system in this + * attribute. If initialization fails, the queue id is set to zero. + */ + MessageQueueId_t id; + /** + * @brief In this attribute, the queue id of the last communication partner is stored + * to allow for replying. + */ + MessageQueueId_t lastPartner; + /** + * @brief The message queue's name -a user specific information for the operating system- is + * generated automatically with the help of this static counter. + */ + /** + * \brief This attribute stores a default destination to send messages to. + * \details It is stored to simplify sending to always-the-same receiver. The attribute may + * be set in the constructor or by a setter call to setDefaultDestination. + */ + MessageQueueId_t defaultDestination; - static uint16_t queueCounter; - /** - * A method to convert an OS-specific return code to the frameworks return value concept. - * @param inValue The return code coming from the OS. - * @return The converted return value. - */ - static ReturnValue_t convertReturnCode(rtems_status_code inValue); + /** + * \brief This attribute stores a reference to the internal error reporter for reporting full + * queues. \details In the event of a full destination queue, the reporter will be notified. The + * reference is set by lazy loading + */ + InternalErrorReporterIF* internalErrorReporter; + + static uint16_t queueCounter; + /** + * A method to convert an OS-specific return code to the frameworks return value concept. + * @param inValue The return code coming from the OS. + * @return The converted return value. + */ + static ReturnValue_t convertReturnCode(rtems_status_code inValue); }; #endif /* FSFW_OSAL_RTEMS_MESSAGEQUEUE_H_ */ diff --git a/src/fsfw/osal/rtems/Mutex.cpp b/src/fsfw/osal/rtems/Mutex.cpp index 2dfa39fa..94f0041e 100644 --- a/src/fsfw/osal/rtems/Mutex.cpp +++ b/src/fsfw/osal/rtems/Mutex.cpp @@ -1,85 +1,79 @@ #include "fsfw/osal/rtems/Mutex.h" + #include "fsfw/serviceinterface/ServiceInterface.h" uint8_t Mutex::count = 0; Mutex::Mutex() { - rtems_name mutexName = ('M' << 24) + ('T' << 16) + ('X' << 8) + count++; - rtems_status_code status = rtems_semaphore_create(mutexName, 1, - RTEMS_BINARY_SEMAPHORE | RTEMS_PRIORITY | RTEMS_INHERIT_PRIORITY, 0, - &mutexId); - if (status != RTEMS_SUCCESSFUL) { + rtems_name mutexName = ('M' << 24) + ('T' << 16) + ('X' << 8) + count++; + rtems_status_code status = rtems_semaphore_create( + mutexName, 1, RTEMS_BINARY_SEMAPHORE | RTEMS_PRIORITY | RTEMS_INHERIT_PRIORITY, 0, &mutexId); + if (status != RTEMS_SUCCESSFUL) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Mutex::Mutex: Creation with name, id " << mutexName << ", " << mutexId << - " failed with " << status << std::endl; + sif::error << "Mutex::Mutex: Creation with name, id " << mutexName << ", " << mutexId + << " failed with " << status << std::endl; #else - sif::printError("Mutex::Mutex: Creation with name, id %s, %d failed with %d\n", mutexName, - static_cast(mutexId), static_cast(status)); + sif::printError("Mutex::Mutex: Creation with name, id %s, %d failed with %d\n", mutexName, + static_cast(mutexId), static_cast(status)); #endif - } + } } Mutex::~Mutex() { - rtems_status_code status = rtems_semaphore_delete(mutexId); - if (status != RTEMS_SUCCESSFUL) { + rtems_status_code status = rtems_semaphore_delete(mutexId); + if (status != RTEMS_SUCCESSFUL) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Mutex: deletion for id " << mutexId - << " failed with " << status << std::endl; + sif::error << "Mutex: deletion for id " << mutexId << " failed with " << status << std::endl; #endif - } + } } -ReturnValue_t Mutex::lockMutex(TimeoutType timeoutType = - TimeoutType::BLOCKING, uint32_t timeoutMs) { - rtems_status_code status = RTEMS_INVALID_ID; - if(timeoutType == MutexIF::TimeoutType::BLOCKING) { - status = rtems_semaphore_obtain(mutexId, - RTEMS_WAIT, RTEMS_NO_TIMEOUT); - } - else if(timeoutType == MutexIF::TimeoutType::POLLING) { - timeoutMs = RTEMS_NO_TIMEOUT; - status = rtems_semaphore_obtain(mutexId, - RTEMS_NO_WAIT, 0); - } - else { - status = rtems_semaphore_obtain(mutexId, - RTEMS_WAIT, timeoutMs); - } +ReturnValue_t Mutex::lockMutex(TimeoutType timeoutType = TimeoutType::BLOCKING, + uint32_t timeoutMs) { + rtems_status_code status = RTEMS_INVALID_ID; + if (timeoutType == MutexIF::TimeoutType::BLOCKING) { + status = rtems_semaphore_obtain(mutexId, RTEMS_WAIT, RTEMS_NO_TIMEOUT); + } else if (timeoutType == MutexIF::TimeoutType::POLLING) { + timeoutMs = RTEMS_NO_TIMEOUT; + status = rtems_semaphore_obtain(mutexId, RTEMS_NO_WAIT, 0); + } else { + status = rtems_semaphore_obtain(mutexId, RTEMS_WAIT, timeoutMs); + } - switch(status){ - case RTEMS_SUCCESSFUL: - //semaphore obtained successfully - return HasReturnvaluesIF::RETURN_OK; - case RTEMS_UNSATISFIED: - //semaphore not available - return MUTEX_NOT_FOUND; - case RTEMS_TIMEOUT: - //timed out waiting for semaphore - return MUTEX_TIMEOUT; - case RTEMS_OBJECT_WAS_DELETED: - //semaphore deleted while waiting - return MUTEX_DESTROYED_WHILE_WAITING; - case RTEMS_INVALID_ID: - //invalid semaphore id - return MUTEX_INVALID_ID; - default: - return HasReturnvaluesIF::RETURN_FAILED; - } + switch (status) { + case RTEMS_SUCCESSFUL: + // semaphore obtained successfully + return HasReturnvaluesIF::RETURN_OK; + case RTEMS_UNSATISFIED: + // semaphore not available + return MUTEX_NOT_FOUND; + case RTEMS_TIMEOUT: + // timed out waiting for semaphore + return MUTEX_TIMEOUT; + case RTEMS_OBJECT_WAS_DELETED: + // semaphore deleted while waiting + return MUTEX_DESTROYED_WHILE_WAITING; + case RTEMS_INVALID_ID: + // invalid semaphore id + return MUTEX_INVALID_ID; + default: + return HasReturnvaluesIF::RETURN_FAILED; + } } ReturnValue_t Mutex::unlockMutex() { - rtems_status_code status = rtems_semaphore_release(mutexId); - switch(status){ - case RTEMS_SUCCESSFUL: - //semaphore obtained successfully - return HasReturnvaluesIF::RETURN_OK; - case RTEMS_NOT_OWNER_OF_RESOURCE: - //semaphore not available - return CURR_THREAD_DOES_NOT_OWN_MUTEX; - case RTEMS_INVALID_ID: - //invalid semaphore id - return MUTEX_INVALID_ID; - default: - return HasReturnvaluesIF::RETURN_FAILED; - } + rtems_status_code status = rtems_semaphore_release(mutexId); + switch (status) { + case RTEMS_SUCCESSFUL: + // semaphore obtained successfully + return HasReturnvaluesIF::RETURN_OK; + case RTEMS_NOT_OWNER_OF_RESOURCE: + // semaphore not available + return CURR_THREAD_DOES_NOT_OWN_MUTEX; + case RTEMS_INVALID_ID: + // invalid semaphore id + return MUTEX_INVALID_ID; + default: + return HasReturnvaluesIF::RETURN_FAILED; + } } diff --git a/src/fsfw/osal/rtems/Mutex.h b/src/fsfw/osal/rtems/Mutex.h index c4917e08..e4280381 100644 --- a/src/fsfw/osal/rtems/Mutex.h +++ b/src/fsfw/osal/rtems/Mutex.h @@ -5,14 +5,15 @@ #include "RtemsBasic.h" class Mutex : public MutexIF { -public: - Mutex(); - ~Mutex(); - ReturnValue_t lockMutex(TimeoutType timeoutType, uint32_t timeoutMs = 0); - ReturnValue_t unlockMutex(); -private: - rtems_id mutexId = 0; - static uint8_t count; + public: + Mutex(); + ~Mutex(); + ReturnValue_t lockMutex(TimeoutType timeoutType, uint32_t timeoutMs = 0); + ReturnValue_t unlockMutex(); + + private: + rtems_id mutexId = 0; + static uint8_t count; }; #endif /* FSFW_OSAL_RTEMS_MUTEX_H_ */ diff --git a/src/fsfw/osal/rtems/MutexFactory.cpp b/src/fsfw/osal/rtems/MutexFactory.cpp index bf7ce666..14a6c938 100644 --- a/src/fsfw/osal/rtems/MutexFactory.cpp +++ b/src/fsfw/osal/rtems/MutexFactory.cpp @@ -1,24 +1,15 @@ -#include "fsfw/osal/rtems/Mutex.h" - #include "fsfw/ipc/MutexFactory.h" +#include "fsfw/osal/rtems/Mutex.h" MutexFactory* MutexFactory::factoryInstance = new MutexFactory(); -MutexFactory::MutexFactory() { -} +MutexFactory::MutexFactory() {} -MutexFactory::~MutexFactory() { -} +MutexFactory::~MutexFactory() {} -MutexFactory* MutexFactory::instance() { - return MutexFactory::factoryInstance; -} +MutexFactory* MutexFactory::instance() { return MutexFactory::factoryInstance; } -MutexIF* MutexFactory::createMutex() { - return new Mutex(); -} +MutexIF* MutexFactory::createMutex() { return new Mutex(); } -void MutexFactory::deleteMutex(MutexIF* mutex) { - delete mutex; -} +void MutexFactory::deleteMutex(MutexIF* mutex) { delete mutex; } diff --git a/src/fsfw/osal/rtems/PeriodicTask.cpp b/src/fsfw/osal/rtems/PeriodicTask.cpp index db98153c..1785c8cf 100644 --- a/src/fsfw/osal/rtems/PeriodicTask.cpp +++ b/src/fsfw/osal/rtems/PeriodicTask.cpp @@ -1,84 +1,80 @@ #include "fsfw/osal/rtems/PeriodicTask.h" -#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/tasks/ExecutableObjectIF.h" -PeriodicTask::PeriodicTask(const char *name, rtems_task_priority setPriority, - size_t setStack, rtems_interval setPeriod, void (*setDeadlineMissedFunc)()) : - RTEMSTaskBase(setPriority, setStack, name), - periodTicks(RtemsBasic::convertMsToTicks(setPeriod)), - deadlineMissedFunc(setDeadlineMissedFunc) { -} +PeriodicTask::PeriodicTask(const char* name, rtems_task_priority setPriority, size_t setStack, + rtems_interval setPeriod, void (*setDeadlineMissedFunc)()) + : RTEMSTaskBase(setPriority, setStack, name), + periodTicks(RtemsBasic::convertMsToTicks(setPeriod)), + deadlineMissedFunc(setDeadlineMissedFunc) {} PeriodicTask::~PeriodicTask(void) { - /* Do not delete objects, we were responsible for pointers only. */ - rtems_rate_monotonic_delete(periodId); + /* Do not delete objects, we were responsible for pointers only. */ + rtems_rate_monotonic_delete(periodId); } rtems_task PeriodicTask::taskEntryPoint(rtems_task_argument argument) { - /* The argument is re-interpreted as MultiObjectTask. The Task object is global, - so it is found from any place. */ - PeriodicTask *originalTask(reinterpret_cast(argument)); - return originalTask->taskFunctionality();; + /* The argument is re-interpreted as MultiObjectTask. The Task object is global, + so it is found from any place. */ + PeriodicTask* originalTask(reinterpret_cast(argument)); + return originalTask->taskFunctionality(); + ; } ReturnValue_t PeriodicTask::startTask() { - rtems_status_code status = rtems_task_start(id, PeriodicTask::taskEntryPoint, - rtems_task_argument((void *) this)); - if (status != RTEMS_SUCCESSFUL) { + rtems_status_code status = + rtems_task_start(id, PeriodicTask::taskEntryPoint, rtems_task_argument((void*)this)); + if (status != RTEMS_SUCCESSFUL) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "ObjectTask::startTask for " << std::hex << this->getId() - << std::dec << " failed." << std::endl; + sif::error << "ObjectTask::startTask for " << std::hex << this->getId() << std::dec + << " failed." << std::endl; #endif - } - switch(status){ + } + switch (status) { case RTEMS_SUCCESSFUL: - /* Task started successfully */ - return HasReturnvaluesIF::RETURN_OK; + /* Task started successfully */ + return HasReturnvaluesIF::RETURN_OK; default: - /* RTEMS_INVALID_ADDRESS - invalid task entry point - RTEMS_INVALID_ID - invalid task id - RTEMS_INCORRECT_STATE - task not in the dormant state - RTEMS_ILLEGAL_ON_REMOTE_OBJECT - cannot start remote task */ - return HasReturnvaluesIF::RETURN_FAILED; - } + /* RTEMS_INVALID_ADDRESS - invalid task entry point + RTEMS_INVALID_ID - invalid task id + RTEMS_INCORRECT_STATE - task not in the dormant state + RTEMS_ILLEGAL_ON_REMOTE_OBJECT - cannot start remote task */ + return HasReturnvaluesIF::RETURN_FAILED; + } } -ReturnValue_t PeriodicTask::sleepFor(uint32_t ms) { - return RTEMSTaskBase::sleepFor(ms); -} +ReturnValue_t PeriodicTask::sleepFor(uint32_t ms) { return RTEMSTaskBase::sleepFor(ms); } void PeriodicTask::taskFunctionality() { - RTEMSTaskBase::setAndStartPeriod(periodTicks,&periodId); - for (const auto& object: objectList) { - object->initializeAfterTaskCreation(); + RTEMSTaskBase::setAndStartPeriod(periodTicks, &periodId); + for (const auto& object : objectList) { + object->initializeAfterTaskCreation(); + } + /* The task's "infinite" inner loop is entered. */ + while (1) { + for (const auto& object : objectList) { + object->performOperation(); } - /* The task's "infinite" inner loop is entered. */ - while (1) { - for (const auto& object: objectList) { - object->performOperation(); - } - rtems_status_code status = RTEMSTaskBase::restartPeriod(periodTicks,periodId); - if (status == RTEMS_TIMEOUT) { - if (this->deadlineMissedFunc != nullptr) { - this->deadlineMissedFunc(); - } - } + rtems_status_code status = RTEMSTaskBase::restartPeriod(periodTicks, periodId); + if (status == RTEMS_TIMEOUT) { + if (this->deadlineMissedFunc != nullptr) { + this->deadlineMissedFunc(); + } } + } } ReturnValue_t PeriodicTask::addComponent(object_id_t object) { - ExecutableObjectIF* newObject = ObjectManager::instance()->get(object); - if (newObject == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - objectList.push_back(newObject); - newObject->setTaskIF(this); + ExecutableObjectIF* newObject = ObjectManager::instance()->get(object); + if (newObject == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + objectList.push_back(newObject); + newObject->setTaskIF(this); - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } -uint32_t PeriodicTask::getPeriodMs() const { - return RtemsBasic::convertTicksToMs(periodTicks); -} +uint32_t PeriodicTask::getPeriodMs() const { return RtemsBasic::convertTicksToMs(periodTicks); } diff --git a/src/fsfw/osal/rtems/PeriodicTask.h b/src/fsfw/osal/rtems/PeriodicTask.h index 2ecce457..e2643ec7 100644 --- a/src/fsfw/osal/rtems/PeriodicTask.h +++ b/src/fsfw/osal/rtems/PeriodicTask.h @@ -1,11 +1,11 @@ #ifndef FSFW_OSAL_RTEMS_PERIODICTASK_H_ #define FSFW_OSAL_RTEMS_PERIODICTASK_H_ -#include "RTEMSTaskBase.h" +#include + #include "../../objectmanager/ObjectManagerIF.h" #include "../../tasks/PeriodicTaskIF.h" - -#include +#include "RTEMSTaskBase.h" class ExecutableObjectIF; @@ -13,95 +13,96 @@ class ExecutableObjectIF; * @brief This class represents a specialized task for periodic activities of multiple objects. * * @details MultiObjectTask is an extension to ObjectTask in the way that it is able to execute - * multiple objects that implement the ExecutableObjectIF interface. The objects must be - * added prior to starting the task. + * multiple objects that implement the ExecutableObjectIF interface. The objects must + * be added prior to starting the task. * @author baetz * @ingroup task_handling */ -class PeriodicTask: public RTEMSTaskBase, public PeriodicTaskIF { -public: - /** - * @brief Standard constructor of the class. - * @details The class is initialized without allocated objects. These need to be added - * with #addObject. - * In the underlying TaskBase class, a new operating system task is created. - * In addition to the TaskBase parameters, the period, the pointer to the - * aforementioned initialization function and an optional "deadline-missed" - * function pointer is passed. - * @param priority Sets the priority of a task. Values range from a low 0 to a high 99. - * @param stack_size The stack size reserved by the operating system for the task. - * @param setPeriod The length of the period with which the task's functionality will be - * executed. It is expressed in clock ticks. - * @param setDeadlineMissedFunc The function pointer to the deadline missed function - * that shall be assigned. - */ - PeriodicTask(const char *name, rtems_task_priority setPriority, size_t setStack, - rtems_interval setPeriod, void (*setDeadlineMissedFunc)()); - /** - * @brief Currently, the executed object's lifetime is not coupled with the task object's - * lifetime, so the destructor is empty. - */ - virtual ~PeriodicTask(void); +class PeriodicTask : public RTEMSTaskBase, public PeriodicTaskIF { + public: + /** + * @brief Standard constructor of the class. + * @details The class is initialized without allocated objects. These need to be added + * with #addObject. + * In the underlying TaskBase class, a new operating system task is created. + * In addition to the TaskBase parameters, the period, the pointer to the + * aforementioned initialization function and an optional "deadline-missed" + * function pointer is passed. + * @param priority Sets the priority of a task. Values range from a low 0 to a high 99. + * @param stack_size The stack size reserved by the operating system for the task. + * @param setPeriod The length of the period with which the task's functionality will be + * executed. It is expressed in clock ticks. + * @param setDeadlineMissedFunc The function pointer to the deadline missed function + * that shall be assigned. + */ + PeriodicTask(const char *name, rtems_task_priority setPriority, size_t setStack, + rtems_interval setPeriod, void (*setDeadlineMissedFunc)()); + /** + * @brief Currently, the executed object's lifetime is not coupled with the task object's + * lifetime, so the destructor is empty. + */ + virtual ~PeriodicTask(void); - /** - * @brief The method to start the task. - * @details The method starts the task with the respective system call. - * Entry point is the taskEntryPoint method described below. - * The address of the task object is passed as an argument - * to the system call. - */ - ReturnValue_t startTask(void); - /** - * Adds an object to the list of objects to be executed. - * The objects are executed in the order added. - * @param object Id of the object to add. - * @return RETURN_OK on success, RETURN_FAILED if the object could not be added. - */ - ReturnValue_t addComponent(object_id_t object) override; + /** + * @brief The method to start the task. + * @details The method starts the task with the respective system call. + * Entry point is the taskEntryPoint method described below. + * The address of the task object is passed as an argument + * to the system call. + */ + ReturnValue_t startTask(void); + /** + * Adds an object to the list of objects to be executed. + * The objects are executed in the order added. + * @param object Id of the object to add. + * @return RETURN_OK on success, RETURN_FAILED if the object could not be added. + */ + ReturnValue_t addComponent(object_id_t object) override; - uint32_t getPeriodMs() const override; + uint32_t getPeriodMs() const override; - ReturnValue_t sleepFor(uint32_t ms) override; -protected: - typedef std::vector ObjectList; //!< Typedef for the List of objects. - /** - * @brief This attribute holds a list of objects to be executed. - */ - ObjectList objectList; - /** - * @brief The period of the task. - * @details The period determines the frequency of the task's execution. It is expressed in clock ticks. - */ - rtems_interval periodTicks; - /** - * @brief id of the associated OS period - */ - rtems_id periodId = 0; - /** - * @brief The pointer to the deadline-missed function. - * @details This pointer stores the function that is executed if the task's deadline is missed. - * So, each may react individually on a timing failure. The pointer may be nullptr, - * then nothing happens on missing the deadline. The deadline is equal to the next execution - * of the periodic task. - */ - void (*deadlineMissedFunc)(void); - /** - * @brief This is the function executed in the new task's context. - * @details It converts the argument back to the thread object type and copies the class instance - * to the task context. The taskFunctionality method is called afterwards. - * @param A pointer to the task object itself is passed as argument. - */ - static rtems_task taskEntryPoint(rtems_task_argument argument); - /** - * @brief The function containing the actual functionality of the task. - * @details The method sets and starts - * the task's period, then enters a loop that is repeated as long as the isRunning - * attribute is true. Within the loop, all performOperation methods of the added - * objects are called. Afterwards the checkAndRestartPeriod system call blocks the task - * until the next period. - * On missing the deadline, the deadlineMissedFunction is executed. - */ - void taskFunctionality(void); + ReturnValue_t sleepFor(uint32_t ms) override; + + protected: + typedef std::vector ObjectList; //!< Typedef for the List of objects. + /** + * @brief This attribute holds a list of objects to be executed. + */ + ObjectList objectList; + /** + * @brief The period of the task. + * @details The period determines the frequency of the task's execution. It is expressed in + * clock ticks. + */ + rtems_interval periodTicks; + /** + * @brief id of the associated OS period + */ + rtems_id periodId = 0; + /** + * @brief The pointer to the deadline-missed function. + * @details This pointer stores the function that is executed if the task's deadline is missed. + * So, each may react individually on a timing failure. The pointer may be + * nullptr, then nothing happens on missing the deadline. The deadline is equal to the next + * execution of the periodic task. + */ + void (*deadlineMissedFunc)(void); + /** + * @brief This is the function executed in the new task's context. + * @details It converts the argument back to the thread object type and copies the class + * instance to the task context. The taskFunctionality method is called afterwards. + * @param A pointer to the task object itself is passed as argument. + */ + static rtems_task taskEntryPoint(rtems_task_argument argument); + /** + * @brief The function containing the actual functionality of the task. + * @details The method sets and starts + * the task's period, then enters a loop that is repeated as long as the + * isRunning attribute is true. Within the loop, all performOperation methods of the added objects + * are called. Afterwards the checkAndRestartPeriod system call blocks the task until the next + * period. On missing the deadline, the deadlineMissedFunction is executed. + */ + void taskFunctionality(void); }; #endif /* FSFW_OSAL_RTEMS_PERIODICTASK_H_ */ diff --git a/src/fsfw/osal/rtems/QueueFactory.cpp b/src/fsfw/osal/rtems/QueueFactory.cpp index ddcc3959..3d517f60 100644 --- a/src/fsfw/osal/rtems/QueueFactory.cpp +++ b/src/fsfw/osal/rtems/QueueFactory.cpp @@ -1,61 +1,56 @@ +#include "fsfw/ipc/QueueFactory.h" + +#include "fsfw/ipc/MessageQueueSenderIF.h" #include "fsfw/osal/rtems/MessageQueue.h" #include "fsfw/osal/rtems/RtemsBasic.h" -#include "fsfw/ipc/QueueFactory.h" -#include "fsfw/ipc/MessageQueueSenderIF.h" - QueueFactory* QueueFactory::factoryInstance = nullptr; - ReturnValue_t MessageQueueSenderIF::sendMessage(MessageQueueId_t sendTo, - MessageQueueMessageIF* message, MessageQueueId_t sentFrom,bool ignoreFault) { - //TODO add ignoreFault functionality - message->setSender(sentFrom); - rtems_status_code result = rtems_message_queue_send(sendTo, message->getBuffer(), - message->getMessageSize()); - switch(result){ - case RTEMS_SUCCESSFUL: - //message sent successfully - return HasReturnvaluesIF::RETURN_OK; - case RTEMS_INVALID_ID: - //invalid queue id - return HasReturnvaluesIF::RETURN_FAILED; - case RTEMS_INVALID_SIZE: - // invalid message size - return HasReturnvaluesIF::RETURN_FAILED; - case RTEMS_INVALID_ADDRESS: - //buffer is NULL - return HasReturnvaluesIF::RETURN_FAILED; - case RTEMS_UNSATISFIED: - //out of message buffers - return HasReturnvaluesIF::RETURN_FAILED; - case RTEMS_TOO_MANY: - //queue's limit has been reached - return MessageQueueIF::FULL; + MessageQueueMessageIF* message, + MessageQueueId_t sentFrom, bool ignoreFault) { + // TODO add ignoreFault functionality + message->setSender(sentFrom); + rtems_status_code result = + rtems_message_queue_send(sendTo, message->getBuffer(), message->getMessageSize()); + switch (result) { + case RTEMS_SUCCESSFUL: + // message sent successfully + return HasReturnvaluesIF::RETURN_OK; + case RTEMS_INVALID_ID: + // invalid queue id + return HasReturnvaluesIF::RETURN_FAILED; + case RTEMS_INVALID_SIZE: + // invalid message size + return HasReturnvaluesIF::RETURN_FAILED; + case RTEMS_INVALID_ADDRESS: + // buffer is NULL + return HasReturnvaluesIF::RETURN_FAILED; + case RTEMS_UNSATISFIED: + // out of message buffers + return HasReturnvaluesIF::RETURN_FAILED; + case RTEMS_TOO_MANY: + // queue's limit has been reached + return MessageQueueIF::FULL; - default: - return HasReturnvaluesIF::RETURN_FAILED; - } + default: + return HasReturnvaluesIF::RETURN_FAILED; + } } QueueFactory* QueueFactory::instance() { - if (factoryInstance == nullptr) { - factoryInstance = new QueueFactory; - } - return factoryInstance; + if (factoryInstance == nullptr) { + factoryInstance = new QueueFactory; + } + return factoryInstance; } -QueueFactory::QueueFactory() { +QueueFactory::QueueFactory() {} + +QueueFactory::~QueueFactory() {} + +MessageQueueIF* QueueFactory::createMessageQueue(uint32_t messageDepth, size_t maxMessageSize) { + return new MessageQueue(messageDepth, maxMessageSize); } -QueueFactory::~QueueFactory() { -} - -MessageQueueIF* QueueFactory::createMessageQueue(uint32_t messageDepth, - size_t maxMessageSize) { - return new MessageQueue(messageDepth, maxMessageSize); -} - -void QueueFactory::deleteMessageQueue(MessageQueueIF* queue) { - delete queue; -} +void QueueFactory::deleteMessageQueue(MessageQueueIF* queue) { delete queue; } diff --git a/src/fsfw/osal/rtems/RTEMSTaskBase.cpp b/src/fsfw/osal/rtems/RTEMSTaskBase.cpp index fc8bbed5..a01b7802 100644 --- a/src/fsfw/osal/rtems/RTEMSTaskBase.cpp +++ b/src/fsfw/osal/rtems/RTEMSTaskBase.cpp @@ -1,84 +1,76 @@ #include "fsfw/osal/rtems/RTEMSTaskBase.h" + #include "fsfw/serviceinterface/ServiceInterface.h" const size_t PeriodicTaskIF::MINIMUM_STACK_SIZE = RTEMS_MINIMUM_STACK_SIZE; RTEMSTaskBase::RTEMSTaskBase(rtems_task_priority set_priority, size_t stack_size, - const char *name) { - rtems_name osalName = 0; - for (uint8_t i = 0; i < 4; i++) { - if (name[i] == 0) { - break; - } - osalName += name[i] << (8 * (3 - i)); - } - //The task is created with the operating system's system call. - rtems_status_code status = RTEMS_UNSATISFIED; - if (set_priority <= 99) { - status = rtems_task_create(osalName, - (0xFF - 2 * set_priority), stack_size, - RTEMS_PREEMPT | RTEMS_NO_TIMESLICE | RTEMS_NO_ASR, - RTEMS_FLOATING_POINT, &id); - } - ReturnValue_t result = convertReturnCode(status); - if (result != HasReturnvaluesIF::RETURN_OK) { + const char *name) { + rtems_name osalName = 0; + for (uint8_t i = 0; i < 4; i++) { + if (name[i] == 0) { + break; + } + osalName += name[i] << (8 * (3 - i)); + } + // The task is created with the operating system's system call. + rtems_status_code status = RTEMS_UNSATISFIED; + if (set_priority <= 99) { + status = rtems_task_create(osalName, (0xFF - 2 * set_priority), stack_size, + RTEMS_PREEMPT | RTEMS_NO_TIMESLICE | RTEMS_NO_ASR, + RTEMS_FLOATING_POINT, &id); + } + ReturnValue_t result = convertReturnCode(status); + if (result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "TaskBase::TaskBase: createTask with name " << std::hex - << osalName << std::dec << " failed with return code " - << (uint32_t) status << std::endl; + sif::error << "TaskBase::TaskBase: createTask with name " << std::hex << osalName << std::dec + << " failed with return code " << (uint32_t)status << std::endl; #endif - this->id = 0; - } + this->id = 0; + } } -RTEMSTaskBase::~RTEMSTaskBase() { - rtems_task_delete(id); -} +RTEMSTaskBase::~RTEMSTaskBase() { rtems_task_delete(id); } -rtems_id RTEMSTaskBase::getId() { - return this->id; -} +rtems_id RTEMSTaskBase::getId() { return this->id; } ReturnValue_t RTEMSTaskBase::sleepFor(uint32_t ms) { - rtems_status_code status = rtems_task_wake_after(RtemsBasic::convertMsToTicks(ms)); - return convertReturnCode(status); + rtems_status_code status = rtems_task_wake_after(RtemsBasic::convertMsToTicks(ms)); + return convertReturnCode(status); } - ReturnValue_t RTEMSTaskBase::convertReturnCode(rtems_status_code inValue) { - switch (inValue) { - case RTEMS_SUCCESSFUL: - return HasReturnvaluesIF::RETURN_OK; - case RTEMS_MP_NOT_CONFIGURED: - return HasReturnvaluesIF::RETURN_FAILED; - case RTEMS_INVALID_NAME: - return HasReturnvaluesIF::RETURN_FAILED; - case RTEMS_TOO_MANY: - return HasReturnvaluesIF::RETURN_FAILED; - case RTEMS_INVALID_ADDRESS: - return HasReturnvaluesIF::RETURN_FAILED; - case RTEMS_UNSATISFIED: - return HasReturnvaluesIF::RETURN_FAILED; - case RTEMS_INVALID_PRIORITY: - return HasReturnvaluesIF::RETURN_FAILED; - default: - return HasReturnvaluesIF::RETURN_FAILED; - } - + switch (inValue) { + case RTEMS_SUCCESSFUL: + return HasReturnvaluesIF::RETURN_OK; + case RTEMS_MP_NOT_CONFIGURED: + return HasReturnvaluesIF::RETURN_FAILED; + case RTEMS_INVALID_NAME: + return HasReturnvaluesIF::RETURN_FAILED; + case RTEMS_TOO_MANY: + return HasReturnvaluesIF::RETURN_FAILED; + case RTEMS_INVALID_ADDRESS: + return HasReturnvaluesIF::RETURN_FAILED; + case RTEMS_UNSATISFIED: + return HasReturnvaluesIF::RETURN_FAILED; + case RTEMS_INVALID_PRIORITY: + return HasReturnvaluesIF::RETURN_FAILED; + default: + return HasReturnvaluesIF::RETURN_FAILED; + } } - ReturnValue_t RTEMSTaskBase::setAndStartPeriod(rtems_interval period, rtems_id *periodId) { - rtems_name periodName = (('P' << 24) + ('e' << 16) + ('r' << 8) + 'd'); - rtems_status_code status = rtems_rate_monotonic_create(periodName, periodId); - if (status == RTEMS_SUCCESSFUL) { - status = restartPeriod(period,*periodId); - } - return convertReturnCode(status); + rtems_name periodName = (('P' << 24) + ('e' << 16) + ('r' << 8) + 'd'); + rtems_status_code status = rtems_rate_monotonic_create(periodName, periodId); + if (status == RTEMS_SUCCESSFUL) { + status = restartPeriod(period, *periodId); + } + return convertReturnCode(status); } -rtems_status_code RTEMSTaskBase::restartPeriod(rtems_interval period, rtems_id periodId){ - //This is necessary to avoid a call with period = 0, which does not start the period. - rtems_status_code status = rtems_rate_monotonic_period(periodId, period + 1); - return status; +rtems_status_code RTEMSTaskBase::restartPeriod(rtems_interval period, rtems_id periodId) { + // This is necessary to avoid a call with period = 0, which does not start the period. + rtems_status_code status = rtems_rate_monotonic_period(periodId, period + 1); + return status; } diff --git a/src/fsfw/osal/rtems/RTEMSTaskBase.h b/src/fsfw/osal/rtems/RTEMSTaskBase.h index 0b8be3e9..784d3594 100644 --- a/src/fsfw/osal/rtems/RTEMSTaskBase.h +++ b/src/fsfw/osal/rtems/RTEMSTaskBase.h @@ -1,8 +1,8 @@ #ifndef FSFW_OSAL_RTEMS_RTEMSTASKBASE_H_ #define FSFW_OSAL_RTEMS_RTEMSTASKBASE_H_ -#include "RtemsBasic.h" #include "../../tasks/PeriodicTaskIF.h" +#include "RtemsBasic.h" /** * @brief This is the basic task handling class for rtems. @@ -10,38 +10,40 @@ * @details Task creation base class for rtems. */ class RTEMSTaskBase { -protected: - /** - * @brief The class stores the task id it got assigned from the operating system in this attribute. - * If initialization fails, the id is set to zero. - */ - rtems_id id; -public: - /** - * @brief The constructor creates and initializes a task. - * @details This is accomplished by using the operating system call to create a task. The name is - * created automatically with the help od taskCounter. Priority and stack size are - * adjustable, all other attributes are set with default values. - * @param priority Sets the priority of a task. Values range from a low 0 to a high 99. - * @param stack_size The stack size reserved by the operating system for the task. - * @param nam The name of the Task, as a null-terminated String. Currently max 4 chars supported (excluding Null-terminator), rest will be truncated - */ - RTEMSTaskBase( rtems_task_priority priority, size_t stack_size, const char *name); - /** - * @brief In the destructor, the created task is deleted. - */ - virtual ~RTEMSTaskBase(); - /** - * @brief This method returns the task id of this class. - */ - rtems_id getId(); + protected: + /** + * @brief The class stores the task id it got assigned from the operating system in this + * attribute. If initialization fails, the id is set to zero. + */ + rtems_id id; - ReturnValue_t sleepFor(uint32_t ms); - static ReturnValue_t setAndStartPeriod(rtems_interval period, rtems_id *periodId); - static rtems_status_code restartPeriod(rtems_interval period, rtems_id periodId); -private: - static ReturnValue_t convertReturnCode(rtems_status_code inValue); + public: + /** + * @brief The constructor creates and initializes a task. + * @details This is accomplished by using the operating system call to create a task. The name + * is created automatically with the help od taskCounter. Priority and stack size are adjustable, + * all other attributes are set with default values. + * @param priority Sets the priority of a task. Values range from a low 0 to a high 99. + * @param stack_size The stack size reserved by the operating system for the task. + * @param nam The name of the Task, as a null-terminated String. Currently max 4 chars + * supported (excluding Null-terminator), rest will be truncated + */ + RTEMSTaskBase(rtems_task_priority priority, size_t stack_size, const char *name); + /** + * @brief In the destructor, the created task is deleted. + */ + virtual ~RTEMSTaskBase(); + /** + * @brief This method returns the task id of this class. + */ + rtems_id getId(); + + ReturnValue_t sleepFor(uint32_t ms); + static ReturnValue_t setAndStartPeriod(rtems_interval period, rtems_id *periodId); + static rtems_status_code restartPeriod(rtems_interval period, rtems_id periodId); + + private: + static ReturnValue_t convertReturnCode(rtems_status_code inValue); }; - #endif /* FSFW_OSAL_RTEMS_RTEMSTASKBASE_H_ */ diff --git a/src/fsfw/osal/rtems/RtemsBasic.h b/src/fsfw/osal/rtems/RtemsBasic.h index 382697a3..3525799c 100644 --- a/src/fsfw/osal/rtems/RtemsBasic.h +++ b/src/fsfw/osal/rtems/RtemsBasic.h @@ -1,26 +1,26 @@ #ifndef FSFW_OSAL_RTEMS_RTEMSBASIC_H_ #define FSFW_OSAL_RTEMS_RTEMSBASIC_H_ -#include "fsfw/returnvalues/HasReturnvaluesIF.h" - #include -#include #include +#include #include #include -class RtemsBasic { -public: - static rtems_interval convertMsToTicks(uint32_t msIn) { - rtems_interval ticks_per_second = rtems_clock_get_ticks_per_second(); - return (ticks_per_second * msIn) / 1000; - } +#include "fsfw/returnvalues/HasReturnvaluesIF.h" - static rtems_interval convertTicksToMs(rtems_interval ticksIn) { - rtems_interval ticks_per_second = rtems_clock_get_ticks_per_second(); - return (ticksIn * 1000) / ticks_per_second; - } +class RtemsBasic { + public: + static rtems_interval convertMsToTicks(uint32_t msIn) { + rtems_interval ticks_per_second = rtems_clock_get_ticks_per_second(); + return (ticks_per_second * msIn) / 1000; + } + + static rtems_interval convertTicksToMs(rtems_interval ticksIn) { + rtems_interval ticks_per_second = rtems_clock_get_ticks_per_second(); + return (ticksIn * 1000) / ticks_per_second; + } }; #endif /* FSFW_OSAL_RTEMS_RTEMSBASIC_H_ */ diff --git a/src/fsfw/osal/rtems/SemaphoreFactory.cpp b/src/fsfw/osal/rtems/SemaphoreFactory.cpp index cec4b833..35099ddc 100644 --- a/src/fsfw/osal/rtems/SemaphoreFactory.cpp +++ b/src/fsfw/osal/rtems/SemaphoreFactory.cpp @@ -1,34 +1,29 @@ #include "fsfw/osal/rtems/BinarySemaphore.h" //#include "fsfw/osal/rtems/CountingSemaphore.h" -#include "fsfw/tasks/SemaphoreFactory.h" #include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/tasks/SemaphoreFactory.h" SemaphoreFactory* SemaphoreFactory::factoryInstance = nullptr; -SemaphoreFactory::SemaphoreFactory() { -} +SemaphoreFactory::SemaphoreFactory() {} -SemaphoreFactory::~SemaphoreFactory() { - delete factoryInstance; -} +SemaphoreFactory::~SemaphoreFactory() { delete factoryInstance; } SemaphoreFactory* SemaphoreFactory::instance() { - if (factoryInstance == nullptr){ - factoryInstance = new SemaphoreFactory(); - } - return SemaphoreFactory::factoryInstance; + if (factoryInstance == nullptr) { + factoryInstance = new SemaphoreFactory(); + } + return SemaphoreFactory::factoryInstance; } SemaphoreIF* SemaphoreFactory::createBinarySemaphore(uint32_t argument) { - return new BinarySemaphore(); + return new BinarySemaphore(); } -SemaphoreIF* SemaphoreFactory::createCountingSemaphore(uint8_t maxCount, - uint8_t initCount, uint32_t argument) { - return nullptr; +SemaphoreIF* SemaphoreFactory::createCountingSemaphore(uint8_t maxCount, uint8_t initCount, + uint32_t argument) { + return nullptr; } -void SemaphoreFactory::deleteSemaphore(SemaphoreIF* semaphore) { - delete semaphore; -} +void SemaphoreFactory::deleteSemaphore(SemaphoreIF* semaphore) { delete semaphore; } diff --git a/src/fsfw/osal/rtems/TaskFactory.cpp b/src/fsfw/osal/rtems/TaskFactory.cpp index dd3e92fc..8bfd53ed 100644 --- a/src/fsfw/osal/rtems/TaskFactory.cpp +++ b/src/fsfw/osal/rtems/TaskFactory.cpp @@ -1,53 +1,49 @@ -#include "fsfw/osal/rtems/FixedTimeslotTask.h" -#include "fsfw/osal/rtems/PeriodicTask.h" -#include "fsfw/osal/rtems/InitTask.h" -#include "fsfw/osal/rtems/RtemsBasic.h" - #include "fsfw/tasks/TaskFactory.h" + +#include "fsfw/osal/rtems/FixedTimeslotTask.h" +#include "fsfw/osal/rtems/InitTask.h" +#include "fsfw/osal/rtems/PeriodicTask.h" +#include "fsfw/osal/rtems/RtemsBasic.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" -//TODO: Different variant than the lazy loading in QueueFactory. What's better and why? +// TODO: Different variant than the lazy loading in QueueFactory. What's better and why? TaskFactory* TaskFactory::factoryInstance = new TaskFactory(); -TaskFactory::~TaskFactory() { +TaskFactory::~TaskFactory() {} + +TaskFactory* TaskFactory::instance() { return TaskFactory::factoryInstance; } + +PeriodicTaskIF* TaskFactory::createPeriodicTask( + TaskName name_, TaskPriority taskPriority_, TaskStackSize stackSize_, + TaskPeriod periodInSeconds_, TaskDeadlineMissedFunction deadLineMissedFunction_) { + rtems_interval taskPeriod = periodInSeconds_ * Clock::getTicksPerSecond(); + + return static_cast( + new PeriodicTask(name_, taskPriority_, stackSize_, taskPeriod, deadLineMissedFunction_)); } -TaskFactory* TaskFactory::instance() { - return TaskFactory::factoryInstance; -} - -PeriodicTaskIF* TaskFactory::createPeriodicTask(TaskName name_, TaskPriority taskPriority_, - TaskStackSize stackSize_,TaskPeriod periodInSeconds_, - TaskDeadlineMissedFunction deadLineMissedFunction_) { - rtems_interval taskPeriod = periodInSeconds_ * Clock::getTicksPerSecond(); - - return static_cast(new PeriodicTask(name_, taskPriority_, stackSize_, - taskPeriod,deadLineMissedFunction_)); -} - -FixedTimeslotTaskIF* TaskFactory::createFixedTimeslotTask(TaskName name_, - TaskPriority taskPriority_,TaskStackSize stackSize_,TaskPeriod periodInSeconds_, - TaskDeadlineMissedFunction deadLineMissedFunction_) { - rtems_interval taskPeriod = periodInSeconds_ * Clock::getTicksPerSecond(); - return static_cast(new FixedTimeslotTask(name_, taskPriority_, - stackSize_, taskPeriod, deadLineMissedFunction_)); +FixedTimeslotTaskIF* TaskFactory::createFixedTimeslotTask( + TaskName name_, TaskPriority taskPriority_, TaskStackSize stackSize_, + TaskPeriod periodInSeconds_, TaskDeadlineMissedFunction deadLineMissedFunction_) { + rtems_interval taskPeriod = periodInSeconds_ * Clock::getTicksPerSecond(); + return static_cast( + new FixedTimeslotTask(name_, taskPriority_, stackSize_, taskPeriod, deadLineMissedFunction_)); } ReturnValue_t TaskFactory::deleteTask(PeriodicTaskIF* task) { - //TODO not implemented - return HasReturnvaluesIF::RETURN_FAILED; + // TODO not implemented + return HasReturnvaluesIF::RETURN_FAILED; } -ReturnValue_t TaskFactory::delayTask(uint32_t delayMs){ - rtems_task_wake_after(RtemsBasic::convertMsToTicks(delayMs)); - //Only return value is "RTEMS_SUCCESSFUL - always successful" so it has been neglected - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t TaskFactory::delayTask(uint32_t delayMs) { + rtems_task_wake_after(RtemsBasic::convertMsToTicks(delayMs)); + // Only return value is "RTEMS_SUCCESSFUL - always successful" so it has been neglected + return HasReturnvaluesIF::RETURN_OK; } void TaskFactory::printMissedDeadline() { - /* TODO: Implement */ - return; + /* TODO: Implement */ + return; } -TaskFactory::TaskFactory() { -} +TaskFactory::TaskFactory() {} diff --git a/src/fsfw/osal/windows/tcpipHelpers.cpp b/src/fsfw/osal/windows/tcpipHelpers.cpp index 37d6fb2f..118fffb4 100644 --- a/src/fsfw/osal/windows/tcpipHelpers.cpp +++ b/src/fsfw/osal/windows/tcpipHelpers.cpp @@ -1,63 +1,62 @@ -#include "fsfw/FSFW.h" #include "fsfw/osal/common/tcpipHelpers.h" -#include "fsfw/tasks/TaskFactory.h" -#include "fsfw/serviceinterface/ServiceInterface.h" - - #include + #include +#include "fsfw/FSFW.h" +#include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/tasks/TaskFactory.h" + void tcpip::handleError(Protocol protocol, ErrorSources errorSrc, dur_millis_t sleepDuration) { #if FSFW_VERBOSE_LEVEL >= 1 - int errCode = WSAGetLastError(); - std::string protocolString; - std::string errorSrcString; - determineErrorStrings(protocol, errorSrc, protocolString, errorSrcString); + int errCode = WSAGetLastError(); + std::string protocolString; + std::string errorSrcString; + determineErrorStrings(protocol, errorSrc, protocolString, errorSrcString); - std::string infoString; - switch(errCode) { - case(WSANOTINITIALISED): { - infoString = "WSANOTINITIALISED"; - break; + std::string infoString; + switch (errCode) { + case (WSANOTINITIALISED): { + infoString = "WSANOTINITIALISED"; + break; } - case(WSAEADDRINUSE): { - infoString = "WSAEADDRINUSE"; - break; + case (WSAEADDRINUSE): { + infoString = "WSAEADDRINUSE"; + break; } - case(WSAEFAULT): { - infoString = "WSAEFAULT"; - break; + case (WSAEFAULT): { + infoString = "WSAEFAULT"; + break; } - case(WSAEADDRNOTAVAIL): { - infoString = "WSAEADDRNOTAVAIL"; - break; + case (WSAEADDRNOTAVAIL): { + infoString = "WSAEADDRNOTAVAIL"; + break; } - case(WSAEINVAL): { - infoString = "WSAEINVAL"; - break; + case (WSAEINVAL): { + infoString = "WSAEINVAL"; + break; } default: { - /* - https://docs.microsoft.com/en-us/windows/win32/winsock/windows-sockets-error-codes-2 - */ - infoString = "Error code: " + std::to_string(errCode); - break; - } + /* + https://docs.microsoft.com/en-us/windows/win32/winsock/windows-sockets-error-codes-2 + */ + infoString = "Error code: " + std::to_string(errCode); + break; } + } #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "tcpip::handleError: " << protocolString << " | " << errorSrcString << - " | " << infoString << std::endl; + sif::warning << "tcpip::handleError: " << protocolString << " | " << errorSrcString << " | " + << infoString << std::endl; #else - sif::printWarning("tcpip::handleError: %s | %s | %s\n", protocolString.c_str(), - errorSrcString.c_str(), infoString.c_str()); + sif::printWarning("tcpip::handleError: %s | %s | %s\n", protocolString.c_str(), + errorSrcString.c_str(), infoString.c_str()); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - if(sleepDuration > 0) { - TaskFactory::instance()->delayTask(sleepDuration); - } + if (sleepDuration > 0) { + TaskFactory::instance()->delayTask(sleepDuration); + } } - diff --git a/src/fsfw/osal/windows/winTaskHelpers.cpp b/src/fsfw/osal/windows/winTaskHelpers.cpp index 20d4d98d..c863c4ca 100644 --- a/src/fsfw/osal/windows/winTaskHelpers.cpp +++ b/src/fsfw/osal/windows/winTaskHelpers.cpp @@ -3,106 +3,102 @@ #include TaskPriority tasks::makeWinPriority(PriorityClass prioClass, PriorityNumber prioNumber) { - return (static_cast(prioClass) << 16) | static_cast (prioNumber); + return (static_cast(prioClass) << 16) | static_cast(prioNumber); } -void tasks::getWinPriorityParameters(TaskPriority priority, - DWORD& priorityClass, int& priorityNumber) { - PriorityClass classInternal = static_cast(priority >> 16 & 0xff); - PriorityNumber numberInternal = static_cast(priority & 0xff); - switch(classInternal) { - case(CLASS_IDLE): { - priorityClass = IDLE_PRIORITY_CLASS; - break; +void tasks::getWinPriorityParameters(TaskPriority priority, DWORD& priorityClass, + int& priorityNumber) { + PriorityClass classInternal = static_cast(priority >> 16 & 0xff); + PriorityNumber numberInternal = static_cast(priority & 0xff); + switch (classInternal) { + case (CLASS_IDLE): { + priorityClass = IDLE_PRIORITY_CLASS; + break; } - case(CLASS_BELOW_NORMAL): { - priorityClass = BELOW_NORMAL_PRIORITY_CLASS; - break; + case (CLASS_BELOW_NORMAL): { + priorityClass = BELOW_NORMAL_PRIORITY_CLASS; + break; } - case(CLASS_NORMAL): { - priorityClass = NORMAL_PRIORITY_CLASS; - break; + case (CLASS_NORMAL): { + priorityClass = NORMAL_PRIORITY_CLASS; + break; } - case(CLASS_ABOVE_NORMAL): { - priorityClass = ABOVE_NORMAL_PRIORITY_CLASS; - break; + case (CLASS_ABOVE_NORMAL): { + priorityClass = ABOVE_NORMAL_PRIORITY_CLASS; + break; } - case(CLASS_HIGH): { - priorityClass = HIGH_PRIORITY_CLASS; - break; + case (CLASS_HIGH): { + priorityClass = HIGH_PRIORITY_CLASS; + break; } - case(CLASS_REALTIME): { - priorityClass = REALTIME_PRIORITY_CLASS; - break; + case (CLASS_REALTIME): { + priorityClass = REALTIME_PRIORITY_CLASS; + break; } default: { - priorityClass = NORMAL_PRIORITY_CLASS; - } + priorityClass = NORMAL_PRIORITY_CLASS; } + } - switch(numberInternal) { - case(IDLE): { - priorityNumber = THREAD_PRIORITY_IDLE; - break; + switch (numberInternal) { + case (IDLE): { + priorityNumber = THREAD_PRIORITY_IDLE; + break; } - case(LOWEST): { - priorityNumber = THREAD_PRIORITY_LOWEST; - break; + case (LOWEST): { + priorityNumber = THREAD_PRIORITY_LOWEST; + break; } - case(BELOW_NORMAL): { - priorityNumber = THREAD_PRIORITY_BELOW_NORMAL; - break; + case (BELOW_NORMAL): { + priorityNumber = THREAD_PRIORITY_BELOW_NORMAL; + break; } - case(NORMAL): { - priorityNumber = THREAD_PRIORITY_NORMAL; - break; + case (NORMAL): { + priorityNumber = THREAD_PRIORITY_NORMAL; + break; } - case(ABOVE_NORMAL): { - priorityNumber = THREAD_PRIORITY_ABOVE_NORMAL; - break; + case (ABOVE_NORMAL): { + priorityNumber = THREAD_PRIORITY_ABOVE_NORMAL; + break; } - case(HIGHEST): { - priorityNumber = THREAD_PRIORITY_HIGHEST; - break; + case (HIGHEST): { + priorityNumber = THREAD_PRIORITY_HIGHEST; + break; } - case(CRITICAL): { - priorityNumber = THREAD_PRIORITY_TIME_CRITICAL; - break; + case (CRITICAL): { + priorityNumber = THREAD_PRIORITY_TIME_CRITICAL; + break; } default: { - priorityNumber = THREAD_PRIORITY_NORMAL; - } + priorityNumber = THREAD_PRIORITY_NORMAL; } + } } ReturnValue_t tasks::setTaskPriority(HANDLE nativeHandle, TaskPriority priority) { - /* List of possible priority classes: - https://docs.microsoft.com/en-us/windows/win32/api/processthreadsapi/nf-processthreadsapi-setpriorityclass - And respective thread priority numbers: - https://docs.microsoft.com/en-us/windows/win32/procthread/scheduling-priorities - */ - DWORD dwPriorityClass = 0; - int nPriorityNumber = 0; - tasks::getWinPriorityParameters(priority, dwPriorityClass, nPriorityNumber); - int result = SetPriorityClass( - reinterpret_cast(nativeHandle), - dwPriorityClass); - if(result != 0) { + /* List of possible priority classes: + https://docs.microsoft.com/en-us/windows/win32/api/processthreadsapi/nf-processthreadsapi-setpriorityclass + And respective thread priority numbers: + https://docs.microsoft.com/en-us/windows/win32/procthread/scheduling-priorities + */ + DWORD dwPriorityClass = 0; + int nPriorityNumber = 0; + tasks::getWinPriorityParameters(priority, dwPriorityClass, nPriorityNumber); + int result = SetPriorityClass(reinterpret_cast(nativeHandle), dwPriorityClass); + if (result != 0) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "PeriodicTask: Windows SetPriorityClass failed with code " - << GetLastError() << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; + sif::error << "PeriodicTask: Windows SetPriorityClass failed with code " << GetLastError() + << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; #endif - } - result = SetThreadPriority( - reinterpret_cast(nativeHandle), - nPriorityNumber); - if(result != 0) { + } + result = SetThreadPriority(reinterpret_cast(nativeHandle), nPriorityNumber); + if (result != 0) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "PeriodicTask: Windows SetPriorityClass failed with code " - << GetLastError() << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; + sif::error << "PeriodicTask: Windows SetPriorityClass failed with code " << GetLastError() + << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; #endif - } - return HasReturnvaluesIF::RETURN_OK; + } + return HasReturnvaluesIF::RETURN_OK; } diff --git a/src/fsfw/osal/windows/winTaskHelpers.h b/src/fsfw/osal/windows/winTaskHelpers.h index 64e52672..87cd92ce 100644 --- a/src/fsfw/osal/windows/winTaskHelpers.h +++ b/src/fsfw/osal/windows/winTaskHelpers.h @@ -1,37 +1,35 @@ -#include "../../tasks/TaskFactory.h" - -#include #include +#include + +#include "../../tasks/TaskFactory.h" #ifdef _WIN32 namespace tasks { -enum PriorityClass: uint16_t { - CLASS_IDLE, - CLASS_BELOW_NORMAL, - CLASS_NORMAL, - CLASS_ABOVE_NORMAL, - CLASS_HIGH, - CLASS_REALTIME +enum PriorityClass : uint16_t { + CLASS_IDLE, + CLASS_BELOW_NORMAL, + CLASS_NORMAL, + CLASS_ABOVE_NORMAL, + CLASS_HIGH, + CLASS_REALTIME }; -enum PriorityNumber: uint16_t { - IDLE, - LOWEST, - BELOW_NORMAL, - NORMAL, - ABOVE_NORMAL, - HIGHEST, - CRITICAL +enum PriorityNumber : uint16_t { + IDLE, + LOWEST, + BELOW_NORMAL, + NORMAL, + ABOVE_NORMAL, + HIGHEST, + CRITICAL }; TaskPriority makeWinPriority(PriorityClass prioClass = PriorityClass::CLASS_NORMAL, - PriorityNumber prioNumber = PriorityNumber::NORMAL); -void getWinPriorityParameters(TaskPriority priority, DWORD& priorityClass, - int& priorityNumber); + PriorityNumber prioNumber = PriorityNumber::NORMAL); +void getWinPriorityParameters(TaskPriority priority, DWORD& priorityClass, int& priorityNumber); ReturnValue_t setTaskPriority(HANDLE nativeHandle, TaskPriority priority); -} +} // namespace tasks #endif - diff --git a/src/fsfw/parameters/HasParametersIF.h b/src/fsfw/parameters/HasParametersIF.h index 84790be6..48557b4a 100644 --- a/src/fsfw/parameters/HasParametersIF.h +++ b/src/fsfw/parameters/HasParametersIF.h @@ -1,10 +1,11 @@ #ifndef FSFW_PARAMETERS_HASPARAMETERSIF_H_ #define FSFW_PARAMETERS_HASPARAMETERSIF_H_ -#include "ParameterWrapper.h" -#include "../returnvalues/HasReturnvaluesIF.h" #include +#include "../returnvalues/HasReturnvaluesIF.h" +#include "ParameterWrapper.h" + /** * Each parameter is identified with a unique parameter ID * The first byte of the parameter ID will denote the domain ID. @@ -26,56 +27,50 @@ using ParameterId_t = uint32_t; * parameter entries. */ class HasParametersIF { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::HAS_PARAMETERS_IF; - static const ReturnValue_t INVALID_IDENTIFIER_ID = MAKE_RETURN_CODE(0x01); - static const ReturnValue_t INVALID_DOMAIN_ID = MAKE_RETURN_CODE(0x02); - static const ReturnValue_t INVALID_VALUE = MAKE_RETURN_CODE(0x03); - static const ReturnValue_t READ_ONLY = MAKE_RETURN_CODE(0x05); + public: + static const uint8_t INTERFACE_ID = CLASS_ID::HAS_PARAMETERS_IF; + static const ReturnValue_t INVALID_IDENTIFIER_ID = MAKE_RETURN_CODE(0x01); + static const ReturnValue_t INVALID_DOMAIN_ID = MAKE_RETURN_CODE(0x02); + static const ReturnValue_t INVALID_VALUE = MAKE_RETURN_CODE(0x03); + static const ReturnValue_t READ_ONLY = MAKE_RETURN_CODE(0x05); - static uint8_t getDomain(ParameterId_t id) { - return id >> 24; - } + static uint8_t getDomain(ParameterId_t id) { return id >> 24; } - static uint8_t getUniqueIdentifierId(ParameterId_t id) { - return id >> 16; - } + static uint8_t getUniqueIdentifierId(ParameterId_t id) { return id >> 16; } - /** - * Get the index of a parameter. Please note that the index is always a - * linear index. For a vector, this is straightforward. - * For a matrix, the linear indexing run from left to right, top to bottom. - * @param id - * @return - */ - static uint16_t getIndex(ParameterId_t id) { - return id; - } + /** + * Get the index of a parameter. Please note that the index is always a + * linear index. For a vector, this is straightforward. + * For a matrix, the linear indexing run from left to right, top to bottom. + * @param id + * @return + */ + static uint16_t getIndex(ParameterId_t id) { return id; } - static uint32_t getFullParameterId(uint8_t domainId, uint8_t uniqueId, uint16_t linearIndex) { - return (domainId << 24) + (uniqueId << 16) + linearIndex; - } + static uint32_t getFullParameterId(uint8_t domainId, uint8_t uniqueId, uint16_t linearIndex) { + return (domainId << 24) + (uniqueId << 16) + linearIndex; + } - virtual ~HasParametersIF() {} + virtual ~HasParametersIF() {} - /** - * This is the generic function overriden by child classes to set - * parameters. To set a parameter, the parameter wrapper is used with - * a variety of set functions. The provided values can be checked with - * newValues. - * Always set parameter before checking newValues! - * - * @param domainId - * @param parameterId - * @param parameterWrapper - * @param newValues - * @param startAtIndex Linear index, runs left to right, top to bottom for - * matrix indexes. - * @return - */ - virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueIdentifier, - ParameterWrapper *parameterWrapper, const ParameterWrapper *newValues, - uint16_t startAtIndex) = 0; + /** + * This is the generic function overriden by child classes to set + * parameters. To set a parameter, the parameter wrapper is used with + * a variety of set functions. The provided values can be checked with + * newValues. + * Always set parameter before checking newValues! + * + * @param domainId + * @param parameterId + * @param parameterWrapper + * @param newValues + * @param startAtIndex Linear index, runs left to right, top to bottom for + * matrix indexes. + * @return + */ + virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueIdentifier, + ParameterWrapper *parameterWrapper, + const ParameterWrapper *newValues, uint16_t startAtIndex) = 0; }; #endif /* FSFW_PARAMETERS_HASPARAMETERSIF_H_ */ diff --git a/src/fsfw/parameters/ParameterHelper.cpp b/src/fsfw/parameters/ParameterHelper.cpp index 9250a1d4..58356af5 100644 --- a/src/fsfw/parameters/ParameterHelper.cpp +++ b/src/fsfw/parameters/ParameterHelper.cpp @@ -1,140 +1,132 @@ #include "fsfw/parameters/ParameterHelper.h" -#include "fsfw/parameters/ParameterMessage.h" #include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/parameters/ParameterMessage.h" -ParameterHelper::ParameterHelper(ReceivesParameterMessagesIF* owner): - owner(owner) {} +ParameterHelper::ParameterHelper(ReceivesParameterMessagesIF* owner) : owner(owner) {} -ParameterHelper::~ParameterHelper() { -} +ParameterHelper::~ParameterHelper() {} -ReturnValue_t ParameterHelper::handleParameterMessage(CommandMessage *message) { - if(storage == nullptr) { - // ParameterHelper was not initialized - return HasReturnvaluesIF::RETURN_FAILED; - } +ReturnValue_t ParameterHelper::handleParameterMessage(CommandMessage* message) { + if (storage == nullptr) { + // ParameterHelper was not initialized + return HasReturnvaluesIF::RETURN_FAILED; + } - ReturnValue_t result = HasReturnvaluesIF::RETURN_FAILED; - switch (message->getCommand()) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_FAILED; + switch (message->getCommand()) { case ParameterMessage::CMD_PARAMETER_DUMP: { - ParameterWrapper description; - uint8_t domain = HasParametersIF::getDomain( - ParameterMessage::getParameterId(message)); - uint8_t uniqueIdentifier = HasParametersIF::getUniqueIdentifierId( - ParameterMessage::getParameterId(message)); - result = owner->getParameter(domain, uniqueIdentifier, - &description, &description, 0); - if (result == HasReturnvaluesIF::RETURN_OK) { - result = sendParameter(message->getSender(), - ParameterMessage::getParameterId(message), &description); - } - } - break; + ParameterWrapper description; + uint8_t domain = HasParametersIF::getDomain(ParameterMessage::getParameterId(message)); + uint8_t uniqueIdentifier = + HasParametersIF::getUniqueIdentifierId(ParameterMessage::getParameterId(message)); + result = owner->getParameter(domain, uniqueIdentifier, &description, &description, 0); + if (result == HasReturnvaluesIF::RETURN_OK) { + result = sendParameter(message->getSender(), ParameterMessage::getParameterId(message), + &description); + } + } break; case ParameterMessage::CMD_PARAMETER_LOAD: { - ParameterId_t parameterId = 0; - uint8_t ptc = 0; - uint8_t pfc = 0; - uint8_t rows = 0; - uint8_t columns = 0; - store_address_t storeId = ParameterMessage::getParameterLoadCommand( - message, ¶meterId, &ptc, &pfc, &rows, &columns); - Type type(Type::getActualType(ptc, pfc)); + ParameterId_t parameterId = 0; + uint8_t ptc = 0; + uint8_t pfc = 0; + uint8_t rows = 0; + uint8_t columns = 0; + store_address_t storeId = ParameterMessage::getParameterLoadCommand( + message, ¶meterId, &ptc, &pfc, &rows, &columns); + Type type(Type::getActualType(ptc, pfc)); - uint8_t domain = HasParametersIF::getDomain(parameterId); - uint8_t uniqueIdentifier = HasParametersIF::getUniqueIdentifierId( - parameterId); - uint16_t linearIndex = HasParametersIF::getIndex(parameterId); + uint8_t domain = HasParametersIF::getDomain(parameterId); + uint8_t uniqueIdentifier = HasParametersIF::getUniqueIdentifierId(parameterId); + uint16_t linearIndex = HasParametersIF::getIndex(parameterId); - ConstStorageAccessor accessor(storeId); - result = storage->getData(storeId, accessor); - if (result != HasReturnvaluesIF::RETURN_OK) { + ConstStorageAccessor accessor(storeId); + result = storage->getData(storeId, accessor); + if (result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "ParameterHelper::handleParameterMessage: Getting" - << " store data failed for load command." << std::endl; + sif::error << "ParameterHelper::handleParameterMessage: Getting" + << " store data failed for load command." << std::endl; #endif - break; - } - - ParameterWrapper streamWrapper; - result = streamWrapper.set(type, rows, columns, accessor.data(), - accessor.size()); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - - ParameterWrapper ownerWrapper; - result = owner->getParameter(domain, uniqueIdentifier, &ownerWrapper, - &streamWrapper, linearIndex); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - - result = ownerWrapper.copyFrom(&streamWrapper, linearIndex); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - - result = sendParameter(message->getSender(), - ParameterMessage::getParameterId(message), &ownerWrapper); break; + } + + ParameterWrapper streamWrapper; + result = streamWrapper.set(type, rows, columns, accessor.data(), accessor.size()); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + + ParameterWrapper ownerWrapper; + result = + owner->getParameter(domain, uniqueIdentifier, &ownerWrapper, &streamWrapper, linearIndex); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + + result = ownerWrapper.copyFrom(&streamWrapper, linearIndex); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + + result = sendParameter(message->getSender(), ParameterMessage::getParameterId(message), + &ownerWrapper); + break; } default: - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; + } - if (result != HasReturnvaluesIF::RETURN_OK) { - rejectCommand(message->getSender(), result, message->getCommand()); - } + if (result != HasReturnvaluesIF::RETURN_OK) { + rejectCommand(message->getSender(), result, message->getCommand()); + } - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t ParameterHelper::sendParameter(MessageQueueId_t to, uint32_t id, - const ParameterWrapper* description) { - size_t serializedSize = description->getSerializedSize(); + const ParameterWrapper* description) { + size_t serializedSize = description->getSerializedSize(); - uint8_t *storeElement = nullptr; - store_address_t address; + uint8_t* storeElement = nullptr; + store_address_t address; - ReturnValue_t result = storage->getFreeElement(&address, serializedSize, - &storeElement); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + ReturnValue_t result = storage->getFreeElement(&address, serializedSize, &storeElement); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - size_t storeElementSize = 0; + size_t storeElementSize = 0; - result = description->serialize(&storeElement, &storeElementSize, - serializedSize, SerializeIF::Endianness::BIG); + result = description->serialize(&storeElement, &storeElementSize, serializedSize, + SerializeIF::Endianness::BIG); - if (result != HasReturnvaluesIF::RETURN_OK) { - storage->deleteData(address); - return result; - } + if (result != HasReturnvaluesIF::RETURN_OK) { + storage->deleteData(address); + return result; + } - CommandMessage reply; + CommandMessage reply; - ParameterMessage::setParameterDumpReply(&reply, id, address); + ParameterMessage::setParameterDumpReply(&reply, id, address); - MessageQueueSenderIF::sendMessage(to, &reply, ownerQueueId); + MessageQueueSenderIF::sendMessage(to, &reply, ownerQueueId); - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t ParameterHelper::initialize() { - ownerQueueId = owner->getCommandQueue(); + ownerQueueId = owner->getCommandQueue(); - storage = ObjectManager::instance()->get(objects::IPC_STORE); - if (storage == nullptr) { - return ObjectManagerIF::CHILD_INIT_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + storage = ObjectManager::instance()->get(objects::IPC_STORE); + if (storage == nullptr) { + return ObjectManagerIF::CHILD_INIT_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } void ParameterHelper::rejectCommand(MessageQueueId_t to, ReturnValue_t reason, - Command_t initialCommand) { - CommandMessage reply; - reply.setReplyRejected(reason, initialCommand); - MessageQueueSenderIF::sendMessage(to, &reply, ownerQueueId); + Command_t initialCommand) { + CommandMessage reply; + reply.setReplyRejected(reason, initialCommand); + MessageQueueSenderIF::sendMessage(to, &reply, ownerQueueId); } diff --git a/src/fsfw/parameters/ParameterHelper.h b/src/fsfw/parameters/ParameterHelper.h index 595b4bc5..00df763d 100644 --- a/src/fsfw/parameters/ParameterHelper.h +++ b/src/fsfw/parameters/ParameterHelper.h @@ -1,9 +1,9 @@ #ifndef FSFW_PARAMETERS_PARAMETERHELPER_H_ #define FSFW_PARAMETERS_PARAMETERHELPER_H_ +#include "../ipc/MessageQueueIF.h" #include "ParameterMessage.h" #include "ReceivesParameterMessagesIF.h" -#include "../ipc/MessageQueueIF.h" /** * @brief Helper class to handle parameter messages. @@ -12,25 +12,25 @@ * to a class which implements ReceivesParameterMessagesIF. */ class ParameterHelper { -public: - ParameterHelper(ReceivesParameterMessagesIF *owner); - virtual ~ParameterHelper(); + public: + ParameterHelper(ReceivesParameterMessagesIF *owner); + virtual ~ParameterHelper(); - ReturnValue_t handleParameterMessage(CommandMessage *message); + ReturnValue_t handleParameterMessage(CommandMessage *message); - ReturnValue_t initialize(); -private: - ReceivesParameterMessagesIF *owner; + ReturnValue_t initialize(); - MessageQueueId_t ownerQueueId = MessageQueueIF::NO_QUEUE; + private: + ReceivesParameterMessagesIF *owner; - StorageManagerIF *storage = nullptr; + MessageQueueId_t ownerQueueId = MessageQueueIF::NO_QUEUE; - ReturnValue_t sendParameter(MessageQueueId_t to, uint32_t id, - const ParameterWrapper *description); + StorageManagerIF *storage = nullptr; - void rejectCommand(MessageQueueId_t to, ReturnValue_t reason, - Command_t initialCommand); + ReturnValue_t sendParameter(MessageQueueId_t to, uint32_t id, + const ParameterWrapper *description); + + void rejectCommand(MessageQueueId_t to, ReturnValue_t reason, Command_t initialCommand); }; #endif /* FSFW_PARAMETERS_PARAMETERHELPER_H_ */ diff --git a/src/fsfw/parameters/ParameterMessage.cpp b/src/fsfw/parameters/ParameterMessage.cpp index ee58339c..9dc58365 100644 --- a/src/fsfw/parameters/ParameterMessage.cpp +++ b/src/fsfw/parameters/ParameterMessage.cpp @@ -3,63 +3,62 @@ #include "fsfw/objectmanager/ObjectManager.h" ParameterId_t ParameterMessage::getParameterId(const CommandMessage* message) { - return message->getParameter(); + return message->getParameter(); } store_address_t ParameterMessage::getStoreId(const CommandMessage* message) { - store_address_t address; - address.raw = message->getParameter2(); - return address; + store_address_t address; + address.raw = message->getParameter2(); + return address; } -void ParameterMessage::setParameterDumpCommand(CommandMessage* message, - ParameterId_t id) { - message->setCommand(CMD_PARAMETER_DUMP); - message->setParameter(id); +void ParameterMessage::setParameterDumpCommand(CommandMessage* message, ParameterId_t id) { + message->setCommand(CMD_PARAMETER_DUMP); + message->setParameter(id); } -void ParameterMessage::setParameterDumpReply(CommandMessage* message, - ParameterId_t id, store_address_t storageID) { - message->setCommand(REPLY_PARAMETER_DUMP); - message->setParameter(id); - message->setParameter2(storageID.raw); +void ParameterMessage::setParameterDumpReply(CommandMessage* message, ParameterId_t id, + store_address_t storageID) { + message->setCommand(REPLY_PARAMETER_DUMP); + message->setParameter(id); + message->setParameter2(storageID.raw); } -void ParameterMessage::setParameterLoadCommand(CommandMessage* message, - ParameterId_t id, store_address_t storeId, uint8_t ptc, uint8_t pfc, - uint8_t rows = 1, uint8_t columns = 1) { - message->setCommand(CMD_PARAMETER_LOAD); - message->setParameter(id); - message->setParameter2(storeId.raw); - uint32_t packedParameterSettings = (ptc << 24) | (pfc << 16) | - (rows << 8) | columns; - message->setParameter3(packedParameterSettings); +void ParameterMessage::setParameterLoadCommand(CommandMessage* message, ParameterId_t id, + store_address_t storeId, uint8_t ptc, uint8_t pfc, + uint8_t rows = 1, uint8_t columns = 1) { + message->setCommand(CMD_PARAMETER_LOAD); + message->setParameter(id); + message->setParameter2(storeId.raw); + uint32_t packedParameterSettings = (ptc << 24) | (pfc << 16) | (rows << 8) | columns; + message->setParameter3(packedParameterSettings); } -store_address_t ParameterMessage::getParameterLoadCommand( - const CommandMessage *message, ParameterId_t* parameterId, uint8_t *ptc, - uint8_t *pfc, uint8_t *rows, uint8_t *columns) { - *parameterId = message->getParameter(); - uint32_t packedParamSettings = message->getParameter3(); - *ptc = packedParamSettings >> 24 & 0xff; - *pfc = packedParamSettings >> 16 & 0xff; - *rows = packedParamSettings >> 8 & 0xff; - *columns = packedParamSettings & 0xff; - return message->getParameter2(); +store_address_t ParameterMessage::getParameterLoadCommand(const CommandMessage* message, + ParameterId_t* parameterId, uint8_t* ptc, + uint8_t* pfc, uint8_t* rows, + uint8_t* columns) { + *parameterId = message->getParameter(); + uint32_t packedParamSettings = message->getParameter3(); + *ptc = packedParamSettings >> 24 & 0xff; + *pfc = packedParamSettings >> 16 & 0xff; + *rows = packedParamSettings >> 8 & 0xff; + *columns = packedParamSettings & 0xff; + return message->getParameter2(); } void ParameterMessage::clear(CommandMessage* message) { - switch (message->getCommand()) { - case CMD_PARAMETER_LOAD: - case REPLY_PARAMETER_DUMP: { - StorageManagerIF *ipcStore = ObjectManager::instance()->get( - objects::IPC_STORE); - if (ipcStore != NULL) { - ipcStore->deleteData(getStoreId(message)); - } - break; - } - default: - break; - } + switch (message->getCommand()) { + case CMD_PARAMETER_LOAD: + case REPLY_PARAMETER_DUMP: { + StorageManagerIF* ipcStore = + ObjectManager::instance()->get(objects::IPC_STORE); + if (ipcStore != NULL) { + ipcStore->deleteData(getStoreId(message)); + } + break; + } + default: + break; + } } diff --git a/src/fsfw/parameters/ParameterMessage.h b/src/fsfw/parameters/ParameterMessage.h index fd4481ee..23d54d98 100644 --- a/src/fsfw/parameters/ParameterMessage.h +++ b/src/fsfw/parameters/ParameterMessage.h @@ -1,9 +1,9 @@ #ifndef FSFW_PARAMETERS_PARAMETERMESSAGE_H_ #define FSFW_PARAMETERS_PARAMETERMESSAGE_H_ -#include "HasParametersIF.h" #include "../ipc/CommandMessage.h" #include "../storagemanager/StorageManagerIF.h" +#include "HasParametersIF.h" /** * @brief ParameterMessage interface @@ -20,43 +20,42 @@ * */ class ParameterMessage { -private: - ParameterMessage(); -public: - static const uint8_t MESSAGE_ID = messagetypes::PARAMETER; - static const Command_t CMD_PARAMETER_LOAD = MAKE_COMMAND_ID( 0x01 ); - static const Command_t CMD_PARAMETER_DUMP = MAKE_COMMAND_ID( 0x02 ); - static const Command_t REPLY_PARAMETER_DUMP = MAKE_COMMAND_ID( 0x03 ); + private: + ParameterMessage(); - static ParameterId_t getParameterId(const CommandMessage* message); - static store_address_t getStoreId(const CommandMessage* message); - static void setParameterDumpCommand(CommandMessage* message, - ParameterId_t id); - static void setParameterDumpReply(CommandMessage* message, - ParameterId_t id, store_address_t storageID); + public: + static const uint8_t MESSAGE_ID = messagetypes::PARAMETER; + static const Command_t CMD_PARAMETER_LOAD = MAKE_COMMAND_ID(0x01); + static const Command_t CMD_PARAMETER_DUMP = MAKE_COMMAND_ID(0x02); + static const Command_t REPLY_PARAMETER_DUMP = MAKE_COMMAND_ID(0x03); - /** - * Command to set a load parameter message. The CCSDS / ECSS type in - * form of a PTC and a PFC is expected. See ECSS-E-ST-70-41C15 p.428 - * for all types or the Type class in globalfunctions. - * @param message - * @param id - * @param storeId - * @param ptc Type information according to CCSDS/ECSS standards - * @param pfc Type information according to CCSDS/ECSS standards - * @param rows Set number of rows in parameter set, minimum one. - * @param columns Set number of columns in parameter set, minimum one - */ - static void setParameterLoadCommand(CommandMessage* message, - ParameterId_t id, store_address_t storeId, uint8_t ptc, - uint8_t pfc, uint8_t rows, uint8_t columns); + static ParameterId_t getParameterId(const CommandMessage* message); + static store_address_t getStoreId(const CommandMessage* message); + static void setParameterDumpCommand(CommandMessage* message, ParameterId_t id); + static void setParameterDumpReply(CommandMessage* message, ParameterId_t id, + store_address_t storageID); - static store_address_t getParameterLoadCommand( - const CommandMessage* message, ParameterId_t* parameterId, - uint8_t* ptc, uint8_t* pfc, uint8_t* rows, uint8_t* columns) ; + /** + * Command to set a load parameter message. The CCSDS / ECSS type in + * form of a PTC and a PFC is expected. See ECSS-E-ST-70-41C15 p.428 + * for all types or the Type class in globalfunctions. + * @param message + * @param id + * @param storeId + * @param ptc Type information according to CCSDS/ECSS standards + * @param pfc Type information according to CCSDS/ECSS standards + * @param rows Set number of rows in parameter set, minimum one. + * @param columns Set number of columns in parameter set, minimum one + */ + static void setParameterLoadCommand(CommandMessage* message, ParameterId_t id, + store_address_t storeId, uint8_t ptc, uint8_t pfc, + uint8_t rows, uint8_t columns); - static void clear(CommandMessage* message); + static store_address_t getParameterLoadCommand(const CommandMessage* message, + ParameterId_t* parameterId, uint8_t* ptc, + uint8_t* pfc, uint8_t* rows, uint8_t* columns); + static void clear(CommandMessage* message); }; #endif /* FSFW_PARAMETERS_PARAMETERMESSAGE_H_ */ diff --git a/src/fsfw/parameters/ParameterWrapper.cpp b/src/fsfw/parameters/ParameterWrapper.cpp index 8c09a822..27552290 100644 --- a/src/fsfw/parameters/ParameterWrapper.cpp +++ b/src/fsfw/parameters/ParameterWrapper.cpp @@ -1,351 +1,333 @@ -#include "fsfw/FSFW.h" #include "fsfw/parameters/ParameterWrapper.h" + +#include "fsfw/FSFW.h" #include "fsfw/serviceinterface/ServiceInterface.h" -ParameterWrapper::ParameterWrapper() : - pointsToStream(false), type(Type::UNKNOWN_TYPE) { -} +ParameterWrapper::ParameterWrapper() : pointsToStream(false), type(Type::UNKNOWN_TYPE) {} -ParameterWrapper::ParameterWrapper(Type type, uint8_t rows, uint8_t columns, - void *data): - pointsToStream(false), type(type), rows(rows), columns(columns), - data(data), readonlyData(data) { -} +ParameterWrapper::ParameterWrapper(Type type, uint8_t rows, uint8_t columns, void *data) + : pointsToStream(false), + type(type), + rows(rows), + columns(columns), + data(data), + readonlyData(data) {} -ParameterWrapper::ParameterWrapper(Type type, uint8_t rows, uint8_t columns, - const void *data): - pointsToStream(false), type(type), rows(rows), columns(columns), - data(nullptr), readonlyData(data) { -} +ParameterWrapper::ParameterWrapper(Type type, uint8_t rows, uint8_t columns, const void *data) + : pointsToStream(false), + type(type), + rows(rows), + columns(columns), + data(nullptr), + readonlyData(data) {} -ParameterWrapper::~ParameterWrapper() { -} +ParameterWrapper::~ParameterWrapper() {} -ReturnValue_t ParameterWrapper::serialize(uint8_t **buffer, size_t *size, - size_t maxSize, Endianness streamEndianness) const { - ReturnValue_t result; +ReturnValue_t ParameterWrapper::serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const { + ReturnValue_t result; - result = SerializeAdapter::serialize(&type, buffer, size, maxSize, - streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + result = SerializeAdapter::serialize(&type, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - result = SerializeAdapter::serialize(&columns, buffer, size, maxSize, - streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::serialize(&rows, buffer, size, maxSize, - streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + result = SerializeAdapter::serialize(&columns, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::serialize(&rows, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - /* serialize uses readonlyData, as it is always valid */ - if (readonlyData == nullptr) { - return NOT_SET; - } - switch (type) { - case Type::UINT8_T: - result = serializeData(buffer, size, maxSize, - streamEndianness); - break; - case Type::INT8_T: - result = serializeData(buffer, size, maxSize, streamEndianness); - break; - case Type::UINT16_T: - result = serializeData(buffer, size, maxSize, - streamEndianness); - break; - case Type::INT16_T: - result = serializeData(buffer, size, maxSize, - streamEndianness); - break; - case Type::UINT32_T: - result = serializeData(buffer, size, maxSize, - streamEndianness); - break; - case Type::INT32_T: - result = serializeData(buffer, size, maxSize, - streamEndianness); - break; - case Type::FLOAT: - result = serializeData(buffer, size, maxSize, streamEndianness); - break; - case Type::DOUBLE: - result = serializeData(buffer, size, maxSize, streamEndianness); - break; - default: - result = UNKNOWN_DATATYPE; - break; - } - return result; + /* serialize uses readonlyData, as it is always valid */ + if (readonlyData == nullptr) { + return NOT_SET; + } + switch (type) { + case Type::UINT8_T: + result = serializeData(buffer, size, maxSize, streamEndianness); + break; + case Type::INT8_T: + result = serializeData(buffer, size, maxSize, streamEndianness); + break; + case Type::UINT16_T: + result = serializeData(buffer, size, maxSize, streamEndianness); + break; + case Type::INT16_T: + result = serializeData(buffer, size, maxSize, streamEndianness); + break; + case Type::UINT32_T: + result = serializeData(buffer, size, maxSize, streamEndianness); + break; + case Type::INT32_T: + result = serializeData(buffer, size, maxSize, streamEndianness); + break; + case Type::FLOAT: + result = serializeData(buffer, size, maxSize, streamEndianness); + break; + case Type::DOUBLE: + result = serializeData(buffer, size, maxSize, streamEndianness); + break; + default: + result = UNKNOWN_DATATYPE; + break; + } + return result; } size_t ParameterWrapper::getSerializedSize() const { - uint32_t serializedSize = 0; - serializedSize += type.getSerializedSize(); - serializedSize += sizeof(rows); - serializedSize += sizeof(columns); - serializedSize += rows * columns * type.getSize(); + uint32_t serializedSize = 0; + serializedSize += type.getSerializedSize(); + serializedSize += sizeof(rows); + serializedSize += sizeof(columns); + serializedSize += rows * columns * type.getSize(); - return serializedSize; + return serializedSize; } -template -ReturnValue_t ParameterWrapper::serializeData(uint8_t **buffer, size_t *size, - size_t maxSize, Endianness streamEndianness) const { - const T *element = (const T*) readonlyData; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - uint16_t dataSize = columns * rows; - while (dataSize != 0) { - result = SerializeAdapter::serialize(element, buffer, size, maxSize, - streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - element++; - dataSize--; - } - return result; -} - -template -ReturnValue_t ParameterWrapper::deSerializeData(uint8_t startingRow, - uint8_t startingColumn, const void *from, uint8_t fromRows, - uint8_t fromColumns) { - - //treat from as a continuous Stream as we copy all of it - const uint8_t *fromAsStream = reinterpret_cast(from); - size_t streamSize = fromRows * fromColumns * sizeof(T); - - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - - for (uint8_t fromRow = 0; fromRow < fromRows; fromRow++) { - - //get the start element of this row in data - uint16_t offset = (((startingRow + fromRow) * - static_cast(columns)) + startingColumn); - T *dataWithDataType = static_cast(data) + offset; - - for (uint8_t fromColumn = 0; fromColumn < fromColumns; fromColumn++) { - result = SerializeAdapter::deSerialize( - dataWithDataType + fromColumn, &fromAsStream, &streamSize, - SerializeIF::Endianness::BIG); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - } - } - - return result; - -} - - -ReturnValue_t ParameterWrapper::deSerialize(const uint8_t **buffer, - size_t *size, Endianness streamEndianness) { - return deSerialize(buffer, size, streamEndianness, 0); -} - -ReturnValue_t ParameterWrapper::deSerialize(const uint8_t **buffer, - size_t *size, Endianness streamEndianness, - uint16_t startWritingAtIndex) { - ParameterWrapper streamDescription; - - ReturnValue_t result = streamDescription.set(*buffer, *size, buffer, size); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - - return copyFrom(&streamDescription, startWritingAtIndex); -} - -ReturnValue_t ParameterWrapper::set(Type type, uint8_t rows, uint8_t columns, - const void *data, size_t dataSize) { - this->type = type; - this->rows = rows; - this->columns = columns; - - size_t expectedSize = type.getSize() * rows * columns; - if (expectedSize < dataSize) { - return SerializeIF::STREAM_TOO_SHORT; +template +ReturnValue_t ParameterWrapper::serializeData(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const { + const T *element = (const T *)readonlyData; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + uint16_t dataSize = columns * rows; + while (dataSize != 0) { + result = SerializeAdapter::serialize(element, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; } + element++; + dataSize--; + } + return result; +} - this->data = nullptr; - this->readonlyData = data; - pointsToStream = true; - return HasReturnvaluesIF::RETURN_OK; +template +ReturnValue_t ParameterWrapper::deSerializeData(uint8_t startingRow, uint8_t startingColumn, + const void *from, uint8_t fromRows, + uint8_t fromColumns) { + // treat from as a continuous Stream as we copy all of it + const uint8_t *fromAsStream = reinterpret_cast(from); + size_t streamSize = fromRows * fromColumns * sizeof(T); + + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + + for (uint8_t fromRow = 0; fromRow < fromRows; fromRow++) { + // get the start element of this row in data + uint16_t offset = (((startingRow + fromRow) * static_cast(columns)) + startingColumn); + T *dataWithDataType = static_cast(data) + offset; + + for (uint8_t fromColumn = 0; fromColumn < fromColumns; fromColumn++) { + result = SerializeAdapter::deSerialize(dataWithDataType + fromColumn, &fromAsStream, + &streamSize, SerializeIF::Endianness::BIG); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + } + } + + return result; +} + +ReturnValue_t ParameterWrapper::deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) { + return deSerialize(buffer, size, streamEndianness, 0); +} + +ReturnValue_t ParameterWrapper::deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness, + uint16_t startWritingAtIndex) { + ParameterWrapper streamDescription; + + ReturnValue_t result = streamDescription.set(*buffer, *size, buffer, size); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + + return copyFrom(&streamDescription, startWritingAtIndex); +} + +ReturnValue_t ParameterWrapper::set(Type type, uint8_t rows, uint8_t columns, const void *data, + size_t dataSize) { + this->type = type; + this->rows = rows; + this->columns = columns; + + size_t expectedSize = type.getSize() * rows * columns; + if (expectedSize < dataSize) { + return SerializeIF::STREAM_TOO_SHORT; + } + + this->data = nullptr; + this->readonlyData = data; + pointsToStream = true; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t ParameterWrapper::set(const uint8_t *stream, size_t streamSize, - const uint8_t **remainingStream, size_t *remainingSize) { - ReturnValue_t result = SerializeAdapter::deSerialize(&type, &stream, - &streamSize, SerializeIF::Endianness::BIG); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + const uint8_t **remainingStream, size_t *remainingSize) { + ReturnValue_t result = + SerializeAdapter::deSerialize(&type, &stream, &streamSize, SerializeIF::Endianness::BIG); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - result = SerializeAdapter::deSerialize(&columns, &stream, &streamSize, - SerializeIF::Endianness::BIG); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::deSerialize(&rows, &stream, &streamSize, - SerializeIF::Endianness::BIG); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + result = + SerializeAdapter::deSerialize(&columns, &stream, &streamSize, SerializeIF::Endianness::BIG); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::deSerialize(&rows, &stream, &streamSize, SerializeIF::Endianness::BIG); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - size_t dataSize = type.getSize() * rows * columns; + size_t dataSize = type.getSize() * rows * columns; - if (streamSize < dataSize) { - return SerializeIF::STREAM_TOO_SHORT; - } + if (streamSize < dataSize) { + return SerializeIF::STREAM_TOO_SHORT; + } - data = nullptr; - readonlyData = stream; - pointsToStream = true; + data = nullptr; + readonlyData = stream; + pointsToStream = true; - stream += dataSize; - if (remainingStream != nullptr) { - *remainingStream = stream; - } - streamSize -= dataSize; - if (remainingSize != nullptr) { - *remainingSize = streamSize; - } + stream += dataSize; + if (remainingStream != nullptr) { + *remainingStream = stream; + } + streamSize -= dataSize; + if (remainingSize != nullptr) { + *remainingSize = streamSize; + } - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t ParameterWrapper::copyFrom(const ParameterWrapper *from, - uint16_t startWritingAtIndex) { - if (data == nullptr) { + uint16_t startWritingAtIndex) { + if (data == nullptr) { #if FSFW_VERBOSE_LEVEL >= 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!" << std::endl; #else - sif::printWarning("ParameterWrapper::copyFrom: Called on read-only variable!\n"); + sif::printWarning("ParameterWrapper::copyFrom: Called on read-only variable!\n"); #endif #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - return READONLY; - } + return READONLY; + } - if (from->readonlyData == nullptr) { + if (from->readonlyData == nullptr) { #if FSFW_VERBOSE_LEVEL >= 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 - sif::printWarning("ParameterWrapper::copyFrom: Source not set!\n"); + sif::printWarning("ParameterWrapper::copyFrom: Source not set!\n"); #endif #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - return SOURCE_NOT_SET; - } + return SOURCE_NOT_SET; + } - if (type != from->type) { + if (type != from->type) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "ParameterWrapper::copyFrom: Datatype missmatch!" << std::endl; + sif::warning << "ParameterWrapper::copyFrom: Datatype missmatch!" << std::endl; #else - sif::printWarning("ParameterWrapper::copyFrom: Datatype missmatch!\n"); + sif::printWarning("ParameterWrapper::copyFrom: Datatype missmatch!\n"); #endif #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - return DATATYPE_MISSMATCH; - } + return DATATYPE_MISSMATCH; + } - // The smallest allowed value for rows and columns is one. - if(rows == 0 or columns == 0) { + // The smallest allowed value for rows and columns is one. + if (rows == 0 or columns == 0) { #if FSFW_VERBOSE_LEVEL >= 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 - sif::printWarning("ParameterWrapper::copyFrom: Columns or rows zero!\n"); + sif::printWarning("ParameterWrapper::copyFrom: Columns or rows zero!\n"); #endif #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - return COLUMN_OR_ROWS_ZERO; - } + return COLUMN_OR_ROWS_ZERO; + } - //check if from fits into this - uint8_t startingRow = 0; - uint8_t startingColumn = 0; - ParameterWrapper::convertLinearIndexToRowAndColumn(startWritingAtIndex, - &startingRow, &startingColumn); + // check if from fits into this + uint8_t startingRow = 0; + uint8_t startingColumn = 0; + ParameterWrapper::convertLinearIndexToRowAndColumn(startWritingAtIndex, &startingRow, + &startingColumn); - if ((from->rows > (rows - startingRow)) - || (from->columns > (columns - startingColumn))) { - return TOO_BIG; - } + if ((from->rows > (rows - startingRow)) || (from->columns > (columns - startingColumn))) { + return TOO_BIG; + } - uint8_t typeSize = type.getSize(); + uint8_t typeSize = type.getSize(); - ReturnValue_t result = HasReturnvaluesIF::RETURN_FAILED; - //copy data - if (from->pointsToStream) { - switch (type) { - case Type::UINT8_T: - result = deSerializeData(startingRow, startingColumn, - from->readonlyData, from->rows, from->columns); - break; - case Type::INT8_T: - result = deSerializeData(startingRow, startingColumn, - from->readonlyData, from->rows, from->columns); - break; - case Type::UINT16_T: - result = deSerializeData(startingRow, startingColumn, - from->readonlyData, from->rows, from->columns); - break; - case Type::INT16_T: - result = deSerializeData(startingRow, startingColumn, - from->readonlyData, from->rows, from->columns); - break; - case Type::UINT32_T: - result = deSerializeData(startingRow, startingColumn, - from->readonlyData, from->rows, from->columns); - break; - case Type::INT32_T: - result = deSerializeData(startingRow, startingColumn, - from->readonlyData, from->rows, from->columns); - break; - case Type::FLOAT: - result = deSerializeData(startingRow, startingColumn, - from->readonlyData, from->rows, from->columns); - break; - case Type::DOUBLE: - result = deSerializeData(startingRow, startingColumn, - from->readonlyData, from->rows, from->columns); - break; - default: - result = UNKNOWN_DATATYPE; - break; - } - } - else { - //need a type to do arithmetic - uint8_t* typedData = static_cast(data); - for (uint8_t fromRow = 0; fromRow < from->rows; fromRow++) { - size_t offset = (((startingRow + fromRow) * static_cast( - columns)) + startingColumn) * typeSize; - std::memcpy(typedData + offset, from->readonlyData, - typeSize * from->columns); - } - } - - return result; -} - -void ParameterWrapper::convertLinearIndexToRowAndColumn(uint16_t index, - uint8_t *row, uint8_t *column) { - if(row == nullptr or column == nullptr) { - return; + ReturnValue_t result = HasReturnvaluesIF::RETURN_FAILED; + // copy data + if (from->pointsToStream) { + switch (type) { + case Type::UINT8_T: + result = deSerializeData(startingRow, startingColumn, from->readonlyData, + from->rows, from->columns); + break; + case Type::INT8_T: + result = deSerializeData(startingRow, startingColumn, from->readonlyData, + from->rows, from->columns); + break; + case Type::UINT16_T: + result = deSerializeData(startingRow, startingColumn, from->readonlyData, + from->rows, from->columns); + break; + case Type::INT16_T: + result = deSerializeData(startingRow, startingColumn, from->readonlyData, + from->rows, from->columns); + break; + case Type::UINT32_T: + result = deSerializeData(startingRow, startingColumn, from->readonlyData, + from->rows, from->columns); + break; + case Type::INT32_T: + result = deSerializeData(startingRow, startingColumn, from->readonlyData, + from->rows, from->columns); + break; + case Type::FLOAT: + result = deSerializeData(startingRow, startingColumn, from->readonlyData, from->rows, + from->columns); + break; + case Type::DOUBLE: + result = deSerializeData(startingRow, startingColumn, from->readonlyData, + from->rows, from->columns); + break; + default: + result = UNKNOWN_DATATYPE; + break; } - // Integer division. - *row = index / columns; - *column = index % columns; + } else { + // need a type to do arithmetic + uint8_t *typedData = static_cast(data); + for (uint8_t fromRow = 0; fromRow < from->rows; fromRow++) { + size_t offset = + (((startingRow + fromRow) * static_cast(columns)) + startingColumn) * typeSize; + std::memcpy(typedData + offset, from->readonlyData, typeSize * from->columns); + } + } + + return result; } -uint16_t ParameterWrapper::convertRowAndColumnToLinearIndex(uint8_t row, - uint8_t column) { - return row * columns + column; +void ParameterWrapper::convertLinearIndexToRowAndColumn(uint16_t index, uint8_t *row, + uint8_t *column) { + if (row == nullptr or column == nullptr) { + return; + } + // Integer division. + *row = index / columns; + *column = index % columns; +} + +uint16_t ParameterWrapper::convertRowAndColumnToLinearIndex(uint8_t row, uint8_t column) { + return row * columns + column; } diff --git a/src/fsfw/parameters/ParameterWrapper.h b/src/fsfw/parameters/ParameterWrapper.h index b0ca210d..873db7b2 100644 --- a/src/fsfw/parameters/ParameterWrapper.h +++ b/src/fsfw/parameters/ParameterWrapper.h @@ -1,11 +1,12 @@ #ifndef FSFW_PARAMETERS_PARAMETERWRAPPER_H_ #define FSFW_PARAMETERS_PARAMETERWRAPPER_H_ +#include + +#include "../globalfunctions/Type.h" #include "../returnvalues/HasReturnvaluesIF.h" #include "../serialize/SerializeAdapter.h" #include "../serialize/SerializeIF.h" -#include "../globalfunctions/Type.h" -#include /** * @brief This wrapper encapsulates the access to parameters provided by HasParametersIF. @@ -20,180 +21,172 @@ * the parameter information field (4 bytes) containing the ECSS PTC, PFC and rows and columns * number. */ -class ParameterWrapper: public SerializeIF { - friend class DataPoolParameterWrapper; -public: - static const uint8_t INTERFACE_ID = CLASS_ID::PARAMETER_WRAPPER; - static const ReturnValue_t UNKNOWN_DATATYPE = MAKE_RETURN_CODE(0x01); - static const ReturnValue_t DATATYPE_MISSMATCH = MAKE_RETURN_CODE(0x02); - static const ReturnValue_t READONLY = MAKE_RETURN_CODE(0x03); - static const ReturnValue_t TOO_BIG = MAKE_RETURN_CODE(0x04); - static const ReturnValue_t SOURCE_NOT_SET = MAKE_RETURN_CODE(0x05); - static const ReturnValue_t OUT_OF_BOUNDS = MAKE_RETURN_CODE(0x06); - static const ReturnValue_t NOT_SET = MAKE_RETURN_CODE(0x07); - static const ReturnValue_t COLUMN_OR_ROWS_ZERO = MAKE_RETURN_CODE(0x08); +class ParameterWrapper : public SerializeIF { + friend class DataPoolParameterWrapper; - ParameterWrapper(); - ParameterWrapper(Type type, uint8_t rows, uint8_t columns, void *data); - ParameterWrapper(Type type, uint8_t rows, uint8_t columns, const void *data); - virtual ~ParameterWrapper(); + public: + static const uint8_t INTERFACE_ID = CLASS_ID::PARAMETER_WRAPPER; + static const ReturnValue_t UNKNOWN_DATATYPE = MAKE_RETURN_CODE(0x01); + static const ReturnValue_t DATATYPE_MISSMATCH = MAKE_RETURN_CODE(0x02); + static const ReturnValue_t READONLY = MAKE_RETURN_CODE(0x03); + static const ReturnValue_t TOO_BIG = MAKE_RETURN_CODE(0x04); + static const ReturnValue_t SOURCE_NOT_SET = MAKE_RETURN_CODE(0x05); + static const ReturnValue_t OUT_OF_BOUNDS = MAKE_RETURN_CODE(0x06); + static const ReturnValue_t NOT_SET = MAKE_RETURN_CODE(0x07); + static const ReturnValue_t COLUMN_OR_ROWS_ZERO = MAKE_RETURN_CODE(0x08); - virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const override; + ParameterWrapper(); + ParameterWrapper(Type type, uint8_t rows, uint8_t columns, void *data); + ParameterWrapper(Type type, uint8_t rows, uint8_t columns, const void *data); + virtual ~ParameterWrapper(); - virtual size_t getSerializedSize() const override; + virtual ReturnValue_t serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const override; - virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) override; + virtual size_t getSerializedSize() const override; - virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness, uint16_t startWritingAtIndex = 0); + virtual ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) override; - /** - * Get a specific parameter value by supplying the row and the column. - * @tparam T Type of target data - * @param value [out] Pointer to storage location - * @param row - * @param column - * @return - * -@c RETURN_OK if element was retrieved successfully - * -@c NOT_SET data has not been set yet - * -@c DATATYPE_MISSMATCH Invalid supplied type - * -@c OUT_OF_BOUNDS Invalid row and/or column. - */ - template - ReturnValue_t getElement(T *value, uint8_t row = 0, - uint8_t column = 0) const; + virtual ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness, uint16_t startWritingAtIndex = 0); - template - void set(T *data, uint8_t rows, uint8_t columns) { - this->data = data; - this->readonlyData = data; - this->type = PodTypeConversion::type; - this->rows = rows; - this->columns = columns; - this->pointsToStream = false; - } + /** + * Get a specific parameter value by supplying the row and the column. + * @tparam T Type of target data + * @param value [out] Pointer to storage location + * @param row + * @param column + * @return + * -@c RETURN_OK if element was retrieved successfully + * -@c NOT_SET data has not been set yet + * -@c DATATYPE_MISSMATCH Invalid supplied type + * -@c OUT_OF_BOUNDS Invalid row and/or column. + */ + template + ReturnValue_t getElement(T *value, uint8_t row = 0, uint8_t column = 0) const; - template - void set(const T *readonlyData, uint8_t rows, uint8_t columns) { - this->data = nullptr; - this->readonlyData = readonlyData; - this->type = PodTypeConversion::type; - this->rows = rows; - this->columns = columns; - this->pointsToStream = false; - } + template + void set(T *data, uint8_t rows, uint8_t columns) { + this->data = data; + this->readonlyData = data; + this->type = PodTypeConversion::type; + this->rows = rows; + this->columns = columns; + this->pointsToStream = false; + } - /** - * Setter function for scalar non-const entries - * @tparam T - * @param member - */ - template - void set(T& member) { - this->set(&member, 1, 1); - } + template + void set(const T *readonlyData, uint8_t rows, uint8_t columns) { + this->data = nullptr; + this->readonlyData = readonlyData; + this->type = PodTypeConversion::type; + this->rows = rows; + this->columns = columns; + this->pointsToStream = false; + } - /** - * Setter function for scalar const entries. - * TODO: This is confusing, it should not be called set. Maybe we should call all functions - * assign instead? - * @tparam T - * @param readonlyMember - */ - template - void set(const T& readonlyMember) { - this->set(&readonlyMember, 1, 1); - } + /** + * Setter function for scalar non-const entries + * @tparam T + * @param member + */ + template + void set(T &member) { + this->set(&member, 1, 1); + } - template - void setVector(T& member) { - /* For a vector entry, the number of rows will be one - (left to right, top to bottom indexing) */ - this->set(member, 1, sizeof(member) / sizeof(member[0])); - } + /** + * Setter function for scalar const entries. + * TODO: This is confusing, it should not be called set. Maybe we should call all functions + * assign instead? + * @tparam T + * @param readonlyMember + */ + template + void set(const T &readonlyMember) { + this->set(&readonlyMember, 1, 1); + } - template - void setVector(const T& member) { - /* For a vector entry, the number of rows will be one - (left to right, top to bottom indexing) */ - this->set(member, 1, sizeof(member) / sizeof(member[0])); - } - template - void setMatrix(T& member) { - this->set(member[0], sizeof(member)/sizeof(member[0]), - sizeof(member[0])/sizeof(member[0][0])); - } + template + void setVector(T &member) { + /* For a vector entry, the number of rows will be one + (left to right, top to bottom indexing) */ + this->set(member, 1, sizeof(member) / sizeof(member[0])); + } - template - void setMatrix(const T& member) { - this->set(member[0], sizeof(member)/sizeof(member[0]), - sizeof(member[0])/sizeof(member[0][0])); - } + template + void setVector(const T &member) { + /* For a vector entry, the number of rows will be one + (left to right, top to bottom indexing) */ + this->set(member, 1, sizeof(member) / sizeof(member[0])); + } + template + void setMatrix(T &member) { + this->set(member[0], sizeof(member) / sizeof(member[0]), + sizeof(member[0]) / sizeof(member[0][0])); + } - ReturnValue_t set(Type type, uint8_t rows, uint8_t columns, - const void *data, size_t dataSize); + template + void setMatrix(const T &member) { + this->set(member[0], sizeof(member) / sizeof(member[0]), + sizeof(member[0]) / sizeof(member[0][0])); + } - ReturnValue_t set(const uint8_t *stream, size_t streamSize, - const uint8_t **remainingStream = nullptr, - size_t *remainingSize = nullptr); + ReturnValue_t set(Type type, uint8_t rows, uint8_t columns, const void *data, size_t dataSize); - ReturnValue_t copyFrom(const ParameterWrapper *from, - uint16_t startWritingAtIndex); + ReturnValue_t set(const uint8_t *stream, size_t streamSize, + const uint8_t **remainingStream = nullptr, size_t *remainingSize = nullptr); -private: + ReturnValue_t copyFrom(const ParameterWrapper *from, uint16_t startWritingAtIndex); - void convertLinearIndexToRowAndColumn(uint16_t index, - uint8_t *row, uint8_t *column); + private: + void convertLinearIndexToRowAndColumn(uint16_t index, uint8_t *row, uint8_t *column); - uint16_t convertRowAndColumnToLinearIndex(uint8_t row, - uint8_t column); + uint16_t convertRowAndColumnToLinearIndex(uint8_t row, uint8_t column); - bool pointsToStream = false; + bool pointsToStream = false; - Type type; - uint8_t rows = 0; - uint8_t columns = 0; - void *data = nullptr; - const void *readonlyData = nullptr; + Type type; + uint8_t rows = 0; + uint8_t columns = 0; + void *data = nullptr; + const void *readonlyData = nullptr; - template - ReturnValue_t serializeData(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const; + template + ReturnValue_t serializeData(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const; - template - ReturnValue_t deSerializeData(uint8_t startingRow, uint8_t startingColumn, - const void *from, uint8_t fromRows, uint8_t fromColumns); + template + ReturnValue_t deSerializeData(uint8_t startingRow, uint8_t startingColumn, const void *from, + uint8_t fromRows, uint8_t fromColumns); }; template -inline ReturnValue_t ParameterWrapper::getElement(T *value, uint8_t row, - uint8_t column) const { - if (readonlyData == nullptr){ - return NOT_SET; - } +inline ReturnValue_t ParameterWrapper::getElement(T *value, uint8_t row, uint8_t column) const { + if (readonlyData == nullptr) { + return NOT_SET; + } - if (PodTypeConversion::type != type) { - return DATATYPE_MISSMATCH; - } + if (PodTypeConversion::type != type) { + return DATATYPE_MISSMATCH; + } - if ((row >= rows) or (column >= columns)) { - return OUT_OF_BOUNDS; - } + if ((row >= rows) or (column >= columns)) { + return OUT_OF_BOUNDS; + } - if (pointsToStream) { - const uint8_t *streamWithType = static_cast(readonlyData); - streamWithType += (row * columns + column) * type.getSize(); - size_t size = type.getSize(); - return SerializeAdapter::deSerialize(value, &streamWithType, - &size, SerializeIF::Endianness::BIG); - } - else { - const T *dataWithType = static_cast(readonlyData); - *value = dataWithType[row * columns + column]; - return HasReturnvaluesIF::RETURN_OK; - } + if (pointsToStream) { + const uint8_t *streamWithType = static_cast(readonlyData); + streamWithType += (row * columns + column) * type.getSize(); + size_t size = type.getSize(); + return SerializeAdapter::deSerialize(value, &streamWithType, &size, + SerializeIF::Endianness::BIG); + } else { + const T *dataWithType = static_cast(readonlyData); + *value = dataWithType[row * columns + column]; + return HasReturnvaluesIF::RETURN_OK; + } } #endif /* FSFW_PARAMETERS_PARAMETERWRAPPER_H_ */ diff --git a/src/fsfw/parameters/ReceivesParameterMessagesIF.h b/src/fsfw/parameters/ReceivesParameterMessagesIF.h index e8c7fa69..c4ab53a9 100644 --- a/src/fsfw/parameters/ReceivesParameterMessagesIF.h +++ b/src/fsfw/parameters/ReceivesParameterMessagesIF.h @@ -1,19 +1,15 @@ #ifndef FSFW_PARAMETERS_RECEIVESPARAMETERMESSAGESIF_H_ #define FSFW_PARAMETERS_RECEIVESPARAMETERMESSAGESIF_H_ - -#include "HasParametersIF.h" #include "../ipc/MessageQueueSenderIF.h" +#include "HasParametersIF.h" class ReceivesParameterMessagesIF : public HasParametersIF { -public: + public: + static const uint8_t DOMAIN_ID_BASE = 0; + virtual ~ReceivesParameterMessagesIF() {} - static const uint8_t DOMAIN_ID_BASE = 0; - virtual ~ReceivesParameterMessagesIF() { - } - - virtual MessageQueueId_t getCommandQueue() const = 0; + virtual MessageQueueId_t getCommandQueue() const = 0; }; - #endif /* FSFW_PARAMETERS_RECEIVESPARAMETERMESSAGESIF_H_ */ diff --git a/src/fsfw/power/Fuse.cpp b/src/fsfw/power/Fuse.cpp index 821bdbc5..81b51c89 100644 --- a/src/fsfw/power/Fuse.cpp +++ b/src/fsfw/power/Fuse.cpp @@ -1,264 +1,243 @@ #include "fsfw/power/Fuse.h" +#include "fsfw/ipc/QueueFactory.h" #include "fsfw/monitoring/LimitViolationReporter.h" #include "fsfw/monitoring/MonitoringMessageContent.h" #include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/serialize/SerialFixedArrayListAdapter.h" -#include "fsfw/ipc/QueueFactory.h" object_id_t Fuse::powerSwitchId = 0; -Fuse::Fuse(object_id_t fuseObjectId, uint8_t fuseId, - sid_t variableSet, VariableIds ids, - float maxCurrent, uint16_t confirmationCount) : - SystemObject(fuseObjectId), oldFuseState(0), fuseId(fuseId), - currentLimit(fuseObjectId, 1, ids.pidCurrent, confirmationCount, - maxCurrent, FUSE_CURRENT_HIGH), - powerMonitor(fuseObjectId, 2, ids.poolIdPower, - confirmationCount), - set(variableSet), voltage(ids.pidVoltage, &set), - current(ids.pidCurrent, &set), state(ids.pidState, &set), - power(ids.poolIdPower, &set, PoolVariableIF::VAR_READ_WRITE), - parameterHelper(this), healthHelper(this, fuseObjectId) { - commandQueue = QueueFactory::instance()->createMessageQueue(); +Fuse::Fuse(object_id_t fuseObjectId, uint8_t fuseId, sid_t variableSet, VariableIds ids, + float maxCurrent, uint16_t confirmationCount) + : SystemObject(fuseObjectId), + oldFuseState(0), + fuseId(fuseId), + currentLimit(fuseObjectId, 1, ids.pidCurrent, confirmationCount, maxCurrent, + FUSE_CURRENT_HIGH), + powerMonitor(fuseObjectId, 2, ids.poolIdPower, confirmationCount), + set(variableSet), + voltage(ids.pidVoltage, &set), + current(ids.pidCurrent, &set), + state(ids.pidState, &set), + power(ids.poolIdPower, &set, PoolVariableIF::VAR_READ_WRITE), + parameterHelper(this), + healthHelper(this, fuseObjectId) { + commandQueue = QueueFactory::instance()->createMessageQueue(); } -Fuse::~Fuse() { - QueueFactory::instance()->deleteMessageQueue(commandQueue); -} +Fuse::~Fuse() { QueueFactory::instance()->deleteMessageQueue(commandQueue); } -void Fuse::addDevice(PowerComponentIF* switchSet) { - devices.push_back(switchSet); -} +void Fuse::addDevice(PowerComponentIF* switchSet) { devices.push_back(switchSet); } ReturnValue_t Fuse::initialize() { - ReturnValue_t result = SystemObject::initialize(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = parameterHelper.initialize(); - if (result != RETURN_OK) { - return result; - } - result = healthHelper.initialize(); - if (result != RETURN_OK) { - return result; - } - powerIF = ObjectManager::instance()->get(powerSwitchId); - if (powerIF == NULL) { - return RETURN_FAILED; - } - return RETURN_OK; + ReturnValue_t result = SystemObject::initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = parameterHelper.initialize(); + if (result != RETURN_OK) { + return result; + } + result = healthHelper.initialize(); + if (result != RETURN_OK) { + return result; + } + powerIF = ObjectManager::instance()->get(powerSwitchId); + if (powerIF == NULL) { + return RETURN_FAILED; + } + return RETURN_OK; } void Fuse::calculatePowerLimits(float* low, float* high) { - for (DeviceList::iterator iter = devices.begin(); iter != devices.end(); - iter++) { - if (areSwitchesOfComponentOn(iter)) { - *low += (*iter)->getMin(); - *high += (*iter)->getMax(); - } - } + for (DeviceList::iterator iter = devices.begin(); iter != devices.end(); iter++) { + if (areSwitchesOfComponentOn(iter)) { + *low += (*iter)->getMin(); + *high += (*iter)->getMax(); + } + } } ReturnValue_t Fuse::check() { - set.read(); - if (!healthHelper.healthTable->isHealthy(getObjectId())) { - setAllMonitorsToUnchecked(); - set.setValidity(false, true); - return set.commit(); - } - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - checkFuseState(); - calculateFusePower(); - //Check if power is valid and if fuse state is off or invalid. - if (!power.isValid() || (state == 0) || !state.isValid()) { - result = powerMonitor.setToInvalid(); - } else { - float lowLimit = 0.0; - float highLimit = RESIDUAL_POWER; - calculatePowerLimits(&lowLimit, &highLimit); - result = powerMonitor.checkPower(power.value, lowLimit, highLimit); - if (result == MonitoringIF::BELOW_LOW_LIMIT) { - reportEvents(POWER_BELOW_LOW_LIMIT); - } else if (result == MonitoringIF::ABOVE_HIGH_LIMIT) { - reportEvents(POWER_ABOVE_HIGH_LIMIT); - } - } - set.commit(); - return result; + set.read(); + if (!healthHelper.healthTable->isHealthy(getObjectId())) { + setAllMonitorsToUnchecked(); + set.setValidity(false, true); + return set.commit(); + } + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + checkFuseState(); + calculateFusePower(); + // Check if power is valid and if fuse state is off or invalid. + if (!power.isValid() || (state == 0) || !state.isValid()) { + result = powerMonitor.setToInvalid(); + } else { + float lowLimit = 0.0; + float highLimit = RESIDUAL_POWER; + calculatePowerLimits(&lowLimit, &highLimit); + result = powerMonitor.checkPower(power.value, lowLimit, highLimit); + if (result == MonitoringIF::BELOW_LOW_LIMIT) { + reportEvents(POWER_BELOW_LOW_LIMIT); + } else if (result == MonitoringIF::ABOVE_HIGH_LIMIT) { + reportEvents(POWER_ABOVE_HIGH_LIMIT); + } + } + set.commit(); + return result; } -ReturnValue_t Fuse::serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const { - ReturnValue_t result = RETURN_FAILED; - for (DeviceList::const_iterator iter = devices.begin(); - iter != devices.end(); iter++) { - result = (*iter)->serialize(buffer, size, maxSize, streamEndianness); - if (result != RETURN_OK) { - return result; - } - } - return RETURN_OK; +ReturnValue_t Fuse::serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const { + ReturnValue_t result = RETURN_FAILED; + for (DeviceList::const_iterator iter = devices.begin(); iter != devices.end(); iter++) { + result = (*iter)->serialize(buffer, size, maxSize, streamEndianness); + if (result != RETURN_OK) { + return result; + } + } + return RETURN_OK; } size_t Fuse::getSerializedSize() const { - uint32_t size = 0; - for (DeviceList::const_iterator iter = devices.begin(); - iter != devices.end(); iter++) { - size += (*iter)->getSerializedSize(); - } - return size; + uint32_t size = 0; + for (DeviceList::const_iterator iter = devices.begin(); iter != devices.end(); iter++) { + size += (*iter)->getSerializedSize(); + } + return size; } -ReturnValue_t Fuse::deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) { - ReturnValue_t result = RETURN_FAILED; - for (DeviceList::iterator iter = devices.begin(); iter != devices.end(); - iter++) { - result = (*iter)->deSerialize(buffer, size, streamEndianness); - if (result != RETURN_OK) { - return result; - } - } - return RETURN_OK; +ReturnValue_t Fuse::deSerialize(const uint8_t** buffer, size_t* size, Endianness streamEndianness) { + ReturnValue_t result = RETURN_FAILED; + for (DeviceList::iterator iter = devices.begin(); iter != devices.end(); iter++) { + result = (*iter)->deSerialize(buffer, size, streamEndianness); + if (result != RETURN_OK) { + return result; + } + } + return RETURN_OK; } -uint8_t Fuse::getFuseId() const { - return fuseId; -} +uint8_t Fuse::getFuseId() const { return fuseId; } void Fuse::calculateFusePower() { - ReturnValue_t result1 = currentLimit.check(); - if (result1 != HasReturnvaluesIF::RETURN_OK || !(voltage.isValid())) { - power.setValid(PoolVariableIF::INVALID); - return; - } - //Calculate fuse power. - power.value = current.value * voltage.value; - power.setValid(PoolVariableIF::VALID); + ReturnValue_t result1 = currentLimit.check(); + if (result1 != HasReturnvaluesIF::RETURN_OK || !(voltage.isValid())) { + power.setValid(PoolVariableIF::INVALID); + return; + } + // Calculate fuse power. + power.value = current.value * voltage.value; + power.setValid(PoolVariableIF::VALID); } ReturnValue_t Fuse::performOperation(uint8_t opCode) { - checkCommandQueue(); - return HasReturnvaluesIF::RETURN_OK; + checkCommandQueue(); + return HasReturnvaluesIF::RETURN_OK; } void Fuse::reportEvents(Event event) { - if (!powerMonitor.isEventEnabled()) { - return; - } - for (DeviceList::iterator iter = devices.begin(); iter != devices.end(); - iter++) { - if (areSwitchesOfComponentOn(iter)) { - EventManagerIF::triggerEvent((*iter)->getDeviceObjectId(), event); - } - } + if (!powerMonitor.isEventEnabled()) { + return; + } + for (DeviceList::iterator iter = devices.begin(); iter != devices.end(); iter++) { + if (areSwitchesOfComponentOn(iter)) { + EventManagerIF::triggerEvent((*iter)->getDeviceObjectId(), event); + } + } } -MessageQueueId_t Fuse::getCommandQueue() const { - return commandQueue->getId(); -} +MessageQueueId_t Fuse::getCommandQueue() const { return commandQueue->getId(); } void Fuse::setAllMonitorsToUnchecked() { - currentLimit.setToUnchecked(); - powerMonitor.setToUnchecked(); + currentLimit.setToUnchecked(); + powerMonitor.setToUnchecked(); } void Fuse::checkCommandQueue() { - CommandMessage command; - ReturnValue_t result = commandQueue->receiveMessage(&command); - if (result != HasReturnvaluesIF::RETURN_OK) { - return; - } - result = healthHelper.handleHealthCommand(&command); - if (result == HasReturnvaluesIF::RETURN_OK) { - return; - } - result = parameterHelper.handleParameterMessage(&command); - if (result == HasReturnvaluesIF::RETURN_OK) { - return; - } - command.setToUnknownCommand(); - commandQueue->reply(&command); + CommandMessage command; + ReturnValue_t result = commandQueue->receiveMessage(&command); + if (result != HasReturnvaluesIF::RETURN_OK) { + return; + } + result = healthHelper.handleHealthCommand(&command); + if (result == HasReturnvaluesIF::RETURN_OK) { + return; + } + result = parameterHelper.handleParameterMessage(&command); + if (result == HasReturnvaluesIF::RETURN_OK) { + return; + } + command.setToUnknownCommand(); + commandQueue->reply(&command); } void Fuse::checkFuseState() { - if (!state.isValid()) { - oldFuseState = 0; - return; - } - if (state == 0) { - if (oldFuseState != 0) { - reportEvents(FUSE_WENT_OFF); - } - } - oldFuseState = state.value; + if (!state.isValid()) { + oldFuseState = 0; + return; + } + if (state == 0) { + if (oldFuseState != 0) { + reportEvents(FUSE_WENT_OFF); + } + } + oldFuseState = state.value; } float Fuse::getPower() { - if (power.isValid()) { - return power.value; - } else { - return 0.0; - } + if (power.isValid()) { + return power.value; + } else { + return 0.0; + } } void Fuse::setDataPoolEntriesInvalid() { - set.read(); - set.setValidity(false, true); - set.commit(); + set.read(); + set.setValidity(false, true); + set.commit(); } ReturnValue_t Fuse::getParameter(uint8_t domainId, uint8_t uniqueId, - ParameterWrapper* parameterWrapper, const ParameterWrapper* newValues, - uint16_t startAtIndex) { - ReturnValue_t result = currentLimit.getParameter(domainId, uniqueId, - parameterWrapper, newValues, startAtIndex); - if (result != INVALID_DOMAIN_ID) { - return result; - } - result = powerMonitor.getParameter(domainId, uniqueId, parameterWrapper, - newValues, startAtIndex); - return result; + ParameterWrapper* parameterWrapper, + const ParameterWrapper* newValues, uint16_t startAtIndex) { + ReturnValue_t result = + currentLimit.getParameter(domainId, uniqueId, parameterWrapper, newValues, startAtIndex); + if (result != INVALID_DOMAIN_ID) { + return result; + } + result = powerMonitor.getParameter(domainId, uniqueId, parameterWrapper, newValues, startAtIndex); + return result; } bool Fuse::areSwitchesOfComponentOn(DeviceList::iterator iter) { - if (powerIF->getSwitchState((*iter)->getSwitchId1()) - != PowerSwitchIF::SWITCH_ON) { - return false; - } - if ((*iter)->hasTwoSwitches()) { - if ((powerIF->getSwitchState((*iter)->getSwitchId2()) - != PowerSwitchIF::SWITCH_ON)) { - return false; - } - } - return true; + if (powerIF->getSwitchState((*iter)->getSwitchId1()) != PowerSwitchIF::SWITCH_ON) { + return false; + } + if ((*iter)->hasTwoSwitches()) { + if ((powerIF->getSwitchState((*iter)->getSwitchId2()) != PowerSwitchIF::SWITCH_ON)) { + return false; + } + } + return true; } -bool Fuse::isPowerValid() { - return power.isValid(); -} +bool Fuse::isPowerValid() { return power.isValid(); } ReturnValue_t Fuse::setHealth(HealthState health) { - healthHelper.setHealth(health); - return RETURN_OK; + healthHelper.setHealth(health); + return RETURN_OK; } -HasHealthIF::HealthState Fuse::getHealth() { - return healthHelper.getHealth(); -} +HasHealthIF::HealthState Fuse::getHealth() { return healthHelper.getHealth(); } -ReturnValue_t Fuse::PowerMonitor::checkPower(float sample, float lowerLimit, - float upperLimit) { - if (sample > upperLimit) { - return this->monitorStateIs(MonitoringIF::ABOVE_HIGH_LIMIT, sample, - upperLimit); - } else if (sample < lowerLimit) { - return this->monitorStateIs(MonitoringIF::BELOW_LOW_LIMIT, sample, - lowerLimit); - } else { - return this->monitorStateIs(RETURN_OK, sample, 0.0); //Within limits. - } +ReturnValue_t Fuse::PowerMonitor::checkPower(float sample, float lowerLimit, float upperLimit) { + if (sample > upperLimit) { + return this->monitorStateIs(MonitoringIF::ABOVE_HIGH_LIMIT, sample, upperLimit); + } else if (sample < lowerLimit) { + return this->monitorStateIs(MonitoringIF::BELOW_LOW_LIMIT, sample, lowerLimit); + } else { + return this->monitorStateIs(RETURN_OK, sample, 0.0); // Within limits. + } } diff --git a/src/fsfw/power/Fuse.h b/src/fsfw/power/Fuse.h index 1dc38721..e6f9c149 100644 --- a/src/fsfw/power/Fuse.h +++ b/src/fsfw/power/Fuse.h @@ -1,107 +1,107 @@ #ifndef FSFW_POWER_FUSE_H_ #define FSFW_POWER_FUSE_H_ -#include "PowerComponentIF.h" -#include "PowerSwitchIF.h" - -#include "../devicehandlers/HealthDevice.h" -#include "../monitoring/AbsLimitMonitor.h" -#include "../returnvalues/HasReturnvaluesIF.h" -#include "../parameters/ParameterHelper.h" #include #include "../datapoollocal/StaticLocalDataSet.h" +#include "../devicehandlers/HealthDevice.h" +#include "../monitoring/AbsLimitMonitor.h" +#include "../parameters/ParameterHelper.h" +#include "../returnvalues/HasReturnvaluesIF.h" +#include "PowerComponentIF.h" +#include "PowerSwitchIF.h" namespace Factory { void setStaticFrameworkObjectIds(); } -class Fuse: public SystemObject, - public HasHealthIF, - public HasReturnvaluesIF, - public ReceivesParameterMessagesIF, - public SerializeIF { - friend void (Factory::setStaticFrameworkObjectIds)(); -private: - static constexpr float RESIDUAL_POWER = 0.005 * 28.5; //!< This is the upper limit of residual power lost by fuses and switches. Worst case is Fuse and one of two switches on. See PCDU ICD 1.9 p29 bottom -public: - struct VariableIds { - gp_id_t pidVoltage; - gp_id_t pidCurrent; - gp_id_t pidState; - gp_id_t poolIdPower; - }; +class Fuse : public SystemObject, + public HasHealthIF, + public HasReturnvaluesIF, + public ReceivesParameterMessagesIF, + public SerializeIF { + friend void(Factory::setStaticFrameworkObjectIds)(); - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PCDU_1; - static const Event FUSE_CURRENT_HIGH = MAKE_EVENT(1, severity::LOW); //!< PSS detected that current on a fuse is totally out of bounds. - static const Event FUSE_WENT_OFF = MAKE_EVENT(2, severity::LOW); //!< PSS detected a fuse that went off. - static const Event POWER_ABOVE_HIGH_LIMIT = MAKE_EVENT(4, severity::LOW); //!< PSS detected a fuse that violates its limits. - static const Event POWER_BELOW_LOW_LIMIT = MAKE_EVENT(5, severity::LOW); //!< PSS detected a fuse that violates its limits. + private: + static constexpr float RESIDUAL_POWER = + 0.005 * 28.5; //!< This is the upper limit of residual power lost by fuses and switches. + //!< Worst case is Fuse and one of two switches on. See PCDU ICD 1.9 p29 bottom + public: + struct VariableIds { + gp_id_t pidVoltage; + gp_id_t pidCurrent; + gp_id_t pidState; + gp_id_t poolIdPower; + }; - typedef std::list DeviceList; - Fuse(object_id_t fuseObjectId, uint8_t fuseId, sid_t variableSet, - VariableIds ids, float maxCurrent, uint16_t confirmationCount = 2); - virtual ~Fuse(); - void addDevice(PowerComponentIF *set); - float getPower(); + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PCDU_1; + static const Event FUSE_CURRENT_HIGH = MAKE_EVENT( + 1, severity::LOW); //!< PSS detected that current on a fuse is totally out of bounds. + static const Event FUSE_WENT_OFF = + MAKE_EVENT(2, severity::LOW); //!< PSS detected a fuse that went off. + static const Event POWER_ABOVE_HIGH_LIMIT = + MAKE_EVENT(4, severity::LOW); //!< PSS detected a fuse that violates its limits. + static const Event POWER_BELOW_LOW_LIMIT = + MAKE_EVENT(5, severity::LOW); //!< PSS detected a fuse that violates its limits. - bool isPowerValid(); + typedef std::list DeviceList; + Fuse(object_id_t fuseObjectId, uint8_t fuseId, sid_t variableSet, VariableIds ids, + float maxCurrent, uint16_t confirmationCount = 2); + virtual ~Fuse(); + void addDevice(PowerComponentIF *set); + float getPower(); - ReturnValue_t check(); - uint8_t getFuseId() const; - ReturnValue_t initialize(); - DeviceList devices; - ReturnValue_t serialize(uint8_t **buffer, size_t *size, size_t maxSize, - SerializeIF::Endianness streamEndianness) const override; - size_t getSerializedSize() const override; - ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, - SerializeIF::Endianness streamEndianness) override; - void setAllMonitorsToUnchecked(); - ReturnValue_t performOperation(uint8_t opCode); - MessageQueueId_t getCommandQueue() const; - void setDataPoolEntriesInvalid(); - ReturnValue_t setHealth(HealthState health); - HasHealthIF::HealthState getHealth(); + bool isPowerValid(); - ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, - ParameterWrapper *parameterWrapper, const ParameterWrapper *newValues, - uint16_t startAtIndex); + ReturnValue_t check(); + uint8_t getFuseId() const; + ReturnValue_t initialize(); + DeviceList devices; + ReturnValue_t serialize(uint8_t **buffer, size_t *size, size_t maxSize, + SerializeIF::Endianness streamEndianness) const override; + size_t getSerializedSize() const override; + ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, + SerializeIF::Endianness streamEndianness) override; + void setAllMonitorsToUnchecked(); + ReturnValue_t performOperation(uint8_t opCode); + MessageQueueId_t getCommandQueue() const; + void setDataPoolEntriesInvalid(); + ReturnValue_t setHealth(HealthState health); + HasHealthIF::HealthState getHealth(); -private: - uint8_t oldFuseState; - uint8_t fuseId; - PowerSwitchIF *powerIF = nullptr; //could be static in our case. - AbsLimitMonitor currentLimit; - class PowerMonitor: public MonitorReporter { - public: - template - PowerMonitor(Args ... args): - MonitorReporter(std::forward(args)...) { - } - ReturnValue_t checkPower(float sample, float lowerLimit, - float upperLimit); - void sendTransitionEvent(float currentValue, ReturnValue_t state) { - } + ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, ParameterWrapper *parameterWrapper, + const ParameterWrapper *newValues, uint16_t startAtIndex); - }; - PowerMonitor powerMonitor; - StaticLocalDataSet<3> set; + private: + uint8_t oldFuseState; + uint8_t fuseId; + PowerSwitchIF *powerIF = nullptr; // could be static in our case. + AbsLimitMonitor currentLimit; + class PowerMonitor : public MonitorReporter { + public: + template + PowerMonitor(Args... args) : MonitorReporter(std::forward(args)...) {} + ReturnValue_t checkPower(float sample, float lowerLimit, float upperLimit); + void sendTransitionEvent(float currentValue, ReturnValue_t state) {} + }; + PowerMonitor powerMonitor; + StaticLocalDataSet<3> set; - lp_var_t voltage; - lp_var_t current; - lp_var_t state; + lp_var_t voltage; + lp_var_t current; + lp_var_t state; - lp_var_t power; - MessageQueueIF* commandQueue = nullptr; - ParameterHelper parameterHelper; - HealthHelper healthHelper; - static object_id_t powerSwitchId; - void calculatePowerLimits(float *low, float *high); - void calculateFusePower(); - void checkFuseState(); - void reportEvents(Event event); - void checkCommandQueue(); + lp_var_t power; + MessageQueueIF *commandQueue = nullptr; + ParameterHelper parameterHelper; + HealthHelper healthHelper; + static object_id_t powerSwitchId; + void calculatePowerLimits(float *low, float *high); + void calculateFusePower(); + void checkFuseState(); + void reportEvents(Event event); + void checkCommandQueue(); - bool areSwitchesOfComponentOn(DeviceList::iterator iter); + bool areSwitchesOfComponentOn(DeviceList::iterator iter); }; #endif /* FSFW_POWER_FUSE_H_ */ diff --git a/src/fsfw/power/PowerComponent.cpp b/src/fsfw/power/PowerComponent.cpp index fb66748a..e4c336c7 100644 --- a/src/fsfw/power/PowerComponent.cpp +++ b/src/fsfw/power/PowerComponent.cpp @@ -1,82 +1,68 @@ #include "fsfw/power/PowerComponent.h" + #include "fsfw/serialize/SerializeAdapter.h" +PowerComponent::PowerComponent() : switchId1(0xFF), switchId2(0xFF), doIHaveTwoSwitches(false) {} -PowerComponent::PowerComponent(): switchId1(0xFF), switchId2(0xFF), - doIHaveTwoSwitches(false) { +PowerComponent::PowerComponent(object_id_t setId, uint8_t moduleId, float min, float max, + uint8_t switchId1, bool twoSwitches, uint8_t switchId2) + : deviceObjectId(setId), + switchId1(switchId1), + switchId2(switchId2), + doIHaveTwoSwitches(twoSwitches), + minPower(min), + maxPower(max), + moduleId(moduleId) {} + +ReturnValue_t PowerComponent::serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const { + ReturnValue_t result = + SerializeAdapter::serialize(&minPower, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return SerializeAdapter::serialize(&maxPower, buffer, size, maxSize, streamEndianness); } -PowerComponent::PowerComponent(object_id_t setId, uint8_t moduleId, float min, - float max, uint8_t switchId1, bool twoSwitches, uint8_t switchId2) : - deviceObjectId(setId), switchId1(switchId1), switchId2(switchId2), - doIHaveTwoSwitches(twoSwitches), minPower(min), maxPower(max), - moduleId(moduleId) { -} +size_t PowerComponent::getSerializedSize() const { return sizeof(minPower) + sizeof(maxPower); } -ReturnValue_t PowerComponent::serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const { - ReturnValue_t result = SerializeAdapter::serialize(&minPower, buffer, - size, maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return SerializeAdapter::serialize(&maxPower, buffer, size, maxSize, - streamEndianness); -} +object_id_t PowerComponent::getDeviceObjectId() { return deviceObjectId; } -size_t PowerComponent::getSerializedSize() const { - return sizeof(minPower) + sizeof(maxPower); -} +uint8_t PowerComponent::getSwitchId1() { return switchId1; } -object_id_t PowerComponent::getDeviceObjectId() { - return deviceObjectId; -} +uint8_t PowerComponent::getSwitchId2() { return switchId2; } -uint8_t PowerComponent::getSwitchId1() { - return switchId1; -} +bool PowerComponent::hasTwoSwitches() { return doIHaveTwoSwitches; } -uint8_t PowerComponent::getSwitchId2() { - return switchId2; -} +float PowerComponent::getMin() { return minPower; } -bool PowerComponent::hasTwoSwitches() { - return doIHaveTwoSwitches; -} - -float PowerComponent::getMin() { - return minPower; -} - -float PowerComponent::getMax() { - return maxPower; -} +float PowerComponent::getMax() { return maxPower; } ReturnValue_t PowerComponent::deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) { - ReturnValue_t result = SerializeAdapter::deSerialize(&minPower, buffer, - size, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return SerializeAdapter::deSerialize(&maxPower, buffer, size, streamEndianness); + Endianness streamEndianness) { + ReturnValue_t result = SerializeAdapter::deSerialize(&minPower, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return SerializeAdapter::deSerialize(&maxPower, buffer, size, streamEndianness); } ReturnValue_t PowerComponent::getParameter(uint8_t domainId, uint8_t uniqueId, - ParameterWrapper* parameterWrapper, const ParameterWrapper* newValues, - uint16_t startAtIndex) { - if (domainId != moduleId) { - return INVALID_DOMAIN_ID; - } - switch (uniqueId) { - case 0: - parameterWrapper->set<>(minPower); - break; - case 1: - parameterWrapper->set<>(maxPower); - break; - default: - return INVALID_IDENTIFIER_ID; - } - return HasReturnvaluesIF::RETURN_OK; + ParameterWrapper* parameterWrapper, + const ParameterWrapper* newValues, + uint16_t startAtIndex) { + if (domainId != moduleId) { + return INVALID_DOMAIN_ID; + } + switch (uniqueId) { + case 0: + parameterWrapper->set<>(minPower); + break; + case 1: + parameterWrapper->set<>(maxPower); + break; + default: + return INVALID_IDENTIFIER_ID; + } + return HasReturnvaluesIF::RETURN_OK; } diff --git a/src/fsfw/power/PowerComponent.h b/src/fsfw/power/PowerComponent.h index 3889a2ae..132c4bd8 100644 --- a/src/fsfw/power/PowerComponent.h +++ b/src/fsfw/power/PowerComponent.h @@ -2,51 +2,48 @@ #define FSFW_POWER_POWERCOMPONENT_H_ #include "PowerComponentIF.h" - -#include "fsfw/objectmanager/frameworkObjects.h" #include "fsfw/objectmanager/SystemObjectIF.h" +#include "fsfw/objectmanager/frameworkObjects.h" +class PowerComponent : public PowerComponentIF { + public: + PowerComponent(object_id_t setId, uint8_t moduleId, float minPower, float maxPower, + uint8_t switchId1, bool twoSwitches = false, uint8_t switchId2 = 0xFF); -class PowerComponent: public PowerComponentIF { -public: - PowerComponent(object_id_t setId, uint8_t moduleId, float minPower, float maxPower, - uint8_t switchId1, bool twoSwitches = false, - uint8_t switchId2 = 0xFF); + virtual object_id_t getDeviceObjectId(); - virtual object_id_t getDeviceObjectId(); + virtual uint8_t getSwitchId1(); + virtual uint8_t getSwitchId2(); - virtual uint8_t getSwitchId1(); - virtual uint8_t getSwitchId2(); + bool hasTwoSwitches(); - bool hasTwoSwitches(); + float getMin(); + float getMax(); - float getMin(); - float getMax(); + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; - ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const override; + size_t getSerializedSize() const override; - size_t getSerializedSize() const override; + ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + Endianness streamEndianness) override; - ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) override; + ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, ParameterWrapper* parameterWrapper, + const ParameterWrapper* newValues, uint16_t startAtIndex); - ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, - ParameterWrapper *parameterWrapper, const ParameterWrapper *newValues, - uint16_t startAtIndex); -private: - const object_id_t deviceObjectId = objects::NO_OBJECT; - const uint8_t switchId1; - const uint8_t switchId2; + private: + const object_id_t deviceObjectId = objects::NO_OBJECT; + const uint8_t switchId1; + const uint8_t switchId2; - const bool doIHaveTwoSwitches; + const bool doIHaveTwoSwitches; - float minPower = 0.0; - float maxPower = 0.0; + float minPower = 0.0; + float maxPower = 0.0; - uint8_t moduleId = 0; + uint8_t moduleId = 0; - PowerComponent(); + PowerComponent(); }; #endif /* FSFW_POWER_POWERCOMPONENT_H_ */ diff --git a/src/fsfw/power/PowerComponentIF.h b/src/fsfw/power/PowerComponentIF.h index f35b4d1d..7e70b358 100644 --- a/src/fsfw/power/PowerComponentIF.h +++ b/src/fsfw/power/PowerComponentIF.h @@ -1,23 +1,22 @@ #ifndef FSFW_POWER_POWERCOMPONENTIF_H_ #define FSFW_POWER_POWERCOMPONENTIF_H_ -#include "../serialize/SerializeIF.h" -#include "../parameters/HasParametersIF.h" #include "../objectmanager/SystemObjectIF.h" +#include "../parameters/HasParametersIF.h" +#include "../serialize/SerializeIF.h" class PowerComponentIF : public SerializeIF, public HasParametersIF { -public: - virtual ~PowerComponentIF() {} + public: + virtual ~PowerComponentIF() {} - virtual object_id_t getDeviceObjectId() = 0; + virtual object_id_t getDeviceObjectId() = 0; - virtual uint8_t getSwitchId1() = 0; - virtual uint8_t getSwitchId2() = 0; - virtual bool hasTwoSwitches() = 0; - - virtual float getMin() = 0; - virtual float getMax() = 0; + virtual uint8_t getSwitchId1() = 0; + virtual uint8_t getSwitchId2() = 0; + virtual bool hasTwoSwitches() = 0; + virtual float getMin() = 0; + virtual float getMax() = 0; }; #endif /* FSFW_POWER_POWERCOMPONENTIF_H_ */ diff --git a/src/fsfw/power/PowerSensor.cpp b/src/fsfw/power/PowerSensor.cpp index e1e31353..08ff4724 100644 --- a/src/fsfw/power/PowerSensor.cpp +++ b/src/fsfw/power/PowerSensor.cpp @@ -2,132 +2,123 @@ #include "fsfw/ipc/QueueFactory.h" -PowerSensor::PowerSensor(object_id_t objectId, sid_t setId, VariableIds ids, - DefaultLimits limits, SensorEvents events, uint16_t confirmationCount) : - SystemObject(objectId), parameterHelper(this), - healthHelper(this, objectId), - powerSensorSet(setId), current(ids.pidCurrent, &powerSensorSet), - voltage(ids.pidVoltage, &powerSensorSet), - power(ids.poolIdPower, &powerSensorSet, PoolVariableIF::VAR_WRITE), - currentLimit(objectId, MODULE_ID_CURRENT, ids.pidCurrent, confirmationCount, - limits.currentMin, limits.currentMax, events.currentLow, - events.currentHigh), - voltageLimit(objectId, MODULE_ID_VOLTAGE, - ids.pidVoltage, confirmationCount, limits.voltageMin, - limits.voltageMax, events.voltageLow, events.voltageHigh) { - commandQueue = QueueFactory::instance()->createMessageQueue(); +PowerSensor::PowerSensor(object_id_t objectId, sid_t setId, VariableIds ids, DefaultLimits limits, + SensorEvents events, uint16_t confirmationCount) + : SystemObject(objectId), + parameterHelper(this), + healthHelper(this, objectId), + powerSensorSet(setId), + current(ids.pidCurrent, &powerSensorSet), + voltage(ids.pidVoltage, &powerSensorSet), + power(ids.poolIdPower, &powerSensorSet, PoolVariableIF::VAR_WRITE), + currentLimit(objectId, MODULE_ID_CURRENT, ids.pidCurrent, confirmationCount, + limits.currentMin, limits.currentMax, events.currentLow, events.currentHigh), + voltageLimit(objectId, MODULE_ID_VOLTAGE, ids.pidVoltage, confirmationCount, + limits.voltageMin, limits.voltageMax, events.voltageLow, events.voltageHigh) { + commandQueue = QueueFactory::instance()->createMessageQueue(); } -PowerSensor::~PowerSensor() { - QueueFactory::instance()->deleteMessageQueue(commandQueue); -} +PowerSensor::~PowerSensor() { QueueFactory::instance()->deleteMessageQueue(commandQueue); } ReturnValue_t PowerSensor::calculatePower() { - powerSensorSet.read(); - ReturnValue_t result1 = HasReturnvaluesIF::RETURN_FAILED; - ReturnValue_t result2 = HasReturnvaluesIF::RETURN_FAILED; - if (healthHelper.healthTable->isHealthy(getObjectId()) && voltage.isValid() - && current.isValid()) { - result1 = voltageLimit.doCheck(voltage.value); - result2 = currentLimit.doCheck(current.value); - } else { - voltageLimit.setToInvalid(); - currentLimit.setToInvalid(); - result1 = OBJECT_NOT_HEALTHY; - } - if (result1 != HasReturnvaluesIF::RETURN_OK - || result2 != HasReturnvaluesIF::RETURN_OK) { - result1 = MonitoringIF::INVALID; - power.setValid(PoolVariableIF::INVALID); - } else { - power.setValid(PoolVariableIF::VALID); - power.value = current.value * voltage.value; - } - powerSensorSet.commit(); - return result1; + powerSensorSet.read(); + ReturnValue_t result1 = HasReturnvaluesIF::RETURN_FAILED; + ReturnValue_t result2 = HasReturnvaluesIF::RETURN_FAILED; + if (healthHelper.healthTable->isHealthy(getObjectId()) && voltage.isValid() && + current.isValid()) { + result1 = voltageLimit.doCheck(voltage.value); + result2 = currentLimit.doCheck(current.value); + } else { + voltageLimit.setToInvalid(); + currentLimit.setToInvalid(); + result1 = OBJECT_NOT_HEALTHY; + } + if (result1 != HasReturnvaluesIF::RETURN_OK || result2 != HasReturnvaluesIF::RETURN_OK) { + result1 = MonitoringIF::INVALID; + power.setValid(PoolVariableIF::INVALID); + } else { + power.setValid(PoolVariableIF::VALID); + power.value = current.value * voltage.value; + } + powerSensorSet.commit(); + return result1; } ReturnValue_t PowerSensor::performOperation(uint8_t opCode) { - checkCommandQueue(); - return HasReturnvaluesIF::RETURN_OK; + checkCommandQueue(); + return HasReturnvaluesIF::RETURN_OK; } -MessageQueueId_t PowerSensor::getCommandQueue() const { - return commandQueue->getId(); -} +MessageQueueId_t PowerSensor::getCommandQueue() const { return commandQueue->getId(); } ReturnValue_t PowerSensor::initialize() { - ReturnValue_t result = SystemObject::initialize(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = healthHelper.initialize(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = parameterHelper.initialize(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return result; + ReturnValue_t result = SystemObject::initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = healthHelper.initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = parameterHelper.initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return result; } void PowerSensor::setAllMonitorsToUnchecked() { - currentLimit.setToUnchecked(); - voltageLimit.setToUnchecked(); + currentLimit.setToUnchecked(); + voltageLimit.setToUnchecked(); } void PowerSensor::checkCommandQueue() { - CommandMessage command; - ReturnValue_t result = commandQueue->receiveMessage(&command); - if (result != HasReturnvaluesIF::RETURN_OK) { - return; - } - result = healthHelper.handleHealthCommand(&command); - if (result == HasReturnvaluesIF::RETURN_OK) { - return; - } - result = parameterHelper.handleParameterMessage(&command); - if (result == HasReturnvaluesIF::RETURN_OK) { - return; - } - command.setToUnknownCommand(); - commandQueue->reply(&command); + CommandMessage command; + ReturnValue_t result = commandQueue->receiveMessage(&command); + if (result != HasReturnvaluesIF::RETURN_OK) { + return; + } + result = healthHelper.handleHealthCommand(&command); + if (result == HasReturnvaluesIF::RETURN_OK) { + return; + } + result = parameterHelper.handleParameterMessage(&command); + if (result == HasReturnvaluesIF::RETURN_OK) { + return; + } + command.setToUnknownCommand(); + commandQueue->reply(&command); } void PowerSensor::setDataPoolEntriesInvalid() { - powerSensorSet.read(); - powerSensorSet.setValidity(false, true); - powerSensorSet.commit(); + powerSensorSet.read(); + powerSensorSet.setValidity(false, true); + powerSensorSet.commit(); } float PowerSensor::getPower() { - if (power.isValid()) { - return power.value; - } else { - return 0.0; - } - + if (power.isValid()) { + return power.value; + } else { + return 0.0; + } } ReturnValue_t PowerSensor::setHealth(HealthState health) { - healthHelper.setHealth(health); - return HasReturnvaluesIF::RETURN_OK; + healthHelper.setHealth(health); + return HasReturnvaluesIF::RETURN_OK; } -HasHealthIF::HealthState PowerSensor::getHealth() { - return healthHelper.getHealth(); -} +HasHealthIF::HealthState PowerSensor::getHealth() { return healthHelper.getHealth(); } ReturnValue_t PowerSensor::getParameter(uint8_t domainId, uint8_t uniqueId, - ParameterWrapper* parameterWrapper, const ParameterWrapper* newValues, - uint16_t startAtIndex) { - ReturnValue_t result = currentLimit.getParameter(domainId, uniqueId, - parameterWrapper, newValues, startAtIndex); - if (result != INVALID_DOMAIN_ID) { - return result; - } - result = voltageLimit.getParameter(domainId, uniqueId, parameterWrapper, - newValues, startAtIndex); - return result; + ParameterWrapper* parameterWrapper, + const ParameterWrapper* newValues, uint16_t startAtIndex) { + ReturnValue_t result = + currentLimit.getParameter(domainId, uniqueId, parameterWrapper, newValues, startAtIndex); + if (result != INVALID_DOMAIN_ID) { + return result; + } + result = voltageLimit.getParameter(domainId, uniqueId, parameterWrapper, newValues, startAtIndex); + return result; } diff --git a/src/fsfw/power/PowerSensor.h b/src/fsfw/power/PowerSensor.h index d00c5420..8e16d0b6 100644 --- a/src/fsfw/power/PowerSensor.h +++ b/src/fsfw/power/PowerSensor.h @@ -3,75 +3,74 @@ #include "fsfw/datapoollocal/StaticLocalDataSet.h" #include "fsfw/devicehandlers/HealthDevice.h" -#include "fsfw/monitoring/LimitMonitor.h" -#include "fsfw/parameters/ParameterHelper.h" -#include "fsfw/objectmanager/SystemObject.h" #include "fsfw/ipc/MessageQueueIF.h" +#include "fsfw/monitoring/LimitMonitor.h" +#include "fsfw/objectmanager/SystemObject.h" +#include "fsfw/parameters/ParameterHelper.h" class PowerController; /** * @brief Does magic. */ -class PowerSensor: public SystemObject, - public ReceivesParameterMessagesIF, - public HasHealthIF { - friend class PowerController; -public: - struct VariableIds { - gp_id_t pidCurrent; - gp_id_t pidVoltage; - gp_id_t poolIdPower; - }; - struct DefaultLimits { - float currentMin; - float currentMax; - float voltageMin; - float voltageMax; - }; - struct SensorEvents { - Event currentLow; - Event currentHigh; - Event voltageLow; - Event voltageHigh; - }; - PowerSensor(object_id_t objectId, sid_t sid, VariableIds setIds, - DefaultLimits limits, SensorEvents events, - uint16_t confirmationCount = 0); - virtual ~PowerSensor(); - ReturnValue_t calculatePower(); - ReturnValue_t performOperation(uint8_t opCode); - void setAllMonitorsToUnchecked(); - MessageQueueId_t getCommandQueue() const; - ReturnValue_t initialize(); - void setDataPoolEntriesInvalid(); - float getPower(); - ReturnValue_t setHealth(HealthState health); - HasHealthIF::HealthState getHealth(); - ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, - ParameterWrapper *parameterWrapper, - const ParameterWrapper *newValues, uint16_t startAtIndex); -private: - MessageQueueIF* commandQueue = nullptr; - ParameterHelper parameterHelper; - HealthHelper healthHelper; - //GlobDataSet set; - StaticLocalDataSet<3> powerSensorSet; - //Variables in - lp_var_t current; - lp_var_t voltage; - //PIDReader current; - //PIDReader voltage; - //Variables out - lp_var_t power; - //gp_float_t power; +class PowerSensor : public SystemObject, public ReceivesParameterMessagesIF, public HasHealthIF { + friend class PowerController; - static const uint8_t MODULE_ID_CURRENT = 1; - static const uint8_t MODULE_ID_VOLTAGE = 2; - void checkCommandQueue(); -protected: - LimitMonitor currentLimit; - LimitMonitor voltageLimit; + public: + struct VariableIds { + gp_id_t pidCurrent; + gp_id_t pidVoltage; + gp_id_t poolIdPower; + }; + struct DefaultLimits { + float currentMin; + float currentMax; + float voltageMin; + float voltageMax; + }; + struct SensorEvents { + Event currentLow; + Event currentHigh; + Event voltageLow; + Event voltageHigh; + }; + PowerSensor(object_id_t objectId, sid_t sid, VariableIds setIds, DefaultLimits limits, + SensorEvents events, uint16_t confirmationCount = 0); + virtual ~PowerSensor(); + ReturnValue_t calculatePower(); + ReturnValue_t performOperation(uint8_t opCode); + void setAllMonitorsToUnchecked(); + MessageQueueId_t getCommandQueue() const; + ReturnValue_t initialize(); + void setDataPoolEntriesInvalid(); + float getPower(); + ReturnValue_t setHealth(HealthState health); + HasHealthIF::HealthState getHealth(); + ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, ParameterWrapper *parameterWrapper, + const ParameterWrapper *newValues, uint16_t startAtIndex); + + private: + MessageQueueIF *commandQueue = nullptr; + ParameterHelper parameterHelper; + HealthHelper healthHelper; + // GlobDataSet set; + StaticLocalDataSet<3> powerSensorSet; + // Variables in + lp_var_t current; + lp_var_t voltage; + // PIDReader current; + // PIDReader voltage; + // Variables out + lp_var_t power; + // gp_float_t power; + + static const uint8_t MODULE_ID_CURRENT = 1; + static const uint8_t MODULE_ID_VOLTAGE = 2; + void checkCommandQueue(); + + protected: + LimitMonitor currentLimit; + LimitMonitor voltageLimit; }; #endif /* FSFW_POWER_POWERSENSOR_H_ */ diff --git a/src/fsfw/power/PowerSwitchIF.h b/src/fsfw/power/PowerSwitchIF.h index b1f53a35..a31d8971 100644 --- a/src/fsfw/power/PowerSwitchIF.h +++ b/src/fsfw/power/PowerSwitchIF.h @@ -13,61 +13,61 @@ * @ingroup interfaces */ class PowerSwitchIF : public HasReturnvaluesIF { -public: - /** - * Empty dtor. - */ - virtual ~PowerSwitchIF() { + public: + /** + * Empty dtor. + */ + virtual ~PowerSwitchIF() {} + /** + * The Returnvalues id of this class, required by HasReturnvaluesIF + */ + static const uint8_t INTERFACE_ID = CLASS_ID::POWER_SWITCH_IF; + static const ReturnValue_t SWITCH_ON = MAKE_RETURN_CODE(1); + static const ReturnValue_t SWITCH_OFF = MAKE_RETURN_CODE(0); + static const ReturnValue_t SWITCH_TIMEOUT = MAKE_RETURN_CODE(2); + static const ReturnValue_t FUSE_ON = MAKE_RETURN_CODE(3); + static const ReturnValue_t FUSE_OFF = MAKE_RETURN_CODE(4); + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PCDU_2; + static const Event SWITCH_WENT_OFF = MAKE_EVENT( + 0, severity::LOW); //!< Someone detected that a switch went off which shouldn't. Severity: + //!< Low, Parameter1: switchId1, Parameter2: switchId2 + /** + * send a direct command to the Power Unit to enable/disable the specified switch. + * + * @param switchNr + * @param onOff on == @c SWITCH_ON; off != @c SWITCH_ON + */ + virtual void sendSwitchCommand(uint8_t switchNr, ReturnValue_t onOff) const = 0; + /** + * Sends a command to the Power Unit to enable a certain fuse. + */ + virtual void sendFuseOnCommand(uint8_t fuseNr) const = 0; - } - /** - * The Returnvalues id of this class, required by HasReturnvaluesIF - */ - static const uint8_t INTERFACE_ID = CLASS_ID::POWER_SWITCH_IF; - static const ReturnValue_t SWITCH_ON = MAKE_RETURN_CODE(1); - static const ReturnValue_t SWITCH_OFF = MAKE_RETURN_CODE(0); - static const ReturnValue_t SWITCH_TIMEOUT = MAKE_RETURN_CODE(2); - static const ReturnValue_t FUSE_ON = MAKE_RETURN_CODE(3); - static const ReturnValue_t FUSE_OFF = MAKE_RETURN_CODE(4); - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PCDU_2; - static const Event SWITCH_WENT_OFF = MAKE_EVENT(0, severity::LOW); //!< Someone detected that a switch went off which shouldn't. Severity: Low, Parameter1: switchId1, Parameter2: switchId2 - /** - * send a direct command to the Power Unit to enable/disable the specified switch. - * - * @param switchNr - * @param onOff on == @c SWITCH_ON; off != @c SWITCH_ON - */ - virtual void sendSwitchCommand(uint8_t switchNr, ReturnValue_t onOff) const = 0; - /** - * Sends a command to the Power Unit to enable a certain fuse. - */ - virtual void sendFuseOnCommand(uint8_t fuseNr) const = 0; - - /** - * get the state of the Switches. - * @param switchNr - * @return - * - @c SWITCH_ON if the specified switch is on. - * - @c SWITCH_OFF if the specified switch is off. - * - @c RETURN_FAILED if an error occured - */ - virtual ReturnValue_t getSwitchState( uint8_t switchNr ) const = 0; - /** - * get state of a fuse. - * @param fuseNr - * @return - * - @c FUSE_ON if the specified fuse is on. - * - @c FUSE_OFF if the specified fuse is off. - * - @c RETURN_FAILED if an error occured - */ - virtual ReturnValue_t getFuseState( uint8_t fuseNr ) const = 0; - /** - * The maximum delay that it will take to change a switch - * - * This may take into account the time to send a command, wait for it to be executed and see the switch changed. - */ - virtual uint32_t getSwitchDelayMs(void) const = 0; + /** + * get the state of the Switches. + * @param switchNr + * @return + * - @c SWITCH_ON if the specified switch is on. + * - @c SWITCH_OFF if the specified switch is off. + * - @c RETURN_FAILED if an error occured + */ + virtual ReturnValue_t getSwitchState(uint8_t switchNr) const = 0; + /** + * get state of a fuse. + * @param fuseNr + * @return + * - @c FUSE_ON if the specified fuse is on. + * - @c FUSE_OFF if the specified fuse is off. + * - @c RETURN_FAILED if an error occured + */ + virtual ReturnValue_t getFuseState(uint8_t fuseNr) const = 0; + /** + * The maximum delay that it will take to change a switch + * + * This may take into account the time to send a command, wait for it to be executed and see the + * switch changed. + */ + virtual uint32_t getSwitchDelayMs(void) const = 0; }; - #endif /* FSFW_POWER_POWERSWITCHIF_H_ */ diff --git a/src/fsfw/power/PowerSwitcher.cpp b/src/fsfw/power/PowerSwitcher.cpp index f849a7fb..0a3f8521 100644 --- a/src/fsfw/power/PowerSwitcher.cpp +++ b/src/fsfw/power/PowerSwitcher.cpp @@ -4,132 +4,119 @@ #include "fsfw/serviceinterface/ServiceInterface.h" PowerSwitcher::PowerSwitcher(uint8_t setSwitch1, uint8_t setSwitch2, - PowerSwitcher::State_t setStartState): - state(setStartState), firstSwitch(setSwitch1), - secondSwitch(setSwitch2) { -} + PowerSwitcher::State_t setStartState) + : state(setStartState), firstSwitch(setSwitch1), secondSwitch(setSwitch2) {} ReturnValue_t PowerSwitcher::initialize(object_id_t powerSwitchId) { - power = ObjectManager::instance()->get(powerSwitchId); - if (power == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + power = ObjectManager::instance()->get(powerSwitchId); + if (power == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t PowerSwitcher::getStateOfSwitches() { - SwitchReturn_t result = howManySwitches(); + SwitchReturn_t result = howManySwitches(); - switch (result) { - case ONE_SWITCH: - return power->getSwitchState(firstSwitch); - case TWO_SWITCHES: { - ReturnValue_t firstSwitchState = power->getSwitchState(firstSwitch); - ReturnValue_t secondSwitchState = power->getSwitchState(firstSwitch); - if ((firstSwitchState == PowerSwitchIF::SWITCH_ON) - && (secondSwitchState == PowerSwitchIF::SWITCH_ON)) { - return PowerSwitchIF::SWITCH_ON; - } - else if ((firstSwitchState == PowerSwitchIF::SWITCH_OFF) - && (secondSwitchState == PowerSwitchIF::SWITCH_OFF)) { - return PowerSwitchIF::SWITCH_OFF; - } - else { - return HasReturnvaluesIF::RETURN_FAILED; - } - } - default: - return HasReturnvaluesIF::RETURN_FAILED; - } + switch (result) { + case ONE_SWITCH: + return power->getSwitchState(firstSwitch); + case TWO_SWITCHES: { + ReturnValue_t firstSwitchState = power->getSwitchState(firstSwitch); + ReturnValue_t secondSwitchState = power->getSwitchState(firstSwitch); + if ((firstSwitchState == PowerSwitchIF::SWITCH_ON) && + (secondSwitchState == PowerSwitchIF::SWITCH_ON)) { + return PowerSwitchIF::SWITCH_ON; + } else if ((firstSwitchState == PowerSwitchIF::SWITCH_OFF) && + (secondSwitchState == PowerSwitchIF::SWITCH_OFF)) { + return PowerSwitchIF::SWITCH_OFF; + } else { + return HasReturnvaluesIF::RETURN_FAILED; + } + } + default: + return HasReturnvaluesIF::RETURN_FAILED; + } } void PowerSwitcher::commandSwitches(ReturnValue_t onOff) { - SwitchReturn_t result = howManySwitches(); - switch (result) { - case TWO_SWITCHES: - power->sendSwitchCommand(secondSwitch, onOff); - /* NO BREAK falls through*/ - case ONE_SWITCH: - power->sendSwitchCommand(firstSwitch, onOff); - break; - } - return; - + SwitchReturn_t result = howManySwitches(); + switch (result) { + case TWO_SWITCHES: + power->sendSwitchCommand(secondSwitch, onOff); + /* NO BREAK falls through*/ + case ONE_SWITCH: + power->sendSwitchCommand(firstSwitch, onOff); + break; + } + return; } void PowerSwitcher::turnOn() { - commandSwitches(PowerSwitchIF::SWITCH_ON); - state = WAIT_ON; + commandSwitches(PowerSwitchIF::SWITCH_ON); + state = WAIT_ON; } void PowerSwitcher::turnOff() { - commandSwitches(PowerSwitchIF::SWITCH_OFF); - state = WAIT_OFF; + commandSwitches(PowerSwitchIF::SWITCH_OFF); + state = WAIT_OFF; } PowerSwitcher::SwitchReturn_t PowerSwitcher::howManySwitches() { - if (secondSwitch == NO_SWITCH) { - return ONE_SWITCH; - } else { - return TWO_SWITCHES; - } + if (secondSwitch == NO_SWITCH) { + return ONE_SWITCH; + } else { + return TWO_SWITCHES; + } } void PowerSwitcher::doStateMachine() { - switch (state) { - case SWITCH_IS_OFF: - case SWITCH_IS_ON: - //Do nothing. - break; - case WAIT_OFF: - if (getStateOfSwitches() == PowerSwitchIF::SWITCH_OFF) { - state = SWITCH_IS_OFF; - } - break; - case WAIT_ON: - if (getStateOfSwitches() == PowerSwitchIF::SWITCH_ON) { - state = SWITCH_IS_ON; - } - break; - default: - //Should never happen. - break; - } + switch (state) { + case SWITCH_IS_OFF: + case SWITCH_IS_ON: + // Do nothing. + break; + case WAIT_OFF: + if (getStateOfSwitches() == PowerSwitchIF::SWITCH_OFF) { + state = SWITCH_IS_OFF; + } + break; + case WAIT_ON: + if (getStateOfSwitches() == PowerSwitchIF::SWITCH_ON) { + state = SWITCH_IS_ON; + } + break; + default: + // Should never happen. + break; + } } ReturnValue_t PowerSwitcher::checkSwitchState() { - switch (state) { - case WAIT_OFF: - case WAIT_ON: - return IN_POWER_TRANSITION; - case SWITCH_IS_OFF: - if (getStateOfSwitches() == PowerSwitchIF::SWITCH_OFF) { - return RETURN_OK; - } else { - return SWITCH_STATE_MISMATCH; - } - case SWITCH_IS_ON: - if (getStateOfSwitches() == PowerSwitchIF::SWITCH_ON) { - return RETURN_OK; - } else { - return SWITCH_STATE_MISMATCH; - } - } - return RETURN_FAILED; + switch (state) { + case WAIT_OFF: + case WAIT_ON: + return IN_POWER_TRANSITION; + case SWITCH_IS_OFF: + if (getStateOfSwitches() == PowerSwitchIF::SWITCH_OFF) { + return RETURN_OK; + } else { + return SWITCH_STATE_MISMATCH; + } + case SWITCH_IS_ON: + if (getStateOfSwitches() == PowerSwitchIF::SWITCH_ON) { + return RETURN_OK; + } else { + return SWITCH_STATE_MISMATCH; + } + } + return RETURN_FAILED; } -PowerSwitcher::State_t PowerSwitcher::getState() { - return state; -} +PowerSwitcher::State_t PowerSwitcher::getState() { return state; } -uint32_t PowerSwitcher::getSwitchDelay() { - return power->getSwitchDelayMs(); -} +uint32_t PowerSwitcher::getSwitchDelay() { return power->getSwitchDelayMs(); } -uint8_t PowerSwitcher::getFirstSwitch() const { - return firstSwitch; -} +uint8_t PowerSwitcher::getFirstSwitch() const { return firstSwitch; } -uint8_t PowerSwitcher::getSecondSwitch() const { - return secondSwitch; -} +uint8_t PowerSwitcher::getSecondSwitch() const { return secondSwitch; } diff --git a/src/fsfw/power/PowerSwitcher.h b/src/fsfw/power/PowerSwitcher.h index f4e2138d..c72c241d 100644 --- a/src/fsfw/power/PowerSwitcher.h +++ b/src/fsfw/power/PowerSwitcher.h @@ -1,50 +1,45 @@ #ifndef FSFW_POWER_POWERSWITCHER_H_ #define FSFW_POWER_POWERSWITCHER_H_ -#include "PowerSwitchIF.h" - #include "../objectmanager/SystemObjectIF.h" #include "../returnvalues/HasReturnvaluesIF.h" #include "../timemanager/Countdown.h" +#include "PowerSwitchIF.h" -class PowerSwitcher: public HasReturnvaluesIF { -public: - enum State_t { - WAIT_OFF, - WAIT_ON, - SWITCH_IS_OFF, - SWITCH_IS_ON, - }; - State_t state; - static const uint8_t INTERFACE_ID = CLASS_ID::POWER_SWITCHER; - static const ReturnValue_t IN_POWER_TRANSITION = MAKE_RETURN_CODE(1); - static const ReturnValue_t SWITCH_STATE_MISMATCH = MAKE_RETURN_CODE(2); - PowerSwitcher( uint8_t setSwitch1, uint8_t setSwitch2 = NO_SWITCH, - State_t setStartState = SWITCH_IS_OFF ); - ReturnValue_t initialize(object_id_t powerSwitchId); - void turnOn(); - void turnOff(); - void doStateMachine(); - State_t getState(); - ReturnValue_t checkSwitchState(); - uint32_t getSwitchDelay(); - uint8_t getFirstSwitch() const; - uint8_t getSecondSwitch() const; -private: - uint8_t firstSwitch; - uint8_t secondSwitch; - PowerSwitchIF* power = nullptr; +class PowerSwitcher : public HasReturnvaluesIF { + public: + enum State_t { + WAIT_OFF, + WAIT_ON, + SWITCH_IS_OFF, + SWITCH_IS_ON, + }; + State_t state; + static const uint8_t INTERFACE_ID = CLASS_ID::POWER_SWITCHER; + static const ReturnValue_t IN_POWER_TRANSITION = MAKE_RETURN_CODE(1); + static const ReturnValue_t SWITCH_STATE_MISMATCH = MAKE_RETURN_CODE(2); + PowerSwitcher(uint8_t setSwitch1, uint8_t setSwitch2 = NO_SWITCH, + State_t setStartState = SWITCH_IS_OFF); + ReturnValue_t initialize(object_id_t powerSwitchId); + void turnOn(); + void turnOff(); + void doStateMachine(); + State_t getState(); + ReturnValue_t checkSwitchState(); + uint32_t getSwitchDelay(); + uint8_t getFirstSwitch() const; + uint8_t getSecondSwitch() const; - static const uint8_t NO_SWITCH = 0xFF; - enum SwitchReturn_t { - ONE_SWITCH = 1, - TWO_SWITCHES = 2 - }; - ReturnValue_t getStateOfSwitches(); - void commandSwitches( ReturnValue_t onOff ); - SwitchReturn_t howManySwitches(); + private: + uint8_t firstSwitch; + uint8_t secondSwitch; + PowerSwitchIF* power = nullptr; + + static const uint8_t NO_SWITCH = 0xFF; + enum SwitchReturn_t { ONE_SWITCH = 1, TWO_SWITCHES = 2 }; + ReturnValue_t getStateOfSwitches(); + void commandSwitches(ReturnValue_t onOff); + SwitchReturn_t howManySwitches(); }; - - #endif /* FSFW_POWER_POWERSWITCHER_H_ */ diff --git a/src/fsfw/pus/CService200ModeCommanding.cpp b/src/fsfw/pus/CService200ModeCommanding.cpp index 66c61dbe..41be3d13 100644 --- a/src/fsfw/pus/CService200ModeCommanding.cpp +++ b/src/fsfw/pus/CService200ModeCommanding.cpp @@ -1,130 +1,122 @@ #include "fsfw/pus/CService200ModeCommanding.h" -#include "fsfw/pus/servicepackets/Service200Packets.h" #include "fsfw/modes/HasModesIF.h" -#include "fsfw/objectmanager/ObjectManager.h" -#include "fsfw/serviceinterface/ServiceInterface.h" -#include "fsfw/serialize/SerialLinkedListAdapter.h" #include "fsfw/modes/ModeMessage.h" +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/pus/servicepackets/Service200Packets.h" +#include "fsfw/serialize/SerialLinkedListAdapter.h" +#include "fsfw/serviceinterface/ServiceInterface.h" -CService200ModeCommanding::CService200ModeCommanding(object_id_t objectId, - uint16_t apid, uint8_t serviceId, uint8_t numParallelCommands, - uint16_t commandTimeoutSeconds): - CommandingServiceBase(objectId, apid, serviceId, - numParallelCommands, commandTimeoutSeconds) {} +CService200ModeCommanding::CService200ModeCommanding(object_id_t objectId, uint16_t apid, + uint8_t serviceId, uint8_t numParallelCommands, + uint16_t commandTimeoutSeconds) + : CommandingServiceBase(objectId, apid, serviceId, numParallelCommands, commandTimeoutSeconds) { +} CService200ModeCommanding::~CService200ModeCommanding() {} ReturnValue_t CService200ModeCommanding::isValidSubservice(uint8_t subservice) { - switch(subservice) { - case(Subservice::COMMAND_MODE_COMMAND): - case(Subservice::COMMAND_MODE_READ): - case(Subservice::COMMAND_MODE_ANNCOUNCE): - return RETURN_OK; - default: - return AcceptsTelecommandsIF::INVALID_SUBSERVICE; - } + switch (subservice) { + case (Subservice::COMMAND_MODE_COMMAND): + case (Subservice::COMMAND_MODE_READ): + case (Subservice::COMMAND_MODE_ANNCOUNCE): + return RETURN_OK; + default: + return AcceptsTelecommandsIF::INVALID_SUBSERVICE; + } } +ReturnValue_t CService200ModeCommanding::getMessageQueueAndObject(uint8_t subservice, + const uint8_t *tcData, + size_t tcDataLen, + MessageQueueId_t *id, + object_id_t *objectId) { + if (tcDataLen < sizeof(object_id_t)) { + return CommandingServiceBase::INVALID_TC; + } + SerializeAdapter::deSerialize(objectId, &tcData, &tcDataLen, SerializeIF::Endianness::BIG); -ReturnValue_t CService200ModeCommanding::getMessageQueueAndObject( - uint8_t subservice, const uint8_t *tcData, size_t tcDataLen, - MessageQueueId_t *id, object_id_t *objectId) { - if(tcDataLen < sizeof(object_id_t)) { - return CommandingServiceBase::INVALID_TC; - } - SerializeAdapter::deSerialize(objectId, &tcData, &tcDataLen, - SerializeIF::Endianness::BIG); - - return checkInterfaceAndAcquireMessageQueue(id,objectId); + return checkInterfaceAndAcquireMessageQueue(id, objectId); } ReturnValue_t CService200ModeCommanding::checkInterfaceAndAcquireMessageQueue( - MessageQueueId_t* messageQueueToSet, object_id_t* objectId) { - HasModesIF * destination = ObjectManager::instance()->get(*objectId); - if(destination == nullptr) { - return CommandingServiceBase::INVALID_OBJECT; + MessageQueueId_t *messageQueueToSet, object_id_t *objectId) { + HasModesIF *destination = ObjectManager::instance()->get(*objectId); + if (destination == nullptr) { + return CommandingServiceBase::INVALID_OBJECT; + } + *messageQueueToSet = destination->getCommandQueue(); + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t CService200ModeCommanding::prepareCommand(CommandMessage *message, uint8_t subservice, + const uint8_t *tcData, size_t tcDataLen, + uint32_t *state, object_id_t objectId) { + ModePacket modeCommandPacket; + ReturnValue_t result = + modeCommandPacket.deSerialize(&tcData, &tcDataLen, SerializeIF::Endianness::BIG); + if (result != RETURN_OK) { + return result; + } + + ModeMessage::setModeMessage(message, ModeMessage::CMD_MODE_COMMAND, modeCommandPacket.getMode(), + modeCommandPacket.getSubmode()); + return result; +} + +ReturnValue_t CService200ModeCommanding::handleReply(const CommandMessage *reply, + Command_t previousCommand, uint32_t *state, + CommandMessage *optionalNextCommand, + object_id_t objectId, bool *isStep) { + Command_t replyId = reply->getCommand(); + ReturnValue_t result = HasReturnvaluesIF::RETURN_FAILED; + switch (replyId) { + case (ModeMessage::REPLY_MODE_REPLY): { + result = prepareModeReply(reply, objectId); + break; } - - *messageQueueToSet = destination->getCommandQueue(); - return HasReturnvaluesIF::RETURN_OK; + case (ModeMessage::REPLY_WRONG_MODE_REPLY): { + result = prepareWrongModeReply(reply, objectId); + break; + } + case (ModeMessage::REPLY_CANT_REACH_MODE): { + result = prepareCantReachModeReply(reply, objectId); + break; + } + case (ModeMessage::REPLY_MODE_INFO): + result = INVALID_REPLY; + break; + default: + result = RETURN_FAILED; + } + return result; } - -ReturnValue_t CService200ModeCommanding::prepareCommand( - CommandMessage* message,uint8_t subservice, const uint8_t *tcData, - size_t tcDataLen, uint32_t *state, object_id_t objectId) { - ModePacket modeCommandPacket; - ReturnValue_t result = modeCommandPacket.deSerialize(&tcData, - &tcDataLen, SerializeIF::Endianness::BIG); - if (result != RETURN_OK) { - return result; - } - - ModeMessage::setModeMessage(message, ModeMessage::CMD_MODE_COMMAND, modeCommandPacket.getMode(), - modeCommandPacket.getSubmode()); - return result; +ReturnValue_t CService200ModeCommanding::prepareModeReply(const CommandMessage *reply, + object_id_t objectId) { + ModePacket modeReplyPacket(objectId, ModeMessage::getMode(reply), ModeMessage::getSubmode(reply)); + return sendTmPacket(Subservice::REPLY_MODE_REPLY, &modeReplyPacket); } - -ReturnValue_t CService200ModeCommanding::handleReply( - const CommandMessage* reply, Command_t previousCommand, - uint32_t *state, CommandMessage* optionalNextCommand, - object_id_t objectId, bool *isStep) { - Command_t replyId = reply->getCommand(); - ReturnValue_t result = HasReturnvaluesIF::RETURN_FAILED; - switch(replyId) { - case(ModeMessage::REPLY_MODE_REPLY): { - result = prepareModeReply(reply, objectId); - break; - } - case(ModeMessage::REPLY_WRONG_MODE_REPLY): { - result = prepareWrongModeReply(reply, objectId); - break; - } - case(ModeMessage::REPLY_CANT_REACH_MODE): { - result = prepareCantReachModeReply(reply, objectId); - break; - } - case(ModeMessage::REPLY_MODE_INFO): - result = INVALID_REPLY; - break; - default: - result = RETURN_FAILED; - } - return result; +ReturnValue_t CService200ModeCommanding::prepareWrongModeReply(const CommandMessage *reply, + object_id_t objectId) { + ModePacket wrongModeReply(objectId, ModeMessage::getMode(reply), ModeMessage::getSubmode(reply)); + ReturnValue_t result = sendTmPacket(Subservice::REPLY_WRONG_MODE_REPLY, &wrongModeReply); + if (result == RETURN_OK) { + // We want to produce an error here in any case because the mode was not correct + return RETURN_FAILED; + } + return result; } -ReturnValue_t CService200ModeCommanding::prepareModeReply( - const CommandMessage *reply, object_id_t objectId) { - ModePacket modeReplyPacket(objectId, - ModeMessage::getMode(reply), - ModeMessage::getSubmode(reply)); - return sendTmPacket(Subservice::REPLY_MODE_REPLY, &modeReplyPacket); -} - -ReturnValue_t CService200ModeCommanding::prepareWrongModeReply( - const CommandMessage *reply, object_id_t objectId) { - ModePacket wrongModeReply(objectId, ModeMessage::getMode(reply), - ModeMessage::getSubmode(reply)); - ReturnValue_t result = sendTmPacket(Subservice::REPLY_WRONG_MODE_REPLY, &wrongModeReply); - if(result == RETURN_OK){ - // We want to produce an error here in any case because the mode was not correct - return RETURN_FAILED; - } - return result; -} - -ReturnValue_t CService200ModeCommanding::prepareCantReachModeReply( - const CommandMessage *reply, object_id_t objectId) { - CantReachModePacket cantReachModePacket(objectId, - ModeMessage::getCantReachModeReason(reply)); - ReturnValue_t result = sendTmPacket(Subservice::REPLY_CANT_REACH_MODE, - &cantReachModePacket); - if(result == RETURN_OK){ - // We want to produce an error here in any case because the mode was not reached - return RETURN_FAILED; - } - return result; +ReturnValue_t CService200ModeCommanding::prepareCantReachModeReply(const CommandMessage *reply, + object_id_t objectId) { + CantReachModePacket cantReachModePacket(objectId, ModeMessage::getCantReachModeReason(reply)); + ReturnValue_t result = sendTmPacket(Subservice::REPLY_CANT_REACH_MODE, &cantReachModePacket); + if (result == RETURN_OK) { + // We want to produce an error here in any case because the mode was not reached + return RETURN_FAILED; + } + return result; } diff --git a/src/fsfw/pus/CService200ModeCommanding.h b/src/fsfw/pus/CService200ModeCommanding.h index d523d6c3..830e5950 100644 --- a/src/fsfw/pus/CService200ModeCommanding.h +++ b/src/fsfw/pus/CService200ModeCommanding.h @@ -13,72 +13,60 @@ * This is a gateway service. It relays device commands using the software bus. * @ingroup pus_services */ -class CService200ModeCommanding: public CommandingServiceBase { -public: +class CService200ModeCommanding : public CommandingServiceBase { + public: + CService200ModeCommanding(object_id_t objectId, uint16_t apid, uint8_t serviceId, + uint8_t numParallelCommands = 4, uint16_t commandTimeoutSeconds = 60); + virtual ~CService200ModeCommanding(); - CService200ModeCommanding(object_id_t objectId, - uint16_t apid, uint8_t serviceId, uint8_t numParallelCommands = 4, - uint16_t commandTimeoutSeconds = 60); - virtual~ CService200ModeCommanding(); + protected: + //! CommandingServiceBase (CSB) abstract functions. See CSB documentation. + ReturnValue_t isValidSubservice(uint8_t subservice) override; + ReturnValue_t getMessageQueueAndObject(uint8_t subservice, const uint8_t *tcData, + size_t tcDataLen, MessageQueueId_t *id, + object_id_t *objectId) override; + ReturnValue_t prepareCommand(CommandMessage *message, uint8_t subservice, const uint8_t *tcData, + size_t tcDataLen, uint32_t *state, object_id_t objectId) override; + ReturnValue_t handleReply(const CommandMessage *reply, Command_t previousCommand, uint32_t *state, + CommandMessage *optionalNextCommand, object_id_t objectId, + bool *isStep) override; -protected: - //! CommandingServiceBase (CSB) abstract functions. See CSB documentation. - ReturnValue_t isValidSubservice(uint8_t subservice) override; - ReturnValue_t getMessageQueueAndObject(uint8_t subservice, - const uint8_t *tcData, size_t tcDataLen, MessageQueueId_t *id, - object_id_t *objectId) override; - ReturnValue_t prepareCommand(CommandMessage* message, - uint8_t subservice, const uint8_t *tcData, size_t tcDataLen, - uint32_t *state, object_id_t objectId) override; - ReturnValue_t handleReply(const CommandMessage* reply, - Command_t previousCommand, uint32_t *state, - CommandMessage* optionalNextCommand, object_id_t objectId, - bool *isStep) override; + private: + ReturnValue_t checkAndAcquireTargetID(object_id_t *objectIdToSet, const uint8_t *tcData, + uint32_t tcDataLen); + ReturnValue_t checkInterfaceAndAcquireMessageQueue(MessageQueueId_t *MessageQueueToSet, + object_id_t *objectId); -private: - ReturnValue_t checkAndAcquireTargetID(object_id_t* objectIdToSet, - const uint8_t* tcData, uint32_t tcDataLen); - ReturnValue_t checkInterfaceAndAcquireMessageQueue( - MessageQueueId_t* MessageQueueToSet, object_id_t* objectId); + ReturnValue_t prepareModeReply(const CommandMessage *reply, object_id_t objectId); + ReturnValue_t prepareWrongModeReply(const CommandMessage *reply, object_id_t objectId); + ReturnValue_t prepareCantReachModeReply(const CommandMessage *reply, object_id_t objectId); - ReturnValue_t prepareModeReply(const CommandMessage *reply, - object_id_t objectId); - ReturnValue_t prepareWrongModeReply(const CommandMessage *reply, - object_id_t objectId); - ReturnValue_t prepareCantReachModeReply(const CommandMessage *reply, - object_id_t objectId); + enum Subservice { //!< [EXPORT] : [COMMENT] Mode Commanding Subservices + //!< [EXPORT] : [COMMAND] Command assembly, subsystem or device mode + COMMAND_MODE_COMMAND = 1, + //!< [EXPORT] : [COMMAND] Command to set the specified Mode, + //! regardless of external control flag + COMMAND_MODE_COMMAND_FORCED = 2, + //!< [EXPORT] : [COMMAND] Read the current mode and + //! reply with a REPLY_MODE_REPLY + COMMAND_MODE_READ = 3, + //!< [EXPORT] : [COMMAND] Trigger an ModeInfo Event. + //! This command does NOT have a reply + COMMAND_MODE_ANNCOUNCE = 4, + //!< [EXPORT] : [COMMAND] Trigger a ModeInfo Event and to send this + //! command to every child. This command does NOT have a reply. + COMMAND_MODE_ANNOUNCE_RECURSIVELY = 5, + //!< [EXPORT] : [REPLY] Reply to a CMD_MODE_COMMAND or CMD_MODE_READ + REPLY_MODE_REPLY = 6, + //!< [EXPORT] : [REPLY] Reply in case a mode command can't be executed. + REPLY_CANT_REACH_MODE = 7, + //!< [EXPORT] : [REPLY] Reply to a CMD_MODE_COMMAND, indicating that a + //! mode was commanded and a transition started but was aborted, + //! the parameters contain the mode that was reached + REPLY_WRONG_MODE_REPLY = 8 + }; - enum Subservice { //!< [EXPORT] : [COMMENT] Mode Commanding Subservices - //!< [EXPORT] : [COMMAND] Command assembly, subsystem or device mode - COMMAND_MODE_COMMAND = 1, - //!< [EXPORT] : [COMMAND] Command to set the specified Mode, - //! regardless of external control flag - COMMAND_MODE_COMMAND_FORCED = 2, - //!< [EXPORT] : [COMMAND] Read the current mode and - //! reply with a REPLY_MODE_REPLY - COMMAND_MODE_READ = 3, - //!< [EXPORT] : [COMMAND] Trigger an ModeInfo Event. - //! This command does NOT have a reply - COMMAND_MODE_ANNCOUNCE = 4, - //!< [EXPORT] : [COMMAND] Trigger a ModeInfo Event and to send this - //! command to every child. This command does NOT have a reply. - COMMAND_MODE_ANNOUNCE_RECURSIVELY = 5, - //!< [EXPORT] : [REPLY] Reply to a CMD_MODE_COMMAND or CMD_MODE_READ - REPLY_MODE_REPLY = 6, - //!< [EXPORT] : [REPLY] Reply in case a mode command can't be executed. - REPLY_CANT_REACH_MODE = 7, - //!< [EXPORT] : [REPLY] Reply to a CMD_MODE_COMMAND, indicating that a - //! mode was commanded and a transition started but was aborted, - //! the parameters contain the mode that was reached - REPLY_WRONG_MODE_REPLY = 8 - }; - - enum modeParameters { - MODE_OFF = 0, - MODE_ON = 1, - MODE_NORMAL = 2, - MODE_RAW = 3 - }; + enum modeParameters { MODE_OFF = 0, MODE_ON = 1, MODE_NORMAL = 2, MODE_RAW = 3 }; }; #endif /* FSFW_PUS_CSERVICE200MODECOMMANDING_H_ */ diff --git a/src/fsfw/pus/CService201HealthCommanding.cpp b/src/fsfw/pus/CService201HealthCommanding.cpp index 1e414c82..4d9806f9 100644 --- a/src/fsfw/pus/CService201HealthCommanding.cpp +++ b/src/fsfw/pus/CService201HealthCommanding.cpp @@ -1,110 +1,104 @@ #include "fsfw/pus/CService201HealthCommanding.h" -#include "fsfw/pus/servicepackets/Service201Packets.h" #include "fsfw/health/HasHealthIF.h" -#include "fsfw/serviceinterface/ServiceInterface.h" -#include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/health/HealthMessage.h" +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/pus/servicepackets/Service201Packets.h" +#include "fsfw/serviceinterface/ServiceInterface.h" - -CService201HealthCommanding::CService201HealthCommanding(object_id_t objectId, - uint16_t apid, uint8_t serviceId, uint8_t numParallelCommands, - uint16_t commandTimeoutSeconds): - CommandingServiceBase(objectId, apid, serviceId, - numParallelCommands, commandTimeoutSeconds) { +CService201HealthCommanding::CService201HealthCommanding(object_id_t objectId, uint16_t apid, + uint8_t serviceId, + uint8_t numParallelCommands, + uint16_t commandTimeoutSeconds) + : CommandingServiceBase(objectId, apid, serviceId, numParallelCommands, commandTimeoutSeconds) { } -CService201HealthCommanding::~CService201HealthCommanding() { -} +CService201HealthCommanding::~CService201HealthCommanding() {} ReturnValue_t CService201HealthCommanding::isValidSubservice(uint8_t subservice) { - switch(subservice) { - case(Subservice::COMMAND_SET_HEALTH): - case(Subservice::COMMAND_ANNOUNCE_HEALTH): - case(Subservice::COMMAND_ANNOUNCE_HEALTH_ALL): - return RETURN_OK; - default: + switch (subservice) { + case (Subservice::COMMAND_SET_HEALTH): + case (Subservice::COMMAND_ANNOUNCE_HEALTH): + case (Subservice::COMMAND_ANNOUNCE_HEALTH_ALL): + return RETURN_OK; + default: #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Invalid Subservice" << std::endl; + sif::error << "Invalid Subservice" << std::endl; #endif - return AcceptsTelecommandsIF::INVALID_SUBSERVICE; - } + return AcceptsTelecommandsIF::INVALID_SUBSERVICE; + } } -ReturnValue_t CService201HealthCommanding::getMessageQueueAndObject( - uint8_t subservice, const uint8_t *tcData, size_t tcDataLen, - MessageQueueId_t *id, object_id_t *objectId) { - if(tcDataLen < sizeof(object_id_t)) { - return CommandingServiceBase::INVALID_TC; - } - SerializeAdapter::deSerialize(objectId, &tcData, &tcDataLen, - SerializeIF::Endianness::BIG); +ReturnValue_t CService201HealthCommanding::getMessageQueueAndObject(uint8_t subservice, + const uint8_t *tcData, + size_t tcDataLen, + MessageQueueId_t *id, + object_id_t *objectId) { + if (tcDataLen < sizeof(object_id_t)) { + return CommandingServiceBase::INVALID_TC; + } + SerializeAdapter::deSerialize(objectId, &tcData, &tcDataLen, SerializeIF::Endianness::BIG); - return checkInterfaceAndAcquireMessageQueue(id,objectId); + return checkInterfaceAndAcquireMessageQueue(id, objectId); } ReturnValue_t CService201HealthCommanding::checkInterfaceAndAcquireMessageQueue( - MessageQueueId_t* messageQueueToSet, object_id_t* objectId) { - HasHealthIF * destination = ObjectManager::instance()->get(*objectId); - if(destination == nullptr) { - return CommandingServiceBase::INVALID_OBJECT; - } + MessageQueueId_t *messageQueueToSet, object_id_t *objectId) { + HasHealthIF *destination = ObjectManager::instance()->get(*objectId); + if (destination == nullptr) { + return CommandingServiceBase::INVALID_OBJECT; + } - *messageQueueToSet = destination->getCommandQueue(); - return HasReturnvaluesIF::RETURN_OK; + *messageQueueToSet = destination->getCommandQueue(); + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t CService201HealthCommanding::prepareCommand( - CommandMessage* message, uint8_t subservice, const uint8_t *tcData, - size_t tcDataLen, uint32_t *state, object_id_t objectId) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - switch(subservice) { - case(Subservice::COMMAND_SET_HEALTH): { - HealthSetCommand healthCommand; - result = healthCommand.deSerialize(&tcData, &tcDataLen, - SerializeIF::Endianness::BIG); - if (result != RETURN_OK) { - break; - } - HealthMessage::setHealthMessage(message, HealthMessage::HEALTH_SET, - healthCommand.getHealth()); +ReturnValue_t CService201HealthCommanding::prepareCommand(CommandMessage *message, + uint8_t subservice, const uint8_t *tcData, + size_t tcDataLen, uint32_t *state, + object_id_t objectId) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + switch (subservice) { + case (Subservice::COMMAND_SET_HEALTH): { + HealthSetCommand healthCommand; + result = healthCommand.deSerialize(&tcData, &tcDataLen, SerializeIF::Endianness::BIG); + if (result != RETURN_OK) { break; + } + HealthMessage::setHealthMessage(message, HealthMessage::HEALTH_SET, + healthCommand.getHealth()); + break; } - case(Subservice::COMMAND_ANNOUNCE_HEALTH): { - HealthMessage::setHealthMessage(message, - HealthMessage::HEALTH_ANNOUNCE); - break; + case (Subservice::COMMAND_ANNOUNCE_HEALTH): { + HealthMessage::setHealthMessage(message, HealthMessage::HEALTH_ANNOUNCE); + break; } - case(Subservice::COMMAND_ANNOUNCE_HEALTH_ALL): { - HealthMessage::setHealthMessage(message, - HealthMessage::HEALTH_ANNOUNCE_ALL); - break; + case (Subservice::COMMAND_ANNOUNCE_HEALTH_ALL): { + HealthMessage::setHealthMessage(message, HealthMessage::HEALTH_ANNOUNCE_ALL); + break; } - } - return result; + } + return result; } -ReturnValue_t CService201HealthCommanding::handleReply - (const CommandMessage* reply, Command_t previousCommand, - uint32_t *state, CommandMessage* optionalNextCommand, - object_id_t objectId, bool *isStep) { - Command_t replyId = reply->getCommand(); - if (replyId == HealthMessage::REPLY_HEALTH_SET) { - return EXECUTION_COMPLETE; - } - else if(replyId == CommandMessageIF::REPLY_REJECTED) { - return reply->getReplyRejectedReason(); - } - return CommandingServiceBase::INVALID_REPLY; +ReturnValue_t CService201HealthCommanding::handleReply(const CommandMessage *reply, + Command_t previousCommand, uint32_t *state, + CommandMessage *optionalNextCommand, + object_id_t objectId, bool *isStep) { + Command_t replyId = reply->getCommand(); + if (replyId == HealthMessage::REPLY_HEALTH_SET) { + return EXECUTION_COMPLETE; + } else if (replyId == CommandMessageIF::REPLY_REJECTED) { + return reply->getReplyRejectedReason(); + } + return CommandingServiceBase::INVALID_REPLY; } // Not used for now, health state already reported by event -ReturnValue_t CService201HealthCommanding::prepareHealthSetReply( - const CommandMessage* reply) { - prepareHealthSetReply(reply); - uint8_t health = static_cast(HealthMessage::getHealth(reply)); - uint8_t oldHealth = static_cast(HealthMessage::getOldHealth(reply)); - HealthSetReply healthSetReply(health, oldHealth); - return sendTmPacket(Subservice::REPLY_HEALTH_SET, &healthSetReply); +ReturnValue_t CService201HealthCommanding::prepareHealthSetReply(const CommandMessage *reply) { + prepareHealthSetReply(reply); + uint8_t health = static_cast(HealthMessage::getHealth(reply)); + uint8_t oldHealth = static_cast(HealthMessage::getOldHealth(reply)); + HealthSetReply healthSetReply(health, oldHealth); + return sendTmPacket(Subservice::REPLY_HEALTH_SET, &healthSetReply); } - diff --git a/src/fsfw/pus/CService201HealthCommanding.h b/src/fsfw/pus/CService201HealthCommanding.h index 124e2ac7..5e52ab39 100644 --- a/src/fsfw/pus/CService201HealthCommanding.h +++ b/src/fsfw/pus/CService201HealthCommanding.h @@ -17,47 +17,44 @@ * child class like this service * */ -class CService201HealthCommanding: public CommandingServiceBase { -public: +class CService201HealthCommanding : public CommandingServiceBase { + public: + CService201HealthCommanding(object_id_t objectId, uint16_t apid, uint8_t serviceId, + uint8_t numParallelCommands = 4, uint16_t commandTimeoutSeconds = 60); + virtual ~CService201HealthCommanding(); - CService201HealthCommanding(object_id_t objectId, uint16_t apid, - uint8_t serviceId, uint8_t numParallelCommands = 4, - uint16_t commandTimeoutSeconds = 60); - virtual~ CService201HealthCommanding(); -protected: - /* CSB abstract function implementations */ - ReturnValue_t isValidSubservice(uint8_t subservice) override; - ReturnValue_t getMessageQueueAndObject(uint8_t subservice, - const uint8_t *tcData, size_t tcDataLen, MessageQueueId_t *id, - object_id_t *objectId) override; - /** Prepare health command */ - ReturnValue_t prepareCommand(CommandMessage* message, - uint8_t subservice, const uint8_t *tcData, size_t tcDataLen, - uint32_t *state, object_id_t objectId) override; - /** Handle health reply */ - ReturnValue_t handleReply(const CommandMessage* reply, - Command_t previousCommand, uint32_t *state, - CommandMessage* optionalNextCommand, object_id_t objectId, - bool *isStep) override; + protected: + /* CSB abstract function implementations */ + ReturnValue_t isValidSubservice(uint8_t subservice) override; + ReturnValue_t getMessageQueueAndObject(uint8_t subservice, const uint8_t *tcData, + size_t tcDataLen, MessageQueueId_t *id, + object_id_t *objectId) override; + /** Prepare health command */ + ReturnValue_t prepareCommand(CommandMessage *message, uint8_t subservice, const uint8_t *tcData, + size_t tcDataLen, uint32_t *state, object_id_t objectId) override; + /** Handle health reply */ + ReturnValue_t handleReply(const CommandMessage *reply, Command_t previousCommand, uint32_t *state, + CommandMessage *optionalNextCommand, object_id_t objectId, + bool *isStep) override; -private: - ReturnValue_t checkAndAcquireTargetID(object_id_t* objectIdToSet, - const uint8_t* tcData, size_t tcDataLen); - ReturnValue_t checkInterfaceAndAcquireMessageQueue( - MessageQueueId_t* MessageQueueToSet, object_id_t* objectId); + private: + ReturnValue_t checkAndAcquireTargetID(object_id_t *objectIdToSet, const uint8_t *tcData, + size_t tcDataLen); + ReturnValue_t checkInterfaceAndAcquireMessageQueue(MessageQueueId_t *MessageQueueToSet, + object_id_t *objectId); - ReturnValue_t prepareHealthSetReply(const CommandMessage *reply); + ReturnValue_t prepareHealthSetReply(const CommandMessage *reply); - enum Subservice { - //! [EXPORT] : [TC] Set health of target object - COMMAND_SET_HEALTH = 1, - //! [EXPORT] : [TM] Reply to health set command which also provides old health - REPLY_HEALTH_SET = 2, - //! [EXPORT] : [TC] Commands object to announce their health as an event - COMMAND_ANNOUNCE_HEALTH = 3, - //! [EXPORT] : [TC] Commands all objects in the health map to announce their health - COMMAND_ANNOUNCE_HEALTH_ALL = 4 - }; + enum Subservice { + //! [EXPORT] : [TC] Set health of target object + COMMAND_SET_HEALTH = 1, + //! [EXPORT] : [TM] Reply to health set command which also provides old health + REPLY_HEALTH_SET = 2, + //! [EXPORT] : [TC] Commands object to announce their health as an event + COMMAND_ANNOUNCE_HEALTH = 3, + //! [EXPORT] : [TC] Commands all objects in the health map to announce their health + COMMAND_ANNOUNCE_HEALTH_ALL = 4 + }; }; #endif /* FSFW_PUS_CSERVICE201HEALTHCOMMANDING_H_ */ diff --git a/src/fsfw/pus/Service17Test.cpp b/src/fsfw/pus/Service17Test.cpp index 20227172..f784acf4 100644 --- a/src/fsfw/pus/Service17Test.cpp +++ b/src/fsfw/pus/Service17Test.cpp @@ -1,52 +1,43 @@ -#include "fsfw/FSFW.h" #include "fsfw/pus/Service17Test.h" -#include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/FSFW.h" #include "fsfw/objectmanager/SystemObject.h" +#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/tmtcpacket/pus/tm/TmPacketStored.h" +Service17Test::Service17Test(object_id_t objectId, uint16_t apid, uint8_t serviceId) + : PusServiceBase(objectId, apid, serviceId), packetSubCounter(0) {} -Service17Test::Service17Test(object_id_t objectId, - uint16_t apid, uint8_t serviceId): - PusServiceBase(objectId, apid, serviceId), - packetSubCounter(0) { -} - -Service17Test::~Service17Test() { -} +Service17Test::~Service17Test() {} ReturnValue_t Service17Test::handleRequest(uint8_t subservice) { - switch(subservice) { - case Subservice::CONNECTION_TEST: { + switch (subservice) { + case Subservice::CONNECTION_TEST: { #if FSFW_USE_PUS_C_TELEMETRY == 0 - TmPacketStoredPusA connectionPacket(apid, serviceId, - Subservice::CONNECTION_TEST_REPORT, packetSubCounter++); + TmPacketStoredPusA connectionPacket(apid, serviceId, Subservice::CONNECTION_TEST_REPORT, + packetSubCounter++); #else - TmPacketStoredPusC connectionPacket(apid, serviceId, - Subservice::CONNECTION_TEST_REPORT, packetSubCounter++); + TmPacketStoredPusC connectionPacket(apid, serviceId, Subservice::CONNECTION_TEST_REPORT, + packetSubCounter++); #endif - connectionPacket.sendPacket(requestQueue->getDefaultDestination(), - requestQueue->getId()); - return HasReturnvaluesIF::RETURN_OK; - } + connectionPacket.sendPacket(requestQueue->getDefaultDestination(), requestQueue->getId()); + return HasReturnvaluesIF::RETURN_OK; + } case Subservice::EVENT_TRIGGER_TEST: { #if FSFW_USE_PUS_C_TELEMETRY == 0 - TmPacketStoredPusA connectionPacket(apid, serviceId, - Subservice::CONNECTION_TEST_REPORT, packetSubCounter++); + TmPacketStoredPusA connectionPacket(apid, serviceId, Subservice::CONNECTION_TEST_REPORT, + packetSubCounter++); #else - TmPacketStoredPusC connectionPacket(apid, serviceId, - Subservice::CONNECTION_TEST_REPORT, packetSubCounter++); + TmPacketStoredPusC connectionPacket(apid, serviceId, Subservice::CONNECTION_TEST_REPORT, + packetSubCounter++); #endif - connectionPacket.sendPacket(requestQueue->getDefaultDestination(), - requestQueue->getId()); - triggerEvent(TEST, 1234, 5678); - return RETURN_OK; + connectionPacket.sendPacket(requestQueue->getDefaultDestination(), requestQueue->getId()); + triggerEvent(TEST, 1234, 5678); + return RETURN_OK; } - default: - return AcceptsTelecommandsIF::INVALID_SUBSERVICE; - } + default: + return AcceptsTelecommandsIF::INVALID_SUBSERVICE; + } } -ReturnValue_t Service17Test::performService() { - return HasReturnvaluesIF::RETURN_OK; -} +ReturnValue_t Service17Test::performService() { return HasReturnvaluesIF::RETURN_OK; } diff --git a/src/fsfw/pus/Service17Test.h b/src/fsfw/pus/Service17Test.h index d1e1ecce..c2248020 100644 --- a/src/fsfw/pus/Service17Test.h +++ b/src/fsfw/pus/Service17Test.h @@ -1,8 +1,8 @@ #ifndef FSFW_PUS_SERVICE17TEST_H_ #define FSFW_PUS_SERVICE17TEST_H_ -#include "fsfw/tmtcservices/PusServiceBase.h" #include "fsfw/objectmanager/SystemObject.h" +#include "fsfw/tmtcservices/PusServiceBase.h" /** * @brief Test Service @@ -17,28 +17,28 @@ * * @ingroup pus_services */ -class Service17Test: public PusServiceBase { -public: - // Custom events which can be triggered - static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PUS_SERVICE_17; - static constexpr Event TEST = MAKE_EVENT(0, severity::INFO); +class Service17Test : public PusServiceBase { + public: + // Custom events which can be triggered + static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PUS_SERVICE_17; + static constexpr Event TEST = MAKE_EVENT(0, severity::INFO); - enum Subservice: uint8_t { - //! [EXPORT] : [COMMAND] Perform connection test - CONNECTION_TEST = 1, - //! [EXPORT] : [REPLY] Connection test reply - CONNECTION_TEST_REPORT = 2, - //! [EXPORT] : [COMMAND] Trigger test reply and test event - EVENT_TRIGGER_TEST = 128, - }; + enum Subservice : uint8_t { + //! [EXPORT] : [COMMAND] Perform connection test + CONNECTION_TEST = 1, + //! [EXPORT] : [REPLY] Connection test reply + CONNECTION_TEST_REPORT = 2, + //! [EXPORT] : [COMMAND] Trigger test reply and test event + EVENT_TRIGGER_TEST = 128, + }; - Service17Test(object_id_t objectId, uint16_t apid, uint8_t serviceId); - virtual ~Service17Test(); - virtual ReturnValue_t handleRequest(uint8_t subservice) override; - virtual ReturnValue_t performService() override; + Service17Test(object_id_t objectId, uint16_t apid, uint8_t serviceId); + virtual ~Service17Test(); + virtual ReturnValue_t handleRequest(uint8_t subservice) override; + virtual ReturnValue_t performService() override; -protected: - uint16_t packetSubCounter = 0; + protected: + uint16_t packetSubCounter = 0; }; #endif /* FSFW_PUS_SERVICE17TEST_H_ */ diff --git a/src/fsfw/pus/Service1TelecommandVerification.cpp b/src/fsfw/pus/Service1TelecommandVerification.cpp index c6b024f9..13d6a1c4 100644 --- a/src/fsfw/pus/Service1TelecommandVerification.cpp +++ b/src/fsfw/pus/Service1TelecommandVerification.cpp @@ -1,115 +1,107 @@ #include "fsfw/pus/Service1TelecommandVerification.h" -#include "fsfw/pus/servicepackets/Service1Packets.h" #include "fsfw/ipc/QueueFactory.h" #include "fsfw/objectmanager/ObjectManager.h" -#include "fsfw/tmtcservices/PusVerificationReport.h" -#include "fsfw/tmtcpacket/pus/tm/TmPacketStored.h" +#include "fsfw/pus/servicepackets/Service1Packets.h" #include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/tmtcpacket/pus/tm/TmPacketStored.h" #include "fsfw/tmtcservices/AcceptsTelemetryIF.h" +#include "fsfw/tmtcservices/PusVerificationReport.h" -Service1TelecommandVerification::Service1TelecommandVerification( - object_id_t objectId, uint16_t apid, uint8_t serviceId, - object_id_t targetDestination, uint16_t messageQueueDepth): - SystemObject(objectId), apid(apid), serviceId(serviceId), - targetDestination(targetDestination) { - tmQueue = QueueFactory::instance()->createMessageQueue(messageQueueDepth); +Service1TelecommandVerification::Service1TelecommandVerification(object_id_t objectId, + uint16_t apid, uint8_t serviceId, + object_id_t targetDestination, + uint16_t messageQueueDepth) + : SystemObject(objectId), + apid(apid), + serviceId(serviceId), + targetDestination(targetDestination) { + tmQueue = QueueFactory::instance()->createMessageQueue(messageQueueDepth); } Service1TelecommandVerification::~Service1TelecommandVerification() { - QueueFactory::instance()->deleteMessageQueue(tmQueue); + QueueFactory::instance()->deleteMessageQueue(tmQueue); } -MessageQueueId_t Service1TelecommandVerification::getVerificationQueue(){ - return tmQueue->getId(); +MessageQueueId_t Service1TelecommandVerification::getVerificationQueue() { + return tmQueue->getId(); } - -ReturnValue_t Service1TelecommandVerification::performOperation( - uint8_t operationCode){ - PusVerificationMessage message; - ReturnValue_t status = tmQueue->receiveMessage(&message); - while(status == HasReturnvaluesIF::RETURN_OK) { - status = sendVerificationReport(&message); - if(status != HasReturnvaluesIF::RETURN_OK) { - return status; - } - status = tmQueue->receiveMessage(&message); - } - if (status == MessageQueueIF::EMPTY) { - return HasReturnvaluesIF::RETURN_OK; - } - else { - return status; - } +ReturnValue_t Service1TelecommandVerification::performOperation(uint8_t operationCode) { + PusVerificationMessage message; + ReturnValue_t status = tmQueue->receiveMessage(&message); + while (status == HasReturnvaluesIF::RETURN_OK) { + status = sendVerificationReport(&message); + if (status != HasReturnvaluesIF::RETURN_OK) { + return status; + } + status = tmQueue->receiveMessage(&message); + } + if (status == MessageQueueIF::EMPTY) { + return HasReturnvaluesIF::RETURN_OK; + } else { + return status; + } } - ReturnValue_t Service1TelecommandVerification::sendVerificationReport( - PusVerificationMessage* message) { - ReturnValue_t result; - if(message->getReportId() % 2 == 0) { - result = generateFailureReport(message); - } else { - result = generateSuccessReport(message); - } - if(result != HasReturnvaluesIF::RETURN_OK){ + PusVerificationMessage* message) { + ReturnValue_t result; + if (message->getReportId() % 2 == 0) { + result = generateFailureReport(message); + } else { + result = generateSuccessReport(message); + } + if (result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Service1TelecommandVerification::sendVerificationReport: " - "Sending verification packet failed !" << std::endl; + sif::error << "Service1TelecommandVerification::sendVerificationReport: " + "Sending verification packet failed !" + << std::endl; #endif - } - return result; + } + return result; } ReturnValue_t Service1TelecommandVerification::generateFailureReport( - PusVerificationMessage *message) { - FailureReport report( - message->getReportId(), message->getTcPacketId(), - message->getTcSequenceControl(), message->getStep(), - message->getErrorCode(), message->getParameter1(), - message->getParameter2()); + PusVerificationMessage* message) { + FailureReport report(message->getReportId(), message->getTcPacketId(), + message->getTcSequenceControl(), message->getStep(), message->getErrorCode(), + message->getParameter1(), message->getParameter2()); #if FSFW_USE_PUS_C_TELEMETRY == 0 - TmPacketStoredPusA tmPacket(apid, serviceId, message->getReportId(), - packetSubCounter++, &report); + TmPacketStoredPusA tmPacket(apid, serviceId, message->getReportId(), packetSubCounter++, &report); #else - TmPacketStoredPusC tmPacket(apid, serviceId, message->getReportId(), - packetSubCounter++, &report); + TmPacketStoredPusC tmPacket(apid, serviceId, message->getReportId(), packetSubCounter++, &report); #endif - ReturnValue_t result = tmPacket.sendPacket(tmQueue->getDefaultDestination(), - tmQueue->getId()); - return result; + ReturnValue_t result = tmPacket.sendPacket(tmQueue->getDefaultDestination(), tmQueue->getId()); + return result; } ReturnValue_t Service1TelecommandVerification::generateSuccessReport( - PusVerificationMessage *message) { - SuccessReport report(message->getReportId(),message->getTcPacketId(), - message->getTcSequenceControl(),message->getStep()); + PusVerificationMessage* message) { + SuccessReport report(message->getReportId(), message->getTcPacketId(), + message->getTcSequenceControl(), message->getStep()); #if FSFW_USE_PUS_C_TELEMETRY == 0 - TmPacketStoredPusA tmPacket(apid, serviceId, message->getReportId(), - packetSubCounter++, &report); + TmPacketStoredPusA tmPacket(apid, serviceId, message->getReportId(), packetSubCounter++, &report); #else - TmPacketStoredPusC tmPacket(apid, serviceId, message->getReportId(), - packetSubCounter++, &report); + TmPacketStoredPusC tmPacket(apid, serviceId, message->getReportId(), packetSubCounter++, &report); #endif - ReturnValue_t result = tmPacket.sendPacket(tmQueue->getDefaultDestination(), - tmQueue->getId()); - return result; + ReturnValue_t result = tmPacket.sendPacket(tmQueue->getDefaultDestination(), tmQueue->getId()); + return result; } - ReturnValue_t Service1TelecommandVerification::initialize() { - // Get target object for TC verification messages - AcceptsTelemetryIF* funnel = ObjectManager::instance()-> - get(targetDestination); - if(funnel == nullptr){ + // Get target object for TC verification messages + AcceptsTelemetryIF* funnel = + ObjectManager::instance()->get(targetDestination); + if (funnel == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Service1TelecommandVerification::initialize: Specified" - " TM funnel invalid. Make sure it is set up and implements" - " AcceptsTelemetryIF." << std::endl; + sif::error << "Service1TelecommandVerification::initialize: Specified" + " TM funnel invalid. Make sure it is set up and implements" + " AcceptsTelemetryIF." + << std::endl; #endif - return ObjectManagerIF::CHILD_INIT_FAILED; - } - tmQueue->setDefaultDestination(funnel->getReportReceptionQueue()); - return SystemObject::initialize(); + return ObjectManagerIF::CHILD_INIT_FAILED; + } + tmQueue->setDefaultDestination(funnel->getReportReceptionQueue()); + return SystemObject::initialize(); } diff --git a/src/fsfw/pus/Service1TelecommandVerification.h b/src/fsfw/pus/Service1TelecommandVerification.h index 26284493..10d2da0e 100644 --- a/src/fsfw/pus/Service1TelecommandVerification.h +++ b/src/fsfw/pus/Service1TelecommandVerification.h @@ -1,12 +1,12 @@ #ifndef FSFW_PUS_SERVICE1TELECOMMANDVERIFICATION_H_ #define FSFW_PUS_SERVICE1TELECOMMANDVERIFICATION_H_ +#include "fsfw/ipc/MessageQueueIF.h" #include "fsfw/objectmanager/SystemObject.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" #include "fsfw/tasks/ExecutableObjectIF.h" #include "fsfw/tmtcservices/AcceptsVerifyMessageIF.h" #include "fsfw/tmtcservices/PusVerificationReport.h" -#include "fsfw/ipc/MessageQueueIF.h" /** * @brief Verify TC acceptance, start, progress and execution. @@ -36,60 +36,60 @@ * generate verification reports. * @ingroup pus_services */ -class Service1TelecommandVerification: public AcceptsVerifyMessageIF, - public SystemObject, - public ExecutableObjectIF, - public HasReturnvaluesIF { -public: - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PUS_SERVICE_1; +class Service1TelecommandVerification : public AcceptsVerifyMessageIF, + public SystemObject, + public ExecutableObjectIF, + public HasReturnvaluesIF { + public: + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PUS_SERVICE_1; - Service1TelecommandVerification(object_id_t objectId, - uint16_t apid, uint8_t serviceId, object_id_t targetDestination, - uint16_t messageQueueDepth); - virtual ~Service1TelecommandVerification(); + Service1TelecommandVerification(object_id_t objectId, uint16_t apid, uint8_t serviceId, + object_id_t targetDestination, uint16_t messageQueueDepth); + virtual ~Service1TelecommandVerification(); - /** - * - * @return ID of Verification Queue - */ - virtual MessageQueueId_t getVerificationQueue() override; + /** + * + * @return ID of Verification Queue + */ + virtual MessageQueueId_t getVerificationQueue() override; - /** - * Performs the service periodically as specified in init_mission(). - * Triggers the handlePacket function to send TC verification messages - * @param operationCode - * @return - */ - ReturnValue_t performOperation(uint8_t operationCode = 0) override; + /** + * Performs the service periodically as specified in init_mission(). + * Triggers the handlePacket function to send TC verification messages + * @param operationCode + * @return + */ + ReturnValue_t performOperation(uint8_t operationCode = 0) override; - /** - * Initializes the destination for TC verification messages and initializes - * Service 1 as a system object - * @return - */ - ReturnValue_t initialize() override; -private: - uint16_t apid = 0; - uint8_t serviceId = 0; + /** + * Initializes the destination for TC verification messages and initializes + * Service 1 as a system object + * @return + */ + ReturnValue_t initialize() override; - object_id_t targetDestination = objects::NO_OBJECT; + private: + uint16_t apid = 0; + uint8_t serviceId = 0; - ReturnValue_t sendVerificationReport(PusVerificationMessage* message); - ReturnValue_t generateFailureReport(PusVerificationMessage* message); - ReturnValue_t generateSuccessReport(PusVerificationMessage* message); + object_id_t targetDestination = objects::NO_OBJECT; - uint16_t packetSubCounter = 0; + ReturnValue_t sendVerificationReport(PusVerificationMessage* message); + ReturnValue_t generateFailureReport(PusVerificationMessage* message); + ReturnValue_t generateSuccessReport(PusVerificationMessage* message); - MessageQueueIF* tmQueue = nullptr; + uint16_t packetSubCounter = 0; - enum class Subservice: uint8_t { - VERIFY_ACCEPTANCE_SUCCESS = 1, //!< [EXPORT] : [TM] - VERIFY_ACCEPTANCE_FAILED = 2, //!< [EXPORT] : [TM] - VERIFY_START_SUCCESS = 3, //!< [EXPORT] : [TM] - VERIFY_START_FAILED = 4, //!< [EXPORT] : [TM] - VERIFY_STEP_SUCCESS = 5, //!< [EXPORT] : [TM] - VERIFY_STEP_FAILED = 6 //!< [EXPORT] : [TM] - }; + MessageQueueIF* tmQueue = nullptr; + + enum class Subservice : uint8_t { + VERIFY_ACCEPTANCE_SUCCESS = 1, //!< [EXPORT] : [TM] + VERIFY_ACCEPTANCE_FAILED = 2, //!< [EXPORT] : [TM] + VERIFY_START_SUCCESS = 3, //!< [EXPORT] : [TM] + VERIFY_START_FAILED = 4, //!< [EXPORT] : [TM] + VERIFY_STEP_SUCCESS = 5, //!< [EXPORT] : [TM] + VERIFY_STEP_FAILED = 6 //!< [EXPORT] : [TM] + }; }; #endif /* FSFW_PUS_SERVICE1TELECOMMANDVERIFICATION_H_ */ diff --git a/src/fsfw/pus/Service20ParameterManagement.cpp b/src/fsfw/pus/Service20ParameterManagement.cpp index e28e7804..61e29412 100644 --- a/src/fsfw/pus/Service20ParameterManagement.cpp +++ b/src/fsfw/pus/Service20ParameterManagement.cpp @@ -1,188 +1,186 @@ #include "fsfw/pus/Service20ParameterManagement.h" -#include "fsfw/pus/servicepackets/Service20Packets.h" -#include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/parameters/HasParametersIF.h" #include "fsfw/parameters/ParameterMessage.h" -#include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/parameters/ReceivesParameterMessagesIF.h" - +#include "fsfw/pus/servicepackets/Service20Packets.h" +#include "fsfw/serviceinterface/ServiceInterface.h" Service20ParameterManagement::Service20ParameterManagement(object_id_t objectId, uint16_t apid, - uint8_t serviceId, uint8_t numberOfParallelCommands, uint16_t commandTimeoutSeconds) : - CommandingServiceBase(objectId, apid, serviceId, - numberOfParallelCommands,commandTimeoutSeconds) {} + uint8_t serviceId, + uint8_t numberOfParallelCommands, + uint16_t commandTimeoutSeconds) + : CommandingServiceBase(objectId, apid, serviceId, numberOfParallelCommands, + commandTimeoutSeconds) {} Service20ParameterManagement::~Service20ParameterManagement() {} - -ReturnValue_t Service20ParameterManagement::isValidSubservice( - uint8_t subservice) { - switch(static_cast(subservice)) { +ReturnValue_t Service20ParameterManagement::isValidSubservice(uint8_t subservice) { + switch (static_cast(subservice)) { case Subservice::PARAMETER_LOAD: case Subservice::PARAMETER_DUMP: - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; default: #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Invalid Subservice for Service 20" << std::endl; + sif::error << "Invalid Subservice for Service 20" << std::endl; #else - sif::printError("Invalid Subservice for Service 20\n"); + sif::printError("Invalid Subservice for Service 20\n"); #endif - return AcceptsTelecommandsIF::INVALID_SUBSERVICE; - } + return AcceptsTelecommandsIF::INVALID_SUBSERVICE; + } } - -ReturnValue_t Service20ParameterManagement::getMessageQueueAndObject( - uint8_t subservice, const uint8_t* tcData, size_t tcDataLen, - MessageQueueId_t* id, object_id_t* objectId) { - ReturnValue_t result = checkAndAcquireTargetID(objectId,tcData,tcDataLen); - if(result != RETURN_OK) { - return result; - } - return checkInterfaceAndAcquireMessageQueue(id,objectId); +ReturnValue_t Service20ParameterManagement::getMessageQueueAndObject(uint8_t subservice, + const uint8_t* tcData, + size_t tcDataLen, + MessageQueueId_t* id, + object_id_t* objectId) { + ReturnValue_t result = checkAndAcquireTargetID(objectId, tcData, tcDataLen); + if (result != RETURN_OK) { + return result; + } + return checkInterfaceAndAcquireMessageQueue(id, objectId); } - -ReturnValue_t Service20ParameterManagement::checkAndAcquireTargetID( - object_id_t* objectIdToSet, const uint8_t* tcData, size_t tcDataLen) { - if(SerializeAdapter::deSerialize(objectIdToSet, &tcData, &tcDataLen, - SerializeIF::Endianness::BIG) != HasReturnvaluesIF::RETURN_OK) { +ReturnValue_t Service20ParameterManagement::checkAndAcquireTargetID(object_id_t* objectIdToSet, + const uint8_t* tcData, + size_t tcDataLen) { + if (SerializeAdapter::deSerialize(objectIdToSet, &tcData, &tcDataLen, + SerializeIF::Endianness::BIG) != HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Service20ParameterManagement::checkAndAcquireTargetID: " - << "Invalid data." << std::endl; + sif::error << "Service20ParameterManagement::checkAndAcquireTargetID: " + << "Invalid data." << std::endl; #else - sif::printError("Service20ParameterManagement::" - "checkAndAcquireTargetID: Invalid data.\n"); + sif::printError( + "Service20ParameterManagement::" + "checkAndAcquireTargetID: Invalid data.\n"); #endif - return CommandingServiceBase::INVALID_TC; - } - return HasReturnvaluesIF::RETURN_OK; + return CommandingServiceBase::INVALID_TC; + } + return HasReturnvaluesIF::RETURN_OK; } - ReturnValue_t Service20ParameterManagement::checkInterfaceAndAcquireMessageQueue( - MessageQueueId_t* messageQueueToSet, object_id_t* objectId) { - // check ReceivesParameterMessagesIF property of target - ReceivesParameterMessagesIF* possibleTarget = - ObjectManager::instance()->get(*objectId); - if(possibleTarget == nullptr) { + MessageQueueId_t* messageQueueToSet, object_id_t* objectId) { + // check ReceivesParameterMessagesIF property of target + ReceivesParameterMessagesIF* possibleTarget = + ObjectManager::instance()->get(*objectId); + if (possibleTarget == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Service20ParameterManagement::checkInterfaceAndAcquire" - <<"MessageQueue: Can't access object" << std::endl; - sif::error << "Object ID: " << std::hex << objectId << std::dec << std::endl; - sif::error << "Make sure it implements ReceivesParameterMessagesIF!" << std::endl; + sif::error << "Service20ParameterManagement::checkInterfaceAndAcquire" + << "MessageQueue: Can't access object" << std::endl; + sif::error << "Object ID: " << std::hex << objectId << std::dec << std::endl; + sif::error << "Make sure it implements ReceivesParameterMessagesIF!" << std::endl; #else - sif::printError("Service20ParameterManagement::checkInterfaceAndAcquire" - "MessageQueue: Can't access object\n"); - sif::printError("Object ID: 0x%08x\n", *objectId); - sif::printError("Make sure it implements ReceivesParameterMessagesIF!\n"); + sif::printError( + "Service20ParameterManagement::checkInterfaceAndAcquire" + "MessageQueue: Can't access object\n"); + sif::printError("Object ID: 0x%08x\n", *objectId); + sif::printError("Make sure it implements ReceivesParameterMessagesIF!\n"); #endif - return CommandingServiceBase::INVALID_OBJECT; - } - *messageQueueToSet = possibleTarget->getCommandQueue(); - return HasReturnvaluesIF::RETURN_OK; + return CommandingServiceBase::INVALID_OBJECT; + } + *messageQueueToSet = possibleTarget->getCommandQueue(); + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t Service20ParameterManagement::prepareCommand( - CommandMessage* message, uint8_t subservice, const uint8_t* tcData, - size_t tcDataLen, uint32_t* state, object_id_t objectId) { - switch(static_cast(subservice)){ +ReturnValue_t Service20ParameterManagement::prepareCommand(CommandMessage* message, + uint8_t subservice, + const uint8_t* tcData, size_t tcDataLen, + uint32_t* state, object_id_t objectId) { + switch (static_cast(subservice)) { case Subservice::PARAMETER_DUMP: { - return prepareDumpCommand(message, tcData, tcDataLen); - } - break; + return prepareDumpCommand(message, tcData, tcDataLen); + } break; case Subservice::PARAMETER_LOAD: { - return prepareLoadCommand(message, tcData, tcDataLen); - } - break; + return prepareLoadCommand(message, tcData, tcDataLen); + } break; default: - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; + } } -ReturnValue_t Service20ParameterManagement::prepareDumpCommand( - CommandMessage* message, const uint8_t* tcData, size_t tcDataLen) { - /* the first part is the objectId, but we have extracted that earlier - and only need the parameterId */ - tcData += sizeof(object_id_t); - tcDataLen -= sizeof(object_id_t); - ParameterId_t parameterId; - if(SerializeAdapter::deSerialize(¶meterId, &tcData, &tcDataLen, - SerializeIF::Endianness::BIG) != HasReturnvaluesIF::RETURN_OK) { - return CommandingServiceBase::INVALID_TC; - } - /* The length should have been decremented to 0 by this point */ - if(tcDataLen != 0) { - return CommandingServiceBase::INVALID_TC; - } +ReturnValue_t Service20ParameterManagement::prepareDumpCommand(CommandMessage* message, + const uint8_t* tcData, + size_t tcDataLen) { + /* the first part is the objectId, but we have extracted that earlier + and only need the parameterId */ + tcData += sizeof(object_id_t); + tcDataLen -= sizeof(object_id_t); + ParameterId_t parameterId; + if (SerializeAdapter::deSerialize(¶meterId, &tcData, &tcDataLen, + SerializeIF::Endianness::BIG) != HasReturnvaluesIF::RETURN_OK) { + return CommandingServiceBase::INVALID_TC; + } + /* The length should have been decremented to 0 by this point */ + if (tcDataLen != 0) { + return CommandingServiceBase::INVALID_TC; + } - ParameterMessage::setParameterDumpCommand(message, parameterId); - return HasReturnvaluesIF::RETURN_OK; + ParameterMessage::setParameterDumpCommand(message, parameterId); + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t Service20ParameterManagement::prepareLoadCommand( - CommandMessage* message, const uint8_t* tcData, size_t tcDataLen) { - if(tcDataLen < sizeof(object_id_t) + sizeof(ParameterId_t) + - sizeof(uint32_t)) { - return CommandingServiceBase::INVALID_TC; - } +ReturnValue_t Service20ParameterManagement::prepareLoadCommand(CommandMessage* message, + const uint8_t* tcData, + size_t tcDataLen) { + if (tcDataLen < sizeof(object_id_t) + sizeof(ParameterId_t) + sizeof(uint32_t)) { + return CommandingServiceBase::INVALID_TC; + } - uint8_t* storePointer = nullptr; - store_address_t storeAddress; - size_t parameterDataLen = tcDataLen - sizeof(object_id_t) - sizeof(ParameterId_t) - - sizeof(uint32_t); - if(parameterDataLen == 0) { - return CommandingServiceBase::INVALID_TC; - } - ReturnValue_t result = IPCStore->getFreeElement(&storeAddress, - parameterDataLen, &storePointer); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + uint8_t* storePointer = nullptr; + store_address_t storeAddress; + size_t parameterDataLen = + tcDataLen - sizeof(object_id_t) - sizeof(ParameterId_t) - sizeof(uint32_t); + if (parameterDataLen == 0) { + return CommandingServiceBase::INVALID_TC; + } + ReturnValue_t result = IPCStore->getFreeElement(&storeAddress, parameterDataLen, &storePointer); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - /* Following format is expected: The first 4 bytes in the TC data are the 4 byte - parameter ID (ParameterId_t). The second 4 bytes are the parameter information field, - containing the following 1 byte fields: - 1. ECSS PTC field - 2. ECSS PFC field - 3. Number of rows - 4. Number of columns */ - ParameterLoadCommand command(storePointer, parameterDataLen); - result = command.deSerialize(&tcData, &tcDataLen, - SerializeIF::Endianness::BIG); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + /* Following format is expected: The first 4 bytes in the TC data are the 4 byte + parameter ID (ParameterId_t). The second 4 bytes are the parameter information field, + containing the following 1 byte fields: + 1. ECSS PTC field + 2. ECSS PFC field + 3. Number of rows + 4. Number of columns */ + ParameterLoadCommand command(storePointer, parameterDataLen); + result = command.deSerialize(&tcData, &tcDataLen, SerializeIF::Endianness::BIG); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - ParameterMessage::setParameterLoadCommand(message, command.getParameterId(), storeAddress, - command.getPtc(), command.getPfc(), command.getRows(), command.getColumns()); - return HasReturnvaluesIF::RETURN_OK; + ParameterMessage::setParameterLoadCommand(message, command.getParameterId(), storeAddress, + command.getPtc(), command.getPfc(), command.getRows(), + command.getColumns()); + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t Service20ParameterManagement::handleReply( - const CommandMessage* reply, Command_t previousCommand, uint32_t* state, - CommandMessage* optionalNextCommand, object_id_t objectId, - bool* isStep) { - Command_t replyId = reply->getCommand(); +ReturnValue_t Service20ParameterManagement::handleReply(const CommandMessage* reply, + Command_t previousCommand, uint32_t* state, + CommandMessage* optionalNextCommand, + object_id_t objectId, bool* isStep) { + Command_t replyId = reply->getCommand(); - switch(replyId) { + switch (replyId) { case ParameterMessage::REPLY_PARAMETER_DUMP: { - ConstAccessorPair parameterData = IPCStore->getData( - ParameterMessage::getStoreId(reply)); - if(parameterData.first != HasReturnvaluesIF::RETURN_OK) { - return HasReturnvaluesIF::RETURN_FAILED; - } + ConstAccessorPair parameterData = IPCStore->getData(ParameterMessage::getStoreId(reply)); + if (parameterData.first != HasReturnvaluesIF::RETURN_OK) { + return HasReturnvaluesIF::RETURN_FAILED; + } - ParameterId_t parameterId = ParameterMessage::getParameterId(reply); - ParameterDumpReply parameterReply(objectId, parameterId, - parameterData.second.data(), parameterData.second.size()); - sendTmPacket(static_cast( - Subservice::PARAMETER_DUMP_REPLY), ¶meterReply); - return HasReturnvaluesIF::RETURN_OK; + ParameterId_t parameterId = ParameterMessage::getParameterId(reply); + ParameterDumpReply parameterReply(objectId, parameterId, parameterData.second.data(), + parameterData.second.size()); + sendTmPacket(static_cast(Subservice::PARAMETER_DUMP_REPLY), ¶meterReply); + return HasReturnvaluesIF::RETURN_OK; } default: - return CommandingServiceBase::INVALID_REPLY; - } + return CommandingServiceBase::INVALID_REPLY; + } } diff --git a/src/fsfw/pus/Service20ParameterManagement.h b/src/fsfw/pus/Service20ParameterManagement.h index 63ec199c..ae1fb4ea 100644 --- a/src/fsfw/pus/Service20ParameterManagement.h +++ b/src/fsfw/pus/Service20ParameterManagement.h @@ -11,50 +11,46 @@ * @author J. Gerhards * */ -class Service20ParameterManagement : public CommandingServiceBase -{ -public: - Service20ParameterManagement(object_id_t objectId, uint16_t apid, uint8_t serviceId, - uint8_t numberOfParallelCommands = 4, uint16_t commandTimeoutSeconds = 60); - virtual ~Service20ParameterManagement(); +class Service20ParameterManagement : public CommandingServiceBase { + public: + Service20ParameterManagement(object_id_t objectId, uint16_t apid, uint8_t serviceId, + uint8_t numberOfParallelCommands = 4, + uint16_t commandTimeoutSeconds = 60); + virtual ~Service20ParameterManagement(); - static constexpr uint8_t NUM_OF_PARALLEL_COMMANDS = 4; - static constexpr uint16_t COMMAND_TIMEOUT_SECONDS = 60; -protected: - /* CommandingServiceBase (CSB) abstract functions. See CSB documentation. */ - ReturnValue_t isValidSubservice(uint8_t subservice) override; - ReturnValue_t getMessageQueueAndObject(uint8_t subservice, - const uint8_t *tcData, size_t tcDataLen, MessageQueueId_t *id, - object_id_t *objectId) override; - ReturnValue_t prepareCommand(CommandMessage* message, uint8_t subservice, - const uint8_t *tcData, size_t tcDataLen, uint32_t *state, - object_id_t objectId) override; - ReturnValue_t handleReply(const CommandMessage* reply, - Command_t previousCommand, uint32_t *state, - CommandMessage* optionalNextCommand, object_id_t objectId, - bool *isStep) override; + static constexpr uint8_t NUM_OF_PARALLEL_COMMANDS = 4; + static constexpr uint16_t COMMAND_TIMEOUT_SECONDS = 60; -private: + protected: + /* CommandingServiceBase (CSB) abstract functions. See CSB documentation. */ + ReturnValue_t isValidSubservice(uint8_t subservice) override; + ReturnValue_t getMessageQueueAndObject(uint8_t subservice, const uint8_t* tcData, + size_t tcDataLen, MessageQueueId_t* id, + object_id_t* objectId) override; + ReturnValue_t prepareCommand(CommandMessage* message, uint8_t subservice, const uint8_t* tcData, + size_t tcDataLen, uint32_t* state, object_id_t objectId) override; + ReturnValue_t handleReply(const CommandMessage* reply, Command_t previousCommand, uint32_t* state, + CommandMessage* optionalNextCommand, object_id_t objectId, + bool* isStep) override; - ReturnValue_t checkAndAcquireTargetID(object_id_t* objectIdToSet, - const uint8_t* tcData, size_t tcDataLen); - ReturnValue_t checkInterfaceAndAcquireMessageQueue( - MessageQueueId_t* messageQueueToSet, object_id_t* objectId); - ReturnValue_t prepareDirectCommand(CommandMessage* message, - const uint8_t* tcData, size_t tcDataLen); + private: + ReturnValue_t checkAndAcquireTargetID(object_id_t* objectIdToSet, const uint8_t* tcData, + size_t tcDataLen); + ReturnValue_t checkInterfaceAndAcquireMessageQueue(MessageQueueId_t* messageQueueToSet, + object_id_t* objectId); + ReturnValue_t prepareDirectCommand(CommandMessage* message, const uint8_t* tcData, + size_t tcDataLen); - ReturnValue_t prepareDumpCommand(CommandMessage* message, - const uint8_t* tcData, size_t tcDataLen); - ReturnValue_t prepareLoadCommand(CommandMessage* message, - const uint8_t* tcData, size_t tcDataLen); - - enum class Subservice { - PARAMETER_LOAD = 128, //!< [EXPORT] : Load a Parameter - PARAMETER_DUMP = 129, //!< [EXPORT] : Dump a Parameter - PARAMETER_DUMP_REPLY = 130, //!< [EXPORT] : Dump a Parameter - }; + ReturnValue_t prepareDumpCommand(CommandMessage* message, const uint8_t* tcData, + size_t tcDataLen); + ReturnValue_t prepareLoadCommand(CommandMessage* message, const uint8_t* tcData, + size_t tcDataLen); + enum class Subservice { + PARAMETER_LOAD = 128, //!< [EXPORT] : Load a Parameter + PARAMETER_DUMP = 129, //!< [EXPORT] : Dump a Parameter + PARAMETER_DUMP_REPLY = 130, //!< [EXPORT] : Dump a Parameter + }; }; - #endif /* FSFW_PUS_SERVICE20PARAMETERMANAGEMENT_H_ */ diff --git a/src/fsfw/pus/Service2DeviceAccess.cpp b/src/fsfw/pus/Service2DeviceAccess.cpp index 0e5edfd3..3430271e 100644 --- a/src/fsfw/pus/Service2DeviceAccess.cpp +++ b/src/fsfw/pus/Service2DeviceAccess.cpp @@ -1,171 +1,156 @@ #include "fsfw/pus/Service2DeviceAccess.h" -#include "fsfw/pus/servicepackets/Service2Packets.h" -#include "fsfw/objectmanager/ObjectManager.h" -#include "fsfw/devicehandlers/DeviceHandlerIF.h" -#include "fsfw/storagemanager/StorageManagerIF.h" -#include "fsfw/devicehandlers/DeviceHandlerMessage.h" -#include "fsfw/serialize/EndianConverter.h" #include "fsfw/action/ActionMessage.h" -#include "fsfw/serialize/SerializeAdapter.h" +#include "fsfw/devicehandlers/DeviceHandlerIF.h" +#include "fsfw/devicehandlers/DeviceHandlerMessage.h" +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/pus/servicepackets/Service2Packets.h" +#include "fsfw/serialize/EndianConverter.h" #include "fsfw/serialize/SerialLinkedListAdapter.h" +#include "fsfw/serialize/SerializeAdapter.h" #include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/storagemanager/StorageManagerIF.h" -Service2DeviceAccess::Service2DeviceAccess(object_id_t objectId, - uint16_t apid, uint8_t serviceId, uint8_t numberOfParallelCommands, - uint16_t commandTimeoutSeconds): - CommandingServiceBase(objectId, apid, serviceId, - numberOfParallelCommands, commandTimeoutSeconds) {} +Service2DeviceAccess::Service2DeviceAccess(object_id_t objectId, uint16_t apid, uint8_t serviceId, + uint8_t numberOfParallelCommands, + uint16_t commandTimeoutSeconds) + : CommandingServiceBase(objectId, apid, serviceId, numberOfParallelCommands, + commandTimeoutSeconds) {} Service2DeviceAccess::~Service2DeviceAccess() {} - ReturnValue_t Service2DeviceAccess::isValidSubservice(uint8_t subservice) { - switch(static_cast(subservice)){ - case Subservice::COMMAND_RAW_COMMANDING: - case Subservice::COMMAND_TOGGLE_WIRETAPPING: - return HasReturnvaluesIF::RETURN_OK; - default: + switch (static_cast(subservice)) { + case Subservice::COMMAND_RAW_COMMANDING: + case Subservice::COMMAND_TOGGLE_WIRETAPPING: + return HasReturnvaluesIF::RETURN_OK; + default: #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Invalid Subservice" << std::endl; + sif::error << "Invalid Subservice" << std::endl; #endif - return AcceptsTelecommandsIF::INVALID_SUBSERVICE; - } + return AcceptsTelecommandsIF::INVALID_SUBSERVICE; + } } -ReturnValue_t Service2DeviceAccess::getMessageQueueAndObject( - uint8_t subservice, const uint8_t* tcData, size_t tcDataLen, - MessageQueueId_t* id, object_id_t* objectId) { - if(tcDataLen < sizeof(object_id_t)) { - return CommandingServiceBase::INVALID_TC; - } - SerializeAdapter::deSerialize(objectId, &tcData, - &tcDataLen, SerializeIF::Endianness::BIG); +ReturnValue_t Service2DeviceAccess::getMessageQueueAndObject(uint8_t subservice, + const uint8_t* tcData, + size_t tcDataLen, MessageQueueId_t* id, + object_id_t* objectId) { + if (tcDataLen < sizeof(object_id_t)) { + return CommandingServiceBase::INVALID_TC; + } + SerializeAdapter::deSerialize(objectId, &tcData, &tcDataLen, SerializeIF::Endianness::BIG); - return checkInterfaceAndAcquireMessageQueue(id,objectId); + return checkInterfaceAndAcquireMessageQueue(id, objectId); } ReturnValue_t Service2DeviceAccess::checkInterfaceAndAcquireMessageQueue( - MessageQueueId_t * messageQueueToSet, object_id_t *objectId) { - DeviceHandlerIF* possibleTarget = - ObjectManager::instance()->get(*objectId); - if(possibleTarget == nullptr) { - return CommandingServiceBase::INVALID_OBJECT; - } - *messageQueueToSet = possibleTarget->getCommandQueue(); - return HasReturnvaluesIF::RETURN_OK; + MessageQueueId_t* messageQueueToSet, object_id_t* objectId) { + DeviceHandlerIF* possibleTarget = ObjectManager::instance()->get(*objectId); + if (possibleTarget == nullptr) { + return CommandingServiceBase::INVALID_OBJECT; + } + *messageQueueToSet = possibleTarget->getCommandQueue(); + return HasReturnvaluesIF::RETURN_OK; } - -ReturnValue_t Service2DeviceAccess::prepareCommand(CommandMessage* message, - uint8_t subservice, const uint8_t* tcData, size_t tcDataLen, - uint32_t* state, object_id_t objectId) { - switch(static_cast(subservice)){ - case Subservice::COMMAND_RAW_COMMANDING: { - return prepareRawCommand(message, tcData, tcDataLen); - } - break; - case Subservice::COMMAND_TOGGLE_WIRETAPPING: { - return prepareWiretappingCommand(message, tcData, tcDataLen); - } - break; - default: - return HasReturnvaluesIF::RETURN_FAILED; - } +ReturnValue_t Service2DeviceAccess::prepareCommand(CommandMessage* message, uint8_t subservice, + const uint8_t* tcData, size_t tcDataLen, + uint32_t* state, object_id_t objectId) { + switch (static_cast(subservice)) { + case Subservice::COMMAND_RAW_COMMANDING: { + return prepareRawCommand(message, tcData, tcDataLen); + } break; + case Subservice::COMMAND_TOGGLE_WIRETAPPING: { + return prepareWiretappingCommand(message, tcData, tcDataLen); + } break; + default: + return HasReturnvaluesIF::RETURN_FAILED; + } } -ReturnValue_t Service2DeviceAccess::prepareRawCommand( - CommandMessage* messageToSet, const uint8_t *tcData,size_t tcDataLen) { - RawCommand RawCommand(tcData,tcDataLen); - // store command into the Inter Process Communication Store - store_address_t storeAddress; - ReturnValue_t result = IPCStore->addData(&storeAddress, - RawCommand.getCommand(), RawCommand.getCommandSize()); - DeviceHandlerMessage::setDeviceHandlerRawCommandMessage(messageToSet, - storeAddress); - return result; +ReturnValue_t Service2DeviceAccess::prepareRawCommand(CommandMessage* messageToSet, + const uint8_t* tcData, size_t tcDataLen) { + RawCommand RawCommand(tcData, tcDataLen); + // store command into the Inter Process Communication Store + store_address_t storeAddress; + ReturnValue_t result = + IPCStore->addData(&storeAddress, RawCommand.getCommand(), RawCommand.getCommandSize()); + DeviceHandlerMessage::setDeviceHandlerRawCommandMessage(messageToSet, storeAddress); + return result; } -ReturnValue_t Service2DeviceAccess::prepareWiretappingCommand( - CommandMessage *messageToSet, const uint8_t *tcData, - size_t tcDataLen) { - if(tcDataLen != WiretappingToggle::WIRETAPPING_COMMAND_SIZE) { - return CommandingServiceBase::INVALID_TC; - } - WiretappingToggle command; - ReturnValue_t result = command.deSerialize(&tcData, &tcDataLen, - SerializeIF::Endianness::BIG); - DeviceHandlerMessage::setDeviceHandlerWiretappingMessage(messageToSet, - command.getWiretappingMode()); - return result; +ReturnValue_t Service2DeviceAccess::prepareWiretappingCommand(CommandMessage* messageToSet, + const uint8_t* tcData, + size_t tcDataLen) { + if (tcDataLen != WiretappingToggle::WIRETAPPING_COMMAND_SIZE) { + return CommandingServiceBase::INVALID_TC; + } + WiretappingToggle command; + ReturnValue_t result = command.deSerialize(&tcData, &tcDataLen, SerializeIF::Endianness::BIG); + DeviceHandlerMessage::setDeviceHandlerWiretappingMessage(messageToSet, + command.getWiretappingMode()); + return result; } - ReturnValue_t Service2DeviceAccess::handleReply(const CommandMessage* reply, - Command_t previousCommand, uint32_t* state, - CommandMessage* optionalNextCommand, object_id_t objectId, - bool* isStep) { - switch(reply->getCommand()) { - case CommandMessage::REPLY_COMMAND_OK: - return HasReturnvaluesIF::RETURN_OK; - case CommandMessage::REPLY_REJECTED: - return reply->getReplyRejectedReason(); - default: - return CommandingServiceBase::INVALID_REPLY; - } + Command_t previousCommand, uint32_t* state, + CommandMessage* optionalNextCommand, + object_id_t objectId, bool* isStep) { + switch (reply->getCommand()) { + case CommandMessage::REPLY_COMMAND_OK: + return HasReturnvaluesIF::RETURN_OK; + case CommandMessage::REPLY_REJECTED: + return reply->getReplyRejectedReason(); + default: + return CommandingServiceBase::INVALID_REPLY; + } } // All device handlers set service 2 as default raw receiver for wiretapping // so we have to handle those unrequested messages. void Service2DeviceAccess::handleUnrequestedReply(CommandMessage* reply) { - switch(reply->getCommand()) { - case DeviceHandlerMessage::REPLY_RAW_COMMAND: - sendWiretappingTm(reply, - static_cast(Subservice::REPLY_WIRETAPPING_RAW_TC)); - break; - case DeviceHandlerMessage::REPLY_RAW_REPLY: - sendWiretappingTm(reply, - static_cast(Subservice::REPLY_RAW)); - break; - default: + switch (reply->getCommand()) { + case DeviceHandlerMessage::REPLY_RAW_COMMAND: + sendWiretappingTm(reply, static_cast(Subservice::REPLY_WIRETAPPING_RAW_TC)); + break; + case DeviceHandlerMessage::REPLY_RAW_REPLY: + sendWiretappingTm(reply, static_cast(Subservice::REPLY_RAW)); + break; + default: #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Unknown message in Service2DeviceAccess::" - "handleUnrequestedReply with command ID " << - reply->getCommand() << std::endl; + sif::error << "Unknown message in Service2DeviceAccess::" + "handleUnrequestedReply with command ID " + << reply->getCommand() << std::endl; #endif - break; - } - //Must be reached by all cases to clear message - reply->clear(); + break; + } + // Must be reached by all cases to clear message + reply->clear(); } -void Service2DeviceAccess::sendWiretappingTm(CommandMessage *reply, - uint8_t subservice) { - // Raw Wiretapping - // Get Address of Data from Message - store_address_t storeAddress = DeviceHandlerMessage::getStoreAddress(reply); - const uint8_t* data = nullptr; - size_t size = 0; - ReturnValue_t result = IPCStore->getData(storeAddress, &data, &size); - if(result != HasReturnvaluesIF::RETURN_OK){ +void Service2DeviceAccess::sendWiretappingTm(CommandMessage* reply, uint8_t subservice) { + // Raw Wiretapping + // Get Address of Data from Message + store_address_t storeAddress = DeviceHandlerMessage::getStoreAddress(reply); + const uint8_t* data = nullptr; + size_t size = 0; + ReturnValue_t result = IPCStore->getData(storeAddress, &data, &size); + if (result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Service2DeviceAccess::sendWiretappingTm: Data Lost in " - "handleUnrequestedReply with failure ID "<< result - << std::endl; + sif::error << "Service2DeviceAccess::sendWiretappingTm: Data Lost in " + "handleUnrequestedReply with failure ID " + << result << std::endl; #endif - return; - } + return; + } - // Init our dummy packet and correct endianness of object ID before - // sending it back. - WiretappingPacket TmPacket(DeviceHandlerMessage::getDeviceObjectId(reply), - data); - TmPacket.objectId = EndianConverter::convertBigEndian(TmPacket.objectId); - sendTmPacket(subservice, TmPacket.data,size, reinterpret_cast( - &TmPacket.objectId), sizeof(TmPacket.objectId)); -} - -MessageQueueId_t Service2DeviceAccess::getDeviceQueue() { - return commandQueue->getId(); + // Init our dummy packet and correct endianness of object ID before + // sending it back. + WiretappingPacket TmPacket(DeviceHandlerMessage::getDeviceObjectId(reply), data); + TmPacket.objectId = EndianConverter::convertBigEndian(TmPacket.objectId); + sendTmPacket(subservice, TmPacket.data, size, reinterpret_cast(&TmPacket.objectId), + sizeof(TmPacket.objectId)); } +MessageQueueId_t Service2DeviceAccess::getDeviceQueue() { return commandQueue->getId(); } diff --git a/src/fsfw/pus/Service2DeviceAccess.h b/src/fsfw/pus/Service2DeviceAccess.h index e518863c..24f79be4 100644 --- a/src/fsfw/pus/Service2DeviceAccess.h +++ b/src/fsfw/pus/Service2DeviceAccess.h @@ -1,8 +1,8 @@ #ifndef FSFW_PUS_SERVICE2DEVICEACCESS_H_ #define FSFW_PUS_SERVICE2DEVICEACCESS_H_ -#include "fsfw/objectmanager/SystemObjectIF.h" #include "fsfw/devicehandlers/AcceptsDeviceResponsesIF.h" +#include "fsfw/objectmanager/SystemObjectIF.h" #include "fsfw/tmtcservices/CommandingServiceBase.h" /** @@ -31,66 +31,61 @@ * - TM[2,131]: Wiretapping Packet TC * @ingroup pus_services */ -class Service2DeviceAccess : public CommandingServiceBase, - public AcceptsDeviceResponsesIF -{ -public: - Service2DeviceAccess(object_id_t objectId, uint16_t apid, - uint8_t serviceId, uint8_t numberOfParallelCommands = 4, - uint16_t commandTimeoutSeconds = 60); - virtual ~Service2DeviceAccess(); +class Service2DeviceAccess : public CommandingServiceBase, public AcceptsDeviceResponsesIF { + public: + Service2DeviceAccess(object_id_t objectId, uint16_t apid, uint8_t serviceId, + uint8_t numberOfParallelCommands = 4, uint16_t commandTimeoutSeconds = 60); + virtual ~Service2DeviceAccess(); -protected: - //! CommandingServiceBase (CSB) abstract functions. See CSB documentation. - ReturnValue_t isValidSubservice(uint8_t subservice) override; - ReturnValue_t getMessageQueueAndObject(uint8_t subservice, - const uint8_t *tcData, size_t tcDataLen, MessageQueueId_t *id, - object_id_t *objectId) override; - ReturnValue_t prepareCommand(CommandMessage* message, uint8_t subservice, - const uint8_t *tcData, size_t tcDataLen, uint32_t *state, - object_id_t objectId) override; - ReturnValue_t handleReply(const CommandMessage* reply, - Command_t previousCommand, uint32_t *state, - CommandMessage* optionalNextCommand, object_id_t objectId, - bool *isStep) override; + protected: + //! CommandingServiceBase (CSB) abstract functions. See CSB documentation. + ReturnValue_t isValidSubservice(uint8_t subservice) override; + ReturnValue_t getMessageQueueAndObject(uint8_t subservice, const uint8_t* tcData, + size_t tcDataLen, MessageQueueId_t* id, + object_id_t* objectId) override; + ReturnValue_t prepareCommand(CommandMessage* message, uint8_t subservice, const uint8_t* tcData, + size_t tcDataLen, uint32_t* state, object_id_t objectId) override; + ReturnValue_t handleReply(const CommandMessage* reply, Command_t previousCommand, uint32_t* state, + CommandMessage* optionalNextCommand, object_id_t objectId, + bool* isStep) override; - /** - * @brief Generates TM packets containing either the TC wiretapping - * packets or the TM wiretapping packets. - * Note that for service 2, all telemetry will be treated as an - * unrequested reply regardless of wiretapping mode. - * @param reply - */ - void handleUnrequestedReply(CommandMessage* reply) override; + /** + * @brief Generates TM packets containing either the TC wiretapping + * packets or the TM wiretapping packets. + * Note that for service 2, all telemetry will be treated as an + * unrequested reply regardless of wiretapping mode. + * @param reply + */ + void handleUnrequestedReply(CommandMessage* reply) override; - MessageQueueId_t getDeviceQueue() override; -private: - /** - * Generates TM packets for Wiretapping Service - * @param reply - * @param subservice - */ - void sendWiretappingTm(CommandMessage* reply,uint8_t subservice); + MessageQueueId_t getDeviceQueue() override; - ReturnValue_t checkInterfaceAndAcquireMessageQueue( - MessageQueueId_t* messageQueueToSet, object_id_t* objectId); + private: + /** + * Generates TM packets for Wiretapping Service + * @param reply + * @param subservice + */ + void sendWiretappingTm(CommandMessage* reply, uint8_t subservice); - ReturnValue_t prepareRawCommand(CommandMessage* messageToSet, - const uint8_t* tcData, size_t tcDataLen); - ReturnValue_t prepareWiretappingCommand(CommandMessage* messageToSet, - const uint8_t* tcData, size_t tcDataLen); + ReturnValue_t checkInterfaceAndAcquireMessageQueue(MessageQueueId_t* messageQueueToSet, + object_id_t* objectId); - enum class Subservice { - //!< [EXPORT] : [COMMAND] Command in device native protocol - COMMAND_RAW_COMMANDING = 128, - //!< [EXPORT] : [COMMAND] Toggle wiretapping of raw communication - COMMAND_TOGGLE_WIRETAPPING = 129, - //!< [EXPORT] : [REPLY] Includes wiretapping TM and normal TM raw replies from device - REPLY_RAW = 130, - //!< [EXPORT] : [REPLY] Wiretapping packets of commands built by device handler - REPLY_WIRETAPPING_RAW_TC = 131 - }; + ReturnValue_t prepareRawCommand(CommandMessage* messageToSet, const uint8_t* tcData, + size_t tcDataLen); + ReturnValue_t prepareWiretappingCommand(CommandMessage* messageToSet, const uint8_t* tcData, + size_t tcDataLen); + + enum class Subservice { + //!< [EXPORT] : [COMMAND] Command in device native protocol + COMMAND_RAW_COMMANDING = 128, + //!< [EXPORT] : [COMMAND] Toggle wiretapping of raw communication + COMMAND_TOGGLE_WIRETAPPING = 129, + //!< [EXPORT] : [REPLY] Includes wiretapping TM and normal TM raw replies from device + REPLY_RAW = 130, + //!< [EXPORT] : [REPLY] Wiretapping packets of commands built by device handler + REPLY_WIRETAPPING_RAW_TC = 131 + }; }; - #endif /* FSFW_PUS_DEVICE2DEVICECOMMANDING_H_ */ diff --git a/src/fsfw/pus/Service3Housekeeping.cpp b/src/fsfw/pus/Service3Housekeeping.cpp index 2b91f366..07574783 100644 --- a/src/fsfw/pus/Service3Housekeeping.cpp +++ b/src/fsfw/pus/Service3Housekeeping.cpp @@ -1,319 +1,308 @@ #include "fsfw/pus/Service3Housekeeping.h" + +#include "fsfw/datapoollocal/HasLocalDataPoolIF.h" +#include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/pus/servicepackets/Service3Packets.h" -#include "fsfw/objectmanager/ObjectManager.h" -#include "fsfw/datapoollocal/HasLocalDataPoolIF.h" - -Service3Housekeeping::Service3Housekeeping(object_id_t objectId, uint16_t apid, - uint8_t serviceId): - CommandingServiceBase(objectId, apid, serviceId, - NUM_OF_PARALLEL_COMMANDS, COMMAND_TIMEOUT_SECONDS) {} +Service3Housekeeping::Service3Housekeeping(object_id_t objectId, uint16_t apid, uint8_t serviceId) + : CommandingServiceBase(objectId, apid, serviceId, NUM_OF_PARALLEL_COMMANDS, + COMMAND_TIMEOUT_SECONDS) {} Service3Housekeeping::~Service3Housekeeping() {} ReturnValue_t Service3Housekeeping::isValidSubservice(uint8_t subservice) { - switch(static_cast(subservice)) { + switch (static_cast(subservice)) { case Subservice::ENABLE_PERIODIC_HK_REPORT_GENERATION: case Subservice::DISABLE_PERIODIC_HK_REPORT_GENERATION: case Subservice::ENABLE_PERIODIC_DIAGNOSTICS_REPORT_GENERATION: case Subservice::DISABLE_PERIODIC_DIAGNOSTICS_REPORT_GENERATION: case Subservice::REPORT_HK_REPORT_STRUCTURES: - case Subservice::REPORT_DIAGNOSTICS_REPORT_STRUCTURES : + case Subservice::REPORT_DIAGNOSTICS_REPORT_STRUCTURES: case Subservice::GENERATE_ONE_PARAMETER_REPORT: case Subservice::GENERATE_ONE_DIAGNOSTICS_REPORT: case Subservice::MODIFY_PARAMETER_REPORT_COLLECTION_INTERVAL: case Subservice::MODIFY_DIAGNOSTICS_REPORT_COLLECTION_INTERVAL: - return HasReturnvaluesIF::RETURN_OK; - // Telemetry or invalid subservice. + return HasReturnvaluesIF::RETURN_OK; + // Telemetry or invalid subservice. case Subservice::HK_DEFINITIONS_REPORT: case Subservice::DIAGNOSTICS_DEFINITION_REPORT: case Subservice::HK_REPORT: case Subservice::DIAGNOSTICS_REPORT: default: - return AcceptsTelecommandsIF::INVALID_SUBSERVICE; - } + return AcceptsTelecommandsIF::INVALID_SUBSERVICE; + } } ReturnValue_t Service3Housekeeping::getMessageQueueAndObject(uint8_t subservice, - const uint8_t *tcData, size_t tcDataLen, - MessageQueueId_t *id, object_id_t *objectId) { - ReturnValue_t result = checkAndAcquireTargetID(objectId,tcData,tcDataLen); - if(result != RETURN_OK) { - return result; - } - return checkInterfaceAndAcquireMessageQueue(id,objectId); + const uint8_t* tcData, + size_t tcDataLen, MessageQueueId_t* id, + object_id_t* objectId) { + ReturnValue_t result = checkAndAcquireTargetID(objectId, tcData, tcDataLen); + if (result != RETURN_OK) { + return result; + } + return checkInterfaceAndAcquireMessageQueue(id, objectId); } -ReturnValue_t Service3Housekeeping::checkAndAcquireTargetID( - object_id_t* objectIdToSet, const uint8_t* tcData, size_t tcDataLen) { - if(SerializeAdapter::deSerialize(objectIdToSet, &tcData, &tcDataLen, - SerializeIF::Endianness::BIG) != HasReturnvaluesIF::RETURN_OK) { - return CommandingServiceBase::INVALID_TC; - } - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t Service3Housekeeping::checkAndAcquireTargetID(object_id_t* objectIdToSet, + const uint8_t* tcData, + size_t tcDataLen) { + if (SerializeAdapter::deSerialize(objectIdToSet, &tcData, &tcDataLen, + SerializeIF::Endianness::BIG) != HasReturnvaluesIF::RETURN_OK) { + return CommandingServiceBase::INVALID_TC; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t Service3Housekeeping::checkInterfaceAndAcquireMessageQueue( - MessageQueueId_t* messageQueueToSet, object_id_t* objectId) { - // check HasLocalDataPoolIF property of target - HasLocalDataPoolIF* possibleTarget = - ObjectManager::instance()->get(*objectId); - if(possibleTarget == nullptr){ - return CommandingServiceBase::INVALID_OBJECT; - } - *messageQueueToSet = possibleTarget->getCommandQueue(); - return HasReturnvaluesIF::RETURN_OK; + MessageQueueId_t* messageQueueToSet, object_id_t* objectId) { + // check HasLocalDataPoolIF property of target + HasLocalDataPoolIF* possibleTarget = + ObjectManager::instance()->get(*objectId); + if (possibleTarget == nullptr) { + return CommandingServiceBase::INVALID_OBJECT; + } + *messageQueueToSet = possibleTarget->getCommandQueue(); + return HasReturnvaluesIF::RETURN_OK; } - -ReturnValue_t Service3Housekeeping::prepareCommand(CommandMessage* message, - uint8_t subservice, const uint8_t *tcData, size_t tcDataLen, - uint32_t *state, object_id_t objectId) { - switch(static_cast(subservice)) { +ReturnValue_t Service3Housekeeping::prepareCommand(CommandMessage* message, uint8_t subservice, + const uint8_t* tcData, size_t tcDataLen, + uint32_t* state, object_id_t objectId) { + switch (static_cast(subservice)) { case Subservice::ENABLE_PERIODIC_HK_REPORT_GENERATION: - return prepareReportingTogglingCommand(message, objectId, true, false, - tcData, tcDataLen); + return prepareReportingTogglingCommand(message, objectId, true, false, tcData, tcDataLen); case Subservice::DISABLE_PERIODIC_HK_REPORT_GENERATION: - return prepareReportingTogglingCommand(message, objectId, false, false, - tcData, tcDataLen); + return prepareReportingTogglingCommand(message, objectId, false, false, tcData, tcDataLen); case Subservice::ENABLE_PERIODIC_DIAGNOSTICS_REPORT_GENERATION: - return prepareReportingTogglingCommand(message, objectId, true, true, - tcData, tcDataLen); + return prepareReportingTogglingCommand(message, objectId, true, true, tcData, tcDataLen); case Subservice::DISABLE_PERIODIC_DIAGNOSTICS_REPORT_GENERATION: - return prepareReportingTogglingCommand(message, objectId, false, true, - tcData, tcDataLen); + return prepareReportingTogglingCommand(message, objectId, false, true, tcData, tcDataLen); case Subservice::REPORT_HK_REPORT_STRUCTURES: - return prepareStructureReportingCommand(message, objectId, false, tcData, - tcDataLen); + return prepareStructureReportingCommand(message, objectId, false, tcData, tcDataLen); case Subservice::REPORT_DIAGNOSTICS_REPORT_STRUCTURES: - return prepareStructureReportingCommand(message, objectId, true, tcData, - tcDataLen); + return prepareStructureReportingCommand(message, objectId, true, tcData, tcDataLen); case Subservice::GENERATE_ONE_PARAMETER_REPORT: - return prepareOneShotReportCommand(message, objectId, false, - tcData, tcDataLen); + return prepareOneShotReportCommand(message, objectId, false, tcData, tcDataLen); case Subservice::GENERATE_ONE_DIAGNOSTICS_REPORT: - return prepareOneShotReportCommand(message, objectId, true, - tcData, tcDataLen); + return prepareOneShotReportCommand(message, objectId, true, tcData, tcDataLen); case Subservice::MODIFY_PARAMETER_REPORT_COLLECTION_INTERVAL: - return prepareCollectionIntervalModificationCommand(message, objectId, - false, tcData, tcDataLen); + return prepareCollectionIntervalModificationCommand(message, objectId, false, tcData, + tcDataLen); case Subservice::MODIFY_DIAGNOSTICS_REPORT_COLLECTION_INTERVAL: - return prepareCollectionIntervalModificationCommand(message, objectId, - true, tcData, tcDataLen); + return prepareCollectionIntervalModificationCommand(message, objectId, true, tcData, + tcDataLen); case Subservice::HK_DEFINITIONS_REPORT: case Subservice::DIAGNOSTICS_DEFINITION_REPORT: case Subservice::HK_REPORT: case Subservice::DIAGNOSTICS_REPORT: - // Those are telemetry packets. - return CommandingServiceBase::INVALID_TC; + // Those are telemetry packets. + return CommandingServiceBase::INVALID_TC; default: - // should never happen, subservice was already checked. - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + // should never happen, subservice was already checked. + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t Service3Housekeeping::prepareReportingTogglingCommand( - CommandMessage *command, object_id_t objectId, - bool enableReporting, bool isDiagnostics, - const uint8_t* tcData, size_t tcDataLen) { - if(tcDataLen < sizeof(sid_t)) { - // TC data should consist of object ID and set ID. - return CommandingServiceBase::INVALID_TC; - } + CommandMessage* command, object_id_t objectId, bool enableReporting, bool isDiagnostics, + const uint8_t* tcData, size_t tcDataLen) { + if (tcDataLen < sizeof(sid_t)) { + // TC data should consist of object ID and set ID. + return CommandingServiceBase::INVALID_TC; + } - sid_t targetSid = buildSid(objectId, &tcData, &tcDataLen); - HousekeepingMessage::setToggleReportingCommand(command, targetSid, - enableReporting, isDiagnostics); - return HasReturnvaluesIF::RETURN_OK; + sid_t targetSid = buildSid(objectId, &tcData, &tcDataLen); + HousekeepingMessage::setToggleReportingCommand(command, targetSid, enableReporting, + isDiagnostics); + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t Service3Housekeeping::prepareStructureReportingCommand( - CommandMessage *command, object_id_t objectId, bool isDiagnostics, - const uint8_t* tcData, size_t tcDataLen) { - if(tcDataLen < sizeof(sid_t)) { - // TC data should consist of object ID and set ID. - return CommandingServiceBase::INVALID_TC; - } +ReturnValue_t Service3Housekeeping::prepareStructureReportingCommand(CommandMessage* command, + object_id_t objectId, + bool isDiagnostics, + const uint8_t* tcData, + size_t tcDataLen) { + if (tcDataLen < sizeof(sid_t)) { + // TC data should consist of object ID and set ID. + return CommandingServiceBase::INVALID_TC; + } - sid_t targetSid = buildSid(objectId, &tcData, &tcDataLen); - HousekeepingMessage::setStructureReportingCommand(command, targetSid, - isDiagnostics); - return HasReturnvaluesIF::RETURN_OK; + sid_t targetSid = buildSid(objectId, &tcData, &tcDataLen); + HousekeepingMessage::setStructureReportingCommand(command, targetSid, isDiagnostics); + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t Service3Housekeeping::prepareOneShotReportCommand( - CommandMessage *command, object_id_t objectId, bool isDiagnostics, - const uint8_t *tcData, size_t tcDataLen) { - if(tcDataLen < sizeof(sid_t)) { - // TC data should consist of object ID and set ID. - return CommandingServiceBase::INVALID_TC; - } +ReturnValue_t Service3Housekeeping::prepareOneShotReportCommand(CommandMessage* command, + object_id_t objectId, + bool isDiagnostics, + const uint8_t* tcData, + size_t tcDataLen) { + if (tcDataLen < sizeof(sid_t)) { + // TC data should consist of object ID and set ID. + return CommandingServiceBase::INVALID_TC; + } - sid_t targetSid = buildSid(objectId, &tcData, &tcDataLen); - HousekeepingMessage::setOneShotReportCommand(command, targetSid, - isDiagnostics); - return HasReturnvaluesIF::RETURN_OK; + sid_t targetSid = buildSid(objectId, &tcData, &tcDataLen); + HousekeepingMessage::setOneShotReportCommand(command, targetSid, isDiagnostics); + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t Service3Housekeeping::prepareCollectionIntervalModificationCommand( - CommandMessage *command, object_id_t objectId, bool isDiagnostics, - const uint8_t *tcData, size_t tcDataLen) { - if(tcDataLen < sizeof(sid_t) + sizeof(float)) { - /* SID plus the size of the new collection interval. */ - return CommandingServiceBase::INVALID_TC; - } + CommandMessage* command, object_id_t objectId, bool isDiagnostics, const uint8_t* tcData, + size_t tcDataLen) { + if (tcDataLen < sizeof(sid_t) + sizeof(float)) { + /* SID plus the size of the new collection interval. */ + return CommandingServiceBase::INVALID_TC; + } - sid_t targetSid = buildSid(objectId, &tcData, &tcDataLen); - float newCollectionInterval = 0; - SerializeAdapter::deSerialize(&newCollectionInterval, &tcData, &tcDataLen, - SerializeIF::Endianness::BIG); - HousekeepingMessage::setCollectionIntervalModificationCommand(command, - targetSid, newCollectionInterval, isDiagnostics); - return HasReturnvaluesIF::RETURN_OK; + sid_t targetSid = buildSid(objectId, &tcData, &tcDataLen); + float newCollectionInterval = 0; + SerializeAdapter::deSerialize(&newCollectionInterval, &tcData, &tcDataLen, + SerializeIF::Endianness::BIG); + HousekeepingMessage::setCollectionIntervalModificationCommand( + command, targetSid, newCollectionInterval, isDiagnostics); + return HasReturnvaluesIF::RETURN_OK; } - ReturnValue_t Service3Housekeeping::handleReply(const CommandMessage* reply, - Command_t previousCommand, uint32_t *state, - CommandMessage* optionalNextCommand, object_id_t objectId, - bool *isStep) { - Command_t command = reply->getCommand(); - switch(command) { - - case(HousekeepingMessage::HK_REPORT): { - ReturnValue_t result = generateHkReply(reply, - static_cast(Subservice::HK_REPORT)); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return CommandingServiceBase::EXECUTION_COMPLETE; + Command_t previousCommand, uint32_t* state, + CommandMessage* optionalNextCommand, + object_id_t objectId, bool* isStep) { + Command_t command = reply->getCommand(); + switch (command) { + case (HousekeepingMessage::HK_REPORT): { + ReturnValue_t result = generateHkReply(reply, static_cast(Subservice::HK_REPORT)); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return CommandingServiceBase::EXECUTION_COMPLETE; } - case(HousekeepingMessage::DIAGNOSTICS_REPORT): { - ReturnValue_t result = generateHkReply(reply, - static_cast(Subservice::DIAGNOSTICS_REPORT)); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return CommandingServiceBase::EXECUTION_COMPLETE; + case (HousekeepingMessage::DIAGNOSTICS_REPORT): { + ReturnValue_t result = + generateHkReply(reply, static_cast(Subservice::DIAGNOSTICS_REPORT)); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return CommandingServiceBase::EXECUTION_COMPLETE; } - case(HousekeepingMessage::HK_DEFINITIONS_REPORT): { - return generateHkReply(reply, static_cast( - Subservice::HK_DEFINITIONS_REPORT)); - break; + case (HousekeepingMessage::HK_DEFINITIONS_REPORT): { + return generateHkReply(reply, static_cast(Subservice::HK_DEFINITIONS_REPORT)); + break; } - case(HousekeepingMessage::DIAGNOSTICS_DEFINITION_REPORT): { - return generateHkReply(reply, static_cast( - Subservice::DIAGNOSTICS_DEFINITION_REPORT)); - break; + case (HousekeepingMessage::DIAGNOSTICS_DEFINITION_REPORT): { + return generateHkReply(reply, + static_cast(Subservice::DIAGNOSTICS_DEFINITION_REPORT)); + break; } - case(HousekeepingMessage::HK_REQUEST_SUCCESS): { - return CommandingServiceBase::EXECUTION_COMPLETE; + case (HousekeepingMessage::HK_REQUEST_SUCCESS): { + return CommandingServiceBase::EXECUTION_COMPLETE; } - case(HousekeepingMessage::HK_REQUEST_FAILURE): { - failureParameter1 = objectId; - ReturnValue_t error = HasReturnvaluesIF::RETURN_FAILED; - HousekeepingMessage::getHkRequestFailureReply(reply,&error); - failureParameter2 = error; - return CommandingServiceBase::EXECUTION_COMPLETE; + case (HousekeepingMessage::HK_REQUEST_FAILURE): { + failureParameter1 = objectId; + ReturnValue_t error = HasReturnvaluesIF::RETURN_FAILED; + HousekeepingMessage::getHkRequestFailureReply(reply, &error); + failureParameter2 = error; + return CommandingServiceBase::EXECUTION_COMPLETE; } default: #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "Service3Housekeeping::handleReply: Invalid reply with " - << "reply command " << command << "!" << std::endl; + sif::warning << "Service3Housekeeping::handleReply: Invalid reply with " + << "reply command " << command << "!" << std::endl; #else - sif::printWarning("Service3Housekeeping::handleReply: Invalid reply with " - "reply command %hu!\n", command); + sif::printWarning( + "Service3Housekeeping::handleReply: Invalid reply with " + "reply command %hu!\n", + command); #endif - return CommandingServiceBase::INVALID_REPLY; - } - return HasReturnvaluesIF::RETURN_OK; + return CommandingServiceBase::INVALID_REPLY; + } + return HasReturnvaluesIF::RETURN_OK; } -void Service3Housekeeping::handleUnrequestedReply( - CommandMessage* reply) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - Command_t command = reply->getCommand(); +void Service3Housekeeping::handleUnrequestedReply(CommandMessage* reply) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + Command_t command = reply->getCommand(); - switch(command) { - - case(HousekeepingMessage::DIAGNOSTICS_REPORT): { - result = generateHkReply(reply, - static_cast(Subservice::DIAGNOSTICS_REPORT)); - break; + switch (command) { + case (HousekeepingMessage::DIAGNOSTICS_REPORT): { + result = generateHkReply(reply, static_cast(Subservice::DIAGNOSTICS_REPORT)); + break; } - case(HousekeepingMessage::HK_REPORT): { - result = generateHkReply(reply, - static_cast(Subservice::HK_REPORT)); - break; + case (HousekeepingMessage::HK_REPORT): { + result = generateHkReply(reply, static_cast(Subservice::HK_REPORT)); + break; } - case(HousekeepingMessage::HK_REQUEST_SUCCESS): { - break; + case (HousekeepingMessage::HK_REQUEST_SUCCESS): { + break; } - case(HousekeepingMessage::HK_REQUEST_FAILURE): { - break; + case (HousekeepingMessage::HK_REQUEST_FAILURE): { + break; } default: { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "Service3Housekeeping::handleUnrequestedReply: Invalid reply with reply " - "command " << command << "!" << std::endl; + sif::warning << "Service3Housekeeping::handleUnrequestedReply: Invalid reply with reply " + "command " + << command << "!" << std::endl; #else - sif::printWarning("Service3Housekeeping::handleUnrequestedReply: Invalid reply with " - "reply command %hu!\n", command); + sif::printWarning( + "Service3Housekeeping::handleUnrequestedReply: Invalid reply with " + "reply command %hu!\n", + command); #endif - return; - } + return; } + } - if(result != HasReturnvaluesIF::RETURN_OK) { - /* Configuration error */ + if (result != HasReturnvaluesIF::RETURN_OK) { + /* Configuration error */ #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "Service3Housekeeping::handleUnrequestedReply: Could not generate reply!" << - std::endl; + sif::warning << "Service3Housekeeping::handleUnrequestedReply: Could not generate reply!" + << std::endl; #else - sif::printWarning("Service3Housekeeping::handleUnrequestedReply: " - "Could not generate reply!\n"); + sif::printWarning( + "Service3Housekeeping::handleUnrequestedReply: " + "Could not generate reply!\n"); #endif - } + } } -MessageQueueId_t Service3Housekeeping::getHkQueue() const { - return commandQueue->getId(); +MessageQueueId_t Service3Housekeeping::getHkQueue() const { return commandQueue->getId(); } + +ReturnValue_t Service3Housekeeping::generateHkReply(const CommandMessage* hkMessage, + uint8_t subserviceId) { + store_address_t storeId; + + sid_t sid = HousekeepingMessage::getHkDataReply(hkMessage, &storeId); + auto resultPair = IPCStore->getData(storeId); + if (resultPair.first != HasReturnvaluesIF::RETURN_OK) { + return resultPair.first; + } + + HkPacket hkPacket(sid, resultPair.second.data(), resultPair.second.size()); + return sendTmPacket(static_cast(subserviceId), hkPacket.hkData, hkPacket.hkSize, nullptr, + 0); } -ReturnValue_t Service3Housekeeping::generateHkReply( - const CommandMessage* hkMessage, uint8_t subserviceId) { - store_address_t storeId; - - sid_t sid = HousekeepingMessage::getHkDataReply(hkMessage, &storeId); - auto resultPair = IPCStore->getData(storeId); - if(resultPair.first != HasReturnvaluesIF::RETURN_OK) { - return resultPair.first; - } - - HkPacket hkPacket(sid, resultPair.second.data(), resultPair.second.size()); - return sendTmPacket(static_cast(subserviceId), - hkPacket.hkData, hkPacket.hkSize, nullptr, 0); -} - -sid_t Service3Housekeeping::buildSid(object_id_t objectId, - const uint8_t** tcData, size_t* tcDataLen) { - sid_t targetSid; - targetSid.objectId = objectId; - // skip deserialization of object ID, was already done. - *tcData += sizeof(object_id_t); - *tcDataLen -= sizeof(object_id_t); - // size check is expected to be performed beforehand! - SerializeAdapter::deSerialize(&targetSid.ownerSetId, tcData, tcDataLen, - SerializeIF::Endianness::BIG); - return targetSid; +sid_t Service3Housekeeping::buildSid(object_id_t objectId, const uint8_t** tcData, + size_t* tcDataLen) { + sid_t targetSid; + targetSid.objectId = objectId; + // skip deserialization of object ID, was already done. + *tcData += sizeof(object_id_t); + *tcDataLen -= sizeof(object_id_t); + // size check is expected to be performed beforehand! + SerializeAdapter::deSerialize(&targetSid.ownerSetId, tcData, tcDataLen, + SerializeIF::Endianness::BIG); + return targetSid; } diff --git a/src/fsfw/pus/Service3Housekeeping.h b/src/fsfw/pus/Service3Housekeeping.h index d2dc6066..c1928891 100644 --- a/src/fsfw/pus/Service3Housekeeping.h +++ b/src/fsfw/pus/Service3Housekeeping.h @@ -23,83 +23,82 @@ * @author R. Mueller * @ingroup pus_services */ -class Service3Housekeeping: public CommandingServiceBase, - public AcceptsHkPacketsIF { -public: - static constexpr uint8_t NUM_OF_PARALLEL_COMMANDS = 4; - static constexpr uint16_t COMMAND_TIMEOUT_SECONDS = 60; +class Service3Housekeeping : public CommandingServiceBase, public AcceptsHkPacketsIF { + public: + static constexpr uint8_t NUM_OF_PARALLEL_COMMANDS = 4; + static constexpr uint16_t COMMAND_TIMEOUT_SECONDS = 60; - Service3Housekeeping(object_id_t objectId, uint16_t apid, uint8_t serviceId); - virtual~ Service3Housekeeping(); -protected: - /* CSB abstract functions implementation . See CSB documentation. */ - ReturnValue_t isValidSubservice(uint8_t subservice) override; - ReturnValue_t getMessageQueueAndObject(uint8_t subservice, - const uint8_t *tcData, size_t tcDataLen, MessageQueueId_t *id, - object_id_t *objectId) override; - ReturnValue_t prepareCommand(CommandMessage* message, - uint8_t subservice, const uint8_t *tcData, size_t tcDataLen, - uint32_t *state, object_id_t objectId) override; - ReturnValue_t handleReply(const CommandMessage* reply, - Command_t previousCommand, uint32_t *state, - CommandMessage* optionalNextCommand, object_id_t objectId, - bool *isStep) override; + Service3Housekeeping(object_id_t objectId, uint16_t apid, uint8_t serviceId); + virtual ~Service3Housekeeping(); - virtual MessageQueueId_t getHkQueue() const; -private: - enum class Subservice { - ENABLE_PERIODIC_HK_REPORT_GENERATION = 5, //!< [EXPORT] : [TC] - DISABLE_PERIODIC_HK_REPORT_GENERATION = 6, //!< [EXPORT] : [TC] + protected: + /* CSB abstract functions implementation . See CSB documentation. */ + ReturnValue_t isValidSubservice(uint8_t subservice) override; + ReturnValue_t getMessageQueueAndObject(uint8_t subservice, const uint8_t* tcData, + size_t tcDataLen, MessageQueueId_t* id, + object_id_t* objectId) override; + ReturnValue_t prepareCommand(CommandMessage* message, uint8_t subservice, const uint8_t* tcData, + size_t tcDataLen, uint32_t* state, object_id_t objectId) override; + ReturnValue_t handleReply(const CommandMessage* reply, Command_t previousCommand, uint32_t* state, + CommandMessage* optionalNextCommand, object_id_t objectId, + bool* isStep) override; - ENABLE_PERIODIC_DIAGNOSTICS_REPORT_GENERATION = 7, //!< [EXPORT] : [TC] - DISABLE_PERIODIC_DIAGNOSTICS_REPORT_GENERATION = 8, //!< [EXPORT] : [TC] + virtual MessageQueueId_t getHkQueue() const; - //! [EXPORT] : [TC] Report HK structure by supplying SID - REPORT_HK_REPORT_STRUCTURES = 9, - //! [EXPORT] : [TC] Report Diagnostics structure by supplying SID - REPORT_DIAGNOSTICS_REPORT_STRUCTURES = 11, + private: + enum class Subservice { + ENABLE_PERIODIC_HK_REPORT_GENERATION = 5, //!< [EXPORT] : [TC] + DISABLE_PERIODIC_HK_REPORT_GENERATION = 6, //!< [EXPORT] : [TC] - //! [EXPORT] : [TM] Report corresponding to Subservice 9 TC - HK_DEFINITIONS_REPORT = 10, - //! [EXPORT] : [TM] Report corresponding to Subservice 11 TC - DIAGNOSTICS_DEFINITION_REPORT = 12, + ENABLE_PERIODIC_DIAGNOSTICS_REPORT_GENERATION = 7, //!< [EXPORT] : [TC] + DISABLE_PERIODIC_DIAGNOSTICS_REPORT_GENERATION = 8, //!< [EXPORT] : [TC] - //! [EXPORT] : [TM] Core packet. Contains Housekeeping data - HK_REPORT = 25, - //! [EXPORT] : [TM] Core packet. Contains diagnostics data - DIAGNOSTICS_REPORT = 26, + //! [EXPORT] : [TC] Report HK structure by supplying SID + REPORT_HK_REPORT_STRUCTURES = 9, + //! [EXPORT] : [TC] Report Diagnostics structure by supplying SID + REPORT_DIAGNOSTICS_REPORT_STRUCTURES = 11, - /* PUS-C */ - GENERATE_ONE_PARAMETER_REPORT = 27, //!< [EXPORT] : [TC] - GENERATE_ONE_DIAGNOSTICS_REPORT = 28, //!< [EXPORT] : [TC] + //! [EXPORT] : [TM] Report corresponding to Subservice 9 TC + HK_DEFINITIONS_REPORT = 10, + //! [EXPORT] : [TM] Report corresponding to Subservice 11 TC + DIAGNOSTICS_DEFINITION_REPORT = 12, - MODIFY_PARAMETER_REPORT_COLLECTION_INTERVAL = 31, //!< [EXPORT] : [TC] - MODIFY_DIAGNOSTICS_REPORT_COLLECTION_INTERVAL = 32, //!< [EXPORT] : [TC] - }; + //! [EXPORT] : [TM] Core packet. Contains Housekeeping data + HK_REPORT = 25, + //! [EXPORT] : [TM] Core packet. Contains diagnostics data + DIAGNOSTICS_REPORT = 26, - ReturnValue_t checkAndAcquireTargetID(object_id_t* objectIdToSet, - const uint8_t* tcData, size_t tcDataLen); - ReturnValue_t checkInterfaceAndAcquireMessageQueue( - MessageQueueId_t* messageQueueToSet, object_id_t* objectId); + /* PUS-C */ + GENERATE_ONE_PARAMETER_REPORT = 27, //!< [EXPORT] : [TC] + GENERATE_ONE_DIAGNOSTICS_REPORT = 28, //!< [EXPORT] : [TC] - ReturnValue_t generateHkReply(const CommandMessage* hkMessage, - uint8_t subserviceId); - ReturnValue_t prepareReportingTogglingCommand(CommandMessage* command, - object_id_t objectId, bool enableReporting, bool isDiagnostics, - const uint8_t* tcData, size_t tcDataLen); - ReturnValue_t prepareStructureReportingCommand(CommandMessage* command, - object_id_t objectId, bool isDiagnostics, const uint8_t* tcData, - size_t tcDataLen); - ReturnValue_t prepareOneShotReportCommand(CommandMessage* command, - object_id_t objectId, bool isDiagnostics, const uint8_t* tcData, - size_t tcDataLen); - ReturnValue_t prepareCollectionIntervalModificationCommand( - CommandMessage* command, object_id_t objectId, bool isDiagnostics, - const uint8_t* tcData, size_t tcDataLen); + MODIFY_PARAMETER_REPORT_COLLECTION_INTERVAL = 31, //!< [EXPORT] : [TC] + MODIFY_DIAGNOSTICS_REPORT_COLLECTION_INTERVAL = 32, //!< [EXPORT] : [TC] + }; - void handleUnrequestedReply(CommandMessage* reply) override; - sid_t buildSid(object_id_t objectId, const uint8_t** tcData, - size_t* tcDataLen); + ReturnValue_t checkAndAcquireTargetID(object_id_t* objectIdToSet, const uint8_t* tcData, + size_t tcDataLen); + ReturnValue_t checkInterfaceAndAcquireMessageQueue(MessageQueueId_t* messageQueueToSet, + object_id_t* objectId); + + ReturnValue_t generateHkReply(const CommandMessage* hkMessage, uint8_t subserviceId); + ReturnValue_t prepareReportingTogglingCommand(CommandMessage* command, object_id_t objectId, + bool enableReporting, bool isDiagnostics, + const uint8_t* tcData, size_t tcDataLen); + ReturnValue_t prepareStructureReportingCommand(CommandMessage* command, object_id_t objectId, + bool isDiagnostics, const uint8_t* tcData, + size_t tcDataLen); + ReturnValue_t prepareOneShotReportCommand(CommandMessage* command, object_id_t objectId, + bool isDiagnostics, const uint8_t* tcData, + size_t tcDataLen); + ReturnValue_t prepareCollectionIntervalModificationCommand(CommandMessage* command, + object_id_t objectId, + bool isDiagnostics, + const uint8_t* tcData, + size_t tcDataLen); + + void handleUnrequestedReply(CommandMessage* reply) override; + sid_t buildSid(object_id_t objectId, const uint8_t** tcData, size_t* tcDataLen); }; #endif /* FSFW_PUS_SERVICE3HOUSEKEEPINGSERVICE_H_ */ diff --git a/src/fsfw/pus/Service5EventReporting.cpp b/src/fsfw/pus/Service5EventReporting.cpp index 2293ab20..4517bc26 100644 --- a/src/fsfw/pus/Service5EventReporting.cpp +++ b/src/fsfw/pus/Service5EventReporting.cpp @@ -1,106 +1,99 @@ #include "fsfw/pus/Service5EventReporting.h" -#include "fsfw/pus/servicepackets/Service5Packets.h" -#include "fsfw/serviceinterface/ServiceInterface.h" -#include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/events/EventManagerIF.h" #include "fsfw/ipc/QueueFactory.h" +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/pus/servicepackets/Service5Packets.h" +#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/tmtcpacket/pus/tm/TmPacketStored.h" - -Service5EventReporting::Service5EventReporting(object_id_t objectId, - uint16_t apid, uint8_t serviceId, size_t maxNumberReportsPerCycle, - uint32_t messageQueueDepth): - PusServiceBase(objectId, apid, serviceId), - maxNumberReportsPerCycle(maxNumberReportsPerCycle) { - eventQueue = QueueFactory::instance()->createMessageQueue(messageQueueDepth); +Service5EventReporting::Service5EventReporting(object_id_t objectId, uint16_t apid, + uint8_t serviceId, size_t maxNumberReportsPerCycle, + uint32_t messageQueueDepth) + : PusServiceBase(objectId, apid, serviceId), + maxNumberReportsPerCycle(maxNumberReportsPerCycle) { + eventQueue = QueueFactory::instance()->createMessageQueue(messageQueueDepth); } Service5EventReporting::~Service5EventReporting() { - QueueFactory::instance()->deleteMessageQueue(eventQueue); + QueueFactory::instance()->deleteMessageQueue(eventQueue); } ReturnValue_t Service5EventReporting::performService() { - EventMessage message; - ReturnValue_t status = RETURN_OK; - for(uint8_t counter = 0; - counter < maxNumberReportsPerCycle; - counter++) - { - // Receive messages even if reporting is disabled for now. - status = eventQueue->receiveMessage(&message); - if(status == MessageQueueIF::EMPTY) { - return HasReturnvaluesIF::RETURN_OK; - } + EventMessage message; + ReturnValue_t status = RETURN_OK; + for (uint8_t counter = 0; counter < maxNumberReportsPerCycle; counter++) { + // Receive messages even if reporting is disabled for now. + status = eventQueue->receiveMessage(&message); + if (status == MessageQueueIF::EMPTY) { + return HasReturnvaluesIF::RETURN_OK; + } - if(enableEventReport) { - status = generateEventReport(message); - if(status != HasReturnvaluesIF::RETURN_OK) { - return status; - } - } - } + if (enableEventReport) { + status = generateEventReport(message); + if (status != HasReturnvaluesIF::RETURN_OK) { + return status; + } + } + } #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "Service5EventReporting::generateEventReport: Too many events" << std::endl; + sif::warning << "Service5EventReporting::generateEventReport: Too many events" << std::endl; #endif - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } - -ReturnValue_t Service5EventReporting::generateEventReport( - EventMessage message) -{ - EventReport report(message.getEventId(),message.getReporter(), - message.getParameter1(),message.getParameter2()); +ReturnValue_t Service5EventReporting::generateEventReport(EventMessage message) { + EventReport report(message.getEventId(), message.getReporter(), message.getParameter1(), + message.getParameter2()); #if FSFW_USE_PUS_C_TELEMETRY == 0 - TmPacketStoredPusA tmPacket(PusServiceBase::apid, PusServiceBase::serviceId, - message.getSeverity(), packetSubCounter++, &report); + TmPacketStoredPusA tmPacket(PusServiceBase::apid, PusServiceBase::serviceId, + message.getSeverity(), packetSubCounter++, &report); #else - TmPacketStoredPusC tmPacket(PusServiceBase::apid, PusServiceBase::serviceId, - message.getSeverity(), packetSubCounter++, &report); + TmPacketStoredPusC tmPacket(PusServiceBase::apid, PusServiceBase::serviceId, + message.getSeverity(), packetSubCounter++, &report); #endif - ReturnValue_t result = tmPacket.sendPacket( - requestQueue->getDefaultDestination(),requestQueue->getId()); - if(result != HasReturnvaluesIF::RETURN_OK) { + ReturnValue_t result = + tmPacket.sendPacket(requestQueue->getDefaultDestination(), requestQueue->getId()); + if (result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "Service5EventReporting::generateEventReport: " - "Could not send TM packet" << std::endl; + sif::warning << "Service5EventReporting::generateEventReport: " + "Could not send TM packet" + << std::endl; #else - sif::printWarning("Service5EventReporting::generateEventReport: " - "Could not send TM packet\n"); + sif::printWarning( + "Service5EventReporting::generateEventReport: " + "Could not send TM packet\n"); #endif - } - return result; + } + return result; } ReturnValue_t Service5EventReporting::handleRequest(uint8_t subservice) { - switch(subservice) { - case Subservice::ENABLE: { - enableEventReport = true; - return HasReturnvaluesIF::RETURN_OK; - } - case Subservice::DISABLE: { - enableEventReport = false; - return HasReturnvaluesIF::RETURN_OK; - } - default: - return AcceptsTelecommandsIF::INVALID_SUBSERVICE; - } + switch (subservice) { + case Subservice::ENABLE: { + enableEventReport = true; + return HasReturnvaluesIF::RETURN_OK; + } + case Subservice::DISABLE: { + enableEventReport = false; + return HasReturnvaluesIF::RETURN_OK; + } + default: + return AcceptsTelecommandsIF::INVALID_SUBSERVICE; + } } - // In addition to the default PUSServiceBase initialization, this service needs // to be registered to the event manager to listen for events. ReturnValue_t Service5EventReporting::initialize() { - EventManagerIF* manager = ObjectManager::instance()->get( - objects::EVENT_MANAGER); - if (manager == NULL) { - return RETURN_FAILED; - } - // register Service 5 as listener for events - ReturnValue_t result = manager->registerListener(eventQueue->getId(),true); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return PusServiceBase::initialize(); + EventManagerIF* manager = ObjectManager::instance()->get(objects::EVENT_MANAGER); + if (manager == NULL) { + return RETURN_FAILED; + } + // register Service 5 as listener for events + ReturnValue_t result = manager->registerListener(eventQueue->getId(), true); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return PusServiceBase::initialize(); } diff --git a/src/fsfw/pus/Service5EventReporting.h b/src/fsfw/pus/Service5EventReporting.h index 35ff34b6..74264130 100644 --- a/src/fsfw/pus/Service5EventReporting.h +++ b/src/fsfw/pus/Service5EventReporting.h @@ -1,8 +1,8 @@ #ifndef FSFW_PUS_SERVICE5EVENTREPORTING_H_ #define FSFW_PUS_SERVICE5EVENTREPORTING_H_ -#include "fsfw/tmtcservices/PusServiceBase.h" #include "fsfw/events/EventMessage.h" +#include "fsfw/tmtcservices/PusServiceBase.h" /** * @brief Report on-board events like information or errors @@ -38,50 +38,48 @@ * @author R. Mueller * @ingroup pus_services */ -class Service5EventReporting: public PusServiceBase { -public: +class Service5EventReporting : public PusServiceBase { + public: + Service5EventReporting(object_id_t objectId, uint16_t apid, uint8_t serviceId, + size_t maxNumberReportsPerCycle = 10, uint32_t messageQueueDepth = 10); + virtual ~Service5EventReporting(); - Service5EventReporting(object_id_t objectId, uint16_t apid, - uint8_t serviceId, size_t maxNumberReportsPerCycle = 10, - uint32_t messageQueueDepth = 10); - virtual ~Service5EventReporting(); + /*** + * Check for events and generate event reports if required. + * @return + */ + ReturnValue_t performService() override; - /*** - * Check for events and generate event reports if required. - * @return - */ - ReturnValue_t performService() override; + /*** + * Turn event generation on or off. + * @return + */ + ReturnValue_t handleRequest(uint8_t subservice) override; - /*** - * Turn event generation on or off. - * @return - */ - ReturnValue_t handleRequest(uint8_t subservice) override; + /** + * The default PusServiceBase initialize has been overridden but is still + * executed. Registers this service as a listener for events at the + * EventManager. + * @return + */ + ReturnValue_t initialize() override; - /** - * The default PusServiceBase initialize has been overridden but is still - * executed. Registers this service as a listener for events at the - * EventManager. - * @return - */ - ReturnValue_t initialize() override; + enum Subservice : uint8_t { + NORMAL_REPORT = 1, //!< [EXPORT] : [REPLY] Generate normal report + ERROR_LOW_SEVERITY = 2, //!< [EXPORT] : [REPLY] Generate error report with low severity + ERROR_MED_SEVERITY = 3, //!< [EXPORT] : [REPLY] Generate error report with medium severity + ERROR_HIGH_SEVERITY = 4, //!< [EXPORT] : [REPLY] Generate error report with high severity + ENABLE = 5, //!< [EXPORT] : [COMMAND] Enable report generation + DISABLE = 6 //!< [EXPORT] : [COMMAND] Disable report generation + }; - enum Subservice: uint8_t { - NORMAL_REPORT = 1, //!< [EXPORT] : [REPLY] Generate normal report - ERROR_LOW_SEVERITY = 2, //!< [EXPORT] : [REPLY] Generate error report with low severity - ERROR_MED_SEVERITY = 3, //!< [EXPORT] : [REPLY] Generate error report with medium severity - ERROR_HIGH_SEVERITY = 4, //!< [EXPORT] : [REPLY] Generate error report with high severity - ENABLE = 5, //!< [EXPORT] : [COMMAND] Enable report generation - DISABLE = 6 //!< [EXPORT] : [COMMAND] Disable report generation - }; + private: + uint16_t packetSubCounter = 0; + MessageQueueIF* eventQueue = nullptr; + bool enableEventReport = true; + const uint8_t maxNumberReportsPerCycle; -private: - uint16_t packetSubCounter = 0; - MessageQueueIF* eventQueue = nullptr; - bool enableEventReport = true; - const uint8_t maxNumberReportsPerCycle; - - ReturnValue_t generateEventReport(EventMessage message); + ReturnValue_t generateEventReport(EventMessage message); }; #endif /* FSFW_PUS_SERVICE5EVENTREPORTING_H_ */ diff --git a/src/fsfw/pus/Service8FunctionManagement.cpp b/src/fsfw/pus/Service8FunctionManagement.cpp index 48820d6e..be8d9058 100644 --- a/src/fsfw/pus/Service8FunctionManagement.cpp +++ b/src/fsfw/pus/Service8FunctionManagement.cpp @@ -1,153 +1,151 @@ #include "fsfw/pus/Service8FunctionManagement.h" -#include "fsfw/pus/servicepackets/Service8Packets.h" -#include "fsfw/objectmanager/ObjectManager.h" -#include "fsfw/objectmanager/SystemObjectIF.h" #include "fsfw/action/HasActionsIF.h" #include "fsfw/devicehandlers/DeviceHandlerIF.h" +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/objectmanager/SystemObjectIF.h" +#include "fsfw/pus/servicepackets/Service8Packets.h" #include "fsfw/serialize/SerializeAdapter.h" #include "fsfw/serviceinterface/ServiceInterface.h" -Service8FunctionManagement::Service8FunctionManagement(object_id_t objectId, - uint16_t apid, uint8_t serviceId, uint8_t numParallelCommands, - uint16_t commandTimeoutSeconds): - CommandingServiceBase(objectId, apid, serviceId, numParallelCommands, - commandTimeoutSeconds) {} +Service8FunctionManagement::Service8FunctionManagement(object_id_t objectId, uint16_t apid, + uint8_t serviceId, + uint8_t numParallelCommands, + uint16_t commandTimeoutSeconds) + : CommandingServiceBase(objectId, apid, serviceId, numParallelCommands, commandTimeoutSeconds) { +} Service8FunctionManagement::~Service8FunctionManagement() {} - -ReturnValue_t Service8FunctionManagement::isValidSubservice( - uint8_t subservice) { - switch(static_cast(subservice)) { - case Subservice::COMMAND_DIRECT_COMMANDING: - return HasReturnvaluesIF::RETURN_OK; - default: - return AcceptsTelecommandsIF::INVALID_SUBSERVICE; - } +ReturnValue_t Service8FunctionManagement::isValidSubservice(uint8_t subservice) { + switch (static_cast(subservice)) { + case Subservice::COMMAND_DIRECT_COMMANDING: + return HasReturnvaluesIF::RETURN_OK; + default: + return AcceptsTelecommandsIF::INVALID_SUBSERVICE; + } } -ReturnValue_t Service8FunctionManagement::getMessageQueueAndObject( - uint8_t subservice, const uint8_t* tcData, size_t tcDataLen, - MessageQueueId_t* id, object_id_t* objectId) { - if(tcDataLen < sizeof(object_id_t)) { - return CommandingServiceBase::INVALID_TC; - } - // Can't fail, size was checked before - SerializeAdapter::deSerialize(objectId, &tcData, &tcDataLen, SerializeIF::Endianness::BIG); +ReturnValue_t Service8FunctionManagement::getMessageQueueAndObject(uint8_t subservice, + const uint8_t* tcData, + size_t tcDataLen, + MessageQueueId_t* id, + object_id_t* objectId) { + if (tcDataLen < sizeof(object_id_t)) { + return CommandingServiceBase::INVALID_TC; + } + // Can't fail, size was checked before + SerializeAdapter::deSerialize(objectId, &tcData, &tcDataLen, SerializeIF::Endianness::BIG); - return checkInterfaceAndAcquireMessageQueue(id,objectId); + return checkInterfaceAndAcquireMessageQueue(id, objectId); } ReturnValue_t Service8FunctionManagement::checkInterfaceAndAcquireMessageQueue( - MessageQueueId_t* messageQueueToSet, object_id_t* objectId) { - // check HasActionIF property of target - HasActionsIF* possibleTarget = ObjectManager::instance()->get(*objectId); - if(possibleTarget == nullptr){ - return CommandingServiceBase::INVALID_OBJECT; - } - *messageQueueToSet = possibleTarget->getCommandQueue(); - return HasReturnvaluesIF::RETURN_OK; + MessageQueueId_t* messageQueueToSet, object_id_t* objectId) { + // check HasActionIF property of target + HasActionsIF* possibleTarget = ObjectManager::instance()->get(*objectId); + if (possibleTarget == nullptr) { + return CommandingServiceBase::INVALID_OBJECT; + } + *messageQueueToSet = possibleTarget->getCommandQueue(); + return HasReturnvaluesIF::RETURN_OK; } - -ReturnValue_t Service8FunctionManagement::prepareCommand( - CommandMessage* message, uint8_t subservice, const uint8_t* tcData, - size_t tcDataLen, uint32_t* state, object_id_t objectId) { - return prepareDirectCommand(message, tcData, tcDataLen); +ReturnValue_t Service8FunctionManagement::prepareCommand(CommandMessage* message, + uint8_t subservice, const uint8_t* tcData, + size_t tcDataLen, uint32_t* state, + object_id_t objectId) { + return prepareDirectCommand(message, tcData, tcDataLen); } -ReturnValue_t Service8FunctionManagement::prepareDirectCommand( - CommandMessage *message, const uint8_t *tcData, size_t tcDataLen) { - if(message == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - if(tcDataLen < sizeof(object_id_t) + sizeof(ActionId_t)) { +ReturnValue_t Service8FunctionManagement::prepareDirectCommand(CommandMessage* message, + const uint8_t* tcData, + size_t tcDataLen) { + if (message == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if (tcDataLen < sizeof(object_id_t) + sizeof(ActionId_t)) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "Service8FunctionManagement::prepareDirectCommand:" - << " TC size smaller thant minimum size of direct command." - << std::endl; + sif::debug << "Service8FunctionManagement::prepareDirectCommand:" + << " TC size smaller thant minimum size of direct command." << std::endl; #endif - return CommandingServiceBase::INVALID_TC; - } + return CommandingServiceBase::INVALID_TC; + } - // Create direct command instance by extracting data from Telecommand - DirectCommand command(tcData, tcDataLen); + // Create direct command instance by extracting data from Telecommand + DirectCommand command(tcData, tcDataLen); - // store additional parameters into the IPC Store - store_address_t parameterAddress; - ReturnValue_t result = IPCStore->addData(¶meterAddress, - command.getParameters(),command.getParametersSize()); + // store additional parameters into the IPC Store + store_address_t parameterAddress; + ReturnValue_t result = + IPCStore->addData(¶meterAddress, command.getParameters(), command.getParametersSize()); - // setCommand expects a Command Message, an Action ID and a store adress - // pointing to additional parameters - ActionMessage::setCommand(message,command.getActionId(),parameterAddress); - return result; + // setCommand expects a Command Message, an Action ID and a store adress + // pointing to additional parameters + ActionMessage::setCommand(message, command.getActionId(), parameterAddress); + return result; } +ReturnValue_t Service8FunctionManagement::handleReply(const CommandMessage* reply, + Command_t previousCommand, uint32_t* state, + CommandMessage* optionalNextCommand, + object_id_t objectId, bool* isStep) { + Command_t replyId = reply->getCommand(); + ReturnValue_t result = HasReturnvaluesIF::RETURN_FAILED; + ActionId_t actionId = ActionMessage::getActionId(reply); + ReturnValue_t returnCode = ActionMessage::getReturnCode(reply); -ReturnValue_t Service8FunctionManagement::handleReply( - const CommandMessage* reply, Command_t previousCommand, - uint32_t* state, CommandMessage* optionalNextCommand, - object_id_t objectId, bool* isStep) { - Command_t replyId = reply->getCommand(); - ReturnValue_t result = HasReturnvaluesIF::RETURN_FAILED; - ActionId_t actionId = ActionMessage::getActionId(reply); - ReturnValue_t returnCode = ActionMessage::getReturnCode(reply); - - switch(replyId) { - case ActionMessage::COMPLETION_SUCCESS: { - DirectReply completionReply(objectId, actionId,returnCode); - result = CommandingServiceBase::EXECUTION_COMPLETE; - break; - } - case ActionMessage::STEP_SUCCESS: { - *isStep = true; - result = HasReturnvaluesIF::RETURN_OK; - break; - } - case ActionMessage::DATA_REPLY: { - /* Multiple data replies are possible, so declare data reply as step */ - *isStep = true; - result = handleDataReply(reply, objectId, actionId); - break; - } - case ActionMessage::STEP_FAILED: - *isStep = true; - /* No break, falls through */ - case ActionMessage::COMPLETION_FAILED: - result = ActionMessage::getReturnCode(reply); - break; - default: - result = INVALID_REPLY; - } - return result; + switch (replyId) { + case ActionMessage::COMPLETION_SUCCESS: { + DirectReply completionReply(objectId, actionId, returnCode); + result = CommandingServiceBase::EXECUTION_COMPLETE; + break; + } + case ActionMessage::STEP_SUCCESS: { + *isStep = true; + result = HasReturnvaluesIF::RETURN_OK; + break; + } + case ActionMessage::DATA_REPLY: { + /* Multiple data replies are possible, so declare data reply as step */ + *isStep = true; + result = handleDataReply(reply, objectId, actionId); + break; + } + case ActionMessage::STEP_FAILED: + *isStep = true; + /* No break, falls through */ + case ActionMessage::COMPLETION_FAILED: + result = ActionMessage::getReturnCode(reply); + break; + default: + result = INVALID_REPLY; + } + return result; } -ReturnValue_t Service8FunctionManagement::handleDataReply( - const CommandMessage* reply, object_id_t objectId, - ActionId_t actionId) { - store_address_t storeId = ActionMessage::getStoreId(reply); - size_t size = 0; - const uint8_t * buffer = nullptr; - ReturnValue_t result = IPCStore->getData(storeId, &buffer, &size); - if(result != RETURN_OK) { +ReturnValue_t Service8FunctionManagement::handleDataReply(const CommandMessage* reply, + object_id_t objectId, + ActionId_t actionId) { + store_address_t storeId = ActionMessage::getStoreId(reply); + size_t size = 0; + const uint8_t* buffer = nullptr; + ReturnValue_t result = IPCStore->getData(storeId, &buffer, &size); + if (result != RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Service 8: Could not retrieve data for data reply" - << std::endl; + sif::error << "Service 8: Could not retrieve data for data reply" << std::endl; #endif - return result; - } - DataReply dataReply(objectId, actionId, buffer, size); - result = sendTmPacket(static_cast( - Subservice::REPLY_DIRECT_COMMANDING_DATA), &dataReply); - - auto deletionResult = IPCStore->deleteData(storeId); - if(deletionResult != HasReturnvaluesIF::RETURN_OK) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "Service8FunctionManagement::handleReply: Deletion" - << " of data in pool failed." << std::endl; -#endif - } return result; + } + DataReply dataReply(objectId, actionId, buffer, size); + result = sendTmPacket(static_cast(Subservice::REPLY_DIRECT_COMMANDING_DATA), &dataReply); + + auto deletionResult = IPCStore->deleteData(storeId); + if (deletionResult != HasReturnvaluesIF::RETURN_OK) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "Service8FunctionManagement::handleReply: Deletion" + << " of data in pool failed." << std::endl; +#endif + } + return result; } diff --git a/src/fsfw/pus/Service8FunctionManagement.h b/src/fsfw/pus/Service8FunctionManagement.h index debdf636..649b3257 100644 --- a/src/fsfw/pus/Service8FunctionManagement.h +++ b/src/fsfw/pus/Service8FunctionManagement.h @@ -28,42 +28,38 @@ * * @ingroup pus_services */ -class Service8FunctionManagement : public CommandingServiceBase -{ -public: - Service8FunctionManagement(object_id_t objectId, uint16_t apid, - uint8_t serviceId, uint8_t numParallelCommands = 4, - uint16_t commandTimeoutSeconds = 60); - virtual ~Service8FunctionManagement(); +class Service8FunctionManagement : public CommandingServiceBase { + public: + Service8FunctionManagement(object_id_t objectId, uint16_t apid, uint8_t serviceId, + uint8_t numParallelCommands = 4, uint16_t commandTimeoutSeconds = 60); + virtual ~Service8FunctionManagement(); -protected: - /* CSB abstract functions implementation . See CSB documentation. */ - ReturnValue_t isValidSubservice(uint8_t subservice) override; - ReturnValue_t getMessageQueueAndObject(uint8_t subservice, - const uint8_t *tcData, size_t tcDataLen, MessageQueueId_t *id, - object_id_t *objectId) override; - ReturnValue_t prepareCommand(CommandMessage* message, - uint8_t subservice, const uint8_t *tcData, size_t tcDataLen, - uint32_t *state, object_id_t objectId) override; - ReturnValue_t handleReply(const CommandMessage* reply, - Command_t previousCommand, uint32_t *state, - CommandMessage* optionalNextCommand, object_id_t objectId, - bool *isStep) override; + protected: + /* CSB abstract functions implementation . See CSB documentation. */ + ReturnValue_t isValidSubservice(uint8_t subservice) override; + ReturnValue_t getMessageQueueAndObject(uint8_t subservice, const uint8_t* tcData, + size_t tcDataLen, MessageQueueId_t* id, + object_id_t* objectId) override; + ReturnValue_t prepareCommand(CommandMessage* message, uint8_t subservice, const uint8_t* tcData, + size_t tcDataLen, uint32_t* state, object_id_t objectId) override; + ReturnValue_t handleReply(const CommandMessage* reply, Command_t previousCommand, uint32_t* state, + CommandMessage* optionalNextCommand, object_id_t objectId, + bool* isStep) override; -private: - enum class Subservice { - //!< [EXPORT] : [COMMAND] Functional commanding - COMMAND_DIRECT_COMMANDING = 128, - //!< [EXPORT] : [REPLY] Data reply - REPLY_DIRECT_COMMANDING_DATA = 130, - }; + private: + enum class Subservice { + //!< [EXPORT] : [COMMAND] Functional commanding + COMMAND_DIRECT_COMMANDING = 128, + //!< [EXPORT] : [REPLY] Data reply + REPLY_DIRECT_COMMANDING_DATA = 130, + }; - ReturnValue_t checkInterfaceAndAcquireMessageQueue( - MessageQueueId_t* messageQueueToSet, object_id_t* objectId); - ReturnValue_t prepareDirectCommand(CommandMessage* message, - const uint8_t* tcData, size_t tcDataLen); - ReturnValue_t handleDataReply(const CommandMessage* reply, - object_id_t objectId, ActionId_t actionId); + ReturnValue_t checkInterfaceAndAcquireMessageQueue(MessageQueueId_t* messageQueueToSet, + object_id_t* objectId); + ReturnValue_t prepareDirectCommand(CommandMessage* message, const uint8_t* tcData, + size_t tcDataLen); + ReturnValue_t handleDataReply(const CommandMessage* reply, object_id_t objectId, + ActionId_t actionId); }; #endif /* FSFW_PUS_SERVICE8FUNCTIONMANAGEMENT_H_ */ diff --git a/src/fsfw/pus/Service9TimeManagement.cpp b/src/fsfw/pus/Service9TimeManagement.cpp index 619b2405..86eef93a 100644 --- a/src/fsfw/pus/Service9TimeManagement.cpp +++ b/src/fsfw/pus/Service9TimeManagement.cpp @@ -1,58 +1,49 @@ #include "fsfw/pus/Service9TimeManagement.h" -#include "fsfw/pus/servicepackets/Service9Packets.h" -#include "fsfw/timemanager/CCSDSTime.h" #include "fsfw/events/EventManagerIF.h" +#include "fsfw/pus/servicepackets/Service9Packets.h" #include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/timemanager/CCSDSTime.h" - -Service9TimeManagement::Service9TimeManagement(object_id_t objectId, - uint16_t apid, uint8_t serviceId) : - PusServiceBase(objectId, apid , serviceId) { -} +Service9TimeManagement::Service9TimeManagement(object_id_t objectId, uint16_t apid, + uint8_t serviceId) + : PusServiceBase(objectId, apid, serviceId) {} Service9TimeManagement::~Service9TimeManagement() {} -ReturnValue_t Service9TimeManagement::performService() { - return RETURN_OK; -} +ReturnValue_t Service9TimeManagement::performService() { return RETURN_OK; } ReturnValue_t Service9TimeManagement::handleRequest(uint8_t subservice) { - switch(subservice){ - case SUBSERVICE::SET_TIME:{ - return setTime(); - } - default: - return AcceptsTelecommandsIF::INVALID_SUBSERVICE; - } + switch (subservice) { + case SUBSERVICE::SET_TIME: { + return setTime(); + } + default: + return AcceptsTelecommandsIF::INVALID_SUBSERVICE; + } } ReturnValue_t Service9TimeManagement::setTime() { - Clock::TimeOfDay_t timeToSet; - TimePacket timePacket(currentPacket.getApplicationData(), - currentPacket.getApplicationDataSize()); - ReturnValue_t result = CCSDSTime::convertFromCcsds(&timeToSet, - timePacket.getTime(), timePacket.getTimeSize()); - if(result != RETURN_OK) { - triggerEvent(CLOCK_SET_FAILURE, result, 0); - return result; - } + Clock::TimeOfDay_t timeToSet; + TimePacket timePacket(currentPacket.getApplicationData(), currentPacket.getApplicationDataSize()); + ReturnValue_t result = + CCSDSTime::convertFromCcsds(&timeToSet, timePacket.getTime(), timePacket.getTimeSize()); + if (result != RETURN_OK) { + triggerEvent(CLOCK_SET_FAILURE, result, 0); + return result; + } - uint32_t formerUptime; - Clock::getUptime(&formerUptime); - result = Clock::setClock(&timeToSet); + uint32_t formerUptime; + Clock::getUptime(&formerUptime); + result = Clock::setClock(&timeToSet); - if(result == RETURN_OK) { - uint32_t newUptime; - Clock::getUptime(&newUptime); - triggerEvent(CLOCK_SET,newUptime,formerUptime); - return RETURN_OK; - } - else { - triggerEvent(CLOCK_SET_FAILURE, result, 0); - return RETURN_FAILED; - } + if (result == RETURN_OK) { + uint32_t newUptime; + Clock::getUptime(&newUptime); + triggerEvent(CLOCK_SET, newUptime, formerUptime); + return RETURN_OK; + } else { + triggerEvent(CLOCK_SET_FAILURE, result, 0); + return RETURN_FAILED; + } } - - - diff --git a/src/fsfw/pus/Service9TimeManagement.h b/src/fsfw/pus/Service9TimeManagement.h index d8e183a4..9369e207 100644 --- a/src/fsfw/pus/Service9TimeManagement.h +++ b/src/fsfw/pus/Service9TimeManagement.h @@ -3,39 +3,36 @@ #include "fsfw/tmtcservices/PusServiceBase.h" -class Service9TimeManagement: public PusServiceBase { -public: +class Service9TimeManagement : public PusServiceBase { + public: + static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PUS_SERVICE_9; + static constexpr Event CLOCK_SET = + MAKE_EVENT(0, severity::INFO); //!< Clock has been set. P1: New Uptime. P2: Old Uptime + static constexpr Event CLOCK_SET_FAILURE = + MAKE_EVENT(1, severity::LOW); //!< Clock could not be set. P1: Returncode. - static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PUS_SERVICE_9; - static constexpr Event CLOCK_SET = MAKE_EVENT(0, severity::INFO); //!< Clock has been set. P1: New Uptime. P2: Old Uptime - static constexpr Event CLOCK_SET_FAILURE = MAKE_EVENT(1, severity::LOW); //!< Clock could not be set. P1: Returncode. + static constexpr uint8_t CLASS_ID = CLASS_ID::PUS_SERVICE_9; - static constexpr uint8_t CLASS_ID = CLASS_ID::PUS_SERVICE_9; + /** + * @brief This service provides the capability to set the on-board time. + */ + Service9TimeManagement(object_id_t objectId, uint16_t apid, uint8_t serviceId); - /** - * @brief This service provides the capability to set the on-board time. - */ - Service9TimeManagement(object_id_t objectId, uint16_t apid, - uint8_t serviceId); + virtual ~Service9TimeManagement(); - virtual ~Service9TimeManagement(); + virtual ReturnValue_t performService() override; - virtual ReturnValue_t performService() override; + /** + * @brief Sets the onboard-time by retrieving the time to set from TC[9,128]. + */ + virtual ReturnValue_t handleRequest(uint8_t subservice) override; - /** - * @brief Sets the onboard-time by retrieving the time to set from TC[9,128]. - */ - virtual ReturnValue_t handleRequest(uint8_t subservice) override; - - virtual ReturnValue_t setTime(); -private: - - enum SUBSERVICE { - SET_TIME = 128 //!< [EXPORT] : [COMMAND] Time command in ASCII, CUC or CDS format - }; + virtual ReturnValue_t setTime(); + private: + enum SUBSERVICE { + SET_TIME = 128 //!< [EXPORT] : [COMMAND] Time command in ASCII, CUC or CDS format + }; }; - - #endif /* FSFW_PUS_SERVICE9TIMEMANAGEMENT_H_ */ diff --git a/src/fsfw/pus/servicepackets/Service1Packets.h b/src/fsfw/pus/servicepackets/Service1Packets.h index 02ae339f..df70f670 100644 --- a/src/fsfw/pus/servicepackets/Service1Packets.h +++ b/src/fsfw/pus/servicepackets/Service1Packets.h @@ -16,151 +16,149 @@ * @brief Subservice 2, 4, 6, 8 * @ingroup spacepackets */ -class FailureReport: public SerializeIF { //!< [EXPORT] : [SUBSERVICE] 2, 4, 6, 8 -public: - FailureReport(uint8_t failureSubtype_, uint16_t packetId_, - uint16_t packetSequenceControl_, uint8_t stepNumber_, - ReturnValue_t errorCode_, uint32_t errorParameter1_, - uint32_t errorParameter2_) : - packetId(packetId_), packetSequenceControl(packetSequenceControl_), - stepNumber(stepNumber_), errorCode(errorCode_), - errorParameter1(errorParameter1_), errorParameter2(errorParameter2_), - failureSubtype(failureSubtype_) {} +class FailureReport : public SerializeIF { //!< [EXPORT] : [SUBSERVICE] 2, 4, 6, 8 + public: + FailureReport(uint8_t failureSubtype_, uint16_t packetId_, uint16_t packetSequenceControl_, + uint8_t stepNumber_, ReturnValue_t errorCode_, uint32_t errorParameter1_, + uint32_t errorParameter2_) + : packetId(packetId_), + packetSequenceControl(packetSequenceControl_), + stepNumber(stepNumber_), + errorCode(errorCode_), + errorParameter1(errorParameter1_), + errorParameter2(errorParameter2_), + failureSubtype(failureSubtype_) {} - /** - * This function is called by the FSFW when calling the tm packet send - * function and supplying the SerializeIF* as parameter - * @param buffer Object content is serialized into the buffer - * @param size - * @param max_size - * @param bigEndian - * @return - */ - virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, SerializeIF::Endianness streamEndianness - ) const override { - ReturnValue_t result = SerializeAdapter::serialize(&packetId, buffer, - size, maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::serialize(&packetSequenceControl, buffer, - size, maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if (failureSubtype == tc_verification::PROGRESS_FAILURE) { - result = SerializeAdapter::serialize(&stepNumber, buffer, size, - maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - } - result = SerializeAdapter::serialize(&errorCode, buffer, size, - maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::serialize(&errorParameter1, buffer, size, - maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + /** + * This function is called by the FSFW when calling the tm packet send + * function and supplying the SerializeIF* as parameter + * @param buffer Object content is serialized into the buffer + * @param size + * @param max_size + * @param bigEndian + * @return + */ + virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + SerializeIF::Endianness streamEndianness) const override { + ReturnValue_t result = + SerializeAdapter::serialize(&packetId, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::serialize(&packetSequenceControl, buffer, size, maxSize, + streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (failureSubtype == tc_verification::PROGRESS_FAILURE) { + result = SerializeAdapter::serialize(&stepNumber, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + } + result = SerializeAdapter::serialize(&errorCode, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::serialize(&errorParameter1, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - result = SerializeAdapter::serialize(&errorParameter2, buffer, size, - maxSize, streamEndianness); - return result; - } + result = SerializeAdapter::serialize(&errorParameter2, buffer, size, maxSize, streamEndianness); + return result; + } + virtual size_t getSerializedSize() const { + size_t size = 0; + size += SerializeAdapter::getSerializedSize(&packetId); + size += sizeof(packetSequenceControl); + if (failureSubtype == tc_verification::PROGRESS_FAILURE) { + size += SerializeAdapter::getSerializedSize(&stepNumber); + } + size += SerializeAdapter::getSerializedSize(&errorCode); + size += SerializeAdapter::getSerializedSize(&errorParameter1); + size += SerializeAdapter::getSerializedSize(&errorParameter2); + return size; + } - virtual size_t getSerializedSize() const { - size_t size = 0; - size += SerializeAdapter::getSerializedSize(&packetId); - size += sizeof(packetSequenceControl); - if(failureSubtype==tc_verification::PROGRESS_FAILURE){ - size += SerializeAdapter::getSerializedSize(&stepNumber); - } - size += SerializeAdapter::getSerializedSize(&errorCode); - size += SerializeAdapter::getSerializedSize(&errorParameter1); - size += SerializeAdapter::getSerializedSize(&errorParameter2); - return size; - } + /** + * Deserialization is not allowed for a report. + * @param buffer + * @param size + * @param bigEndian + * @return + */ + ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + SerializeIF::Endianness streamEndianness) override { + return HasReturnvaluesIF::RETURN_FAILED; + } - /** - * Deserialization is not allowed for a report. - * @param buffer - * @param size - * @param bigEndian - * @return - */ - ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - SerializeIF::Endianness streamEndianness) override { - return HasReturnvaluesIF::RETURN_FAILED; - } -private: - uint16_t packetId; //!< [EXPORT] : [COMMENT] Packet ID of respective Telecommand - uint16_t packetSequenceControl; //!< [EXPORT] : [COMMENT] Packet SSC of respective Telecommand - uint8_t stepNumber; //!< [EXPORT] : [OPTIONAL][SUBSERVICE] 6 - ReturnValue_t errorCode; //!< [EXPORT] : [COMMENT] Error code which can be looked up in generated error code file - uint32_t errorParameter1; - uint32_t errorParameter2; - const uint8_t failureSubtype; //!< [EXPORT] : [IGNORE] + private: + uint16_t packetId; //!< [EXPORT] : [COMMENT] Packet ID of respective Telecommand + uint16_t packetSequenceControl; //!< [EXPORT] : [COMMENT] Packet SSC of respective Telecommand + uint8_t stepNumber; //!< [EXPORT] : [OPTIONAL][SUBSERVICE] 6 + ReturnValue_t errorCode; //!< [EXPORT] : [COMMENT] Error code which can be looked up in generated + //!< error code file + uint32_t errorParameter1; + uint32_t errorParameter2; + const uint8_t failureSubtype; //!< [EXPORT] : [IGNORE] }; /** * @brief Subservices 1, 3, 5, 7 * @ingroup spacepackets */ -class SuccessReport: public SerializeIF { //!< [EXPORT] : [SUBSERVICE] 1, 3, 5, 7 -public: - SuccessReport(uint8_t subtype_, uint16_t packetId_, - uint16_t packetSequenceControl_,uint8_t stepNumber_) : - packetId(packetId_), packetSequenceControl(packetSequenceControl_), - stepNumber(stepNumber_), subtype(subtype_) {} +class SuccessReport : public SerializeIF { //!< [EXPORT] : [SUBSERVICE] 1, 3, 5, 7 + public: + SuccessReport(uint8_t subtype_, uint16_t packetId_, uint16_t packetSequenceControl_, + uint8_t stepNumber_) + : packetId(packetId_), + packetSequenceControl(packetSequenceControl_), + stepNumber(stepNumber_), + subtype(subtype_) {} - virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, SerializeIF::Endianness streamEndianness - ) const override { - ReturnValue_t result = SerializeAdapter::serialize(&packetId, buffer, - size, maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::serialize(&packetSequenceControl, buffer, - size, maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if (subtype == tc_verification::PROGRESS_SUCCESS) { - result = SerializeAdapter::serialize(&stepNumber, buffer, size, - maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - } - return result; - } + virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + SerializeIF::Endianness streamEndianness) const override { + ReturnValue_t result = + SerializeAdapter::serialize(&packetId, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::serialize(&packetSequenceControl, buffer, size, maxSize, + streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (subtype == tc_verification::PROGRESS_SUCCESS) { + result = SerializeAdapter::serialize(&stepNumber, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + } + return result; + } - virtual size_t getSerializedSize() const override { - size_t size = 0; - size += SerializeAdapter::getSerializedSize(&packetId); - size += sizeof(packetSequenceControl); - if(subtype == tc_verification::PROGRESS_SUCCESS){ - size += SerializeAdapter::getSerializedSize(&stepNumber); - } - return size; + virtual size_t getSerializedSize() const override { + size_t size = 0; + size += SerializeAdapter::getSerializedSize(&packetId); + size += sizeof(packetSequenceControl); + if (subtype == tc_verification::PROGRESS_SUCCESS) { + size += SerializeAdapter::getSerializedSize(&stepNumber); + } + return size; + } - } + ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + SerializeIF::Endianness streamEndianness) override { + return HasReturnvaluesIF::RETURN_FAILED; + } - ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - SerializeIF::Endianness streamEndianness) override { - return HasReturnvaluesIF::RETURN_FAILED; - } -private: - uint16_t packetId; //!< [EXPORT] : [COMMENT] Packet ID of respective Telecommand - uint16_t packetSequenceControl; //!< [EXPORT] : [COMMENT] Packet SSC of respective Telecommand - uint8_t stepNumber; //!< [EXPORT] : [OPTIONAL][SUBSERVICE] 6 - const uint8_t subtype; //!< [EXPORT] : [IGNORE] + private: + uint16_t packetId; //!< [EXPORT] : [COMMENT] Packet ID of respective Telecommand + uint16_t packetSequenceControl; //!< [EXPORT] : [COMMENT] Packet SSC of respective Telecommand + uint8_t stepNumber; //!< [EXPORT] : [OPTIONAL][SUBSERVICE] 6 + const uint8_t subtype; //!< [EXPORT] : [IGNORE] }; #endif /* MISSION_PUS_SERVICEPACKETS_SERVICE1PACKETS_H_ */ diff --git a/src/fsfw/pus/servicepackets/Service200Packets.h b/src/fsfw/pus/servicepackets/Service200Packets.h index cb9ad4a7..701e3f09 100644 --- a/src/fsfw/pus/servicepackets/Service200Packets.h +++ b/src/fsfw/pus/servicepackets/Service200Packets.h @@ -1,63 +1,61 @@ #ifndef FSFW_PUS_SERVICEPACKETS_SERVICE200PACKETS_H_ #define FSFW_PUS_SERVICEPACKETS_SERVICE200PACKETS_H_ -#include "../../serialize/SerialLinkedListAdapter.h" #include "../../modes/ModeMessage.h" +#include "../../serialize/SerialLinkedListAdapter.h" #include "../../serialize/SerializeIF.h" /** * @brief Subservice 1, 2, 3, 4, 5 * @ingroup spacepackets */ -class ModePacket : public SerialLinkedListAdapter { //!< [EXPORT] : [SUBSERVICE] 1, 2, 6 -public: +class ModePacket + : public SerialLinkedListAdapter { //!< [EXPORT] : [SUBSERVICE] 1, 2, 6 + public: + ModePacket() { setLinks(); } - ModePacket() { - setLinks(); - } + ModePacket(object_id_t objectId, Mode_t mode, Submode_t submode) + : objectId(objectId), mode(mode), submode(submode) { + setLinks(); + } - ModePacket(object_id_t objectId, Mode_t mode, Submode_t submode) : - objectId(objectId), mode(mode), submode(submode) { - setLinks(); - } + Mode_t getMode() { return mode.entry; } - Mode_t getMode() { - return mode.entry; - } + Submode_t getSubmode() { return submode.entry; } - Submode_t getSubmode() { - return submode.entry; - } + // Forbid copying, pointers are used. + ModePacket(const ModePacket&) = delete; + ModePacket& operator=(const ModePacket&) = delete; - // Forbid copying, pointers are used. - ModePacket(const ModePacket&) = delete; - ModePacket& operator=(const ModePacket&) = delete; -private: - - void setLinks() { - setStart(&objectId); - objectId.setNext(&mode); - mode.setNext(&submode); - } - SerializeElement objectId; //!< [EXPORT] : [COMMENT] Target or source object - SerializeElement mode; //!< [EXPORT] : [COMMENT] 0: MODE_OFF, 1: MODE_ON, 2: MODE_NORMAL, 3: MODE_RAW - SerializeElement submode; //!< [EXPORT] : [COMMENT] Usually 0, device specific submode possible + private: + void setLinks() { + setStart(&objectId); + objectId.setNext(&mode); + mode.setNext(&submode); + } + SerializeElement objectId; //!< [EXPORT] : [COMMENT] Target or source object + SerializeElement + mode; //!< [EXPORT] : [COMMENT] 0: MODE_OFF, 1: MODE_ON, 2: MODE_NORMAL, 3: MODE_RAW + SerializeElement + submode; //!< [EXPORT] : [COMMENT] Usually 0, device specific submode possible }; /** * @brief Subservice 7 * @ingroup spacepackets */ -class CantReachModePacket: public SerialLinkedListAdapter { //!< [EXPORT] : [SUBSERVICE] 7 -public: - CantReachModePacket(object_id_t objectId, ReturnValue_t reason): - objectId(objectId), reason(reason) { - setStart(&this->objectId); - this->objectId.setNext(&this->reason); - } +class CantReachModePacket + : public SerialLinkedListAdapter { //!< [EXPORT] : [SUBSERVICE] 7 + public: + CantReachModePacket(object_id_t objectId, ReturnValue_t reason) + : objectId(objectId), reason(reason) { + setStart(&this->objectId); + this->objectId.setNext(&this->reason); + } - SerializeElement objectId; //!< [EXPORT] : [COMMENT] Reply source object - SerializeElement reason; //!< [EXPORT] : [COMMENT] Reason the mode could not be reached + SerializeElement objectId; //!< [EXPORT] : [COMMENT] Reply source object + SerializeElement + reason; //!< [EXPORT] : [COMMENT] Reason the mode could not be reached }; #endif /* FSFW_PUS_SERVICEPACKETS_SERVICE200PACKETS_H_ */ diff --git a/src/fsfw/pus/servicepackets/Service201Packets.h b/src/fsfw/pus/servicepackets/Service201Packets.h index aed821f9..dcf30c2e 100644 --- a/src/fsfw/pus/servicepackets/Service201Packets.h +++ b/src/fsfw/pus/servicepackets/Service201Packets.h @@ -1,48 +1,44 @@ #ifndef FSFW_PUS_SERVICEPACKETS_SERVICE201PACKETS_H_ #define FSFW_PUS_SERVICEPACKETS_SERVICE201PACKETS_H_ +#include "../../health/HasHealthIF.h" #include "../../serialize/SerialLinkedListAdapter.h" #include "../../serialize/SerializeIF.h" -#include "../../health/HasHealthIF.h" -class HealthSetCommand: public SerialLinkedListAdapter { //!< [EXPORT] : [SUBSERVICE] 1 -public: +class HealthSetCommand + : public SerialLinkedListAdapter { //!< [EXPORT] : [SUBSERVICE] 1 + public: + HealthSetCommand() { setLinks(); } - HealthSetCommand() { - setLinks(); - } + HasHealthIF::HealthState getHealth() { + return static_cast(health.entry); + } - HasHealthIF::HealthState getHealth() { - return static_cast(health.entry); - } -private: - void setLinks() { - setStart(&objectId); - objectId.setNext(&health); - } - SerializeElement objectId; //!< [EXPORT] : [COMMENT] Target object Id - SerializeElement health; //!< [EXPORT] : [COMMENT] Health to set + private: + void setLinks() { + setStart(&objectId); + objectId.setNext(&health); + } + SerializeElement objectId; //!< [EXPORT] : [COMMENT] Target object Id + SerializeElement health; //!< [EXPORT] : [COMMENT] Health to set }; +class HealthSetReply : public SerialLinkedListAdapter { //!< [EXPORT] : [SUBSERVICE] 2 + public: + HealthSetReply(uint8_t health_, uint8_t oldHealth_) : health(health_), oldHealth(oldHealth_) { + setLinks(); + } -class HealthSetReply: public SerialLinkedListAdapter { //!< [EXPORT] : [SUBSERVICE] 2 -public: - HealthSetReply(uint8_t health_, uint8_t oldHealth_): - health(health_), oldHealth(oldHealth_) - { - setLinks(); - } - -private: - HealthSetReply(const HealthSetReply &reply); - void setLinks() { - setStart(&objectId); - objectId.setNext(&health); - health.setNext(&oldHealth); - } - SerializeElement objectId; //!< [EXPORT] : [COMMENT] Source object ID - SerializeElement health; //!< [EXPORT] : [COMMENT] New Health - SerializeElement oldHealth; //!< [EXPORT] : [COMMENT] Old Health + private: + HealthSetReply(const HealthSetReply &reply); + void setLinks() { + setStart(&objectId); + objectId.setNext(&health); + health.setNext(&oldHealth); + } + SerializeElement objectId; //!< [EXPORT] : [COMMENT] Source object ID + SerializeElement health; //!< [EXPORT] : [COMMENT] New Health + SerializeElement oldHealth; //!< [EXPORT] : [COMMENT] Old Health }; #endif /* FSFW_PUS_SERVICEPACKETS_SERVICE201PACKETS_H_ */ diff --git a/src/fsfw/pus/servicepackets/Service20Packets.h b/src/fsfw/pus/servicepackets/Service20Packets.h index 6c7eb6f5..ceefa1ee 100644 --- a/src/fsfw/pus/servicepackets/Service20Packets.h +++ b/src/fsfw/pus/servicepackets/Service20Packets.h @@ -4,8 +4,8 @@ #include #include #include -#include #include +#include #include /** @@ -15,127 +15,108 @@ * This command can be used to handle both load and dump commands as well. * @author */ -class ParameterCommand: public SerialLinkedListAdapter { //!< [EXPORT] : [SUBSERVICE] 128, 129, 130 -public: - - /** - * This constructor is used for load replies. The data is expected in the correct formast - * in the store pointer. - * @param storePointer - * @param parameterDataLen - */ - ParameterCommand(uint8_t* storePointer, size_t parameterDataLen): - parameterBuffer(storePointer, parameterDataLen) { +class ParameterCommand + : public SerialLinkedListAdapter { //!< [EXPORT] : [SUBSERVICE] 128, 129, 130 + public: + /** + * This constructor is used for load replies. The data is expected in the correct formast + * in the store pointer. + * @param storePointer + * @param parameterDataLen + */ + ParameterCommand(uint8_t* storePointer, size_t parameterDataLen) + : parameterBuffer(storePointer, parameterDataLen) { #if FSFW_VERBOSE_LEVEL >= 1 - if(parameterDataLen == 0) { + if (parameterDataLen == 0) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "ParameterCommand: Parameter data length is 0" << std::endl; + sif::warning << "ParameterCommand: Parameter data length is 0" << std::endl; #else - sif::printWarning("ParameterCommand: Parameter data length is 0!\n"); + sif::printWarning("ParameterCommand: Parameter data length is 0!\n"); #endif - } + } #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - setLoadLinks(); - } + setLoadLinks(); + } - /** - * This constructor is used for dump replies. It is assumed the 4 byte parameter - * information field is located inside the parameter buffer. - * @param objectId - * @param parameterId - * @param parameterBuffer - * @param parameterBufferSize - */ - ParameterCommand(object_id_t objectId, ParameterId_t parameterId, - const uint8_t* parameterBuffer, size_t parameterBufferSize): - objectId(objectId), parameterId(parameterId), - parameterBuffer(parameterBuffer, parameterBufferSize) { - setDumpReplyLinks(); - } + /** + * This constructor is used for dump replies. It is assumed the 4 byte parameter + * information field is located inside the parameter buffer. + * @param objectId + * @param parameterId + * @param parameterBuffer + * @param parameterBufferSize + */ + ParameterCommand(object_id_t objectId, ParameterId_t parameterId, const uint8_t* parameterBuffer, + size_t parameterBufferSize) + : objectId(objectId), + parameterId(parameterId), + parameterBuffer(parameterBuffer, parameterBufferSize) { + setDumpReplyLinks(); + } - ParameterId_t getParameterId() const { - return parameterId.entry; - } + ParameterId_t getParameterId() const { return parameterId.entry; } - const uint8_t* getParameterBuffer() { - return parameterBuffer.entry.getConstBuffer(); - } + const uint8_t* getParameterBuffer() { return parameterBuffer.entry.getConstBuffer(); } - size_t getParameterBufferLen() const { - return parameterBuffer.getSerializedSize(); - } + size_t getParameterBufferLen() const { return parameterBuffer.getSerializedSize(); } - uint8_t getDomainId() const { - return (parameterId.entry >> 24) & 0xff; - } + uint8_t getDomainId() const { return (parameterId.entry >> 24) & 0xff; } - uint8_t getUniqueId() const { - return (parameterId.entry >> 16) & 0xff; - } + uint8_t getUniqueId() const { return (parameterId.entry >> 16) & 0xff; } - uint16_t getLinearIndex() const { - return parameterId.entry & 0xffff; - } + uint16_t getLinearIndex() const { return parameterId.entry & 0xffff; } - uint8_t getPtc() const { - return ccsdsType.entry >> 8 & 0xff; - } + uint8_t getPtc() const { return ccsdsType.entry >> 8 & 0xff; } - uint8_t getPfc() const { - return ccsdsType.entry & 0xff; - } + uint8_t getPfc() const { return ccsdsType.entry & 0xff; } - uint8_t getRows() const { - return rows.entry; - } + uint8_t getRows() const { return rows.entry; } - uint8_t getColumns() const { - return columns.entry; - } + uint8_t getColumns() const { return columns.entry; } -private: - void setLoadLinks() { - setStart(&objectId); - objectId.setNext(¶meterId); - parameterId.setNext(&ccsdsType); - ccsdsType.setNext(&rows); - rows.setNext(&columns); - columns.setNext(¶meterBuffer); - } + private: + void setLoadLinks() { + setStart(&objectId); + objectId.setNext(¶meterId); + parameterId.setNext(&ccsdsType); + ccsdsType.setNext(&rows); + rows.setNext(&columns); + columns.setNext(¶meterBuffer); + } - void setDumpReplyLinks() { - /* For a dump reply, the parameter information is contained in the parameter buffer - with the actual parameters */ - setStart(&objectId); - objectId.setNext(¶meterId); - parameterId.setNext(¶meterBuffer); - } + void setDumpReplyLinks() { + /* For a dump reply, the parameter information is contained in the parameter buffer + with the actual parameters */ + setStart(&objectId); + objectId.setNext(¶meterId); + parameterId.setNext(¶meterBuffer); + } - void setDumpRequestLinks() { - setStart(&objectId); - objectId.setNext(¶meterId); - } + void setDumpRequestLinks() { + setStart(&objectId); + objectId.setNext(¶meterId); + } - SerializeElement objectId = 0; - SerializeElement parameterId = 0; - //! [EXPORT] : [COMMENT] Type consisting of one byte PTC and one byte PFC. - SerializeElement ccsdsType = 0; - SerializeElement rows = 0; - SerializeElement columns = 0; - SerializeElement> parameterBuffer; + SerializeElement objectId = 0; + SerializeElement parameterId = 0; + //! [EXPORT] : [COMMENT] Type consisting of one byte PTC and one byte PFC. + SerializeElement ccsdsType = 0; + SerializeElement rows = 0; + SerializeElement columns = 0; + SerializeElement> parameterBuffer; }; -class ParameterLoadCommand: public ParameterCommand { -public: - ParameterLoadCommand(uint8_t* parameterPacket, size_t parameterDataLen): - ParameterCommand(parameterPacket, parameterDataLen) {} +class ParameterLoadCommand : public ParameterCommand { + public: + ParameterLoadCommand(uint8_t* parameterPacket, size_t parameterDataLen) + : ParameterCommand(parameterPacket, parameterDataLen) {} }; -class ParameterDumpReply: public ParameterCommand { -public: - ParameterDumpReply(object_id_t objectId, ParameterId_t parameterId, - const uint8_t* parameterBuffer, size_t parameterBufferSize): - ParameterCommand(objectId, parameterId, parameterBuffer, parameterBufferSize) {} +class ParameterDumpReply : public ParameterCommand { + public: + ParameterDumpReply(object_id_t objectId, ParameterId_t parameterId, + const uint8_t* parameterBuffer, size_t parameterBufferSize) + : ParameterCommand(objectId, parameterId, parameterBuffer, parameterBufferSize) {} }; #endif /* FSFW_PUS_SERVICEPACKETS_SERVICE20PACKETS_H_ */ diff --git a/src/fsfw/pus/servicepackets/Service2Packets.h b/src/fsfw/pus/servicepackets/Service2Packets.h index 285a8f9f..ecef71e9 100644 --- a/src/fsfw/pus/servicepackets/Service2Packets.h +++ b/src/fsfw/pus/servicepackets/Service2Packets.h @@ -10,67 +10,58 @@ * @brief Subservice 128 * @ingroup spacepackets */ -class RawCommand { //!< [EXPORT] : [SUBSERVICE] 128 -public: - RawCommand(const uint8_t* buffer, size_t size) { - // Deserialize Adapter to get correct endianness - SerializeAdapter::deSerialize(&objectId, &buffer, &size, - SerializeIF::Endianness::BIG); - commandBuffer = buffer; - // size is decremented by AutoSerializeAdapter, - // remaining size is data size - dataSize = size; - } - object_id_t getObjectId() const { - return objectId; - } +class RawCommand { //!< [EXPORT] : [SUBSERVICE] 128 + public: + RawCommand(const uint8_t* buffer, size_t size) { + // Deserialize Adapter to get correct endianness + SerializeAdapter::deSerialize(&objectId, &buffer, &size, SerializeIF::Endianness::BIG); + commandBuffer = buffer; + // size is decremented by AutoSerializeAdapter, + // remaining size is data size + dataSize = size; + } + object_id_t getObjectId() const { return objectId; } - const uint8_t* getCommand() { - return commandBuffer; - } + const uint8_t* getCommand() { return commandBuffer; } - size_t getCommandSize() const { - return dataSize; - } -private: - object_id_t objectId = 0; - const uint8_t* commandBuffer = nullptr; //!< [EXPORT] : [MAXSIZE] 256 Bytes - size_t dataSize = 0; //!< [EXPORT] : [IGNORE] + size_t getCommandSize() const { return dataSize; } + + private: + object_id_t objectId = 0; + const uint8_t* commandBuffer = nullptr; //!< [EXPORT] : [MAXSIZE] 256 Bytes + size_t dataSize = 0; //!< [EXPORT] : [IGNORE] }; - /** * @brief Subservice 129: Command packet to set wiretapping mode * @ingroup spacepackets */ -class WiretappingToggle: public SerialLinkedListAdapter{ //!< [EXPORT] : [SUBSERVICE] 129 -public: - static const size_t WIRETAPPING_COMMAND_SIZE = 5; - WiretappingToggle(){ - setStart(&objectId); - objectId.setNext(&wiretappingMode); - } +class WiretappingToggle + : public SerialLinkedListAdapter { //!< [EXPORT] : [SUBSERVICE] 129 + public: + static const size_t WIRETAPPING_COMMAND_SIZE = 5; + WiretappingToggle() { + setStart(&objectId); + objectId.setNext(&wiretappingMode); + } - uint8_t getWiretappingMode() const { - return wiretappingMode.entry; - } -private: - SerializeElement objectId; - SerializeElement wiretappingMode; //!< [EXPORT] : [INPUT] Mode 0: OFF, Mode 1: RAW + uint8_t getWiretappingMode() const { return wiretappingMode.entry; } + + private: + SerializeElement objectId; + SerializeElement wiretappingMode; //!< [EXPORT] : [INPUT] Mode 0: OFF, Mode 1: RAW }; - /** * @brief Subservices 130 and 131: TM packets * @ingroup spacepackets */ -class WiretappingPacket { //!< [EXPORT] : [SUBSERVICE] 130, 131 -public: - object_id_t objectId; //!< [EXPORT] : [COMMENT] Object ID of source object - const uint8_t* data; //!< [EXPORT] : [MAXSIZE] Raw Command Max. Size - WiretappingPacket(object_id_t objectId, const uint8_t* buffer): - objectId(objectId), data(buffer) { - } +class WiretappingPacket { //!< [EXPORT] : [SUBSERVICE] 130, 131 + public: + object_id_t objectId; //!< [EXPORT] : [COMMENT] Object ID of source object + const uint8_t* data; //!< [EXPORT] : [MAXSIZE] Raw Command Max. Size + WiretappingPacket(object_id_t objectId, const uint8_t* buffer) + : objectId(objectId), data(buffer) {} }; #endif /* FSFW_PUS_SERVICEPACKETS_SERVICE2PACKETS_H_ */ diff --git a/src/fsfw/pus/servicepackets/Service3Packets.h b/src/fsfw/pus/servicepackets/Service3Packets.h index 05732e11..d6c98b61 100644 --- a/src/fsfw/pus/servicepackets/Service3Packets.h +++ b/src/fsfw/pus/servicepackets/Service3Packets.h @@ -2,20 +2,20 @@ #define FSFW_PUS_SERVICEPACKETS_SERVICE3PACKETS_H_ #include + #include /** * @brief Subservices 25 and 26: TM packets * @ingroup spacepackets */ -class HkPacket { //!< [EXPORT] : [SUBSERVICE] 25, 26 -public: - sid_t sid; //!< [EXPORT] : [COMMENT] Structure ID (SID) of housekeeping data. - const uint8_t* hkData; //!< [EXPORT] : [MAXSIZE] Deduced size - size_t hkSize; //!< [EXPORT] : [IGNORE] +class HkPacket { //!< [EXPORT] : [SUBSERVICE] 25, 26 + public: + sid_t sid; //!< [EXPORT] : [COMMENT] Structure ID (SID) of housekeeping data. + const uint8_t* hkData; //!< [EXPORT] : [MAXSIZE] Deduced size + size_t hkSize; //!< [EXPORT] : [IGNORE] - HkPacket(sid_t sid, const uint8_t* data, size_t size): - sid(sid), hkData(data), hkSize(size) {} + HkPacket(sid_t sid, const uint8_t* data, size_t size) : sid(sid), hkData(data), hkSize(size) {} }; #endif /* FSFW_PUS_SERVICEPACKETS_SERVICE3PACKETS_H_ */ diff --git a/src/fsfw/pus/servicepackets/Service5Packets.h b/src/fsfw/pus/servicepackets/Service5Packets.h index f903d6a2..9ff2e4d4 100644 --- a/src/fsfw/pus/servicepackets/Service5Packets.h +++ b/src/fsfw/pus/servicepackets/Service5Packets.h @@ -4,7 +4,6 @@ #include "../../serialize/SerializeAdapter.h" #include "../../tmtcservices/VerificationCodes.h" - /** * @brief Subservice 1, 2, 3, 4 * Structure of Event Report. @@ -16,61 +15,56 @@ * * @ingroup spacepackets */ -class EventReport: public SerializeIF { //!< [EXPORT] : [SUBSERVICE] 1, 2, 3, 4 -public: +class EventReport : public SerializeIF { //!< [EXPORT] : [SUBSERVICE] 1, 2, 3, 4 + public: + EventReport(EventId_t reportId_, object_id_t objectId_, uint32_t parameter1_, + uint32_t parameter2_) + : reportId(reportId_), + objectId(objectId_), + parameter1(parameter1_), + parameter2(parameter2_) {} - EventReport(EventId_t reportId_, object_id_t objectId_, uint32_t parameter1_, - uint32_t parameter2_): - reportId(reportId_),objectId(objectId_), parameter1(parameter1_), - parameter2(parameter2_) {} + virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + SerializeIF::Endianness streamEndianness) const override { + ReturnValue_t result = + SerializeAdapter::serialize(&reportId, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::serialize(&objectId, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::serialize(¶meter1, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::serialize(¶meter2, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return result; + } - virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, - SerializeIF::Endianness streamEndianness) const override - { - ReturnValue_t result = SerializeAdapter::serialize(&reportId, buffer, - size, maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::serialize(&objectId, buffer, size, - maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::serialize(¶meter1, buffer, size, - maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::serialize(¶meter2, buffer, size, - maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return result; - } + virtual size_t getSerializedSize() const override { + uint32_t size = 0; + size += SerializeAdapter::getSerializedSize(&reportId); + size += SerializeAdapter::getSerializedSize(&objectId); + size += SerializeAdapter::getSerializedSize(¶meter1); + size += SerializeAdapter::getSerializedSize(¶meter2); + return size; + } - virtual size_t getSerializedSize() const override { - uint32_t size = 0; - size += SerializeAdapter::getSerializedSize(&reportId); - size += SerializeAdapter::getSerializedSize(&objectId); - size += SerializeAdapter::getSerializedSize(¶meter1); - size += SerializeAdapter::getSerializedSize(¶meter2); - return size; + virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + SerializeIF::Endianness streamEndianness) override { + return HasReturnvaluesIF::RETURN_FAILED; + } - } - - virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - SerializeIF::Endianness streamEndianness) override { - return HasReturnvaluesIF::RETURN_FAILED; - } -private: - EventId_t reportId; - object_id_t objectId; - uint32_t parameter1; - uint32_t parameter2; + private: + EventId_t reportId; + object_id_t objectId; + uint32_t parameter1; + uint32_t parameter2; }; - #endif /* FSFW_PUS_SERVICEPACKETS_SERVICE5PACKETS_H_ */ diff --git a/src/fsfw/pus/servicepackets/Service8Packets.h b/src/fsfw/pus/servicepackets/Service8Packets.h index a27cf8bb..981ef439 100644 --- a/src/fsfw/pus/servicepackets/Service8Packets.h +++ b/src/fsfw/pus/servicepackets/Service8Packets.h @@ -4,53 +4,40 @@ #include "../../action/ActionMessage.h" #include "../../objectmanager/SystemObjectIF.h" #include "../../serialize/SerialBufferAdapter.h" -#include "../../serialize/SerializeElement.h" -#include "../../serialize/SerialLinkedListAdapter.h" #include "../../serialize/SerialFixedArrayListAdapter.h" - +#include "../../serialize/SerialLinkedListAdapter.h" +#include "../../serialize/SerializeElement.h" /** * @brief Subservice 128 * @ingroup spacepackets */ -class DirectCommand: public SerialLinkedListAdapter { //!< [EXPORT] : [SUBSERVICE] 128 -public: +class DirectCommand + : public SerialLinkedListAdapter { //!< [EXPORT] : [SUBSERVICE] 128 + public: + DirectCommand(const uint8_t* tcData, size_t size) { + SerializeAdapter::deSerialize(&objectId, &tcData, &size, SerializeIF::Endianness::BIG); + SerializeAdapter::deSerialize(&actionId, &tcData, &size, SerializeIF::Endianness::BIG); + parameterBuffer = tcData; + parametersSize = size; + } - DirectCommand(const uint8_t* tcData, size_t size) { - SerializeAdapter::deSerialize(&objectId, &tcData, &size, - SerializeIF::Endianness::BIG); - SerializeAdapter::deSerialize(&actionId, &tcData, &size, - SerializeIF::Endianness::BIG); - parameterBuffer = tcData; - parametersSize = size; - } + ActionId_t getActionId() const { return actionId; } - ActionId_t getActionId() const { - return actionId; - } + object_id_t getObjectId() const { return objectId; } - object_id_t getObjectId() const { - return objectId; - } + const uint8_t* getParameters() { return parameterBuffer; } - const uint8_t* getParameters() { - return parameterBuffer; - } - - uint32_t getParametersSize() const { - return parametersSize; - } - -private: - DirectCommand(const DirectCommand &command); - object_id_t objectId = 0; - ActionId_t actionId = 0; - uint32_t parametersSize; //!< [EXPORT] : [IGNORE] - const uint8_t * parameterBuffer; //!< [EXPORT] : [MAXSIZE] 65535 Bytes + uint32_t getParametersSize() const { return parametersSize; } + private: + DirectCommand(const DirectCommand& command); + object_id_t objectId = 0; + ActionId_t actionId = 0; + uint32_t parametersSize; //!< [EXPORT] : [IGNORE] + const uint8_t* parameterBuffer; //!< [EXPORT] : [MAXSIZE] 65535 Bytes }; - /** * @brief Subservice 130 * Data reply (subservice 130) consists of @@ -59,63 +46,64 @@ private: * 3. Data * @ingroup spacepackets */ -class DataReply: public SerialLinkedListAdapter { //!< [EXPORT] : [SUBSERVICE] 130 -public: - typedef uint16_t typeOfMaxDataSize; - static const uint16_t MAX_DATA_LENGTH = sizeof(typeOfMaxDataSize); - DataReply(object_id_t objectId_, ActionId_t actionId_, - const uint8_t * replyDataBuffer_ = NULL, uint16_t replyDataSize_ = 0): - objectId(objectId_), actionId(actionId_), replyData(replyDataBuffer_,replyDataSize_){ - setLinks(); - } +class DataReply : public SerialLinkedListAdapter { //!< [EXPORT] : [SUBSERVICE] 130 + public: + typedef uint16_t typeOfMaxDataSize; + static const uint16_t MAX_DATA_LENGTH = sizeof(typeOfMaxDataSize); + DataReply(object_id_t objectId_, ActionId_t actionId_, const uint8_t* replyDataBuffer_ = NULL, + uint16_t replyDataSize_ = 0) + : objectId(objectId_), actionId(actionId_), replyData(replyDataBuffer_, replyDataSize_) { + setLinks(); + } -private: - DataReply(const DataReply &reply); - void setLinks() { - setStart(&objectId); - objectId.setNext(&actionId); - actionId.setNext(&replyData); - } - SerializeElement objectId; - SerializeElement actionId; - SerializeElement> replyData; + private: + DataReply(const DataReply& reply); + void setLinks() { + setStart(&objectId); + objectId.setNext(&actionId); + actionId.setNext(&replyData); + } + SerializeElement objectId; + SerializeElement actionId; + SerializeElement> replyData; }; - /** * @brief Subservice 132 * @details * Not used yet. Telecommand Verification takes care of this. * @ingroup spacepackets */ -class DirectReply: public SerialLinkedListAdapter { //!< [EXPORT] : [SUBSERVICE] 132 -public: - typedef uint16_t typeOfMaxDataSize; - static const uint16_t MAX_DATA_LENGTH = sizeof(typeOfMaxDataSize); +class DirectReply : public SerialLinkedListAdapter { //!< [EXPORT] : [SUBSERVICE] 132 + public: + typedef uint16_t typeOfMaxDataSize; + static const uint16_t MAX_DATA_LENGTH = sizeof(typeOfMaxDataSize); - DirectReply(object_id_t objectId_, ActionId_t actionId_, ReturnValue_t returnCode_, - bool isStep_ = false, uint8_t step_ = 0): - isStep(isStep_), objectId(objectId_), actionId(actionId_), - returnCode(returnCode_),step(step_) { - setLinks(); - } -private: + DirectReply(object_id_t objectId_, ActionId_t actionId_, ReturnValue_t returnCode_, + bool isStep_ = false, uint8_t step_ = 0) + : isStep(isStep_), + objectId(objectId_), + actionId(actionId_), + returnCode(returnCode_), + step(step_) { + setLinks(); + } - void setLinks() { - setStart(&objectId); - objectId.setNext(&actionId); - actionId.setNext(&returnCode); - if(isStep) { - returnCode.setNext(&step); - } - } - - bool isStep; //!< [EXPORT] : [IGNORE] - SerializeElement objectId; //!< [EXPORT] : [IGNORE] - SerializeElement actionId; //!< [EXPORT] : [IGNORE] - SerializeElement returnCode; //!< [EXPORT] : [IGNORE] - SerializeElement step; //!< [EXPORT] : [OPTIONAL] [IGNORE] + private: + void setLinks() { + setStart(&objectId); + objectId.setNext(&actionId); + actionId.setNext(&returnCode); + if (isStep) { + returnCode.setNext(&step); + } + } + bool isStep; //!< [EXPORT] : [IGNORE] + SerializeElement objectId; //!< [EXPORT] : [IGNORE] + SerializeElement actionId; //!< [EXPORT] : [IGNORE] + SerializeElement returnCode; //!< [EXPORT] : [IGNORE] + SerializeElement step; //!< [EXPORT] : [OPTIONAL] [IGNORE] }; #endif /* FSFW_PUS_SERVICEPACKETS_SERVICE8PACKETS_H_ */ diff --git a/src/fsfw/pus/servicepackets/Service9Packets.h b/src/fsfw/pus/servicepackets/Service9Packets.h index 11bd2600..076536e8 100644 --- a/src/fsfw/pus/servicepackets/Service9Packets.h +++ b/src/fsfw/pus/servicepackets/Service9Packets.h @@ -9,24 +9,20 @@ * It only contains the time encoded as ASCII, CRC, CUC or CDS * @ingroup spacepackets */ -class TimePacket : SerialLinkedListAdapter { //!< [EXPORT] : [SUBSERVICE] 128 -public: - TimePacket(const uint8_t * timeBuffer_, uint32_t timeSize_) { - timeBuffer = timeBuffer_; - timeSize = timeSize_; - } - const uint8_t* getTime() { - return timeBuffer; - } +class TimePacket : SerialLinkedListAdapter { //!< [EXPORT] : [SUBSERVICE] 128 + public: + TimePacket(const uint8_t* timeBuffer_, uint32_t timeSize_) { + timeBuffer = timeBuffer_; + timeSize = timeSize_; + } + const uint8_t* getTime() { return timeBuffer; } - uint32_t getTimeSize() const { - return timeSize; - } + uint32_t getTimeSize() const { return timeSize; } -private: - TimePacket(const TimePacket &command); - const uint8_t * timeBuffer; - uint32_t timeSize; //!< [EXPORT] : [IGNORE] + private: + TimePacket(const TimePacket& command); + const uint8_t* timeBuffer; + uint32_t timeSize; //!< [EXPORT] : [IGNORE] }; #endif /* FSFW_PUS_SERVICEPACKETS_SERVICE9PACKETS_H_ */ diff --git a/src/fsfw/returnvalues/FwClassIds.h b/src/fsfw/returnvalues/FwClassIds.h index 96f96660..d07cedc9 100644 --- a/src/fsfw/returnvalues/FwClassIds.h +++ b/src/fsfw/returnvalues/FwClassIds.h @@ -6,83 +6,83 @@ // The comment block at the end is used by the returnvalue exporter. // It is recommended to add it as well for mission returnvalues namespace CLASS_ID { -enum: uint8_t { - FW_CLASS_ID_START = 0, // [EXPORT] : [START] - OPERATING_SYSTEM_ABSTRACTION, //OS - OBJECT_MANAGER_IF, //OM - DEVICE_HANDLER_BASE, //DHB - RMAP_CHANNEL, //RMP - POWER_SWITCH_IF, //PS - HAS_MEMORY_IF, //PP - DEVICE_STATE_MACHINE_BASE, //DSMB - DATA_SET_CLASS, //DPS - POOL_RAW_ACCESS_CLASS, //DPR - CONTROLLER_BASE, //CTR - SUBSYSTEM_BASE, //SB - MODE_STORE_IF, //MS - SUBSYSTEM, //SS - HAS_MODES_IF, //HM - COMMAND_MESSAGE, //CM - CCSDS_TIME_HELPER_CLASS, //TIM - ARRAY_LIST, //AL - ASSEMBLY_BASE, //AB - MEMORY_HELPER, //MH - SERIALIZE_IF, //SE - FIXED_MAP, //FM - FIXED_MULTIMAP, //FMM - HAS_HEALTH_IF, //HHI - FIFO_CLASS, //FF - MESSAGE_PROXY, //MQP - TRIPLE_REDUNDACY_CHECK, //TRC - TC_PACKET_CHECK, //TCC - PACKET_DISTRIBUTION, //TCD - ACCEPTS_TELECOMMANDS_IF, //PUS - DEVICE_SERVICE_BASE, //DSB - COMMAND_SERVICE_BASE, //CSB - TM_STORE_BACKEND_IF, //TMB - TM_STORE_FRONTEND_IF, //TMF - STORAGE_AND_RETRIEVAL_SERVICE, //SR - MATCH_TREE_CLASS, //MT - EVENT_MANAGER_IF, //EV - HANDLES_FAILURES_IF, //FDI - DEVICE_HANDLER_IF, //DHI - STORAGE_MANAGER_IF, //SM - THERMAL_COMPONENT_IF, //TC - INTERNAL_ERROR_CODES, //IEC - TRAP, //TRP - CCSDS_HANDLER_IF, //CCS - PARAMETER_WRAPPER, //PAW - HAS_PARAMETERS_IF, //HPA - ASCII_CONVERTER, //ASC - POWER_SWITCHER, //POS - LIMITS_IF, //LIM - COMMANDS_ACTIONS_IF, //CF - HAS_ACTIONS_IF, //HF - DEVICE_COMMUNICATION_IF, //DC - BSP, //BSP - CFDP, //CFDP - TIME_STAMPER_IF, //TSI - SGP4PROPAGATOR_CLASS, //SGP4 - MUTEX_IF, //MUX - MESSAGE_QUEUE_IF,//MQI - SEMAPHORE_IF, //SPH - LOCAL_POOL_OWNER_IF, //LPIF - POOL_VARIABLE_IF, //PVA - HOUSEKEEPING_MANAGER, //HKM - DLE_ENCODER, //DLEE - PUS_SERVICE_3, //PUS3 - PUS_SERVICE_9, //PUS9 - FILE_SYSTEM, //FILS - LINUX_OSAL, //UXOS - HAL_SPI, //HSPI - HAL_UART, //HURT - HAL_I2C, //HI2C - HAL_GPIO, //HGIO - FIXED_SLOT_TASK_IF, //FTIF - MGM_LIS3MDL, //MGMLIS3 - MGM_RM3100, //MGMRM3100 - SPACE_PACKET_PARSER, //SPPA - FW_CLASS_ID_COUNT // [EXPORT] : [END] +enum : uint8_t { + FW_CLASS_ID_START = 0, // [EXPORT] : [START] + OPERATING_SYSTEM_ABSTRACTION, // OS + OBJECT_MANAGER_IF, // OM + DEVICE_HANDLER_BASE, // DHB + RMAP_CHANNEL, // RMP + POWER_SWITCH_IF, // PS + HAS_MEMORY_IF, // PP + DEVICE_STATE_MACHINE_BASE, // DSMB + DATA_SET_CLASS, // DPS + POOL_RAW_ACCESS_CLASS, // DPR + CONTROLLER_BASE, // CTR + SUBSYSTEM_BASE, // SB + MODE_STORE_IF, // MS + SUBSYSTEM, // SS + HAS_MODES_IF, // HM + COMMAND_MESSAGE, // CM + CCSDS_TIME_HELPER_CLASS, // TIM + ARRAY_LIST, // AL + ASSEMBLY_BASE, // AB + MEMORY_HELPER, // MH + SERIALIZE_IF, // SE + FIXED_MAP, // FM + FIXED_MULTIMAP, // FMM + HAS_HEALTH_IF, // HHI + FIFO_CLASS, // FF + MESSAGE_PROXY, // MQP + TRIPLE_REDUNDACY_CHECK, // TRC + TC_PACKET_CHECK, // TCC + PACKET_DISTRIBUTION, // TCD + ACCEPTS_TELECOMMANDS_IF, // PUS + DEVICE_SERVICE_BASE, // DSB + COMMAND_SERVICE_BASE, // CSB + TM_STORE_BACKEND_IF, // TMB + TM_STORE_FRONTEND_IF, // TMF + STORAGE_AND_RETRIEVAL_SERVICE, // SR + MATCH_TREE_CLASS, // MT + EVENT_MANAGER_IF, // EV + HANDLES_FAILURES_IF, // FDI + DEVICE_HANDLER_IF, // DHI + STORAGE_MANAGER_IF, // SM + THERMAL_COMPONENT_IF, // TC + INTERNAL_ERROR_CODES, // IEC + TRAP, // TRP + CCSDS_HANDLER_IF, // CCS + PARAMETER_WRAPPER, // PAW + HAS_PARAMETERS_IF, // HPA + ASCII_CONVERTER, // ASC + POWER_SWITCHER, // POS + LIMITS_IF, // LIM + COMMANDS_ACTIONS_IF, // CF + HAS_ACTIONS_IF, // HF + DEVICE_COMMUNICATION_IF, // DC + BSP, // BSP + CFDP, // CFDP + TIME_STAMPER_IF, // TSI + SGP4PROPAGATOR_CLASS, // SGP4 + MUTEX_IF, // MUX + MESSAGE_QUEUE_IF, // MQI + SEMAPHORE_IF, // SPH + LOCAL_POOL_OWNER_IF, // LPIF + POOL_VARIABLE_IF, // PVA + HOUSEKEEPING_MANAGER, // HKM + DLE_ENCODER, // DLEE + PUS_SERVICE_3, // PUS3 + PUS_SERVICE_9, // PUS9 + FILE_SYSTEM, // FILS + LINUX_OSAL, // UXOS + HAL_SPI, // HSPI + HAL_UART, // HURT + HAL_I2C, // HI2C + HAL_GPIO, // HGIO + FIXED_SLOT_TASK_IF, // FTIF + MGM_LIS3MDL, // MGMLIS3 + MGM_RM3100, // MGMRM3100 + SPACE_PACKET_PARSER, // SPPA + FW_CLASS_ID_COUNT // [EXPORT] : [END] }; } diff --git a/src/fsfw/returnvalues/HasReturnvaluesIF.h b/src/fsfw/returnvalues/HasReturnvaluesIF.h index e9321ace..eec80228 100644 --- a/src/fsfw/returnvalues/HasReturnvaluesIF.h +++ b/src/fsfw/returnvalues/HasReturnvaluesIF.h @@ -1,31 +1,31 @@ #ifndef FSFW_RETURNVALUES_HASRETURNVALUESIF_H_ #define FSFW_RETURNVALUES_HASRETURNVALUESIF_H_ -#include "FwClassIds.h" #include + #include -#define MAKE_RETURN_CODE( number ) ((INTERFACE_ID << 8) + (number)) +#include "FwClassIds.h" + +#define MAKE_RETURN_CODE(number) ((INTERFACE_ID << 8) + (number)) typedef uint16_t ReturnValue_t; - class HasReturnvaluesIF { -public: - static const ReturnValue_t RETURN_OK = 0; - static const ReturnValue_t RETURN_FAILED = 1; - virtual ~HasReturnvaluesIF() {} + public: + static const ReturnValue_t RETURN_OK = 0; + static const ReturnValue_t RETURN_FAILED = 1; + virtual ~HasReturnvaluesIF() {} - /** - * It is discouraged to use the input parameters 0,0 and 0,1 as this - * will generate the RETURN_OK and RETURN_FAILED returnvalues. - * @param interfaceId - * @param number - * @return - */ - static constexpr ReturnValue_t makeReturnCode(uint8_t classId, - uint8_t number) { - return (static_cast(classId) << 8) + number; - } + /** + * It is discouraged to use the input parameters 0,0 and 0,1 as this + * will generate the RETURN_OK and RETURN_FAILED returnvalues. + * @param interfaceId + * @param number + * @return + */ + static constexpr ReturnValue_t makeReturnCode(uint8_t classId, uint8_t number) { + return (static_cast(classId) << 8) + number; + } }; #endif /* FSFW_RETURNVALUES_HASRETURNVALUESIF_H_ */ diff --git a/src/fsfw/rmap/RMAP.cpp b/src/fsfw/rmap/RMAP.cpp index 6ac4904d..00cb8d33 100644 --- a/src/fsfw/rmap/RMAP.cpp +++ b/src/fsfw/rmap/RMAP.cpp @@ -1,91 +1,79 @@ #include "fsfw/rmap/RMAP.h" -#include "fsfw/rmap/rmapStructs.h" -#include "fsfw/rmap/RMAPChannelIF.h" - -#include "fsfw/devicehandlers/DeviceCommunicationIF.h" #include -ReturnValue_t RMAP::reset(RMAPCookie* cookie) { - return cookie->getChannel()->reset(); -} +#include "fsfw/devicehandlers/DeviceCommunicationIF.h" +#include "fsfw/rmap/RMAPChannelIF.h" +#include "fsfw/rmap/rmapStructs.h" -RMAP::RMAP(){ +ReturnValue_t RMAP::reset(RMAPCookie *cookie) { return cookie->getChannel()->reset(); } -} +RMAP::RMAP() {} -ReturnValue_t RMAP::sendWriteCommand(RMAPCookie *cookie, const uint8_t* buffer, - size_t length) { - uint8_t instruction; - - if ((buffer == NULL) && (length != 0)) { - return DeviceCommunicationIF::NULLPOINTER; - } - if (cookie->getChannel() == NULL) { - return COMMAND_NO_CHANNEL; - } - instruction = RMAPIds::RMAP_COMMAND_WRITE | cookie->getCommandMask(); - return cookie->getChannel()->sendCommand(cookie, instruction, buffer, - length); +ReturnValue_t RMAP::sendWriteCommand(RMAPCookie *cookie, const uint8_t *buffer, size_t length) { + uint8_t instruction; + if ((buffer == NULL) && (length != 0)) { + return DeviceCommunicationIF::NULLPOINTER; + } + if (cookie->getChannel() == NULL) { + return COMMAND_NO_CHANNEL; + } + instruction = RMAPIds::RMAP_COMMAND_WRITE | cookie->getCommandMask(); + return cookie->getChannel()->sendCommand(cookie, instruction, buffer, length); } ReturnValue_t RMAP::getWriteReply(RMAPCookie *cookie) { - if (cookie->getChannel() == NULL) { - return COMMAND_NO_CHANNEL; - } - if (cookie->getHeader()->instruction & (1 << RMAPIds::RMAP_COMMAND_BIT_WRITE)) { - return cookie->getChannel()->getReply(cookie, NULL, NULL); - } else { - return REPLY_MISSMATCH; - } + if (cookie->getChannel() == NULL) { + return COMMAND_NO_CHANNEL; + } + if (cookie->getHeader()->instruction & (1 << RMAPIds::RMAP_COMMAND_BIT_WRITE)) { + return cookie->getChannel()->getReply(cookie, NULL, NULL); + } else { + return REPLY_MISSMATCH; + } } -ReturnValue_t RMAP::writeBlocking(RMAPCookie *cookie, uint8_t* buffer, - uint32_t length, uint32_t timeout_us) { - if (cookie->getChannel() == NULL) { - return COMMAND_NO_CHANNEL; - } - return cookie->getChannel()->sendCommandBlocking(cookie, buffer, length, - NULL, NULL, timeout_us); - +ReturnValue_t RMAP::writeBlocking(RMAPCookie *cookie, uint8_t *buffer, uint32_t length, + uint32_t timeout_us) { + if (cookie->getChannel() == NULL) { + return COMMAND_NO_CHANNEL; + } + return cookie->getChannel()->sendCommandBlocking(cookie, buffer, length, NULL, NULL, timeout_us); } ReturnValue_t RMAP::sendReadCommand(RMAPCookie *cookie, uint32_t expLength) { - uint8_t command; - if (cookie->getChannel() == NULL) { - return COMMAND_NO_CHANNEL; - } - command = RMAPIds::RMAP_COMMAND_READ - | (cookie->getCommandMask() & ~(1 << RMAPIds::RMAP_COMMAND_BIT_VERIFY)); - - return cookie->getChannel()->sendCommand(cookie, command, NULL, expLength); + uint8_t command; + if (cookie->getChannel() == NULL) { + return COMMAND_NO_CHANNEL; + } + command = RMAPIds::RMAP_COMMAND_READ | + (cookie->getCommandMask() & ~(1 << RMAPIds::RMAP_COMMAND_BIT_VERIFY)); + return cookie->getChannel()->sendCommand(cookie, command, NULL, expLength); } -ReturnValue_t RMAP::getReadReply(RMAPCookie *cookie, uint8_t **buffer, - size_t *size) { - if (cookie->getChannel() == NULL) { - return COMMAND_NO_CHANNEL; - } - if (buffer == NULL || size == NULL) { - return DeviceCommunicationIF::NULLPOINTER; - } - if (cookie->getHeader()->instruction & (1 << RMAPIds::RMAP_COMMAND_BIT_WRITE)) { - return REPLY_MISSMATCH; - } else { - return cookie->getChannel()->getReply(cookie, buffer, size); - } - +ReturnValue_t RMAP::getReadReply(RMAPCookie *cookie, uint8_t **buffer, size_t *size) { + if (cookie->getChannel() == NULL) { + return COMMAND_NO_CHANNEL; + } + if (buffer == NULL || size == NULL) { + return DeviceCommunicationIF::NULLPOINTER; + } + if (cookie->getHeader()->instruction & (1 << RMAPIds::RMAP_COMMAND_BIT_WRITE)) { + return REPLY_MISSMATCH; + } else { + return cookie->getChannel()->getReply(cookie, buffer, size); + } } -ReturnValue_t RMAP::readBlocking(RMAPCookie *cookie, uint32_t expLength, - uint8_t** buffer, uint32_t *size, uint32_t timeout_us) { - if (cookie->getChannel() == NULL) { - return COMMAND_NO_CHANNEL; - } - if (buffer == NULL || size == NULL) { - return DeviceCommunicationIF::NULLPOINTER; - } - return cookie->getChannel()->sendCommandBlocking(cookie, NULL, expLength, - buffer, size, timeout_us); +ReturnValue_t RMAP::readBlocking(RMAPCookie *cookie, uint32_t expLength, uint8_t **buffer, + uint32_t *size, uint32_t timeout_us) { + if (cookie->getChannel() == NULL) { + return COMMAND_NO_CHANNEL; + } + if (buffer == NULL || size == NULL) { + return DeviceCommunicationIF::NULLPOINTER; + } + return cookie->getChannel()->sendCommandBlocking(cookie, NULL, expLength, buffer, size, + timeout_us); } diff --git a/src/fsfw/rmap/RMAP.h b/src/fsfw/rmap/RMAP.h index ff310db0..d46fc318 100644 --- a/src/fsfw/rmap/RMAP.h +++ b/src/fsfw/rmap/RMAP.h @@ -1,228 +1,245 @@ #ifndef FSFW_RMAP_RMAP_H_ #define FSFW_RMAP_RMAP_H_ -#include "rmapConf.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" #include "fsfw/rmap/RMAPCookie.h" +#include "rmapConf.h" -//SHOULDTODO: clean up includes for RMAP, should be enough to include RMAP.h but right now it's quite chaotic... +// SHOULDTODO: clean up includes for RMAP, should be enough to include RMAP.h but right now it's +// quite chaotic... /** * API for a Cookie/Channel based RMAP implementation. * - * The API offers the four basic RMAP actions: sending a Read or Write command and getting the reply to each. - * As RMAP is an asynchronous protocol, these are implemented as four seperate calls. There are blocking - * calls which combine a send and get call using a timeout, but these are "real" blocking, looping in between - * the calls. + * The API offers the four basic RMAP actions: sending a Read or Write command and getting the reply + * to each. As RMAP is an asynchronous protocol, these are implemented as four seperate calls. There + * are blocking calls which combine a send and get call using a timeout, but these are "real" + * blocking, looping in between the calls. * - * Cookies are used to contain Information between a send[Read,Write]Command and a get[Read,Write]Reply call, - * one can think of them like *nix file descriptors. A cookie is valid from a sendX call until the related getX - * call. That means if a cookie is used in a getX call, the reply to the sendX call the cookie was used with - * previously is returned. - * Depending on the underlying RMAPChannel implementation, a cookie can also be valid for more than one getX - * call, but this should not be assumed generally. - * A cookie encapsulates information like the RMAP Channel to use, as well as the RMAP Address - * and a Command Mask used for specifying which RMAP capabilities are used. - * Cookies are created without interaction with this API, there is no open() call. The RMAP implementation - * will initialize all fields which are not set by the cookie's constructor. + * Cookies are used to contain Information between a send[Read,Write]Command and a + * get[Read,Write]Reply call, one can think of them like *nix file descriptors. A cookie is valid + * from a sendX call until the related getX call. That means if a cookie is used in a getX call, the + * reply to the sendX call the cookie was used with previously is returned. Depending on the + * underlying RMAPChannel implementation, a cookie can also be valid for more than one getX call, + * but this should not be assumed generally. A cookie encapsulates information like the RMAP Channel + * to use, as well as the RMAP Address and a Command Mask used for specifying which RMAP + * capabilities are used. Cookies are created without interaction with this API, there is no open() + * call. The RMAP implementation will initialize all fields which are not set by the cookie's + * constructor. * - * The RMAP implementation relies on Channels. A channel is used to construct the RMAP Headers and handle the - * protocol. It is access via the RMAPChannelIF. Thus it is possible to use different Implementations which only - * need to implement the RMAPChannelIF. A channel is also responsible for accessing the lower layers, for example - * a SPaceWire transport layer. + * The RMAP implementation relies on Channels. A channel is used to construct the RMAP Headers and + * handle the protocol. It is access via the RMAPChannelIF. Thus it is possible to use different + * Implementations which only need to implement the RMAPChannelIF. A channel is also responsible for + * accessing the lower layers, for example a SPaceWire transport layer. * - * There is one RMAP Channel per physical device. The cookie-channel as well as the device-channel assignment - * can be changed at runtime to allow for example redundancy switching. This API is static as the information which - * channel to use is contained within the cookie. + * There is one RMAP Channel per physical device. The cookie-channel as well as the device-channel + * assignment can be changed at runtime to allow for example redundancy switching. This API is + * static as the information which channel to use is contained within the cookie. */ -class RMAP: public HasReturnvaluesIF { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::RMAP_CHANNEL; +class RMAP : public HasReturnvaluesIF { + public: + static const uint8_t INTERFACE_ID = CLASS_ID::RMAP_CHANNEL; - //static const ReturnValue_t COMMAND_OK = MAKE_RETURN_CODE(0x00); - static const ReturnValue_t COMMAND_NO_DESCRIPTORS_AVAILABLE = - MAKE_RETURN_CODE(0xE1); //no descriptors available for sending command; command was not sent - static const ReturnValue_t COMMAND_BUFFER_FULL = MAKE_RETURN_CODE(0xE2); //no receiver buffer available for expected len; command was not sent - static const ReturnValue_t COMMAND_CHANNEL_OUT_OF_RANGE = MAKE_RETURN_CODE( - 0xE3); //The cookie points to an invalid channel; command was not sent -//Replaced by DeviceCommunicationIF::TOO_MUCH_DATA static const ReturnValue_t COMMAND_TOO_BIG = MAKE_RETURN_CODE(0xE4); //the data that was to be sent was too long for the hw to handle (write command) or the expected len was bigger than maximal expected len (read command) - //command was not sent -//replaced by DeviceCommunicationIF::NULLPOINTER static const ReturnValue_t COMMAND_NULLPOINTER = MAKE_RETURN_CODE(0xE5); //datalen was != 0 but data was == NULL in write command, or nullpointer in read command - static const ReturnValue_t COMMAND_CHANNEL_DEACTIVATED = MAKE_RETURN_CODE( - 0xE6); //the channel has no port set - static const ReturnValue_t COMMAND_PORT_OUT_OF_RANGE = MAKE_RETURN_CODE( - 0xE7); //The specified port is not valid - static const ReturnValue_t COMMAND_PORT_IN_USE = MAKE_RETURN_CODE(0xE8);//The specified port is already in use - static const ReturnValue_t COMMAND_NO_CHANNEL = MAKE_RETURN_CODE(0xE9);//The cookie to work with has no channel assigned. - static const ReturnValue_t NO_HW_CRC = MAKE_RETURN_CODE(0xEA);//The SpW port does not support HW CRC generation, which is unsupported - //return values for both get_write_reply and get_read_reply - static const ReturnValue_t REPLY_NO_REPLY = MAKE_RETURN_CODE(0xD0); //no reply was received - static const ReturnValue_t REPLY_NOT_SENT = MAKE_RETURN_CODE(0xD1); //command was not sent, implies no reply - static const ReturnValue_t REPLY_NOT_YET_SENT = MAKE_RETURN_CODE(0xD2); //command is still waiting to be sent - static const ReturnValue_t REPLY_MISSMATCH = MAKE_RETURN_CODE(0xD3);//a read command was issued, but get_write_rply called, or other way round - static const ReturnValue_t REPLY_TIMEOUT = MAKE_RETURN_CODE(0xD4);//timeout -//replaced by DeviceCommunicationIF::NULLPOINTER static const ReturnValue_t REPLY_NULLPOINTER = MAKE_RETURN_CODE(0xD5);//one of the arguments in a read reply was NULL - //return values for get_reply - static const ReturnValue_t REPLY_INTERFACE_BUSY = MAKE_RETURN_CODE( - 0xC0);//Interface is busy (transmission buffer still being processed) - static const ReturnValue_t REPLY_TRANSMISSION_ERROR = - MAKE_RETURN_CODE(0xC1); //Interface encountered errors during last operation, data could not be processed. (transmission error) - static const ReturnValue_t REPLY_INVALID_DATA = MAKE_RETURN_CODE( - 0xC2); //Invalid data (amount / value) - static const ReturnValue_t REPLY_NOT_SUPPORTED = MAKE_RETURN_CODE( - 0xC3); + // static const ReturnValue_t COMMAND_OK = MAKE_RETURN_CODE(0x00); + static const ReturnValue_t COMMAND_NO_DESCRIPTORS_AVAILABLE = + MAKE_RETURN_CODE(0xE1); // no descriptors available for sending command; command was not sent + static const ReturnValue_t COMMAND_BUFFER_FULL = MAKE_RETURN_CODE( + 0xE2); // no receiver buffer available for expected len; command was not sent + static const ReturnValue_t COMMAND_CHANNEL_OUT_OF_RANGE = + MAKE_RETURN_CODE(0xE3); // The cookie points to an invalid channel; command was not sent + // Replaced by DeviceCommunicationIF::TOO_MUCH_DATA static const ReturnValue_t COMMAND_TOO_BIG = + // MAKE_RETURN_CODE(0xE4); //the data that was to be sent was too long for the hw to handle (write + // command) or the expected len was bigger than maximal expected len (read command) command was + // not sent + // replaced by DeviceCommunicationIF::NULLPOINTER static const ReturnValue_t COMMAND_NULLPOINTER + // = MAKE_RETURN_CODE(0xE5); //datalen was != 0 but data was == NULL in write command, or + // nullpointer in read command + static const ReturnValue_t COMMAND_CHANNEL_DEACTIVATED = + MAKE_RETURN_CODE(0xE6); // the channel has no port set + static const ReturnValue_t COMMAND_PORT_OUT_OF_RANGE = + MAKE_RETURN_CODE(0xE7); // The specified port is not valid + static const ReturnValue_t COMMAND_PORT_IN_USE = + MAKE_RETURN_CODE(0xE8); // The specified port is already in use + static const ReturnValue_t COMMAND_NO_CHANNEL = + MAKE_RETURN_CODE(0xE9); // The cookie to work with has no channel assigned. + static const ReturnValue_t NO_HW_CRC = MAKE_RETURN_CODE( + 0xEA); // The SpW port does not support HW CRC generation, which is unsupported + // return values for both get_write_reply and get_read_reply + static const ReturnValue_t REPLY_NO_REPLY = MAKE_RETURN_CODE(0xD0); // no reply was received + static const ReturnValue_t REPLY_NOT_SENT = + MAKE_RETURN_CODE(0xD1); // command was not sent, implies no reply + static const ReturnValue_t REPLY_NOT_YET_SENT = + MAKE_RETURN_CODE(0xD2); // command is still waiting to be sent + static const ReturnValue_t REPLY_MISSMATCH = MAKE_RETURN_CODE( + 0xD3); // a read command was issued, but get_write_rply called, or other way round + static const ReturnValue_t REPLY_TIMEOUT = MAKE_RETURN_CODE(0xD4); // timeout + // replaced by DeviceCommunicationIF::NULLPOINTER static const ReturnValue_t REPLY_NULLPOINTER = + // MAKE_RETURN_CODE(0xD5);//one of the arguments in a read reply was NULL return values for + // get_reply + static const ReturnValue_t REPLY_INTERFACE_BUSY = + MAKE_RETURN_CODE(0xC0); // Interface is busy (transmission buffer still being processed) + static const ReturnValue_t REPLY_TRANSMISSION_ERROR = + MAKE_RETURN_CODE(0xC1); // Interface encountered errors during last operation, data could not + // be processed. (transmission error) + static const ReturnValue_t REPLY_INVALID_DATA = + MAKE_RETURN_CODE(0xC2); // Invalid data (amount / value) + static const ReturnValue_t REPLY_NOT_SUPPORTED = MAKE_RETURN_CODE(0xC3); - //return values for reset - static const ReturnValue_t LINK_DOWN = MAKE_RETURN_CODE(0xF0);//The spw link is down - //Other SpW codes: - static const ReturnValue_t SPW_CREDIT = MAKE_RETURN_CODE(0xF1); - static const ReturnValue_t SPW_ESCAPE = MAKE_RETURN_CODE(0xF2); - static const ReturnValue_t SPW_DISCONNECT = MAKE_RETURN_CODE(0xF3); - static const ReturnValue_t SPW_PARITY = MAKE_RETURN_CODE(0xF4); - static const ReturnValue_t SPW_WRITE_SYNC = MAKE_RETURN_CODE(0xF5); - static const ReturnValue_t SPW_INVALID_ADDRESS = MAKE_RETURN_CODE(0xF6); - static const ReturnValue_t SPW_EARLY_EOP = MAKE_RETURN_CODE(0xF7); - static const ReturnValue_t SPW_DMA = MAKE_RETURN_CODE(0xF8); - static const ReturnValue_t SPW_LINK_ERROR = MAKE_RETURN_CODE(0xF9); + // return values for reset + static const ReturnValue_t LINK_DOWN = MAKE_RETURN_CODE(0xF0); // The spw link is down + // Other SpW codes: + static const ReturnValue_t SPW_CREDIT = MAKE_RETURN_CODE(0xF1); + static const ReturnValue_t SPW_ESCAPE = MAKE_RETURN_CODE(0xF2); + static const ReturnValue_t SPW_DISCONNECT = MAKE_RETURN_CODE(0xF3); + static const ReturnValue_t SPW_PARITY = MAKE_RETURN_CODE(0xF4); + static const ReturnValue_t SPW_WRITE_SYNC = MAKE_RETURN_CODE(0xF5); + static const ReturnValue_t SPW_INVALID_ADDRESS = MAKE_RETURN_CODE(0xF6); + static const ReturnValue_t SPW_EARLY_EOP = MAKE_RETURN_CODE(0xF7); + static const ReturnValue_t SPW_DMA = MAKE_RETURN_CODE(0xF8); + static const ReturnValue_t SPW_LINK_ERROR = MAKE_RETURN_CODE(0xF9); + // RMAP standard replies + static const ReturnValue_t REPLY_OK = MAKE_RETURN_CODE(0); + static const ReturnValue_t REPLY_GENERAL_ERROR_CODE = + MAKE_RETURN_CODE(1); // The detected error does not fit into the other + // error cases or the node does not support + // further distinction between the errors + static const ReturnValue_t REPLY_UNUSED_PACKET_TYPE_OR_COMMAND_CODE = + MAKE_RETURN_CODE(2); // The Header CRC was decoded correctly but + // the packet type is reserved or the command + // is not used by the RMAP protocol. + static const ReturnValue_t REPLY_INVALID_KEY = + MAKE_RETURN_CODE(3); // The Header CRC was decoded correctly but + // the device key did not match that expected + // by the target user application + static const ReturnValue_t REPLY_INVALID_DATA_CRC = + MAKE_RETURN_CODE(4); // Error in the CRC of the data field + static const ReturnValue_t REPLY_EARLY_EOP = + MAKE_RETURN_CODE(5); // EOP marker detected before the end of the data + static const ReturnValue_t REPLY_TOO_MUCH_DATA = + MAKE_RETURN_CODE(6); // More than the expected amount of data in a + // command has been received + static const ReturnValue_t REPLY_EEP = + MAKE_RETURN_CODE(7); // EEP marker detected immediately after the + // header CRC or during the transfer of data + // and Data CRC or immediately thereafter. + // Indicates that there was a communication + // failure of some sort on the network + static const ReturnValue_t REPLY_RESERVED = MAKE_RETURN_CODE(8); // Reserved + static const ReturnValue_t REPLY_VERIFY_BUFFER_OVERRUN = + MAKE_RETURN_CODE(9); // The verify before write bit of the command + // was set so that the data field was buffered in + // order to verify the Data CRC before + // transferring the data to target memory. The + // data field was longer than able to fit inside + // the verify buffer resulting in a buffer overrun + // Note that the command is not executed in + // this case + static const ReturnValue_t REPLY_COMMAND_NOT_IMPLEMENTED_OR_NOT_AUTHORISED = + MAKE_RETURN_CODE(10); // The target user application did not authorise + // the requested operation. This may be because + // the command requested has not been + // implemented + static const ReturnValue_t REPLY_RMW_DATA_LENGTH_ERROR = + MAKE_RETURN_CODE(11); // The amount of data in a RMW command is + // invalid (0x01 0x03 0x05 0x07 or greater + // than 0x08) + static const ReturnValue_t REPLY_INVALID_TARGET_LOGICAL_ADDRESS = + MAKE_RETURN_CODE(12); // The Header CRC was decoded correctly but + // the Target Logical Address was not the value + // expected by the target - //RMAP standard replies - static const ReturnValue_t REPLY_OK = MAKE_RETURN_CODE(0); - static const ReturnValue_t REPLY_GENERAL_ERROR_CODE = MAKE_RETURN_CODE(1);// The detected error does not fit into the other - // error cases or the node does not support - // further distinction between the errors - static const ReturnValue_t REPLY_UNUSED_PACKET_TYPE_OR_COMMAND_CODE = - MAKE_RETURN_CODE(2); // The Header CRC was decoded correctly but - // the packet type is reserved or the command - // is not used by the RMAP protocol. - static const ReturnValue_t REPLY_INVALID_KEY = MAKE_RETURN_CODE(3); // The Header CRC was decoded correctly but - // the device key did not match that expected - // by the target user application - static const ReturnValue_t REPLY_INVALID_DATA_CRC = MAKE_RETURN_CODE(4);// Error in the CRC of the data field - static const ReturnValue_t REPLY_EARLY_EOP = MAKE_RETURN_CODE(5);// EOP marker detected before the end of the data - static const ReturnValue_t REPLY_TOO_MUCH_DATA = MAKE_RETURN_CODE(6);// More than the expected amount of data in a - // command has been received - static const ReturnValue_t REPLY_EEP = MAKE_RETURN_CODE(7); // EEP marker detected immediately after the - // header CRC or during the transfer of data - // and Data CRC or immediately thereafter. - // Indicates that there was a communication - // failure of some sort on the network - static const ReturnValue_t REPLY_RESERVED = MAKE_RETURN_CODE(8);// Reserved - static const ReturnValue_t REPLY_VERIFY_BUFFER_OVERRUN = MAKE_RETURN_CODE( - 9); // The verify before write bit of the command - // was set so that the data field was buffered in - // order to verify the Data CRC before - // transferring the data to target memory. The - // data field was longer than able to fit inside - // the verify buffer resulting in a buffer overrun - // Note that the command is not executed in - // this case - static const ReturnValue_t REPLY_COMMAND_NOT_IMPLEMENTED_OR_NOT_AUTHORISED = - MAKE_RETURN_CODE(10);// The target user application did not authorise - // the requested operation. This may be because - // the command requested has not been - // implemented - static const ReturnValue_t REPLY_RMW_DATA_LENGTH_ERROR = MAKE_RETURN_CODE( - 11); // The amount of data in a RMW command is - // invalid (0x01 0x03 0x05 0x07 or greater - // than 0x08) - static const ReturnValue_t REPLY_INVALID_TARGET_LOGICAL_ADDRESS = - MAKE_RETURN_CODE(12); // The Header CRC was decoded correctly but - // the Target Logical Address was not the value - // expected by the target + /** + * Resets the underlying channel. + * + * @param cookie The cookie which points to the channel to reset + * @return + */ + static ReturnValue_t reset(RMAPCookie *cookie); - /** - * Resets the underlying channel. - * - * @param cookie The cookie which points to the channel to reset - * @return - */ - static ReturnValue_t reset(RMAPCookie *cookie); + /** + * send an RMAP write command + * + * datalen is only 24bit wide, rest will be ignored + * IMPORTANT: the data buffer must be datalen+1 large, as the driver might + * write a CRC sum at data[datalen] + * if you want to send an empty packet, just do datalen = 0 and data = NULL + * + * @param cookie The cookie to write to + * @param buffer the data to write + * @param length length of data + * @return + * - @c COMMAND_NULLPOINTER datalen was != 0 but data was == NULL in write + * command + * - return codes of RMAPChannelIF::sendCommand() + */ + static ReturnValue_t sendWriteCommand(RMAPCookie *cookie, const uint8_t *buffer, size_t length); - /** - * send an RMAP write command - * - * datalen is only 24bit wide, rest will be ignored - * IMPORTANT: the data buffer must be datalen+1 large, as the driver might - * write a CRC sum at data[datalen] - * if you want to send an empty packet, just do datalen = 0 and data = NULL - * - * @param cookie The cookie to write to - * @param buffer the data to write - * @param length length of data - * @return - * - @c COMMAND_NULLPOINTER datalen was != 0 but data was == NULL in write command - * - return codes of RMAPChannelIF::sendCommand() - */ - static ReturnValue_t sendWriteCommand(RMAPCookie *cookie, const uint8_t* buffer, - size_t length); + /** + * get the reply to a write command + * + * @param cookie the cookie the command was sent with + * @return + * - @c REPLY_MISSMATCH a read command was issued, but getWriteReply called + * - return codes of RMAPChannelIF::getReply() + */ + static ReturnValue_t getWriteReply(RMAPCookie *cookie); - /** - * get the reply to a write command - * - * @param cookie the cookie the command was sent with - * @return - * - @c REPLY_MISSMATCH a read command was issued, but getWriteReply called - * - return codes of RMAPChannelIF::getReply() - */ - static ReturnValue_t getWriteReply(RMAPCookie *cookie); + /** + * @see sendWriteCommand() + * @see getWriteReply() + * + * @param timeout_us the time after the function returns, if no reply was received + * + * @return + * - All of sendWriteCommand() + * - All of getWriteReply() + * - @c REPLY_TIMEOUT timeout + */ + static ReturnValue_t writeBlocking(RMAPCookie *cookie, uint8_t *buffer, uint32_t length, + uint32_t timeout_us); - /** - * @see sendWriteCommand() - * @see getWriteReply() - * - * @param timeout_us the time after the function returns, if no reply was received - * - * @return - * - All of sendWriteCommand() - * - All of getWriteReply() - * - @c REPLY_TIMEOUT timeout - */ - static ReturnValue_t writeBlocking(RMAPCookie *cookie, uint8_t* buffer, - uint32_t length, uint32_t timeout_us); + /** + * send an RMAP read command + * + * @param cookie to cookie to read from + * @param expLength the expected maximum length of the reply + * @return + * - @c COMMAND_NULLPOINTER datalen was != 0 but data was == NULL in write + * command, or nullpointer in read command + * - return codes of RMAPChannelIF::sendCommand() + */ + static ReturnValue_t sendReadCommand(RMAPCookie *cookie, uint32_t expLength); - /** - * send an RMAP read command - * - * @param cookie to cookie to read from - * @param expLength the expected maximum length of the reply - * @return - * - @c COMMAND_NULLPOINTER datalen was != 0 but data was == NULL in write command, or nullpointer in read command - * - return codes of RMAPChannelIF::sendCommand() - */ - static ReturnValue_t sendReadCommand(RMAPCookie *cookie, - uint32_t expLength); + /** + * get a reply to an RMAP read command + * + * @param cookie the cookie that was read from + * @param[out] buffer the location of the data + * @param[out] size size of the data + * @return + * - @c COMMAND_NULLPOINTER buffer or size was NULL + * - @c REPLY_MISSMATCH a write command was issued, but getReadReply called + * - return codes of RMAPChannelIF::getReply() + */ + static ReturnValue_t getReadReply(RMAPCookie *cookie, uint8_t **buffer, size_t *size); - /** - * get a reply to an RMAP read command - * - * @param cookie the cookie that was read from - * @param[out] buffer the location of the data - * @param[out] size size of the data - * @return - * - @c COMMAND_NULLPOINTER buffer or size was NULL - * - @c REPLY_MISSMATCH a write command was issued, but getReadReply called - * - return codes of RMAPChannelIF::getReply() - */ - static ReturnValue_t getReadReply(RMAPCookie *cookie, uint8_t **buffer, - size_t *size); + /** + * @see sendReadCommand() + * @see getReadReply() + * + * @param timeout_us the time after the function returns, if no reply was received + * + * @return + * - All of sendReadCommand() + * - All of getReadReply() + * - @c REPLY_TIMEOUT timeout + */ + static ReturnValue_t readBlocking(RMAPCookie *cookie, uint32_t expLength, uint8_t **buffer, + uint32_t *size, uint32_t timeout_us); - /** - * @see sendReadCommand() - * @see getReadReply() - * - * @param timeout_us the time after the function returns, if no reply was received - * - * @return - * - All of sendReadCommand() - * - All of getReadReply() - * - @c REPLY_TIMEOUT timeout - */ - static ReturnValue_t readBlocking(RMAPCookie *cookie, uint32_t expLength, - uint8_t** buffer, uint32_t *size, uint32_t timeout_us); - -protected: - RMAP(); + protected: + RMAP(); }; #endif /* RMAPpp_H_ */ diff --git a/src/fsfw/rmap/RMAPChannelIF.h b/src/fsfw/rmap/RMAPChannelIF.h index 7fbda348..77b56eb9 100644 --- a/src/fsfw/rmap/RMAPChannelIF.h +++ b/src/fsfw/rmap/RMAPChannelIF.h @@ -1,117 +1,127 @@ #ifndef FSFW_RMAP_RMAPCHANNELIF_H_ #define FSFW_RMAP_RMAPCHANNELIF_H_ -#include "rmapConf.h" -#include "RMAPCookie.h" -#include "fsfw/returnvalues/HasReturnvaluesIF.h" #include +#include "RMAPCookie.h" +#include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "rmapConf.h" + class RMAPChannelIF { -public: - virtual ~RMAPChannelIF(){}; - /** - * Reset an RMAP channel - * - * Clears the receive buffer (all received messages are deleted) and resets the descriptor table. - * Also checks for errors in the descriptors and submits them to FDIR (aka stdout) - * - * @param channel to reset - * - * @return - * - @c LINK_DOWN when the link is down and all replies were missed - * - @c COMMAND_CHANNEL_DEACTIVATED if the channel's port is NULL - * - @c RETURN_OK else - */ - virtual ReturnValue_t reset()=0; + public: + virtual ~RMAPChannelIF(){}; + /** + * Reset an RMAP channel + * + * Clears the receive buffer (all received messages are deleted) and resets the descriptor table. + * Also checks for errors in the descriptors and submits them to FDIR (aka stdout) + * + * @param channel to reset + * + * @return + * - @c LINK_DOWN when the link is down and all replies were missed + * - @c COMMAND_CHANNEL_DEACTIVATED if the channel's port is NULL + * - @c RETURN_OK else + */ + virtual ReturnValue_t reset() = 0; - /** - * Check if a channel is active (ie has a port) - * - * @param channel_nr - * @return - * - @c COMMAND_OK if channel is active - * - @c COMMAND_CHANNEL_DEACTIVATED if channel is deactivated - */ - virtual ReturnValue_t isActive()=0; + /** + * Check if a channel is active (ie has a port) + * + * @param channel_nr + * @return + * - @c COMMAND_OK if channel is active + * - @c COMMAND_CHANNEL_DEACTIVATED if channel is deactivated + */ + virtual ReturnValue_t isActive() = 0; - /** - * Assign a SpaceWire port to the Channel - * - * @param port Number of the port. SpaceWire devices are mapped to port numbers to allow checking of the validity - * @param dest_addr the destination address used by all packets sent from this channel - * @param src_addr the source address used by all packets sent from this channel and used when checking incoming packets - * @return - * - @c COMMAND_OK if port was changed - * - @c COMMAND_PORT_OUT_OF_RANGE if the port is invalid - */ - virtual ReturnValue_t setPort(int8_t port, uint8_t dest_addr, - uint8_t src_addr)=0; + /** + * Assign a SpaceWire port to the Channel + * + * @param port Number of the port. SpaceWire devices are mapped to port numbers to allow + * checking of the validity + * @param dest_addr the destination address used by all packets sent from this channel + * @param src_addr the source address used by all packets sent from this channel and used when + * checking incoming packets + * @return + * - @c COMMAND_OK if port was changed + * - @c COMMAND_PORT_OUT_OF_RANGE if the port is invalid + */ + virtual ReturnValue_t setPort(int8_t port, uint8_t dest_addr, uint8_t src_addr) = 0; - /** - * Assign a SpaceWire port to the Channel - * - * same as setPort(int8_t port, uint8_t dest_addr, uint8_t src_addr), only the addresses are left unchanged - * - * @param port Number of the port. SpaceWire devices are mapped to port numbers to allow checking of the validity - * @return - * - @c COMMAND_OK if port was changed - * - @c COMMAND_PORT_OUT_OF_RANGE if the port is invalid - */ - virtual ReturnValue_t setPort(int8_t port)=0; + /** + * Assign a SpaceWire port to the Channel + * + * same as setPort(int8_t port, uint8_t dest_addr, uint8_t src_addr), only the addresses are left + * unchanged + * + * @param port Number of the port. SpaceWire devices are mapped to port numbers to allow + * checking of the validity + * @return + * - @c COMMAND_OK if port was changed + * - @c COMMAND_PORT_OUT_OF_RANGE if the port is invalid + */ + virtual ReturnValue_t setPort(int8_t port) = 0; - /** - * Send an RMAP command - * - * @param cookie the cookie used with this call - * @param instruction the instruction byte that will be sent (this defines if it is a read or write command) - * @param data data to be sent - * @param datalen length of data - * @return - * - @c RETURN_OK - * - @c COMMAND_NO_DESCRIPTORS_AVAILABLE no descriptors available for sending command; command was not sent - * - @c COMMAND_BUFFER_FULL no receiver buffer available for expected len; command was not sent - * - @c COMMAND_TOO_BIG the data that was to be sent was too long for the hw to handle (write command) or the expected len was bigger than maximal expected len (read command) command was not sent - * - @c COMMAND_CHANNEL_DEACTIVATED the channel has no port set - * - @c NOT_SUPPORTED if you dont feel like implementing something... - */ - virtual ReturnValue_t sendCommand(RMAPCookie *cookie, uint8_t instruction, - const uint8_t *data, size_t datalen)=0; + /** + * Send an RMAP command + * + * @param cookie the cookie used with this call + * @param instruction the instruction byte that will be sent (this defines if it is a read or + * write command) + * @param data data to be sent + * @param datalen length of data + * @return + * - @c RETURN_OK + * - @c COMMAND_NO_DESCRIPTORS_AVAILABLE no descriptors available for sending command; + * command was not sent + * - @c COMMAND_BUFFER_FULL no receiver buffer available for expected len; command + * was not sent + * - @c COMMAND_TOO_BIG the data that was to be sent was too long for the hw to + * handle (write command) or the expected len was bigger than maximal expected len (read command) + * command was not sent + * - @c COMMAND_CHANNEL_DEACTIVATED the channel has no port set + * - @c NOT_SUPPORTED if you dont feel like implementing + * something... + */ + virtual ReturnValue_t sendCommand(RMAPCookie *cookie, uint8_t instruction, const uint8_t *data, + size_t datalen) = 0; - /** - * get the reply to an rmap command - * - * @param cookie the cookie the command was sent with - * @param databuffer a pointer to a pointer the location of the reply will be written to - * @param len a pointer to the variable the length of the reply will be written to - * @return - * - @c REPLY_NO_REPLY no reply was received - * - @c REPLY_NOT_SENT command was not sent, implies no reply - * - @c REPLY_NOT_YET_SENT command is still waiting to be sent - * - @c WRITE_REPLY_INTERFACE_BUSY Interface is busy (transmission buffer still being processed) - * - @c WRITE_REPLY_TRANSMISSION_ERROR Interface encountered errors during last operation, data could not be processed. (transmission error) - * - @c WRITE_REPLY_INVALID_DATA Invalid data (amount / value) - * - @c WRITE_REPLY_NOT_SUPPORTED - * - all RMAP standard replies - */ - virtual ReturnValue_t getReply(RMAPCookie *cookie, uint8_t **databuffer, - size_t *len)=0; - - /** - * - * @param cookie - * @param data - * @param datalen - * @param databuffer - * @param len - * @param timeout_us - * @return - * - all replies of sendCommand() and getReply() - * - @c REPLY_TIMEOUT timeout - */ - virtual ReturnValue_t sendCommandBlocking(RMAPCookie *cookie, uint8_t *data, - uint32_t datalen, uint8_t **databuffer, uint32_t *len, - uint32_t timeout_us)=0; + /** + * get the reply to an rmap command + * + * @param cookie the cookie the command was sent with + * @param databuffer a pointer to a pointer the location of the reply will be written to + * @param len a pointer to the variable the length of the reply will be written to + * @return + * - @c REPLY_NO_REPLY no reply was received + * - @c REPLY_NOT_SENT command was not sent, implies no reply + * - @c REPLY_NOT_YET_SENT command is still waiting to be sent + * - @c WRITE_REPLY_INTERFACE_BUSY Interface is busy (transmission buffer still being + * processed) + * - @c WRITE_REPLY_TRANSMISSION_ERROR Interface encountered errors during last + * operation, data could not be processed. (transmission error) + * - @c WRITE_REPLY_INVALID_DATA Invalid data (amount / value) + * - @c WRITE_REPLY_NOT_SUPPORTED + * - all RMAP standard replies + */ + virtual ReturnValue_t getReply(RMAPCookie *cookie, uint8_t **databuffer, size_t *len) = 0; + /** + * + * @param cookie + * @param data + * @param datalen + * @param databuffer + * @param len + * @param timeout_us + * @return + * - all replies of sendCommand() and getReply() + * - @c REPLY_TIMEOUT timeout + */ + virtual ReturnValue_t sendCommandBlocking(RMAPCookie *cookie, uint8_t *data, uint32_t datalen, + uint8_t **databuffer, uint32_t *len, + uint32_t timeout_us) = 0; }; #endif /* FSFW_RMAP_RMAPCHANNELIF_H_ */ diff --git a/src/fsfw/rmap/RMAPCookie.cpp b/src/fsfw/rmap/RMAPCookie.cpp index 393a5ce0..8807407b 100644 --- a/src/fsfw/rmap/RMAPCookie.cpp +++ b/src/fsfw/rmap/RMAPCookie.cpp @@ -1,126 +1,104 @@ -#include "fsfw/rmap/RMAPChannelIF.h" #include "fsfw/rmap/RMAPCookie.h" #include +#include "fsfw/rmap/RMAPChannelIF.h" RMAPCookie::RMAPCookie() { - this->header.dest_address = 0; - this->header.protocol = 0x01; - this->header.instruction = 0; - this->header.dest_key = 0; - this->header.source_address = 0; - this->header.tid_h = 0; - this->header.tid_l = 0; - this->header.extended_address = 0; - this->header.address_hh = 0; - this->header.address_h = 0; - this->header.address_l = 0; - this->header.address_ll = 0; - this->header.datalen_h = 0; - this->header.datalen_m = 0; - this->header.datalen_l = 0; - this->header.header_crc = 0; - this->channel = NULL; - this->command_mask = 0; + this->header.dest_address = 0; + this->header.protocol = 0x01; + this->header.instruction = 0; + this->header.dest_key = 0; + this->header.source_address = 0; + this->header.tid_h = 0; + this->header.tid_l = 0; + this->header.extended_address = 0; + this->header.address_hh = 0; + this->header.address_h = 0; + this->header.address_l = 0; + this->header.address_ll = 0; + this->header.datalen_h = 0; + this->header.datalen_m = 0; + this->header.datalen_l = 0; + this->header.header_crc = 0; + this->channel = NULL; + this->command_mask = 0; - this->dataCRC = 0; + this->dataCRC = 0; - this->maxReplyLen = 0; + this->maxReplyLen = 0; } - - RMAPCookie::RMAPCookie(uint32_t set_address, uint8_t set_extended_address, - RMAPChannelIF *set_channel, uint8_t set_command_mask, - size_t maxReplyLen) { - this->header.dest_address = 0; - this->header.protocol = 0x01; - this->header.instruction = 0; - this->header.dest_key = 0; - this->header.source_address = 0; - this->header.tid_h = 0; - this->header.tid_l = 0; - this->header.extended_address = set_extended_address; - setAddress(set_address); - this->header.datalen_h = 0; - this->header.datalen_m = 0; - this->header.datalen_l = 0; - this->header.header_crc = 0; - this->channel = set_channel; - this->command_mask = set_command_mask; - this->dataCRC = 0; + RMAPChannelIF *set_channel, uint8_t set_command_mask, size_t maxReplyLen) { + this->header.dest_address = 0; + this->header.protocol = 0x01; + this->header.instruction = 0; + this->header.dest_key = 0; + this->header.source_address = 0; + this->header.tid_h = 0; + this->header.tid_l = 0; + this->header.extended_address = set_extended_address; + setAddress(set_address); + this->header.datalen_h = 0; + this->header.datalen_m = 0; + this->header.datalen_l = 0; + this->header.header_crc = 0; + this->channel = set_channel; + this->command_mask = set_command_mask; + this->dataCRC = 0; - this->maxReplyLen = maxReplyLen; + this->maxReplyLen = maxReplyLen; } - void RMAPCookie::setAddress(uint32_t address) { - this->header.address_hh = (address & 0xFF000000) >> 24; - this->header.address_h = (address & 0x00FF0000) >> 16; - this->header.address_l = (address & 0x0000FF00) >> 8; - this->header.address_ll = address & 0x000000FF; + this->header.address_hh = (address & 0xFF000000) >> 24; + this->header.address_h = (address & 0x00FF0000) >> 16; + this->header.address_l = (address & 0x0000FF00) >> 8; + this->header.address_ll = address & 0x000000FF; } void RMAPCookie::setExtendedAddress(uint8_t extendedAddress) { - this->header.extended_address = extendedAddress; + this->header.extended_address = extendedAddress; } -void RMAPCookie::setChannel(RMAPChannelIF *channel) { - this->channel = channel; -} +void RMAPCookie::setChannel(RMAPChannelIF *channel) { this->channel = channel; } -void RMAPCookie::setCommandMask(uint8_t commandMask) { - this->command_mask = commandMask; -} +void RMAPCookie::setCommandMask(uint8_t commandMask) { this->command_mask = commandMask; } uint32_t RMAPCookie::getAddress() { - return (header.address_hh << 24) + (header.address_h << 16) - + (header.address_l << 8) + (header.address_ll); + return (header.address_hh << 24) + (header.address_h << 16) + (header.address_l << 8) + + (header.address_ll); } -uint8_t RMAPCookie::getExtendedAddress() { - return header.extended_address; -} +uint8_t RMAPCookie::getExtendedAddress() { return header.extended_address; } -RMAPChannelIF *RMAPCookie::getChannel() { - return channel; -} +RMAPChannelIF *RMAPCookie::getChannel() { return channel; } -uint8_t RMAPCookie::getCommandMask() { - return command_mask; -} +uint8_t RMAPCookie::getCommandMask() { return command_mask; } -RMAPCookie::~RMAPCookie() { +RMAPCookie::~RMAPCookie() {} -} +size_t RMAPCookie::getMaxReplyLen() const { return maxReplyLen; } -size_t RMAPCookie::getMaxReplyLen() const { - return maxReplyLen; -} +void RMAPCookie::setMaxReplyLen(size_t maxReplyLen) { this->maxReplyLen = maxReplyLen; } -void RMAPCookie::setMaxReplyLen(size_t maxReplyLen) { - this->maxReplyLen = maxReplyLen; -} - -RMAPStructs::rmap_cmd_header* RMAPCookie::getHeader(){ - return &this->header; -} +RMAPStructs::rmap_cmd_header *RMAPCookie::getHeader() { return &this->header; } uint16_t RMAPCookie::getTransactionIdentifier() const { - return static_cast((header.tid_h << 8) | (header.tid_l)); + return static_cast((header.tid_h << 8) | (header.tid_l)); } void RMAPCookie::setTransactionIdentifier(uint16_t id_) { - header.tid_l = id_ & 0xFF; - header.tid_h = (id_ >> 8 ) & 0xFF; + header.tid_l = id_ & 0xFF; + header.tid_h = (id_ >> 8) & 0xFF; } uint32_t RMAPCookie::getDataLength() const { - return static_cast(header.datalen_h << 16 | header.datalen_m << 8 | header.datalen_l); + return static_cast(header.datalen_h << 16 | header.datalen_m << 8 | header.datalen_l); } void RMAPCookie::setDataLength(uint32_t length_) { - header.datalen_l = length_ & 0xff; - header.datalen_m = (length_ >> 8) & 0xff; - header.datalen_h = (length_ >> 16) & 0xff; + header.datalen_l = length_ & 0xff; + header.datalen_m = (length_ >> 8) & 0xff; + header.datalen_h = (length_ >> 16) & 0xff; } diff --git a/src/fsfw/rmap/RMAPCookie.h b/src/fsfw/rmap/RMAPCookie.h index 032e5a46..e075256b 100644 --- a/src/fsfw/rmap/RMAPCookie.h +++ b/src/fsfw/rmap/RMAPCookie.h @@ -1,61 +1,56 @@ #ifndef FSFW_RMAP_RMAPCOOKIE_H_ #define FSFW_RMAP_RMAPCOOKIE_H_ +#include + +#include "fsfw/devicehandlers/CookieIF.h" #include "rmapConf.h" #include "rmapStructs.h" -#include "fsfw/devicehandlers/CookieIF.h" -#include class RMAPChannelIF; class RMAPCookie : public CookieIF { -public: - //To Uli: Sorry, I need an empty ctor to initialize an array of cookies. - RMAPCookie(); + public: + // To Uli: Sorry, I need an empty ctor to initialize an array of cookies. + RMAPCookie(); - RMAPCookie(uint32_t set_address, uint8_t set_extended_address, - RMAPChannelIF *set_channel, uint8_t set_command_mask, - size_t maxReplyLen = 0); - virtual ~RMAPCookie(); + RMAPCookie(uint32_t set_address, uint8_t set_extended_address, RMAPChannelIF *set_channel, + uint8_t set_command_mask, size_t maxReplyLen = 0); + virtual ~RMAPCookie(); + void setAddress(uint32_t address); + uint32_t getAddress(); - void setAddress(uint32_t address); - uint32_t getAddress(); + void setExtendedAddress(uint8_t); + uint8_t getExtendedAddress(); - void setExtendedAddress(uint8_t); - uint8_t getExtendedAddress(); + void setChannel(RMAPChannelIF *channel); + RMAPChannelIF *getChannel(); - void setChannel(RMAPChannelIF *channel); - RMAPChannelIF *getChannel(); + void setCommandMask(uint8_t commandMask); + uint8_t getCommandMask(); - void setCommandMask(uint8_t commandMask); - uint8_t getCommandMask(); + size_t getMaxReplyLen() const; + void setMaxReplyLen(size_t maxReplyLen); - size_t getMaxReplyLen() const; - void setMaxReplyLen(size_t maxReplyLen); + uint16_t getTransactionIdentifier() const; + void setTransactionIdentifier(uint16_t id_); - uint16_t getTransactionIdentifier() const; - void setTransactionIdentifier(uint16_t id_); + RMAPStructs::rmap_cmd_header *getHeader(); - RMAPStructs::rmap_cmd_header* getHeader(); + uint32_t getDataLength() const; + void setDataLength(uint32_t lenght_); - uint32_t getDataLength() const; - void setDataLength(uint32_t lenght_); + uint8_t getDataCrc() const { return dataCRC; } - uint8_t getDataCrc() const { - return dataCRC; - } + void setDataCrc(uint8_t dataCrc) { dataCRC = dataCrc; } - void setDataCrc(uint8_t dataCrc) { - dataCRC = dataCrc; - } - -protected: - RMAPStructs::rmap_cmd_header header; - RMAPChannelIF *channel; - uint8_t command_mask; - uint32_t maxReplyLen; - uint8_t dataCRC; + protected: + RMAPStructs::rmap_cmd_header header; + RMAPChannelIF *channel; + uint8_t command_mask; + uint32_t maxReplyLen; + uint8_t dataCRC; }; #endif /* FSFW_RMAP_RMAPCOOKIE_H_ */ diff --git a/src/fsfw/rmap/RmapDeviceCommunicationIF.cpp b/src/fsfw/rmap/RmapDeviceCommunicationIF.cpp index 2fab613e..cf5d49ea 100644 --- a/src/fsfw/rmap/RmapDeviceCommunicationIF.cpp +++ b/src/fsfw/rmap/RmapDeviceCommunicationIF.cpp @@ -1,47 +1,41 @@ #include "fsfw/rmap/RmapDeviceCommunicationIF.h" + #include "fsfw/rmap/RMAP.h" -//TODO Cast here are all potential bugs -RmapDeviceCommunicationIF::~RmapDeviceCommunicationIF() { +// TODO Cast here are all potential bugs +RmapDeviceCommunicationIF::~RmapDeviceCommunicationIF() {} + +ReturnValue_t RmapDeviceCommunicationIF::sendMessage(CookieIF *cookie, const uint8_t *sendData, + size_t sendLen) { + return RMAP::sendWriteCommand((RMAPCookie *)cookie, sendData, sendLen); } -ReturnValue_t RmapDeviceCommunicationIF::sendMessage(CookieIF *cookie, - const uint8_t * sendData, size_t sendLen) { - return RMAP::sendWriteCommand((RMAPCookie *) cookie, sendData, sendLen); +ReturnValue_t RmapDeviceCommunicationIF::getSendSuccess(CookieIF *cookie) { + return RMAP::getWriteReply((RMAPCookie *)cookie); } -ReturnValue_t RmapDeviceCommunicationIF::getSendSuccess(CookieIF* cookie) { - return RMAP::getWriteReply((RMAPCookie *) cookie); +ReturnValue_t RmapDeviceCommunicationIF::requestReceiveMessage(CookieIF *cookie, + size_t requestLen) { + return RMAP::sendReadCommand((RMAPCookie *)cookie, ((RMAPCookie *)cookie)->getMaxReplyLen()); } -ReturnValue_t RmapDeviceCommunicationIF::requestReceiveMessage( - CookieIF *cookie, size_t requestLen) { - return RMAP::sendReadCommand((RMAPCookie *) cookie, - ((RMAPCookie *) cookie)->getMaxReplyLen()); +ReturnValue_t RmapDeviceCommunicationIF::readReceivedMessage(CookieIF *cookie, uint8_t **buffer, + size_t *size) { + return RMAP::getReadReply((RMAPCookie *)cookie, buffer, size); } -ReturnValue_t RmapDeviceCommunicationIF::readReceivedMessage(CookieIF* cookie, - uint8_t** buffer, size_t * size) { - return RMAP::getReadReply((RMAPCookie *) cookie, buffer, size); +ReturnValue_t RmapDeviceCommunicationIF::setAddress(CookieIF *cookie, uint32_t address) { + ((RMAPCookie *)cookie)->setAddress(address); + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t RmapDeviceCommunicationIF::setAddress(CookieIF* cookie, - uint32_t address) { - - ((RMAPCookie *) cookie)->setAddress(address); - return HasReturnvaluesIF::RETURN_OK; +uint32_t RmapDeviceCommunicationIF::getAddress(CookieIF *cookie) { + return ((RMAPCookie *)cookie)->getAddress(); } -uint32_t RmapDeviceCommunicationIF::getAddress(CookieIF* cookie) { - return ((RMAPCookie *) cookie)->getAddress(); +ReturnValue_t RmapDeviceCommunicationIF::setParameter(CookieIF *cookie, uint32_t parameter) { + // TODO Empty? + return HasReturnvaluesIF::RETURN_FAILED; } -ReturnValue_t RmapDeviceCommunicationIF::setParameter(CookieIF* cookie, - uint32_t parameter) { - //TODO Empty? - return HasReturnvaluesIF::RETURN_FAILED; -} - -uint32_t RmapDeviceCommunicationIF::getParameter(CookieIF* cookie) { - return 0; -} +uint32_t RmapDeviceCommunicationIF::getParameter(CookieIF *cookie) { return 0; } diff --git a/src/fsfw/rmap/RmapDeviceCommunicationIF.h b/src/fsfw/rmap/RmapDeviceCommunicationIF.h index 36baf87b..abe94685 100644 --- a/src/fsfw/rmap/RmapDeviceCommunicationIF.h +++ b/src/fsfw/rmap/RmapDeviceCommunicationIF.h @@ -1,8 +1,8 @@ #ifndef FSFW_RMAP_RMAPDEVICECOMMUNICATIONINTERFACE_H_ #define FSFW_RMAP_RMAPDEVICECOMMUNICATIONINTERFACE_H_ -#include "rmapConf.h" #include "fsfw/devicehandlers/DeviceCommunicationIF.h" +#include "rmapConf.h" /** * @brief This class is a implementation of a DeviceCommunicationIF for RMAP calls. @@ -13,78 +13,73 @@ * * \ingroup rmap */ -class RmapDeviceCommunicationIF: public DeviceCommunicationIF { +class RmapDeviceCommunicationIF : public DeviceCommunicationIF { + public: + virtual ~RmapDeviceCommunicationIF(); -public: - virtual ~RmapDeviceCommunicationIF(); + /** + * @brief Device specific initialization, using the cookie. + * @details + * The cookie is already prepared in the factory. If the communication + * interface needs to be set up in some way and requires cookie information, + * this can be performed in this function, which is called on device handler + * initialization. + * @param cookie + * @return -@c RETURN_OK if initialization was successfull + * - Everything else triggers failure event with returnvalue as parameter 1 + */ + virtual ReturnValue_t initializeInterface(CookieIF *cookie) = 0; - /** - * @brief Device specific initialization, using the cookie. - * @details - * The cookie is already prepared in the factory. If the communication - * interface needs to be set up in some way and requires cookie information, - * this can be performed in this function, which is called on device handler - * initialization. - * @param cookie - * @return -@c RETURN_OK if initialization was successfull - * - Everything else triggers failure event with returnvalue as parameter 1 - */ - virtual ReturnValue_t initializeInterface(CookieIF * cookie) = 0; + /** + * Called by DHB in the SEND_WRITE doSendWrite(). + * This function is used to send data to the physical device + * by implementing and calling related drivers or wrapper functions. + * @param cookie + * @param data + * @param len + * @return -@c RETURN_OK for successfull send + * - Everything else triggers failure event with returnvalue as parameter 1 + */ + virtual ReturnValue_t sendMessage(CookieIF *cookie, const uint8_t *sendData, size_t sendLen); - /** - * Called by DHB in the SEND_WRITE doSendWrite(). - * This function is used to send data to the physical device - * by implementing and calling related drivers or wrapper functions. - * @param cookie - * @param data - * @param len - * @return -@c RETURN_OK for successfull send - * - Everything else triggers failure event with returnvalue as parameter 1 - */ - virtual ReturnValue_t sendMessage(CookieIF *cookie, const uint8_t * sendData, - size_t sendLen); + /** + * Called by DHB in the GET_WRITE doGetWrite(). + * Get send confirmation that the data in sendMessage() was sent successfully. + * @param cookie + * @return -@c RETURN_OK if data was sent successfull + * - Everything else triggers falure event with returnvalue as parameter 1 + */ + virtual ReturnValue_t getSendSuccess(CookieIF *cookie); - /** - * Called by DHB in the GET_WRITE doGetWrite(). - * Get send confirmation that the data in sendMessage() was sent successfully. - * @param cookie - * @return -@c RETURN_OK if data was sent successfull - * - Everything else triggers falure event with returnvalue as parameter 1 - */ - virtual ReturnValue_t getSendSuccess(CookieIF *cookie); + /** + * Called by DHB in the SEND_WRITE doSendRead(). + * It is assumed that it is always possible to request a reply + * from a device. + * + * @param cookie + * @return -@c RETURN_OK to confirm the request for data has been sent. + * -@c NO_READ_REQUEST if no request shall be made. readReceivedMessage() + * will not be called in the respective communication cycle. + * - Everything else triggers failure event with returnvalue as parameter 1 + */ + virtual ReturnValue_t requestReceiveMessage(CookieIF *cookie, size_t requestLen); - /** - * Called by DHB in the SEND_WRITE doSendRead(). - * It is assumed that it is always possible to request a reply - * from a device. - * - * @param cookie - * @return -@c RETURN_OK to confirm the request for data has been sent. - * -@c NO_READ_REQUEST if no request shall be made. readReceivedMessage() - * will not be called in the respective communication cycle. - * - Everything else triggers failure event with returnvalue as parameter 1 - */ - virtual ReturnValue_t requestReceiveMessage(CookieIF *cookie, size_t requestLen); + /** + * Called by DHB in the GET_WRITE doGetRead(). + * This function is used to receive data from the physical device + * by implementing and calling related drivers or wrapper functions. + * @param cookie + * @param data + * @param len + * @return @c RETURN_OK for successfull receive + * - Everything else triggers failure event with returnvalue as parameter 1 + */ + virtual ReturnValue_t readReceivedMessage(CookieIF *cookie, uint8_t **buffer, size_t *size); - /** - * Called by DHB in the GET_WRITE doGetRead(). - * This function is used to receive data from the physical device - * by implementing and calling related drivers or wrapper functions. - * @param cookie - * @param data - * @param len - * @return @c RETURN_OK for successfull receive - * - Everything else triggers failure event with returnvalue as parameter 1 - */ - virtual ReturnValue_t readReceivedMessage(CookieIF *cookie, uint8_t **buffer, - size_t *size); - - ReturnValue_t setAddress(CookieIF* cookie, - uint32_t address); - uint32_t getAddress(CookieIF* cookie); - ReturnValue_t setParameter(CookieIF* cookie, - uint32_t parameter); - uint32_t getParameter(CookieIF* cookie); + ReturnValue_t setAddress(CookieIF *cookie, uint32_t address); + uint32_t getAddress(CookieIF *cookie); + ReturnValue_t setParameter(CookieIF *cookie, uint32_t parameter); + uint32_t getParameter(CookieIF *cookie); }; #endif /* FSFW_RMAP_RMAPDEVICECOMMUNICATIONINTERFACE_H_ */ diff --git a/src/fsfw/rmap/rmapStructs.h b/src/fsfw/rmap/rmapStructs.h index de8b3a59..44eedc16 100644 --- a/src/fsfw/rmap/rmapStructs.h +++ b/src/fsfw/rmap/rmapStructs.h @@ -1,11 +1,12 @@ #ifndef FSFW_RMAP_RMAPSTRUCTS_H_ #define FSFW_RMAP_RMAPSTRUCTS_H_ -#include "rmapConf.h" - #include -//SHOULDDO: having the defines within a namespace would be nice. Problem are the defines referencing the previous define, eg RMAP_COMMAND_WRITE +#include "rmapConf.h" + +// SHOULDDO: having the defines within a namespace would be nice. Problem are the defines +// referencing the previous define, eg RMAP_COMMAND_WRITE ////////////////////////////////////////////////////////////////////////////////// // RMAP command bits @@ -15,7 +16,7 @@ //#define RMAP_COMMAND_BIT_VERIFY 4 //#define RMAP_COMMAND_BIT 6 -namespace RMAPIds{ +namespace RMAPIds { static const uint8_t RMAP_COMMAND_BIT_INCREMENT = 2; static const uint8_t RMAP_COMMAND_BIT_REPLY = 3; @@ -25,76 +26,81 @@ static const uint8_t RMAP_COMMAND_BIT = 6; ////////////////////////////////////////////////////////////////////////////////// // RMAP commands -static const uint8_t RMAP_COMMAND_WRITE = ((1< #include +#include + +#include "../osal/Endiness.h" /** * Helper class to convert variables or bitstreams between machine @@ -34,91 +35,90 @@ * Thus, there is only one function supplied to do the conversion. */ class EndianConverter { -private: - EndianConverter() {}; -public: - /** - * Convert a typed variable between big endian and machine endian. - * Intended for plain old datatypes. - */ - template - static T convertBigEndian(T in) { + private: + EndianConverter(){}; + + public: + /** + * Convert a typed variable between big endian and machine endian. + * Intended for plain old datatypes. + */ + template + static T convertBigEndian(T in) { #ifndef BYTE_ORDER_SYSTEM #error BYTE_ORDER_SYSTEM not defined #elif BYTE_ORDER_SYSTEM == LITTLE_ENDIAN - T tmp; - uint8_t *pointerOut = (uint8_t*) &tmp; - uint8_t *pointerIn = (uint8_t*) ∈ - for (size_t count = 0; count < sizeof(T); count++) { - pointerOut[sizeof(T) - count - 1] = pointerIn[count]; - } - return tmp; + T tmp; + uint8_t *pointerOut = (uint8_t *)&tmp; + uint8_t *pointerIn = (uint8_t *)∈ + for (size_t count = 0; count < sizeof(T); count++) { + pointerOut[sizeof(T) - count - 1] = pointerIn[count]; + } + return tmp; #elif BYTE_ORDER_SYSTEM == BIG_ENDIAN - return in; + return in; #else #error Unknown Byte Order #endif - } + } - /** - * convert a bytestream representing a single variable between big endian - * and machine endian. - */ - static void convertBigEndian(uint8_t *out, const uint8_t *in, - size_t size) { + /** + * convert a bytestream representing a single variable between big endian + * and machine endian. + */ + static void convertBigEndian(uint8_t *out, const uint8_t *in, size_t size) { #ifndef BYTE_ORDER_SYSTEM #error BYTE_ORDER_SYSTEM not defined #elif BYTE_ORDER_SYSTEM == LITTLE_ENDIAN - for (size_t count = 0; count < size; count++) { - out[size - count - 1] = in[count]; - } - return; + for (size_t count = 0; count < size; count++) { + out[size - count - 1] = in[count]; + } + return; #elif BYTE_ORDER_SYSTEM == BIG_ENDIAN - memcpy(out, in, size); - return; + memcpy(out, in, size); + return; #endif - } + } - /** - * Convert a typed variable between little endian and machine endian. - * Intended for plain old datatypes. - */ - template - static T convertLittleEndian(T in) { + /** + * Convert a typed variable between little endian and machine endian. + * Intended for plain old datatypes. + */ + template + static T convertLittleEndian(T in) { #ifndef BYTE_ORDER_SYSTEM - #error BYTE_ORDER_SYSTEM not defined - #elif BYTE_ORDER_SYSTEM == BIG_ENDIAN - T tmp; - uint8_t *pointerOut = (uint8_t *) &tmp; - uint8_t *pointerIn = (uint8_t *) ∈ - for (size_t count = 0; count < sizeof(T); count++) { - pointerOut[sizeof(T) - count - 1] = pointerIn[count]; - } - return tmp; - #elif BYTE_ORDER_SYSTEM == LITTLE_ENDIAN - return in; +#error BYTE_ORDER_SYSTEM not defined +#elif BYTE_ORDER_SYSTEM == BIG_ENDIAN + T tmp; + uint8_t *pointerOut = (uint8_t *)&tmp; + uint8_t *pointerIn = (uint8_t *)∈ + for (size_t count = 0; count < sizeof(T); count++) { + pointerOut[sizeof(T) - count - 1] = pointerIn[count]; + } + return tmp; +#elif BYTE_ORDER_SYSTEM == LITTLE_ENDIAN + return in; #else - #error Unknown Byte Order - #endif - } - /** - * convert a bytestream representing a single variable between little endian - * and machine endian. - */ - static void convertLittleEndian(uint8_t *out, const uint8_t *in, - size_t size) { -#ifndef BYTE_ORDER_SYSTEM - #error BYTE_ORDER_SYSTEM not defined - #elif BYTE_ORDER_SYSTEM == BIG_ENDIAN - for (size_t count = 0; count < size; count++) { - out[size - count - 1] = in[count]; - } - return; - #elif BYTE_ORDER_SYSTEM == LITTLE_ENDIAN - memcpy(out, in, size); - return; +#error Unknown Byte Order #endif - } + } + /** + * convert a bytestream representing a single variable between little endian + * and machine endian. + */ + static void convertLittleEndian(uint8_t *out, const uint8_t *in, size_t size) { +#ifndef BYTE_ORDER_SYSTEM +#error BYTE_ORDER_SYSTEM not defined +#elif BYTE_ORDER_SYSTEM == BIG_ENDIAN + for (size_t count = 0; count < size; count++) { + out[size - count - 1] = in[count]; + } + return; +#elif BYTE_ORDER_SYSTEM == LITTLE_ENDIAN + memcpy(out, in, size); + return; +#endif + } }; #endif /* FSFW_SERIALIZE_ENDIANCONVERTER_H_ */ diff --git a/src/fsfw/serialize/SerialArrayListAdapter.h b/src/fsfw/serialize/SerialArrayListAdapter.h index daa3fe7f..d7c99aae 100644 --- a/src/fsfw/serialize/SerialArrayListAdapter.h +++ b/src/fsfw/serialize/SerialArrayListAdapter.h @@ -1,86 +1,79 @@ #ifndef FSFW_SERIALIZE_SERIALARRAYLISTADAPTER_H_ #define FSFW_SERIALIZE_SERIALARRAYLISTADAPTER_H_ -#include "SerializeIF.h" -#include "../container/ArrayList.h" #include +#include "../container/ArrayList.h" +#include "SerializeIF.h" + /** * Also serializes length field ! * @author baetz * @ingroup serialize */ -template +template class SerialArrayListAdapter : public SerializeIF { -public: - SerialArrayListAdapter(ArrayList *adaptee) : adaptee(adaptee) { - } + public: + SerialArrayListAdapter(ArrayList* adaptee) : adaptee(adaptee) {} - virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const { - return serialize(adaptee, buffer, size, maxSize, streamEndianness); - } + virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const { + return serialize(adaptee, buffer, size, maxSize, streamEndianness); + } - static ReturnValue_t serialize(const ArrayList* list, - uint8_t** buffer, size_t* size, size_t maxSize, - Endianness streamEndianness) { - ReturnValue_t result = SerializeAdapter::serialize(&list->size, - buffer, size, maxSize, streamEndianness); - count_t i = 0; - while ((result == HasReturnvaluesIF::RETURN_OK) && (i < list->size)) { - result = SerializeAdapter::serialize(&list->entries[i], buffer, size, - maxSize, streamEndianness); - ++i; - } - return result; - } + static ReturnValue_t serialize(const ArrayList* list, uint8_t** buffer, size_t* size, + size_t maxSize, Endianness streamEndianness) { + ReturnValue_t result = + SerializeAdapter::serialize(&list->size, buffer, size, maxSize, streamEndianness); + count_t i = 0; + while ((result == HasReturnvaluesIF::RETURN_OK) && (i < list->size)) { + result = + SerializeAdapter::serialize(&list->entries[i], buffer, size, maxSize, streamEndianness); + ++i; + } + return result; + } - virtual size_t getSerializedSize() const { - return getSerializedSize(adaptee); - } + virtual size_t getSerializedSize() const { return getSerializedSize(adaptee); } - static uint32_t getSerializedSize(const ArrayList* list) { - uint32_t printSize = sizeof(count_t); - count_t i = 0; + static uint32_t getSerializedSize(const ArrayList* list) { + uint32_t printSize = sizeof(count_t); + count_t i = 0; - for (i = 0; i < list->size; ++i) { - printSize += SerializeAdapter::getSerializedSize(&list->entries[i]); - } + for (i = 0; i < list->size; ++i) { + printSize += SerializeAdapter::getSerializedSize(&list->entries[i]); + } - return printSize; - } + return printSize; + } - virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) { - return deSerialize(adaptee, buffer, size, streamEndianness); - } + virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + Endianness streamEndianness) { + return deSerialize(adaptee, buffer, size, streamEndianness); + } - static ReturnValue_t deSerialize(ArrayList* list, - const uint8_t** buffer, size_t* size, - Endianness streamEndianness) { - count_t tempSize = 0; - ReturnValue_t result = SerializeAdapter::deSerialize(&tempSize, - buffer, size, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if (tempSize > list->maxSize()) { - return SerializeIF::TOO_MANY_ELEMENTS; - } + static ReturnValue_t deSerialize(ArrayList* list, const uint8_t** buffer, + size_t* size, Endianness streamEndianness) { + count_t tempSize = 0; + ReturnValue_t result = SerializeAdapter::deSerialize(&tempSize, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (tempSize > list->maxSize()) { + return SerializeIF::TOO_MANY_ELEMENTS; + } - list->size = tempSize; - count_t i = 0; - while ((result == HasReturnvaluesIF::RETURN_OK) && (i < list->size)) { - result = SerializeAdapter::deSerialize( - &list->front()[i], buffer, size, - streamEndianness); - ++i; - } - return result; - } + list->size = tempSize; + count_t i = 0; + while ((result == HasReturnvaluesIF::RETURN_OK) && (i < list->size)) { + result = SerializeAdapter::deSerialize(&list->front()[i], buffer, size, streamEndianness); + ++i; + } + return result; + } -private: - ArrayList *adaptee; + private: + ArrayList* adaptee; }; #endif /* FSFW_SERIALIZE_SERIALARRAYLISTADAPTER_H_ */ diff --git a/src/fsfw/serialize/SerialBufferAdapter.cpp b/src/fsfw/serialize/SerialBufferAdapter.cpp index 6db17d5e..83129982 100644 --- a/src/fsfw/serialize/SerialBufferAdapter.cpp +++ b/src/fsfw/serialize/SerialBufferAdapter.cpp @@ -1,133 +1,132 @@ #include "fsfw/serialize/SerialBufferAdapter.h" -#include "fsfw/serviceinterface/ServiceInterface.h" + #include -template -SerialBufferAdapter::SerialBufferAdapter(const uint8_t* buffer, - count_t bufferLength, bool serializeLength) : - serializeLength(serializeLength), - constBuffer(buffer), buffer(nullptr), - bufferLength(bufferLength) {} +#include "fsfw/serviceinterface/ServiceInterface.h" -template -SerialBufferAdapter::SerialBufferAdapter(uint8_t* buffer, - count_t bufferLength, bool serializeLength) : - serializeLength(serializeLength), constBuffer(buffer), buffer(buffer), - bufferLength(bufferLength) {} +template +SerialBufferAdapter::SerialBufferAdapter(const uint8_t* buffer, count_t bufferLength, + bool serializeLength) + : serializeLength(serializeLength), + constBuffer(buffer), + buffer(nullptr), + bufferLength(bufferLength) {} +template +SerialBufferAdapter::SerialBufferAdapter(uint8_t* buffer, count_t bufferLength, + bool serializeLength) + : serializeLength(serializeLength), + constBuffer(buffer), + buffer(buffer), + bufferLength(bufferLength) {} -template -SerialBufferAdapter::~SerialBufferAdapter() { +template +SerialBufferAdapter::~SerialBufferAdapter() {} + +template +ReturnValue_t SerialBufferAdapter::serialize(uint8_t** buffer, size_t* size, + size_t maxSize, + Endianness streamEndianness) const { + if (serializeLength) { + ReturnValue_t result = + SerializeAdapter::serialize(&bufferLength, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + } + + if (*size + bufferLength > maxSize) { + return BUFFER_TOO_SHORT; + } + + if (this->constBuffer != nullptr) { + std::memcpy(*buffer, this->constBuffer, bufferLength); + } else if (this->buffer != nullptr) { + // This will propably be never reached, constBuffer should always be + // set if non-const buffer is set. + std::memcpy(*buffer, this->buffer, bufferLength); + } else { + return HasReturnvaluesIF::RETURN_FAILED; + } + *size += bufferLength; + (*buffer) += bufferLength; + return HasReturnvaluesIF::RETURN_OK; } -template -ReturnValue_t SerialBufferAdapter::serialize(uint8_t** buffer, - size_t* size, size_t maxSize, Endianness streamEndianness) const { - if (serializeLength) { - ReturnValue_t result = SerializeAdapter::serialize(&bufferLength, - buffer, size, maxSize, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - } - - if (*size + bufferLength > maxSize) { - return BUFFER_TOO_SHORT; - } - - if (this->constBuffer != nullptr) { - std::memcpy(*buffer, this->constBuffer, bufferLength); - } - else if (this->buffer != nullptr) { - // This will propably be never reached, constBuffer should always be - // set if non-const buffer is set. - std::memcpy(*buffer, this->buffer, bufferLength); - } - else { - return HasReturnvaluesIF::RETURN_FAILED; - } - *size += bufferLength; - (*buffer) += bufferLength; - return HasReturnvaluesIF::RETURN_OK; - -} - -template +template size_t SerialBufferAdapter::getSerializedSize() const { - if (serializeLength) { - return bufferLength + SerializeAdapter::getSerializedSize(&bufferLength); - } else { - return bufferLength; - } + if (serializeLength) { + return bufferLength + SerializeAdapter::getSerializedSize(&bufferLength); + } else { + return bufferLength; + } } -template -ReturnValue_t SerialBufferAdapter::deSerialize(const uint8_t** buffer, - size_t* size, Endianness streamEndianness) { - if (this->buffer == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } +template +ReturnValue_t SerialBufferAdapter::deSerialize(const uint8_t** buffer, size_t* size, + Endianness streamEndianness) { + if (this->buffer == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } - if(serializeLength){ - count_t lengthField = 0; - ReturnValue_t result = SerializeAdapter::deSerialize(&lengthField, - buffer, size, streamEndianness); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if(lengthField > bufferLength) { - return TOO_MANY_ELEMENTS; - } - bufferLength = lengthField; - } + if (serializeLength) { + count_t lengthField = 0; + ReturnValue_t result = + SerializeAdapter::deSerialize(&lengthField, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (lengthField > bufferLength) { + return TOO_MANY_ELEMENTS; + } + bufferLength = lengthField; + } - if (bufferLength <= *size) { - *size -= bufferLength; - std::memcpy(this->buffer, *buffer, bufferLength); - (*buffer) += bufferLength; - return HasReturnvaluesIF::RETURN_OK; - } - else { - return STREAM_TOO_SHORT; - } + if (bufferLength <= *size) { + *size -= bufferLength; + std::memcpy(this->buffer, *buffer, bufferLength); + (*buffer) += bufferLength; + return HasReturnvaluesIF::RETURN_OK; + } else { + return STREAM_TOO_SHORT; + } } -template -uint8_t * SerialBufferAdapter::getBuffer() { - if(buffer == nullptr) { +template +uint8_t* SerialBufferAdapter::getBuffer() { + if (buffer == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Wrong access function for stored type !" - " Use getConstBuffer()." << std::endl; + sif::error << "Wrong access function for stored type !" + " Use getConstBuffer()." + << std::endl; #endif - return nullptr; - } - return buffer; + return nullptr; + } + return buffer; } -template -const uint8_t * SerialBufferAdapter::getConstBuffer() const { - if(constBuffer == nullptr) { +template +const uint8_t* SerialBufferAdapter::getConstBuffer() const { + if (constBuffer == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "SerialBufferAdapter::getConstBuffer:" - " Buffers are unitialized!" << std::endl; + sif::error << "SerialBufferAdapter::getConstBuffer:" + " Buffers are unitialized!" + << std::endl; #endif - return nullptr; - } - return constBuffer; + return nullptr; + } + return constBuffer; } -template -void SerialBufferAdapter::setBuffer(uint8_t* buffer, - count_t bufferLength) { - this->buffer = buffer; - this->constBuffer = buffer; - this->bufferLength = bufferLength; +template +void SerialBufferAdapter::setBuffer(uint8_t* buffer, count_t bufferLength) { + this->buffer = buffer; + this->constBuffer = buffer; + this->bufferLength = bufferLength; } - -//forward Template declaration for linker +// forward Template declaration for linker template class SerialBufferAdapter; template class SerialBufferAdapter; template class SerialBufferAdapter; template class SerialBufferAdapter; - diff --git a/src/fsfw/serialize/SerialBufferAdapter.h b/src/fsfw/serialize/SerialBufferAdapter.h index 48f5ce53..3b95fa20 100644 --- a/src/fsfw/serialize/SerialBufferAdapter.h +++ b/src/fsfw/serialize/SerialBufferAdapter.h @@ -1,8 +1,8 @@ #ifndef SERIALBUFFERADAPTER_H_ #define SERIALBUFFERADAPTER_H_ -#include "fsfw/serialize/SerializeIF.h" #include "fsfw/serialize/SerializeAdapter.h" +#include "fsfw/serialize/SerializeIF.h" /** * This adapter provides an interface for SerializeIF to serialize or deserialize @@ -18,61 +18,59 @@ * * \ingroup serialize */ -template -class SerialBufferAdapter: public SerializeIF { -public: +template +class SerialBufferAdapter : public SerializeIF { + public: + /** + * Constructor for constant uint8_t buffer. Length field can be serialized optionally. + * Type of length can be supplied as template type. + * @param buffer + * @param bufferLength + * @param serializeLength + */ + SerialBufferAdapter(const uint8_t* buffer, count_t bufferLength, bool serializeLength = false); - /** - * Constructor for constant uint8_t buffer. Length field can be serialized optionally. - * Type of length can be supplied as template type. - * @param buffer - * @param bufferLength - * @param serializeLength - */ - SerialBufferAdapter(const uint8_t* buffer, count_t bufferLength, - bool serializeLength = false); + /** + * Constructor for non-constant uint8_t buffer. + * Length field can be serialized optionally. + * Type of length can be supplied as template type. + * @param buffer + * @param bufferLength + * @param serializeLength Length field will be serialized with size count_t + */ + SerialBufferAdapter(uint8_t* buffer, count_t bufferLength, bool serializeLength = false); - /** - * Constructor for non-constant uint8_t buffer. - * Length field can be serialized optionally. - * Type of length can be supplied as template type. - * @param buffer - * @param bufferLength - * @param serializeLength Length field will be serialized with size count_t - */ - SerialBufferAdapter(uint8_t* buffer, count_t bufferLength, - bool serializeLength = false); + virtual ~SerialBufferAdapter(); - virtual ~SerialBufferAdapter(); + virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override; - virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const override; + virtual size_t getSerializedSize() const override; - virtual size_t getSerializedSize() const override; + /** + * @brief This function deserializes a buffer into the member buffer. + * @details + * If a length field is present, it is ignored, as the size should have + * been set in the constructor. If the size is not known beforehand, + * consider using SerialFixedArrayListAdapter instead. + * @param buffer [out] Resulting buffer + * @param size remaining size to deserialize, should be larger than buffer + * + size field size + * @param bigEndian + * @return + */ + virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + Endianness streamEndianness) override; - /** - * @brief This function deserializes a buffer into the member buffer. - * @details - * If a length field is present, it is ignored, as the size should have - * been set in the constructor. If the size is not known beforehand, - * consider using SerialFixedArrayListAdapter instead. - * @param buffer [out] Resulting buffer - * @param size remaining size to deserialize, should be larger than buffer - * + size field size - * @param bigEndian - * @return - */ - virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) override; + uint8_t* getBuffer(); + const uint8_t* getConstBuffer() const; + void setBuffer(uint8_t* buffer, count_t bufferLength); - uint8_t * getBuffer(); - const uint8_t * getConstBuffer() const; - void setBuffer(uint8_t* buffer, count_t bufferLength); -private: - bool serializeLength = false; - const uint8_t *constBuffer = nullptr; - uint8_t *buffer = nullptr; - count_t bufferLength = 0; + private: + bool serializeLength = false; + const uint8_t* constBuffer = nullptr; + uint8_t* buffer = nullptr; + count_t bufferLength = 0; }; #endif /* SERIALBUFFERADAPTER_H_ */ diff --git a/src/fsfw/serialize/SerialFixedArrayListAdapter.h b/src/fsfw/serialize/SerialFixedArrayListAdapter.h index 70ca987a..403a7596 100644 --- a/src/fsfw/serialize/SerialFixedArrayListAdapter.h +++ b/src/fsfw/serialize/SerialFixedArrayListAdapter.h @@ -1,8 +1,8 @@ #ifndef FSFW_SERIALIZE_SERIALFIXEDARRAYLISTADAPTER_H_ #define FSFW_SERIALIZE_SERIALFIXEDARRAYLISTADAPTER_H_ -#include "SerialArrayListAdapter.h" #include "../container/FixedArrayList.h" +#include "SerialArrayListAdapter.h" /** * @brief This adapter provides an interface for SerializeIF to serialize and @@ -20,38 +20,33 @@ * to one byte. * @ingroup serialize */ -template -class SerialFixedArrayListAdapter : - public FixedArrayList, - public SerializeIF { -public: - /** - * Constructor arguments are forwarded to FixedArrayList constructor. - * Refer to the fixed array list constructors for different options. - * @param args - */ - template - SerialFixedArrayListAdapter(Args... args) : - FixedArrayList( - std::forward(args)...){} +template +class SerialFixedArrayListAdapter : public FixedArrayList, + public SerializeIF { + public: + /** + * Constructor arguments are forwarded to FixedArrayList constructor. + * Refer to the fixed array list constructors for different options. + * @param args + */ + template + SerialFixedArrayListAdapter(Args... args) + : FixedArrayList(std::forward(args)...) {} - ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const { - return SerialArrayListAdapter::serialize(this, - buffer, size, maxSize, streamEndianness); - } + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const { + return SerialArrayListAdapter::serialize(this, buffer, size, maxSize, + streamEndianness); + } - size_t getSerializedSize() const { - return SerialArrayListAdapter:: - getSerializedSize(this); - } - - ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) { - return SerialArrayListAdapter::deSerialize(this, - buffer, size, streamEndianness); - } + size_t getSerializedSize() const { + return SerialArrayListAdapter::getSerializedSize(this); + } + ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, Endianness streamEndianness) { + return SerialArrayListAdapter::deSerialize(this, buffer, size, + streamEndianness); + } }; #endif /* FSFW_SERIALIZE_SERIALFIXEDARRAYLISTADAPTER_H_ */ diff --git a/src/fsfw/serialize/SerialLinkedListAdapter.h b/src/fsfw/serialize/SerialLinkedListAdapter.h index 430a21ac..4975c0a5 100644 --- a/src/fsfw/serialize/SerialLinkedListAdapter.h +++ b/src/fsfw/serialize/SerialLinkedListAdapter.h @@ -6,7 +6,7 @@ #include "SerializeElement.h" #include "SerializeIF.h" - /** +/** * @brief Implement the conversion of object data to data streams * or vice-versa, using linked lists. * @details @@ -33,96 +33,84 @@ * @author baetz * @ingroup serialize */ -template -class SerialLinkedListAdapter: public SinglyLinkedList, public SerializeIF { -public: +template +class SerialLinkedListAdapter : public SinglyLinkedList, public SerializeIF { + public: + SerialLinkedListAdapter(typename LinkedElement::Iterator start, bool printCount = false) + : SinglyLinkedList(start), printCount(printCount) {} - SerialLinkedListAdapter(typename LinkedElement::Iterator start, - bool printCount = false) : - SinglyLinkedList(start), printCount(printCount) { - } + SerialLinkedListAdapter(LinkedElement* first, bool printCount = false) + : SinglyLinkedList(first), printCount(printCount) {} - SerialLinkedListAdapter(LinkedElement* first, bool printCount = false) : - SinglyLinkedList(first), printCount(printCount) { + SerialLinkedListAdapter(bool printCount = false) + : SinglyLinkedList(), printCount(printCount) {} - } + virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override { + if (printCount) { + count_t mySize = SinglyLinkedList::getSize(); + ReturnValue_t result = + SerializeAdapter::serialize(&mySize, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + } + return serialize(SinglyLinkedList::start, buffer, size, maxSize, streamEndianness); + } - SerialLinkedListAdapter(bool printCount = false) : - SinglyLinkedList(), printCount(printCount) { - } + static ReturnValue_t serialize(const LinkedElement* element, uint8_t** buffer, size_t* size, + size_t maxSize, Endianness streamEndianness) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + while ((result == HasReturnvaluesIF::RETURN_OK) and (element != nullptr)) { + result = element->value->serialize(buffer, size, maxSize, streamEndianness); + element = element->getNext(); + } + return result; + } - virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const override { - if (printCount) { - count_t mySize = SinglyLinkedList::getSize(); - ReturnValue_t result = SerializeAdapter::serialize(&mySize, - buffer, size, maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - } - return serialize(SinglyLinkedList::start, buffer, size, maxSize, - streamEndianness); - } + virtual size_t getSerializedSize() const override { + if (printCount) { + return SerialLinkedListAdapter::getSerializedSize() + sizeof(count_t); + } else { + return getSerializedSize(SinglyLinkedList::start); + } + } - static ReturnValue_t serialize(const LinkedElement* element, - uint8_t** buffer, size_t* size, size_t maxSize, - Endianness streamEndianness) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - while ((result == HasReturnvaluesIF::RETURN_OK) and (element != nullptr)) { - result = element->value->serialize(buffer, size, maxSize, - streamEndianness); - element = element->getNext(); - } - return result; - } + static size_t getSerializedSize(const LinkedElement* element) { + size_t size = 0; + while (element != nullptr) { + size += element->value->getSerializedSize(); + element = element->getNext(); + } + return size; + } - virtual size_t getSerializedSize() const override { - if (printCount) { - return SerialLinkedListAdapter::getSerializedSize() - + sizeof(count_t); - } else { - return getSerializedSize(SinglyLinkedList::start); - } - } + virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + Endianness streamEndianness) override { + return deSerialize(SinglyLinkedList::start, buffer, size, streamEndianness); + } - static size_t getSerializedSize(const LinkedElement *element) { - size_t size = 0; - while (element != nullptr) { - size += element->value->getSerializedSize(); - element = element->getNext(); - } - return size; - } + static ReturnValue_t deSerialize(LinkedElement* element, const uint8_t** buffer, size_t* size, + Endianness streamEndianness) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + while ((result == HasReturnvaluesIF::RETURN_OK) and (element != nullptr)) { + result = element->value->deSerialize(buffer, size, streamEndianness); + element = element->getNext(); + } + return result; + } + /** + * Copying is forbidden by deleting the copy constructor and the copy + * assignment operator because of the pointers to the linked list members. + * Unless the child class implements an own copy constructor or + * copy assignment operator, these operation will throw a compiler error. + * @param + */ + SerialLinkedListAdapter(const SerialLinkedListAdapter&) = delete; + SerialLinkedListAdapter& operator=(const SerialLinkedListAdapter&) = delete; - virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) override { - return deSerialize(SinglyLinkedList::start, buffer, size, - streamEndianness); - } - - static ReturnValue_t deSerialize(LinkedElement* element, - const uint8_t** buffer, size_t* size, Endianness streamEndianness) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - while ((result == HasReturnvaluesIF::RETURN_OK) and (element != nullptr)) { - result = element->value->deSerialize(buffer, size, streamEndianness); - element = element->getNext(); - } - return result; - } - - /** - * Copying is forbidden by deleting the copy constructor and the copy - * assignment operator because of the pointers to the linked list members. - * Unless the child class implements an own copy constructor or - * copy assignment operator, these operation will throw a compiler error. - * @param - */ - SerialLinkedListAdapter(const SerialLinkedListAdapter &) = delete; - SerialLinkedListAdapter& operator=(const SerialLinkedListAdapter&) = delete; - - bool printCount; + bool printCount; }; #endif /* FSFW_SERIALIZE_SERIALLINKEDLISTADAPTER_H_ */ diff --git a/src/fsfw/serialize/SerializeAdapter.h b/src/fsfw/serialize/SerializeAdapter.h index 2831472c..5feda889 100644 --- a/src/fsfw/serialize/SerializeAdapter.h +++ b/src/fsfw/serialize/SerializeAdapter.h @@ -1,11 +1,12 @@ #ifndef _FSFW_SERIALIZE_SERIALIZEADAPTER_H_ #define _FSFW_SERIALIZE_SERIALIZEADAPTER_H_ +#include +#include + #include "../returnvalues/HasReturnvaluesIF.h" #include "EndianConverter.h" #include "SerializeIF.h" -#include -#include /** * @brief These adapters provides an interface to use the SerializeIF functions @@ -19,251 +20,244 @@ * @ingroup serialize */ class SerializeAdapter { -public: - /*** - * @brief Serialize a trivial copy-able type or a child of SerializeIF. - * @details - * The right template to be called is determined in the function itself. - * For objects of non trivial copy-able type this function is almost never - * called by the user directly. Instead helpers for specific types like - * SerialArrayListAdapter or SerialLinkedListAdapter are the right choice here. - * - * @param[in] object: Object to serialize, the used type is deduced from this pointer - * @param[in/out] buffer: Pointer to the buffer to serialize into. Buffer position will be - * incremented by the function. - * @param[in/out] size: Pointer to size of current written buffer. - * SIze will be incremented by the function. - * @param[in] maxSize: Max size of Buffer - * @param[in] streamEndianness: Endianness of serialized element as in according to - * SerializeIF::Endianness - * @return - * - @c BUFFER_TOO_SHORT The given buffer in is too short - * - @c RETURN_FAILED Generic Error - * - @c RETURN_OK Successful serialization - */ - template - static ReturnValue_t serialize(const T *object, uint8_t **buffer, - size_t *size, size_t maxSize, - SerializeIF::Endianness streamEndianness) { - InternalSerializeAdapter::value> adapter; - return adapter.serialize(object, buffer, size, maxSize, - streamEndianness); + public: + /*** + * @brief Serialize a trivial copy-able type or a child of SerializeIF. + * @details + * The right template to be called is determined in the function itself. + * For objects of non trivial copy-able type this function is almost never + * called by the user directly. Instead helpers for specific types like + * SerialArrayListAdapter or SerialLinkedListAdapter are the right choice here. + * + * @param[in] object: Object to serialize, the used type is deduced from this pointer + * @param[in/out] buffer: Pointer to the buffer to serialize into. Buffer position will be + * incremented by the function. + * @param[in/out] size: Pointer to size of current written buffer. + * SIze will be incremented by the function. + * @param[in] maxSize: Max size of Buffer + * @param[in] streamEndianness: Endianness of serialized element as in according to + * SerializeIF::Endianness + * @return + * - @c BUFFER_TOO_SHORT The given buffer in is too short + * - @c RETURN_FAILED Generic Error + * - @c RETURN_OK Successful serialization + */ + template + static ReturnValue_t serialize(const T *object, uint8_t **buffer, size_t *size, size_t maxSize, + SerializeIF::Endianness streamEndianness) { + InternalSerializeAdapter::value> adapter; + return adapter.serialize(object, buffer, size, maxSize, streamEndianness); + } + + /*** + * This function can be used to serialize a trivial copy-able type or a child of SerializeIF. + * The right template to be called is determined in the function itself. + * For objects of non trivial copy-able type this function is almost never + * called by the user directly. Instead helpers for specific types like + * SerialArrayListAdapter or SerialLinkedListAdapter are the right choice here. + * + * @param[in] object: Object to serialize, the used type is deduced from this pointer + * @param[in/out] buffer: Buffer to serialize into. + * @param[out] serSize: Serialized size + * @param[in] maxSize: Max size of buffer + * @param[in] streamEndianness: Endianness of serialized element as in according to + * SerializeIF::Endianness + * @return + * - @c BUFFER_TOO_SHORT The given buffer in is too short + * - @c RETURN_FAILED Generic Error + * - @c RETURN_OK Successful serialization + */ + template + static ReturnValue_t serialize(const T *object, uint8_t *const buffer, size_t *serSize, + size_t maxSize, SerializeIF::Endianness streamEndianness) { + if (object == nullptr or buffer == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + InternalSerializeAdapter::value> adapter; + uint8_t **tempPtr = const_cast(&buffer); + size_t tmpSize = 0; + ReturnValue_t result = adapter.serialize(object, tempPtr, &tmpSize, maxSize, streamEndianness); + if (serSize != nullptr) { + *serSize = tmpSize; + } + return result; + } + + /** + * @brief Function to return the serialized size of the object in the pointer. + * @details + * May be a trivially copy-able object or a child of SerializeIF. + * + * @param object Pointer to Object + * @return Serialized size of object + */ + template + static size_t getSerializedSize(const T *object) { + InternalSerializeAdapter::value> adapter; + return adapter.getSerializedSize(object); + } + + /** + * @brief Deserializes a object from a given buffer of given size. + * + * @details + * Object Must be trivially copy-able or a child of SerializeIF. + * Buffer will be moved to the current read location. Size will be decreased by the function. + * + * @param[in] object: Pointer to object to deserialize + * @param[in/out] buffer: Pointer to the buffer to deSerialize from. Buffer position will be + * incremented by the function + * @param[in/out] size: Pointer to remaining size of the buffer to read from. + * Will be decreased by function. + * @param[in] streamEndianness: Endianness as in according to SerializeIF::Endianness + * @return + * - @c STREAM_TOO_SHORT The input stream is too short to deSerialize the object + * - @c TOO_MANY_ELEMENTS The buffer has more inputs than expected + * - @c RETURN_FAILED Generic Error + * - @c RETURN_OK Successful deserialization + */ + template + static ReturnValue_t deSerialize(T *object, const uint8_t **buffer, size_t *size, + SerializeIF::Endianness streamEndianness) { + InternalSerializeAdapter::value> adapter; + return adapter.deSerialize(object, buffer, size, streamEndianness); + } + + /** + * @brief Deserializes a object from a given buffer of given size. + * + * @details + * Object Must be trivially copy-able or a child of SerializeIF. + * + * @param[in] object: Pointer to object to deserialize + * @param[in] buffer: Buffer to deSerialize from + * @param[out] deserSize: Deserialized length + * @param[in] streamEndianness: Endianness as in according to SerializeIF::Endianness + * @return + * - @c STREAM_TOO_SHORT The input stream is too short to deSerialize the object + * - @c TOO_MANY_ELEMENTS The buffer has more inputs than expected + * - @c RETURN_FAILED Generic Error + * - @c RETURN_OK Successful deserialization + */ + template + static ReturnValue_t deSerialize(T *object, const uint8_t *buffer, size_t *deserSize, + SerializeIF::Endianness streamEndianness) { + if (object == nullptr or buffer == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + InternalSerializeAdapter::value> adapter; + const uint8_t **tempPtr = &buffer; + size_t maxVal = -1; + ReturnValue_t result = adapter.deSerialize(object, tempPtr, &maxVal, streamEndianness); + if (deserSize != nullptr) { + *deserSize = -1 - maxVal; + } + return result; + } + + private: + /** + * Internal template to deduce the right function calls at compile time + */ + template + class InternalSerializeAdapter; + + /** + * Template to be used if T is not a child of SerializeIF + * + * @tparam T T must be trivially_copyable + */ + template + class InternalSerializeAdapter { + static_assert(std::is_trivially_copyable::value, + "If a type needs to be serialized it must be a child of " + "SerializeIF or trivially copy-able"); + + public: + static ReturnValue_t serialize(const T *object, uint8_t **buffer, size_t *size, size_t max_size, + SerializeIF::Endianness streamEndianness) { + size_t ignoredSize = 0; + if (size == nullptr) { + size = &ignoredSize; + } + // Check remaining size is large enough and check integer + // overflow of *size + size_t newSize = sizeof(T) + *size; + if ((newSize <= max_size) and (newSize > *size)) { + T tmp; + switch (streamEndianness) { + case SerializeIF::Endianness::BIG: + tmp = EndianConverter::convertBigEndian(*object); + break; + case SerializeIF::Endianness::LITTLE: + tmp = EndianConverter::convertLittleEndian(*object); + break; + default: + case SerializeIF::Endianness::MACHINE: + tmp = *object; + break; + } + std::memcpy(*buffer, &tmp, sizeof(T)); + *size += sizeof(T); + (*buffer) += sizeof(T); + return HasReturnvaluesIF::RETURN_OK; + } else { + return SerializeIF::BUFFER_TOO_SHORT; + } } - /*** - * This function can be used to serialize a trivial copy-able type or a child of SerializeIF. - * The right template to be called is determined in the function itself. - * For objects of non trivial copy-able type this function is almost never - * called by the user directly. Instead helpers for specific types like - * SerialArrayListAdapter or SerialLinkedListAdapter are the right choice here. - * - * @param[in] object: Object to serialize, the used type is deduced from this pointer - * @param[in/out] buffer: Buffer to serialize into. - * @param[out] serSize: Serialized size - * @param[in] maxSize: Max size of buffer - * @param[in] streamEndianness: Endianness of serialized element as in according to - * SerializeIF::Endianness - * @return - * - @c BUFFER_TOO_SHORT The given buffer in is too short - * - @c RETURN_FAILED Generic Error - * - @c RETURN_OK Successful serialization - */ - template - static ReturnValue_t serialize(const T *object, uint8_t* const buffer, size_t* serSize, - size_t maxSize, SerializeIF::Endianness streamEndianness) { - if(object == nullptr or buffer == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; + ReturnValue_t deSerialize(T *object, const uint8_t **buffer, size_t *size, + SerializeIF::Endianness streamEndianness) { + T tmp; + if (*size >= sizeof(T)) { + *size -= sizeof(T); + std::memcpy(&tmp, *buffer, sizeof(T)); + switch (streamEndianness) { + case SerializeIF::Endianness::BIG: + *object = EndianConverter::convertBigEndian(tmp); + break; + case SerializeIF::Endianness::LITTLE: + *object = EndianConverter::convertLittleEndian(tmp); + break; + default: + case SerializeIF::Endianness::MACHINE: + *object = tmp; + break; } - InternalSerializeAdapter::value> adapter; - uint8_t** tempPtr = const_cast(&buffer); - size_t tmpSize = 0; - ReturnValue_t result = adapter.serialize(object, tempPtr, &tmpSize, maxSize, - streamEndianness); - if(serSize != nullptr) { - *serSize = tmpSize; - } - return result; + + *buffer += sizeof(T); + return HasReturnvaluesIF::RETURN_OK; + } else { + return SerializeIF::STREAM_TOO_SHORT; + } } - /** - * @brief Function to return the serialized size of the object in the pointer. - * @details - * May be a trivially copy-able object or a child of SerializeIF. - * - * @param object Pointer to Object - * @return Serialized size of object - */ - template - static size_t getSerializedSize(const T *object){ - InternalSerializeAdapter::value> adapter; - return adapter.getSerializedSize(object); + uint32_t getSerializedSize(const T *object) { return sizeof(T); } + }; + + /** + * Template for objects that inherit from SerializeIF + * + * @tparam T A child of SerializeIF + */ + template + class InternalSerializeAdapter { + public: + ReturnValue_t serialize(const T *object, uint8_t **buffer, size_t *size, size_t max_size, + SerializeIF::Endianness streamEndianness) const { + size_t ignoredSize = 0; + if (size == nullptr) { + size = &ignoredSize; + } + return object->serialize(buffer, size, max_size, streamEndianness); } + size_t getSerializedSize(const T *object) const { return object->getSerializedSize(); } - /** - * @brief Deserializes a object from a given buffer of given size. - * - * @details - * Object Must be trivially copy-able or a child of SerializeIF. - * Buffer will be moved to the current read location. Size will be decreased by the function. - * - * @param[in] object: Pointer to object to deserialize - * @param[in/out] buffer: Pointer to the buffer to deSerialize from. Buffer position will be - * incremented by the function - * @param[in/out] size: Pointer to remaining size of the buffer to read from. - * Will be decreased by function. - * @param[in] streamEndianness: Endianness as in according to SerializeIF::Endianness - * @return - * - @c STREAM_TOO_SHORT The input stream is too short to deSerialize the object - * - @c TOO_MANY_ELEMENTS The buffer has more inputs than expected - * - @c RETURN_FAILED Generic Error - * - @c RETURN_OK Successful deserialization - */ - template - static ReturnValue_t deSerialize(T *object, const uint8_t **buffer, - size_t *size, SerializeIF::Endianness streamEndianness) { - InternalSerializeAdapter::value> adapter; - return adapter.deSerialize(object, buffer, size, streamEndianness); + ReturnValue_t deSerialize(T *object, const uint8_t **buffer, size_t *size, + SerializeIF::Endianness streamEndianness) { + return object->deSerialize(buffer, size, streamEndianness); } - - /** - * @brief Deserializes a object from a given buffer of given size. - * - * @details - * Object Must be trivially copy-able or a child of SerializeIF. - * - * @param[in] object: Pointer to object to deserialize - * @param[in] buffer: Buffer to deSerialize from - * @param[out] deserSize: Deserialized length - * @param[in] streamEndianness: Endianness as in according to SerializeIF::Endianness - * @return - * - @c STREAM_TOO_SHORT The input stream is too short to deSerialize the object - * - @c TOO_MANY_ELEMENTS The buffer has more inputs than expected - * - @c RETURN_FAILED Generic Error - * - @c RETURN_OK Successful deserialization - */ - template - static ReturnValue_t deSerialize(T *object, const uint8_t* buffer, - size_t* deserSize, SerializeIF::Endianness streamEndianness) { - if(object == nullptr or buffer == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - InternalSerializeAdapter::value> adapter; - const uint8_t** tempPtr = &buffer; - size_t maxVal = -1; - ReturnValue_t result = adapter.deSerialize(object, tempPtr, &maxVal, streamEndianness); - if(deserSize != nullptr) { - *deserSize = -1 - maxVal; - } - return result; - } - -private: - /** - * Internal template to deduce the right function calls at compile time - */ - template class InternalSerializeAdapter; - - /** - * Template to be used if T is not a child of SerializeIF - * - * @tparam T T must be trivially_copyable - */ - template - class InternalSerializeAdapter { - static_assert (std::is_trivially_copyable::value, - "If a type needs to be serialized it must be a child of " - "SerializeIF or trivially copy-able"); - public: - static ReturnValue_t serialize(const T *object, uint8_t **buffer, - size_t *size, size_t max_size, - SerializeIF::Endianness streamEndianness) { - size_t ignoredSize = 0; - if (size == nullptr) { - size = &ignoredSize; - } - // Check remaining size is large enough and check integer - // overflow of *size - size_t newSize = sizeof(T) + *size; - if ((newSize <= max_size) and (newSize > *size)) { - T tmp; - switch (streamEndianness) { - case SerializeIF::Endianness::BIG: - tmp = EndianConverter::convertBigEndian(*object); - break; - case SerializeIF::Endianness::LITTLE: - tmp = EndianConverter::convertLittleEndian(*object); - break; - default: - case SerializeIF::Endianness::MACHINE: - tmp = *object; - break; - } - std::memcpy(*buffer, &tmp, sizeof(T)); - *size += sizeof(T); - (*buffer) += sizeof(T); - return HasReturnvaluesIF::RETURN_OK; - } else { - return SerializeIF::BUFFER_TOO_SHORT; - } - } - - ReturnValue_t deSerialize(T *object, const uint8_t **buffer, - size_t *size, SerializeIF::Endianness streamEndianness) { - T tmp; - if (*size >= sizeof(T)) { - *size -= sizeof(T); - std::memcpy(&tmp, *buffer, sizeof(T)); - switch (streamEndianness) { - case SerializeIF::Endianness::BIG: - *object = EndianConverter::convertBigEndian(tmp); - break; - case SerializeIF::Endianness::LITTLE: - *object = EndianConverter::convertLittleEndian(tmp); - break; - default: - case SerializeIF::Endianness::MACHINE: - *object = tmp; - break; - } - - *buffer += sizeof(T); - return HasReturnvaluesIF::RETURN_OK; - } else { - return SerializeIF::STREAM_TOO_SHORT; - } - } - - uint32_t getSerializedSize(const T *object) { - return sizeof(T); - } - }; - - /** - * Template for objects that inherit from SerializeIF - * - * @tparam T A child of SerializeIF - */ - template - class InternalSerializeAdapter { - public: - ReturnValue_t serialize(const T *object, uint8_t **buffer, size_t *size, - size_t max_size, - SerializeIF::Endianness streamEndianness) const { - size_t ignoredSize = 0; - if (size == nullptr) { - size = &ignoredSize; - } - return object->serialize(buffer, size, max_size, streamEndianness); - } - size_t getSerializedSize(const T *object) const { - return object->getSerializedSize(); - } - - ReturnValue_t deSerialize(T *object, const uint8_t **buffer, - size_t *size, SerializeIF::Endianness streamEndianness) { - return object->deSerialize(buffer, size, streamEndianness); - } - }; + }; }; #endif /* _FSFW_SERIALIZE_SERIALIZEADAPTER_H_ */ diff --git a/src/fsfw/serialize/SerializeElement.h b/src/fsfw/serialize/SerializeElement.h index db66f9cc..07f3fea9 100644 --- a/src/fsfw/serialize/SerializeElement.h +++ b/src/fsfw/serialize/SerializeElement.h @@ -1,10 +1,11 @@ #ifndef FSFW_SERIALIZE_SERIALIZEELEMENT_H_ #define FSFW_SERIALIZE_SERIALIZEELEMENT_H_ -#include "SerializeAdapter.h" -#include "../container/SinglyLinkedList.h" #include +#include "../container/SinglyLinkedList.h" +#include "SerializeAdapter.h" + /** * @brief This class is used to mark datatypes for serialization with the * SerialLinkedListAdapter @@ -16,48 +17,36 @@ * specified sequence order. * @ingroup serialize */ -template -class SerializeElement: public SerializeIF, public LinkedElement { -public: - template - SerializeElement(Args ... args) : - LinkedElement(this), entry(std::forward(args)...) { +template +class SerializeElement : public SerializeIF, public LinkedElement { + public: + template + SerializeElement(Args... args) + : LinkedElement(this), entry(std::forward(args)...) {} + SerializeElement() : LinkedElement(this), entry() {} - } - SerializeElement() : - LinkedElement(this), entry() { - } + ReturnValue_t serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const override { + return SerializeAdapter::serialize(&entry, buffer, size, maxSize, streamEndianness); + } - ReturnValue_t serialize(uint8_t **buffer, size_t *size, size_t maxSize, - Endianness streamEndianness) const override { - return SerializeAdapter::serialize(&entry, buffer, size, maxSize, - streamEndianness); - } + size_t getSerializedSize() const override { return SerializeAdapter::getSerializedSize(&entry); } - size_t getSerializedSize() const override { - return SerializeAdapter::getSerializedSize(&entry); - } + virtual ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) override { + return SerializeAdapter::deSerialize(&entry, buffer, size, streamEndianness); + } - virtual ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) override { - return SerializeAdapter::deSerialize(&entry, buffer, size, - streamEndianness); - } + operator T() { return entry; } - operator T() { - return entry; - } + SerializeElement &operator=(T newValue) { + entry = newValue; + return *this; + } - SerializeElement& operator=(T newValue) { - entry = newValue; - return *this; - } + T *operator->() { return &entry; } - T* operator->() { - return &entry; - } - - T entry; + T entry; }; #endif /* FSFW_SERIALIZE_SERIALIZEELEMENT_H_ */ diff --git a/src/fsfw/serialize/SerializeIF.h b/src/fsfw/serialize/SerializeIF.h index dfd854e3..d806c161 100644 --- a/src/fsfw/serialize/SerializeIF.h +++ b/src/fsfw/serialize/SerializeIF.h @@ -1,9 +1,10 @@ #ifndef FSFW_SERIALIZE_SERIALIZEIF_H_ #define FSFW_SERIALIZE_SERIALIZEIF_H_ -#include "../returnvalues/HasReturnvaluesIF.h" #include +#include "../returnvalues/HasReturnvaluesIF.h" + /** * @defgroup serialize Serialization * Contains serialization services. @@ -17,74 +18,78 @@ * @ingroup serialize */ class SerializeIF { -public: - enum class Endianness : uint8_t { - BIG, - LITTLE, - MACHINE, - NETWORK = BIG // Added for convenience like htons on sockets - }; + public: + enum class Endianness : uint8_t { + BIG, + LITTLE, + MACHINE, + NETWORK = BIG // Added for convenience like htons on sockets + }; - static const uint8_t INTERFACE_ID = CLASS_ID::SERIALIZE_IF; - static const ReturnValue_t BUFFER_TOO_SHORT = MAKE_RETURN_CODE(1); // !< The given buffer in serialize is too short - static const ReturnValue_t STREAM_TOO_SHORT = MAKE_RETURN_CODE(2); // !< The input stream in deserialize is too short - static const ReturnValue_t TOO_MANY_ELEMENTS = MAKE_RETURN_CODE(3);// !< There are too many elements to be deserialized + static const uint8_t INTERFACE_ID = CLASS_ID::SERIALIZE_IF; + static const ReturnValue_t BUFFER_TOO_SHORT = + MAKE_RETURN_CODE(1); // !< The given buffer in serialize is too short + static const ReturnValue_t STREAM_TOO_SHORT = + MAKE_RETURN_CODE(2); // !< The input stream in deserialize is too short + static const ReturnValue_t TOO_MANY_ELEMENTS = + MAKE_RETURN_CODE(3); // !< There are too many elements to be deserialized - virtual ~SerializeIF() { - } - /** - * @brief - * Function to serialize the object into a buffer with maxSize. Size represents the written amount. - * If a part of the buffer has been used already, size must be set to the used amount of bytes. - * - * @details - * Implementations of this function must increase the size variable and move the buffer pointer. - * MaxSize must be checked by implementations of this function - * and BUFFER_TOO_SHORT has to be returned if size would be larger than maxSize. - * - * Custom implementations might use additional return values. - * - * @param[in/out] buffer Buffer to serialize into, will be set to the current write location - * @param[in/out] size Size that has been used in the buffer already, will be increased by the function - * @param[in] maxSize The size of the buffer that is allowed to be used for serialize. - * @param[in] streamEndianness Endianness of the serialized data according to SerializeIF::Endianness - * @return - * - @c BUFFER_TOO_SHORT The given buffer in is too short - * - @c RETURN_FAILED Generic error - * - @c RETURN_OK Successful serialization - */ - virtual ReturnValue_t serialize(uint8_t **buffer, size_t *size, - size_t maxSize, Endianness streamEndianness) const = 0; + virtual ~SerializeIF() {} + /** + * @brief + * Function to serialize the object into a buffer with maxSize. Size represents the written + * amount. If a part of the buffer has been used already, size must be set to the used amount of + * bytes. + * + * @details + * Implementations of this function must increase the size variable and move the buffer pointer. + * MaxSize must be checked by implementations of this function + * and BUFFER_TOO_SHORT has to be returned if size would be larger than maxSize. + * + * Custom implementations might use additional return values. + * + * @param[in/out] buffer Buffer to serialize into, will be set to the current write location + * @param[in/out] size Size that has been used in the buffer already, will be increased by the + * function + * @param[in] maxSize The size of the buffer that is allowed to be used for serialize. + * @param[in] streamEndianness Endianness of the serialized data according to + * SerializeIF::Endianness + * @return + * - @c BUFFER_TOO_SHORT The given buffer in is too short + * - @c RETURN_FAILED Generic error + * - @c RETURN_OK Successful serialization + */ + virtual ReturnValue_t serialize(uint8_t **buffer, size_t *size, size_t maxSize, + Endianness streamEndianness) const = 0; - /** - * Gets the size of a object if it would be serialized in a buffer - * @return Size of serialized object - */ - virtual size_t getSerializedSize() const = 0; - - /** - * @brief - * Deserializes a object from a given buffer of given size. - * - * @details - * Buffer must be moved to the current read location by the implementation - * of this function. Size must be decreased by the implementation. - * Implementations are not allowed to alter the buffer as indicated by const pointer. - * - * Custom implementations might use additional return values. - * - * @param[in/out] buffer Buffer to deSerialize from. Will be moved by the function. - * @param[in/out] size Remaining size of the buffer to read from. Will be decreased by function. - * @param[in] streamEndianness Endianness as in according to SerializeIF::Endianness - * @return - * - @c STREAM_TOO_SHORT The input stream is too short to deSerialize the object - * - @c TOO_MANY_ELEMENTS The buffer has more inputs than expected - * - @c RETURN_FAILED Generic Error - * - @c RETURN_OK Successful deserialization - */ - virtual ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) = 0; + /** + * Gets the size of a object if it would be serialized in a buffer + * @return Size of serialized object + */ + virtual size_t getSerializedSize() const = 0; + /** + * @brief + * Deserializes a object from a given buffer of given size. + * + * @details + * Buffer must be moved to the current read location by the implementation + * of this function. Size must be decreased by the implementation. + * Implementations are not allowed to alter the buffer as indicated by const pointer. + * + * Custom implementations might use additional return values. + * + * @param[in/out] buffer Buffer to deSerialize from. Will be moved by the function. + * @param[in/out] size Remaining size of the buffer to read from. Will be decreased by function. + * @param[in] streamEndianness Endianness as in according to SerializeIF::Endianness + * @return + * - @c STREAM_TOO_SHORT The input stream is too short to deSerialize the object + * - @c TOO_MANY_ELEMENTS The buffer has more inputs than expected + * - @c RETURN_FAILED Generic Error + * - @c RETURN_OK Successful deserialization + */ + virtual ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, + Endianness streamEndianness) = 0; }; #endif /* FSFW_SERIALIZE_SERIALIZEIF_H_ */ diff --git a/src/fsfw/serviceinterface/ServiceInterfaceBuffer.cpp b/src/fsfw/serviceinterface/ServiceInterfaceBuffer.cpp index 0411e674..dd928efe 100644 --- a/src/fsfw/serviceinterface/ServiceInterfaceBuffer.cpp +++ b/src/fsfw/serviceinterface/ServiceInterfaceBuffer.cpp @@ -2,11 +2,12 @@ #if FSFW_CPP_OSTREAM_ENABLED == 1 -#include "fsfw/timemanager/Clock.h" +#include + +#include #include "fsfw/serviceinterface/serviceInterfaceDefintions.h" -#include -#include +#include "fsfw/timemanager/Clock.h" #if defined(WIN32) && FSFW_COLORED_OUTPUT == 1 #include "Windows.h" @@ -17,254 +18,240 @@ extern "C" void printChar(const char*, bool errStream); #ifndef UT699 -ServiceInterfaceBuffer::ServiceInterfaceBuffer(std::string setMessage, - bool addCrToPreamble, bool buffered , bool errStream, uint16_t port): - isActive(true), logMessage(setMessage), - addCrToPreamble(addCrToPreamble), buffered(buffered), - errStream(errStream) { - if(buffered) { - // Set pointers if the stream is buffered. - setp( buf, buf + BUF_SIZE ); - } +ServiceInterfaceBuffer::ServiceInterfaceBuffer(std::string setMessage, bool addCrToPreamble, + bool buffered, bool errStream, uint16_t port) + : isActive(true), + logMessage(setMessage), + addCrToPreamble(addCrToPreamble), + buffered(buffered), + errStream(errStream) { + if (buffered) { + // Set pointers if the stream is buffered. + setp(buf, buf + BUF_SIZE); + } #if FSFW_COLORED_OUTPUT == 1 - if(setMessage.find("DEBUG") != std::string::npos) { - colorPrefix = sif::ANSI_COLOR_CYAN; - } - else if(setMessage.find("INFO") != std::string::npos) { - colorPrefix = sif::ANSI_COLOR_GREEN; - } - else if(setMessage.find("WARNING") != std::string::npos) { - colorPrefix = sif::ANSI_COLOR_MAGENTA; - } - else if(setMessage.find("ERROR") != std::string::npos) { - colorPrefix = sif::ANSI_COLOR_RED; - } - else { - colorPrefix = sif::ANSI_COLOR_RESET; - } + if (setMessage.find("DEBUG") != std::string::npos) { + colorPrefix = sif::ANSI_COLOR_CYAN; + } else if (setMessage.find("INFO") != std::string::npos) { + colorPrefix = sif::ANSI_COLOR_GREEN; + } else if (setMessage.find("WARNING") != std::string::npos) { + colorPrefix = sif::ANSI_COLOR_MAGENTA; + } else if (setMessage.find("ERROR") != std::string::npos) { + colorPrefix = sif::ANSI_COLOR_RED; + } else { + colorPrefix = sif::ANSI_COLOR_RESET; + } #ifdef WIN32 - HANDLE hOut = GetStdHandle(STD_OUTPUT_HANDLE); - DWORD dwMode = 0; - GetConsoleMode(hOut, &dwMode); - dwMode |= ENABLE_VIRTUAL_TERMINAL_PROCESSING; - SetConsoleMode(hOut, dwMode); + HANDLE hOut = GetStdHandle(STD_OUTPUT_HANDLE); + DWORD dwMode = 0; + GetConsoleMode(hOut, &dwMode); + dwMode |= ENABLE_VIRTUAL_TERMINAL_PROCESSING; + SetConsoleMode(hOut, dwMode); #endif #endif - preamble.reserve(MAX_PREAMBLE_SIZE); - preamble.resize(MAX_PREAMBLE_SIZE); + preamble.reserve(MAX_PREAMBLE_SIZE); + preamble.resize(MAX_PREAMBLE_SIZE); } void ServiceInterfaceBuffer::putChars(char const* begin, char const* end) { - char array[BUF_SIZE]; - uint32_t length = end - begin; - if (length > sizeof(array)) { - length = sizeof(array); - } - memcpy(array, begin, length); + char array[BUF_SIZE]; + uint32_t length = end - begin; + if (length > sizeof(array)) { + length = sizeof(array); + } + memcpy(array, begin, length); - for(; begin != end; begin++){ - if(errStream) { - printChar(begin, true); - } - else { - printChar(begin, false); - } - } + for (; begin != end; begin++) { + if (errStream) { + printChar(begin, true); + } else { + printChar(begin, false); + } + } } #endif int ServiceInterfaceBuffer::overflow(int c) { - if(not buffered and this->isActive) { - if (c != Traits::eof()) { - if(errStream) { - printChar(reinterpret_cast(&c), true); - } - else { - printChar(reinterpret_cast(&c), false); - } - } - return 0; - } - // Handle output - putChars(pbase(), pptr()); - if (c != Traits::eof()) { - char c2 = c; - // Handle the one character that didn't fit to buffer - putChars(&c2, &c2 + 1); - } - // This tells that buffer is empty again - setp(buf, buf + BUF_SIZE - 1); - // I'm not sure about this return value! - return 0; + if (not buffered and this->isActive) { + if (c != Traits::eof()) { + if (errStream) { + printChar(reinterpret_cast(&c), true); + } else { + printChar(reinterpret_cast(&c), false); + } + } + return 0; + } + // Handle output + putChars(pbase(), pptr()); + if (c != Traits::eof()) { + char c2 = c; + // Handle the one character that didn't fit to buffer + putChars(&c2, &c2 + 1); + } + // This tells that buffer is empty again + setp(buf, buf + BUF_SIZE - 1); + // I'm not sure about this return value! + return 0; } int ServiceInterfaceBuffer::sync(void) { - if(not this->isActive and not buffered) { - if(not buffered) { - setp(buf, buf + BUF_SIZE - 1); - } - return 0; - } - if(not buffered) { - return 0; - } + if (not this->isActive and not buffered) { + if (not buffered) { + setp(buf, buf + BUF_SIZE - 1); + } + return 0; + } + if (not buffered) { + return 0; + } - size_t preambleSize = 0; - std::string* preamble = getPreamble(&preambleSize); - // Write logMessage and time - this->putChars(preamble->data(), preamble->data() + preambleSize); - // Handle output - this->putChars(pbase(), pptr()); - // This tells that buffer is empty again - setp(buf, buf + BUF_SIZE - 1); - return 0; + size_t preambleSize = 0; + std::string* preamble = getPreamble(&preambleSize); + // Write logMessage and time + this->putChars(preamble->data(), preamble->data() + preambleSize); + // Handle output + this->putChars(pbase(), pptr()); + // This tells that buffer is empty again + setp(buf, buf + BUF_SIZE - 1); + return 0; } -bool ServiceInterfaceBuffer::isBuffered() const { - return buffered; -} +bool ServiceInterfaceBuffer::isBuffered() const { return buffered; } -std::string* ServiceInterfaceBuffer::getPreamble(size_t * preambleSize) { - Clock::TimeOfDay_t loggerTime; - Clock::getDateAndTime(&loggerTime); - size_t currentSize = 0; - char* parsePosition = &preamble[0]; - if(addCrToPreamble) { - preamble[0] = '\r'; - currentSize += 1; - parsePosition += 1; - } +std::string* ServiceInterfaceBuffer::getPreamble(size_t* preambleSize) { + Clock::TimeOfDay_t loggerTime; + Clock::getDateAndTime(&loggerTime); + size_t currentSize = 0; + char* parsePosition = &preamble[0]; + if (addCrToPreamble) { + preamble[0] = '\r'; + currentSize += 1; + parsePosition += 1; + } #if FSFW_COLORED_OUTPUT == 1 - currentSize += sprintf(parsePosition, "%s", colorPrefix.c_str()); - parsePosition += colorPrefix.size(); + currentSize += sprintf(parsePosition, "%s", colorPrefix.c_str()); + parsePosition += colorPrefix.size(); #endif - int32_t charCount = sprintf(parsePosition, - "%s%s | %02" SCNu32 ":%02" SCNu32 ":%02" SCNu32 ".%03" SCNu32 " | ", - this->logMessage.c_str(), sif::ANSI_COLOR_RESET, loggerTime.hour, - loggerTime.minute, - loggerTime.second, - loggerTime.usecond /1000); - if(charCount < 0) { - printf("ServiceInterfaceBuffer: Failure parsing preamble\r\n"); - return &preamble; - } - if(charCount > MAX_PREAMBLE_SIZE) { - printf("ServiceInterfaceBuffer: Char count too large for maximum " - "preamble size"); - return &preamble; - } - currentSize += charCount; - if(preambleSize != nullptr) { - *preambleSize = currentSize; - } - return &preamble; + int32_t charCount = + sprintf(parsePosition, "%s%s | %02" SCNu32 ":%02" SCNu32 ":%02" SCNu32 ".%03" SCNu32 " | ", + this->logMessage.c_str(), sif::ANSI_COLOR_RESET, loggerTime.hour, loggerTime.minute, + loggerTime.second, loggerTime.usecond / 1000); + if (charCount < 0) { + printf("ServiceInterfaceBuffer: Failure parsing preamble\r\n"); + return &preamble; + } + if (charCount > MAX_PREAMBLE_SIZE) { + printf( + "ServiceInterfaceBuffer: Char count too large for maximum " + "preamble size"); + return &preamble; + } + currentSize += charCount; + if (preambleSize != nullptr) { + *preambleSize = currentSize; + } + return &preamble; } -bool ServiceInterfaceBuffer::crAdditionEnabled() const { - return addCrToPreamble; -} +bool ServiceInterfaceBuffer::crAdditionEnabled() const { return addCrToPreamble; } #if FSFW_COLORED_OUTPUT == 1 void ServiceInterfaceBuffer::setAsciiColorPrefix(std::string colorPrefix) { - this->colorPrefix = colorPrefix; + this->colorPrefix = colorPrefix; } #endif #ifdef UT699 #include "../osal/rtems/Interrupt.h" -ServiceInterfaceBuffer::ServiceInterfaceBuffer(std::string set_message, - uint16_t port) { - this->log_message = set_message; - this->isActive = true; - setp( buf, buf + BUF_SIZE ); +ServiceInterfaceBuffer::ServiceInterfaceBuffer(std::string set_message, uint16_t port) { + this->log_message = set_message; + this->isActive = true; + setp(buf, buf + BUF_SIZE); } void ServiceInterfaceBuffer::putChars(char const* begin, char const* end) { - char array[BUF_SIZE]; - uint32_t length = end - begin; - if (length > sizeof(array)) { - length = sizeof(array); - } - memcpy(array, begin, length); + char array[BUF_SIZE]; + uint32_t length = end - begin; + if (length > sizeof(array)) { + length = sizeof(array); + } + memcpy(array, begin, length); - if (!Interrupt::isInterruptInProgress()) { - std::cout << array; - } else { - //Uncomment the following line if you need ISR debug output. -// printk(array); - } + if (!Interrupt::isInterruptInProgress()) { + std::cout << array; + } else { + // Uncomment the following line if you need ISR debug output. + // printk(array); + } } -#endif //UT699 +#endif // UT699 #ifdef ML505 #include -ServiceInterfaceBuffer::ServiceInterfaceBuffer(std::string set_message, - uint16_t port) : - isActive(true), log_message(set_message), udpSocket(0), remoteAddressLength( - sizeof(remoteAddress)) { - setp(buf, buf + BUF_SIZE); - memset((uint8_t*) &remoteAddress, 0, sizeof(remoteAddress)); - remoteAddress.sin_family = AF_INET; - remoteAddress.sin_port = htons(port); - remoteAddress.sin_addr.s_addr = htonl(inet_addr("192.168.250.100")); +ServiceInterfaceBuffer::ServiceInterfaceBuffer(std::string set_message, uint16_t port) + : isActive(true), + log_message(set_message), + udpSocket(0), + remoteAddressLength(sizeof(remoteAddress)) { + setp(buf, buf + BUF_SIZE); + memset((uint8_t*)&remoteAddress, 0, sizeof(remoteAddress)); + remoteAddress.sin_family = AF_INET; + remoteAddress.sin_port = htons(port); + remoteAddress.sin_addr.s_addr = htonl(inet_addr("192.168.250.100")); } void ServiceInterfaceBuffer::putChars(char const* begin, char const* end) { + char array[BUF_SIZE]; + uint32_t length = end - begin; + if (length > sizeof(array)) { + length = sizeof(array); + } + memcpy(array, begin, length); - char array[BUF_SIZE]; - uint32_t length = end - begin; - if (length > sizeof(array)) { - length = sizeof(array); - } - memcpy(array, begin, length); - - if (udpSocket <= 0) { - initSocket(); - } - - if (udpSocket > 0) { - sendto(udpSocket, array, length, 0, (sockaddr*) &remoteAddress, - sizeof(remoteAddress)); - } + if (udpSocket <= 0) { + initSocket(); + } + if (udpSocket > 0) { + sendto(udpSocket, array, length, 0, (sockaddr*)&remoteAddress, sizeof(remoteAddress)); + } } void ServiceInterfaceBuffer::initSocket() { - sockaddr_in address; - memset((uint8_t*) &address, 0, sizeof(address)); - address.sin_family = AF_INET; - address.sin_port = htons(0); - address.sin_addr.s_addr = htonl(INADDR_ANY); + sockaddr_in address; + memset((uint8_t*)&address, 0, sizeof(address)); + address.sin_family = AF_INET; + address.sin_port = htons(0); + address.sin_addr.s_addr = htonl(INADDR_ANY); - udpSocket = socket(PF_INET, SOCK_DGRAM, 0); - if (socket < 0) { - printf("Error opening socket!\n"); - return; - } - timeval timeout = { 0, 20 }; - if (setsockopt(udpSocket, SOL_SOCKET, SO_RCVTIMEO, &timeout, - sizeof(timeout)) < 0) { - printf("Error setting SO_RCVTIMEO socket options!\n"); - return; - } - if (setsockopt(udpSocket, SOL_SOCKET, SO_SNDTIMEO, &timeout, - sizeof(timeout)) < 0) { - printf("Error setting SO_SNDTIMEO socket options!\n"); - return; - } - if (bind(udpSocket, (sockaddr *) &address, sizeof(address)) < 0) { - printf("Error binding socket!\n"); - } + udpSocket = socket(PF_INET, SOCK_DGRAM, 0); + if (socket < 0) { + printf("Error opening socket!\n"); + return; + } + timeval timeout = {0, 20}; + if (setsockopt(udpSocket, SOL_SOCKET, SO_RCVTIMEO, &timeout, sizeof(timeout)) < 0) { + printf("Error setting SO_RCVTIMEO socket options!\n"); + return; + } + if (setsockopt(udpSocket, SOL_SOCKET, SO_SNDTIMEO, &timeout, sizeof(timeout)) < 0) { + printf("Error setting SO_SNDTIMEO socket options!\n"); + return; + } + if (bind(udpSocket, (sockaddr*)&address, sizeof(address)) < 0) { + printf("Error binding socket!\n"); + } } -#endif //ML505 +#endif // ML505 #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ diff --git a/src/fsfw/serviceinterface/ServiceInterfaceBuffer.h b/src/fsfw/serviceinterface/ServiceInterfaceBuffer.h index ad1148a2..9cda75c6 100644 --- a/src/fsfw/serviceinterface/ServiceInterfaceBuffer.h +++ b/src/fsfw/serviceinterface/ServiceInterfaceBuffer.h @@ -1,14 +1,15 @@ #ifndef FRAMEWORK_SERVICEINTERFACE_SERVICEINTERFACEBUFFER_H_ #define FRAMEWORK_SERVICEINTERFACE_SERVICEINTERFACEBUFFER_H_ -#include "../returnvalues/HasReturnvaluesIF.h" #include +#include "../returnvalues/HasReturnvaluesIF.h" + #if FSFW_CPP_OSTREAM_ENABLED == 1 +#include #include #include -#include #ifndef UT699 @@ -20,138 +21,140 @@ * It also calls the char printing function which is implemented in the * board supply package (BSP). */ -class ServiceInterfaceBuffer: - public std::streambuf { - friend class ServiceInterfaceStream; -public: - static constexpr uint8_t MAX_PREAMBLE_SIZE = 40; +class ServiceInterfaceBuffer : public std::streambuf { + friend class ServiceInterfaceStream; - ServiceInterfaceBuffer(std::string setMessage, bool addCrToPreamble, - bool buffered, bool errStream, uint16_t port); + public: + static constexpr uint8_t MAX_PREAMBLE_SIZE = 40; -protected: - bool isActive; - //! This is called when buffer becomes full. If - //! buffer is not used, then this is called every - //! time when characters are put to stream. - int overflow(int c = Traits::eof()) override; + ServiceInterfaceBuffer(std::string setMessage, bool addCrToPreamble, bool buffered, + bool errStream, uint16_t port); - //! This function is called when stream is flushed, - //! for example when std::endl is put to stream. - int sync(void) override; + protected: + bool isActive; + //! This is called when buffer becomes full. If + //! buffer is not used, then this is called every + //! time when characters are put to stream. + int overflow(int c = Traits::eof()) override; - bool isBuffered() const; -private: - //! For additional message information - std::string logMessage; - std::string preamble; + //! This function is called when stream is flushed, + //! for example when std::endl is put to stream. + int sync(void) override; + + bool isBuffered() const; + + private: + //! For additional message information + std::string logMessage; + std::string preamble; #if FSFW_COLORED_OUTPUT == 1 - std::string colorPrefix; - void setAsciiColorPrefix(std::string colorPrefix); + std::string colorPrefix; + void setAsciiColorPrefix(std::string colorPrefix); #endif - // For EOF detection - typedef std::char_traits Traits; + // For EOF detection + typedef std::char_traits Traits; - //! This is useful for some terminal programs which do not have - //! implicit carriage return with newline characters. - bool addCrToPreamble; + //! This is useful for some terminal programs which do not have + //! implicit carriage return with newline characters. + bool addCrToPreamble; - //! Specifies whether the stream operates in buffered or unbuffered mode. - bool buffered; - //! This specifies to print to stderr and work in unbuffered mode. - bool errStream; + //! Specifies whether the stream operates in buffered or unbuffered mode. + bool buffered; + //! This specifies to print to stderr and work in unbuffered mode. + bool errStream; - //! Needed for buffered mode. - static size_t const BUF_SIZE = fsfwconfig::FSFW_PRINT_BUFFER_SIZE; - char buf[BUF_SIZE]; + //! Needed for buffered mode. + static size_t const BUF_SIZE = fsfwconfig::FSFW_PRINT_BUFFER_SIZE; + char buf[BUF_SIZE]; - //! In this function, the characters are parsed. - void putChars(char const* begin, char const* end); + //! In this function, the characters are parsed. + void putChars(char const* begin, char const* end); - std::string* getPreamble(size_t * preambleSize = nullptr); + std::string* getPreamble(size_t* preambleSize = nullptr); - bool crAdditionEnabled() const; + bool crAdditionEnabled() const; }; #endif - #ifdef UT699 -class ServiceInterfaceBuffer: public std::basic_streambuf > { - friend class ServiceInterfaceStream; -public: - ServiceInterfaceBuffer(std::string set_message, uint16_t port); -protected: - bool isActive; - // This is called when buffer becomes full. If - // buffer is not used, then this is called every - // time when characters are put to stream. - virtual int overflow(int c = Traits::eof()); +class ServiceInterfaceBuffer : public std::basic_streambuf > { + friend class ServiceInterfaceStream; - // This function is called when stream is flushed, - // for example when std::endl is put to stream. - virtual int sync(void); + public: + ServiceInterfaceBuffer(std::string set_message, uint16_t port); -private: - // For additional message information - std::string log_message; - // For EOF detection - typedef std::char_traits Traits; + protected: + bool isActive; + // This is called when buffer becomes full. If + // buffer is not used, then this is called every + // time when characters are put to stream. + virtual int overflow(int c = Traits::eof()); - // Work in buffer mode. It is also possible to work without buffer. - static size_t const BUF_SIZE = 128; - char buf[BUF_SIZE]; + // This function is called when stream is flushed, + // for example when std::endl is put to stream. + virtual int sync(void); - // In this function, the characters are parsed. - void putChars(char const* begin, char const* end); + private: + // For additional message information + std::string log_message; + // For EOF detection + typedef std::char_traits Traits; + + // Work in buffer mode. It is also possible to work without buffer. + static size_t const BUF_SIZE = 128; + char buf[BUF_SIZE]; + + // In this function, the characters are parsed. + void putChars(char const* begin, char const* end); }; -#endif //UT699 +#endif // UT699 #ifdef ML505 -#include -#include #include #include #include +#include +#include -class ServiceInterfaceBuffer: public std::basic_streambuf > { - friend class ServiceInterfaceStream; -public: - ServiceInterfaceBuffer(std::string set_message, uint16_t port); -protected: - bool isActive; - // This is called when buffer becomes full. If - // buffer is not used, then this is called every - // time when characters are put to stream. - virtual int overflow(int c = Traits::eof()); +class ServiceInterfaceBuffer : public std::basic_streambuf > { + friend class ServiceInterfaceStream; - // This function is called when stream is flushed, - // for example when std::endl is put to stream. - virtual int sync(void); + public: + ServiceInterfaceBuffer(std::string set_message, uint16_t port); -private: - // For additional message information - std::string log_message; - // For EOF detection - typedef std::char_traits Traits; + protected: + bool isActive; + // This is called when buffer becomes full. If + // buffer is not used, then this is called every + // time when characters are put to stream. + virtual int overflow(int c = Traits::eof()); - // Work in buffer mode. It is also possible to work without buffer. - static size_t const BUF_SIZE = 128; - char buf[BUF_SIZE]; + // This function is called when stream is flushed, + // for example when std::endl is put to stream. + virtual int sync(void); - // In this function, the characters are parsed. - void putChars(char const* begin, char const* end); + private: + // For additional message information + std::string log_message; + // For EOF detection + typedef std::char_traits Traits; - int udpSocket; - sockaddr_in remoteAddress; - socklen_t remoteAddressLength; - void initSocket(); + // Work in buffer mode. It is also possible to work without buffer. + static size_t const BUF_SIZE = 128; + char buf[BUF_SIZE]; + + // In this function, the characters are parsed. + void putChars(char const* begin, char const* end); + + int udpSocket; + sockaddr_in remoteAddress; + socklen_t remoteAddressLength; + void initSocket(); }; -#endif //ML505 +#endif // ML505 #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ diff --git a/src/fsfw/serviceinterface/ServiceInterfacePrinter.cpp b/src/fsfw/serviceinterface/ServiceInterfacePrinter.cpp index e42e515d..78d12a56 100644 --- a/src/fsfw/serviceinterface/ServiceInterfacePrinter.cpp +++ b/src/fsfw/serviceinterface/ServiceInterfacePrinter.cpp @@ -1,11 +1,12 @@ -#include "fsfw/FSFW.h" #include "fsfw/serviceinterface/ServiceInterfacePrinter.h" -#include "fsfw/serviceinterface/serviceInterfaceDefintions.h" -#include "fsfw/timemanager/Clock.h" #include #include +#include "fsfw/FSFW.h" +#include "fsfw/serviceinterface/serviceInterfaceDefintions.h" +#include "fsfw/timemanager/Clock.h" + static sif::PrintLevel printLevel = sif::PrintLevel::DEBUG_LEVEL; #if defined(WIN32) && FSFW_COLORED_OUTPUT == 1 static bool consoleInitialized = false; @@ -17,113 +18,104 @@ static bool addCrAtEnd = false; uint8_t printBuffer[fsfwconfig::FSFW_PRINT_BUFFER_SIZE]; -void fsfwPrint(sif::PrintLevel printType, const char* fmt, va_list arg) { - +void fsfwPrint(sif::PrintLevel printType, const char *fmt, va_list arg) { #if defined(WIN32) && FSFW_COLORED_OUTPUT == 1 - if(not consoleInitialized) { - HANDLE hOut = GetStdHandle(STD_OUTPUT_HANDLE); - DWORD dwMode = 0; - GetConsoleMode(hOut, &dwMode); - dwMode |= ENABLE_VIRTUAL_TERMINAL_PROCESSING; - SetConsoleMode(hOut, dwMode); - } - consoleInitialized = true; + if (not consoleInitialized) { + HANDLE hOut = GetStdHandle(STD_OUTPUT_HANDLE); + DWORD dwMode = 0; + GetConsoleMode(hOut, &dwMode); + dwMode |= ENABLE_VIRTUAL_TERMINAL_PROCESSING; + SetConsoleMode(hOut, dwMode); + } + consoleInitialized = true; #endif - size_t len = 0; - char* bufferPosition = reinterpret_cast(printBuffer); + size_t len = 0; + char *bufferPosition = reinterpret_cast(printBuffer); - /* Check logger level */ - if(printType == sif::PrintLevel::NONE or printType > printLevel) { - return; - } + /* Check logger level */ + if (printType == sif::PrintLevel::NONE or printType > printLevel) { + return; + } - /* Log message to terminal */ + /* Log message to terminal */ #if FSFW_COLORED_OUTPUT == 1 - if(printType == sif::PrintLevel::INFO_LEVEL) { - len += sprintf(bufferPosition, sif::ANSI_COLOR_GREEN); - } - else if(printType == sif::PrintLevel::DEBUG_LEVEL) { - len += sprintf(bufferPosition, sif::ANSI_COLOR_CYAN); - } - else if(printType == sif::PrintLevel::WARNING_LEVEL) { - len += sprintf(bufferPosition, sif::ANSI_COLOR_YELLOW); - } - else if(printType == sif::PrintLevel::ERROR_LEVEL) { - len += sprintf(bufferPosition, sif::ANSI_COLOR_RED); - } + if (printType == sif::PrintLevel::INFO_LEVEL) { + len += sprintf(bufferPosition, sif::ANSI_COLOR_GREEN); + } else if (printType == sif::PrintLevel::DEBUG_LEVEL) { + len += sprintf(bufferPosition, sif::ANSI_COLOR_CYAN); + } else if (printType == sif::PrintLevel::WARNING_LEVEL) { + len += sprintf(bufferPosition, sif::ANSI_COLOR_YELLOW); + } else if (printType == sif::PrintLevel::ERROR_LEVEL) { + len += sprintf(bufferPosition, sif::ANSI_COLOR_RED); + } #endif - if (printType == sif::PrintLevel::INFO_LEVEL) { - len += sprintf(bufferPosition + len, "INFO"); - } - if(printType == sif::PrintLevel::DEBUG_LEVEL) { - len += sprintf(bufferPosition + len, "DEBUG"); - } - if(printType == sif::PrintLevel::WARNING_LEVEL) { - len += sprintf(bufferPosition + len, "WARNING"); - } + if (printType == sif::PrintLevel::INFO_LEVEL) { + len += sprintf(bufferPosition + len, "INFO"); + } + if (printType == sif::PrintLevel::DEBUG_LEVEL) { + len += sprintf(bufferPosition + len, "DEBUG"); + } + if (printType == sif::PrintLevel::WARNING_LEVEL) { + len += sprintf(bufferPosition + len, "WARNING"); + } - if(printType == sif::PrintLevel::ERROR_LEVEL) { - len += sprintf(bufferPosition + len, "ERROR"); - } + if (printType == sif::PrintLevel::ERROR_LEVEL) { + len += sprintf(bufferPosition + len, "ERROR"); + } #if FSFW_COLORED_OUTPUT == 1 - len += sprintf(bufferPosition + len, sif::ANSI_COLOR_RESET); + len += sprintf(bufferPosition + len, sif::ANSI_COLOR_RESET); #endif - Clock::TimeOfDay_t now; - Clock::getDateAndTime(&now); - /* - * Log current time to terminal if desired. - */ - len += sprintf(bufferPosition + len, " | %lu:%02lu:%02lu.%03lu | ", - (unsigned long) now.hour, - (unsigned long) now.minute, - (unsigned long) now.second, - (unsigned long) now.usecond /1000); + Clock::TimeOfDay_t now; + Clock::getDateAndTime(&now); + /* + * Log current time to terminal if desired. + */ + len += sprintf(bufferPosition + len, " | %lu:%02lu:%02lu.%03lu | ", (unsigned long)now.hour, + (unsigned long)now.minute, (unsigned long)now.second, + (unsigned long)now.usecond / 1000); - len += vsnprintf(bufferPosition + len, sizeof(printBuffer) - len, fmt, arg); + len += vsnprintf(bufferPosition + len, sizeof(printBuffer) - len, fmt, arg); - if(addCrAtEnd) { - len += sprintf(bufferPosition + len, "\r"); - } + if (addCrAtEnd) { + len += sprintf(bufferPosition + len, "\r"); + } - printf("%s", printBuffer); + printf("%s", printBuffer); } - void sif::printInfo(const char *fmt, ...) { - va_list args; - va_start(args, fmt); - fsfwPrint(sif::PrintLevel::INFO_LEVEL, fmt, args); - va_end(args); + va_list args; + va_start(args, fmt); + fsfwPrint(sif::PrintLevel::INFO_LEVEL, fmt, args); + va_end(args); } void sif::printWarning(const char *fmt, ...) { - va_list args; - va_start(args, fmt); - fsfwPrint(sif::PrintLevel::WARNING_LEVEL, fmt, args); - va_end(args); + va_list args; + va_start(args, fmt); + fsfwPrint(sif::PrintLevel::WARNING_LEVEL, fmt, args); + va_end(args); } void sif::printDebug(const char *fmt, ...) { - va_list args; - va_start(args, fmt); - fsfwPrint(sif::PrintLevel::DEBUG_LEVEL, fmt, args); - va_end(args); + va_list args; + va_start(args, fmt); + fsfwPrint(sif::PrintLevel::DEBUG_LEVEL, fmt, args); + va_end(args); } -void sif::setToAddCrAtEnd(bool addCrAtEnd_) { - addCrAtEnd = addCrAtEnd_; -} +void sif::setToAddCrAtEnd(bool addCrAtEnd_) { addCrAtEnd = addCrAtEnd_; } void sif::printError(const char *fmt, ...) { - va_list args; - va_start(args, fmt); - fsfwPrint(sif::PrintLevel::ERROR_LEVEL, fmt, args); - va_end(args); + va_list args; + va_start(args, fmt); + fsfwPrint(sif::PrintLevel::ERROR_LEVEL, fmt, args); + va_end(args); } #else @@ -135,10 +127,6 @@ void sif::printError(const char *fmt, ...) {} #endif /* FSFW_DISABLE_PRINTOUT == 0 */ -void sif::setPrintLevel(PrintLevel printLevel_) { - printLevel = printLevel_; -} +void sif::setPrintLevel(PrintLevel printLevel_) { printLevel = printLevel_; } -sif::PrintLevel sif::getPrintLevel() { - return printLevel; -} +sif::PrintLevel sif::getPrintLevel() { return printLevel; } diff --git a/src/fsfw/serviceinterface/ServiceInterfacePrinter.h b/src/fsfw/serviceinterface/ServiceInterfacePrinter.h index 98421444..89d793c3 100644 --- a/src/fsfw/serviceinterface/ServiceInterfacePrinter.h +++ b/src/fsfw/serviceinterface/ServiceInterfacePrinter.h @@ -10,26 +10,20 @@ //! Example usage: //! sif::printInfo("Status register: " BYTE_TO_BINARY_PATTERN "\n",BYTE_TO_BINARY(0x1f)); #define BYTE_TO_BINARY_PATTERN "%c%c%c%c%c%c%c%c" -#define BYTE_TO_BINARY(byte) \ - (byte & 0x80 ? '1' : '0'), \ - (byte & 0x40 ? '1' : '0'), \ - (byte & 0x20 ? '1' : '0'), \ - (byte & 0x10 ? '1' : '0'), \ - (byte & 0x08 ? '1' : '0'), \ - (byte & 0x04 ? '1' : '0'), \ - (byte & 0x02 ? '1' : '0'), \ - (byte & 0x01 ? '1' : '0') - +#define BYTE_TO_BINARY(byte) \ + (byte & 0x80 ? '1' : '0'), (byte & 0x40 ? '1' : '0'), (byte & 0x20 ? '1' : '0'), \ + (byte & 0x10 ? '1' : '0'), (byte & 0x08 ? '1' : '0'), (byte & 0x04 ? '1' : '0'), \ + (byte & 0x02 ? '1' : '0'), (byte & 0x01 ? '1' : '0') namespace sif { enum PrintLevel { - NONE = 0, - //! Strange error when using just ERROR.. - ERROR_LEVEL = 1, - WARNING_LEVEL = 2, - INFO_LEVEL = 3, - DEBUG_LEVEL = 4 + NONE = 0, + //! Strange error when using just ERROR.. + ERROR_LEVEL = 1, + WARNING_LEVEL = 2, + INFO_LEVEL = 3, + DEBUG_LEVEL = 4 }; /** @@ -50,11 +44,11 @@ void setToAddCrAtEnd(bool addCrAtEnd_); * a timestamp. * @param fmt Formatted string */ -void printInfo(const char *fmt, ...); +void printInfo(const char* fmt, ...); void printWarning(const char* fmt, ...); void printDebug(const char* fmt, ...); void printError(const char* fmt, ...); -} +} // namespace sif #endif /* FSFW_SERVICEINTERFACE_SERVICEINTERFACEPRINTER */ diff --git a/src/fsfw/serviceinterface/ServiceInterfaceStream.cpp b/src/fsfw/serviceinterface/ServiceInterfaceStream.cpp index 6139299b..386fb545 100644 --- a/src/fsfw/serviceinterface/ServiceInterfaceStream.cpp +++ b/src/fsfw/serviceinterface/ServiceInterfaceStream.cpp @@ -2,28 +2,20 @@ #if FSFW_CPP_OSTREAM_ENABLED == 1 -ServiceInterfaceStream::ServiceInterfaceStream(std::string setMessage, - bool addCrToPreamble, bool buffered, bool errStream, uint16_t port) : - std::ostream(&streambuf), - streambuf(setMessage, addCrToPreamble, buffered, errStream, port) {} +ServiceInterfaceStream::ServiceInterfaceStream(std::string setMessage, bool addCrToPreamble, + bool buffered, bool errStream, uint16_t port) + : std::ostream(&streambuf), streambuf(setMessage, addCrToPreamble, buffered, errStream, port) {} -void ServiceInterfaceStream::setActive( bool myActive) { - this->streambuf.isActive = myActive; -} +void ServiceInterfaceStream::setActive(bool myActive) { this->streambuf.isActive = myActive; } -std::string* ServiceInterfaceStream::getPreamble() { - return streambuf.getPreamble(); -} +std::string* ServiceInterfaceStream::getPreamble() { return streambuf.getPreamble(); } -bool ServiceInterfaceStream::crAdditionEnabled() const { - return streambuf.crAdditionEnabled(); -} +bool ServiceInterfaceStream::crAdditionEnabled() const { return streambuf.crAdditionEnabled(); } #if FSFW_COLORED_OUTPUT == 1 void ServiceInterfaceStream::setAsciiColorPrefix(std::string asciiColorCode) { - streambuf.setAsciiColorPrefix(asciiColorCode); + streambuf.setAsciiColorPrefix(asciiColorCode); } #endif #endif - diff --git a/src/fsfw/serviceinterface/ServiceInterfaceStream.h b/src/fsfw/serviceinterface/ServiceInterfaceStream.h index 545ab241..0b3d6745 100644 --- a/src/fsfw/serviceinterface/ServiceInterfaceStream.h +++ b/src/fsfw/serviceinterface/ServiceInterfaceStream.h @@ -1,13 +1,14 @@ #ifndef FRAMEWORK_SERVICEINTERFACE_SERVICEINTERFACESTREAM_H_ #define FRAMEWORK_SERVICEINTERFACE_SERVICEINTERFACESTREAM_H_ -#include "ServiceInterfaceBuffer.h" #include +#include "ServiceInterfaceBuffer.h" + #if FSFW_CPP_OSTREAM_ENABLED == 1 -#include #include +#include /** * Generic service interface stream which can be used like std::cout or @@ -15,43 +16,42 @@ * to output. Can be run in buffered or unbuffered mode. */ class ServiceInterfaceStream : public std::ostream { -public: - /** - * This constructor is used by specifying the preamble message. - * Optionally, the output can be directed to stderr and a CR character - * can be prepended to the preamble. - * @param setMessage message of preamble. - * @param addCrToPreamble Useful for applications like Puttty. - * @param buffered specify whether to use buffered mode. - * @param errStream specify which output stream to use (stderr or stdout). - */ - ServiceInterfaceStream(std::string setMessage, - bool addCrToPreamble = false, bool buffered = true, - bool errStream = false, uint16_t port = 1234); + public: + /** + * This constructor is used by specifying the preamble message. + * Optionally, the output can be directed to stderr and a CR character + * can be prepended to the preamble. + * @param setMessage message of preamble. + * @param addCrToPreamble Useful for applications like Puttty. + * @param buffered specify whether to use buffered mode. + * @param errStream specify which output stream to use (stderr or stdout). + */ + ServiceInterfaceStream(std::string setMessage, bool addCrToPreamble = false, bool buffered = true, + bool errStream = false, uint16_t port = 1234); - //! An inactive stream will not print anything. - void setActive( bool ); + //! An inactive stream will not print anything. + void setActive(bool); - /** - * This can be used to retrieve the preamble in case it should be printed in - * the unbuffered mode. - * @return Preamle consisting of log message and timestamp. - */ - std::string* getPreamble(); + /** + * This can be used to retrieve the preamble in case it should be printed in + * the unbuffered mode. + * @return Preamle consisting of log message and timestamp. + */ + std::string* getPreamble(); - /** - * Can be used to determine if the stream was configured to add CR characters in addition - * to newline characters. - * @return - */ - bool crAdditionEnabled() const; + /** + * Can be used to determine if the stream was configured to add CR characters in addition + * to newline characters. + * @return + */ + bool crAdditionEnabled() const; #if FSFW_COLORED_OUTPUT == 1 - void setAsciiColorPrefix(std::string asciiColorCode); + void setAsciiColorPrefix(std::string asciiColorCode); #endif -protected: - ServiceInterfaceBuffer streambuf; + protected: + ServiceInterfaceBuffer streambuf; }; // Forward declaration of interface streams. These should be instantiated in @@ -61,7 +61,7 @@ extern ServiceInterfaceStream debug; extern ServiceInterfaceStream info; extern ServiceInterfaceStream warning; extern ServiceInterfaceStream error; -} +} // namespace sif #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ diff --git a/src/fsfw/serviceinterface/serviceInterfaceDefintions.h b/src/fsfw/serviceinterface/serviceInterfaceDefintions.h index eb36a84b..85710578 100644 --- a/src/fsfw/serviceinterface/serviceInterfaceDefintions.h +++ b/src/fsfw/serviceinterface/serviceInterfaceDefintions.h @@ -3,12 +3,7 @@ namespace sif { -enum class OutputTypes { - OUT_INFO, - OUT_DEBUG, - OUT_WARNING, - OUT_ERROR -}; +enum class OutputTypes { OUT_INFO, OUT_DEBUG, OUT_WARNING, OUT_ERROR }; static const char* const ANSI_COLOR_RED = "\x1b[31m"; static const char* const ANSI_COLOR_GREEN = "\x1b[32m"; @@ -18,6 +13,6 @@ static const char* const ANSI_COLOR_MAGENTA = "\x1b[35m"; static const char* const ANSI_COLOR_CYAN = "\x1b[36m"; static const char* const ANSI_COLOR_RESET = "\x1b[0m"; -} +} // namespace sif #endif /* FSFW_SERVICEINTERFACE_SERVICEINTERFACEDEFINTIONS_H_ */ diff --git a/src/fsfw/storagemanager/ConstStorageAccessor.cpp b/src/fsfw/storagemanager/ConstStorageAccessor.cpp index 67736d51..df2fc750 100644 --- a/src/fsfw/storagemanager/ConstStorageAccessor.cpp +++ b/src/fsfw/storagemanager/ConstStorageAccessor.cpp @@ -1,98 +1,90 @@ #include "fsfw/storagemanager/ConstStorageAccessor.h" -#include "fsfw/storagemanager/StorageManagerIF.h" - -#include "fsfw/serviceinterface/ServiceInterfaceStream.h" -#include "fsfw/globalfunctions/arrayprinter.h" #include -ConstStorageAccessor::ConstStorageAccessor(store_address_t storeId): - storeId(storeId) {} +#include "fsfw/globalfunctions/arrayprinter.h" +#include "fsfw/serviceinterface/ServiceInterfaceStream.h" +#include "fsfw/storagemanager/StorageManagerIF.h" -ConstStorageAccessor::ConstStorageAccessor(store_address_t storeId, - StorageManagerIF* store): - storeId(storeId), store(store) { - internalState = AccessState::ASSIGNED; +ConstStorageAccessor::ConstStorageAccessor(store_address_t storeId) : storeId(storeId) {} + +ConstStorageAccessor::ConstStorageAccessor(store_address_t storeId, StorageManagerIF* store) + : storeId(storeId), store(store) { + internalState = AccessState::ASSIGNED; } ConstStorageAccessor::~ConstStorageAccessor() { - if(deleteData and store != nullptr) { - store->deleteData(storeId); - } + if (deleteData and store != nullptr) { + store->deleteData(storeId); + } } -ConstStorageAccessor::ConstStorageAccessor(ConstStorageAccessor&& other): - constDataPointer(other.constDataPointer), storeId(other.storeId), - size_(other.size_), store(other.store), deleteData(other.deleteData), - internalState(other.internalState) { - // This prevent premature deletion - other.store = nullptr; +ConstStorageAccessor::ConstStorageAccessor(ConstStorageAccessor&& other) + : constDataPointer(other.constDataPointer), + storeId(other.storeId), + size_(other.size_), + store(other.store), + deleteData(other.deleteData), + internalState(other.internalState) { + // This prevent premature deletion + other.store = nullptr; } -ConstStorageAccessor& ConstStorageAccessor::operator=( - ConstStorageAccessor&& other) { - constDataPointer = other.constDataPointer; - storeId = other.storeId; - store = other.store; - size_ = other.size_; - deleteData = other.deleteData; - this->store = other.store; - // This prevents premature deletion - other.store = nullptr; - return *this; +ConstStorageAccessor& ConstStorageAccessor::operator=(ConstStorageAccessor&& other) { + constDataPointer = other.constDataPointer; + storeId = other.storeId; + store = other.store; + size_ = other.size_; + deleteData = other.deleteData; + this->store = other.store; + // This prevents premature deletion + other.store = nullptr; + return *this; } -const uint8_t* ConstStorageAccessor::data() const { - return constDataPointer; -} +const uint8_t* ConstStorageAccessor::data() const { return constDataPointer; } size_t ConstStorageAccessor::size() const { - if(internalState == AccessState::UNINIT) { + if (internalState == AccessState::UNINIT) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "StorageAccessor: Not initialized!" << std::endl; + sif::warning << "StorageAccessor: Not initialized!" << std::endl; #endif - } - return size_; + } + return size_; } -ReturnValue_t ConstStorageAccessor::getDataCopy(uint8_t *pointer, - size_t maxSize) { - if(internalState == AccessState::UNINIT) { +ReturnValue_t ConstStorageAccessor::getDataCopy(uint8_t* pointer, size_t maxSize) { + if (internalState == AccessState::UNINIT) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "StorageAccessor: Not initialized!" << std::endl; + sif::warning << "StorageAccessor: Not initialized!" << std::endl; #endif - return HasReturnvaluesIF::RETURN_FAILED; - } - if(size_ > maxSize) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if (size_ > maxSize) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "StorageAccessor: Supplied buffer not large enough" - << std::endl; + sif::error << "StorageAccessor: Supplied buffer not large enough" << std::endl; #endif - return HasReturnvaluesIF::RETURN_FAILED; - } - std::copy(constDataPointer, constDataPointer + size_, pointer); - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_FAILED; + } + std::copy(constDataPointer, constDataPointer + size_, pointer); + return HasReturnvaluesIF::RETURN_OK; } -void ConstStorageAccessor::release() { - deleteData = false; -} +void ConstStorageAccessor::release() { deleteData = false; } -store_address_t ConstStorageAccessor::getId() const { - return storeId; -} +store_address_t ConstStorageAccessor::getId() const { return storeId; } void ConstStorageAccessor::print() const { - if(internalState == AccessState::UNINIT or constDataPointer == nullptr) { + if (internalState == AccessState::UNINIT or constDataPointer == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "StorageAccessor: Not initialized!" << std::endl; + sif::warning << "StorageAccessor: Not initialized!" << std::endl; #endif - return; - } - arrayprinter::print(constDataPointer, size_); + return; + } + arrayprinter::print(constDataPointer, size_); } void ConstStorageAccessor::assignStore(StorageManagerIF* store) { - internalState = AccessState::ASSIGNED; - this->store = store; + internalState = AccessState::ASSIGNED; + this->store = store; } diff --git a/src/fsfw/storagemanager/ConstStorageAccessor.h b/src/fsfw/storagemanager/ConstStorageAccessor.h index 570c20ce..a2ddad6c 100644 --- a/src/fsfw/storagemanager/ConstStorageAccessor.h +++ b/src/fsfw/storagemanager/ConstStorageAccessor.h @@ -1,10 +1,11 @@ #ifndef FSFW_STORAGEMANAGER_CONSTSTORAGEACCESSOR_H_ #define FSFW_STORAGEMANAGER_CONSTSTORAGEACCESSOR_H_ -#include "storeAddress.h" -#include "../returnvalues/HasReturnvaluesIF.h" #include +#include "../returnvalues/HasReturnvaluesIF.h" +#include "storeAddress.h" + class StorageManagerIF; /** @@ -19,96 +20,94 @@ class StorageManagerIF; * mechanisms to automatically clear storage data. */ class ConstStorageAccessor { - //! StorageManager classes have exclusive access to private variables. - friend class PoolManager; - friend class LocalPool; -public: - /** - * @brief Simple constructor which takes the store ID of the storage - * entry to access. - * @param storeId - */ - ConstStorageAccessor(store_address_t storeId); - ConstStorageAccessor(store_address_t storeId, StorageManagerIF* store); + //! StorageManager classes have exclusive access to private variables. + friend class PoolManager; + friend class LocalPool; - /** - * @brief The destructor in default configuration takes care of - * deleting the accessed pool entry and unlocking the mutex - */ - virtual ~ConstStorageAccessor(); + public: + /** + * @brief Simple constructor which takes the store ID of the storage + * entry to access. + * @param storeId + */ + ConstStorageAccessor(store_address_t storeId); + ConstStorageAccessor(store_address_t storeId, StorageManagerIF* store); - /** - * @brief Returns a pointer to the read-only data - * @return - */ - const uint8_t* data() const; + /** + * @brief The destructor in default configuration takes care of + * deleting the accessed pool entry and unlocking the mutex + */ + virtual ~ConstStorageAccessor(); - /** - * @brief Copies the read-only data to the supplied pointer - * @param pointer - */ - virtual ReturnValue_t getDataCopy(uint8_t *pointer, size_t maxSize); + /** + * @brief Returns a pointer to the read-only data + * @return + */ + const uint8_t* data() const; - /** - * @brief Calling this will prevent the Accessor from deleting the data - * when the destructor is called. - */ - void release(); + /** + * @brief Copies the read-only data to the supplied pointer + * @param pointer + */ + virtual ReturnValue_t getDataCopy(uint8_t* pointer, size_t maxSize); - /** - * Get the size of the data - * @return - */ - size_t size() const; + /** + * @brief Calling this will prevent the Accessor from deleting the data + * when the destructor is called. + */ + void release(); - /** - * Get the storage ID. - * @return - */ - store_address_t getId() const; + /** + * Get the size of the data + * @return + */ + size_t size() const; - void print() const; + /** + * Get the storage ID. + * @return + */ + store_address_t getId() const; - /** - * @brief Move ctor and move assignment allow returning accessors as - * a returnvalue. They prevent resource being free prematurely. - * Refer to: https://github.com/MicrosoftDocs/cpp-docs/blob/master/docs/cpp/ - * move-constructors-and-move-assignment-operators-cpp.md - * @param - * @return - */ - ConstStorageAccessor& operator= (ConstStorageAccessor&&); - ConstStorageAccessor(ConstStorageAccessor&&); + void print() const; - //! The copy ctor and copy assignemnt should be deleted implicitely - //! according to https://foonathan.net/2019/02/special-member-functions/ - //! but I still deleted them to make it more explicit. (remember rule of 5). - ConstStorageAccessor& operator=(const ConstStorageAccessor&) = delete; - ConstStorageAccessor(const ConstStorageAccessor&) = delete; -protected: - const uint8_t* constDataPointer = nullptr; - store_address_t storeId; - size_t size_ = 0; - //! Managing pool, has to assign itself. - StorageManagerIF* store = nullptr; - bool deleteData = true; + /** + * @brief Move ctor and move assignment allow returning accessors as + * a returnvalue. They prevent resource being free prematurely. + * Refer to: https://github.com/MicrosoftDocs/cpp-docs/blob/master/docs/cpp/ + * move-constructors-and-move-assignment-operators-cpp.md + * @param + * @return + */ + ConstStorageAccessor& operator=(ConstStorageAccessor&&); + ConstStorageAccessor(ConstStorageAccessor&&); - enum class AccessState { - UNINIT, - ASSIGNED - }; - //! Internal state for safety reasons. - AccessState internalState = AccessState::UNINIT; - /** - * Used by the pool manager instances to assign themselves to the - * accessor. This is necessary to delete the data when the acessor - * exits the scope ! The internal state will be considered read - * when this function is called, so take care all data is set properly as - * well. - * @param - */ - void assignStore(StorageManagerIF*); + //! The copy ctor and copy assignemnt should be deleted implicitely + //! according to https://foonathan.net/2019/02/special-member-functions/ + //! but I still deleted them to make it more explicit. (remember rule of 5). + ConstStorageAccessor& operator=(const ConstStorageAccessor&) = delete; + ConstStorageAccessor(const ConstStorageAccessor&) = delete; + + protected: + const uint8_t* constDataPointer = nullptr; + store_address_t storeId; + size_t size_ = 0; + //! Managing pool, has to assign itself. + StorageManagerIF* store = nullptr; + bool deleteData = true; + + enum class AccessState { UNINIT, ASSIGNED }; + //! Internal state for safety reasons. + AccessState internalState = AccessState::UNINIT; + /** + * Used by the pool manager instances to assign themselves to the + * accessor. This is necessary to delete the data when the acessor + * exits the scope ! The internal state will be considered read + * when this function is called, so take care all data is set properly as + * well. + * @param + */ + void assignStore(StorageManagerIF*); }; - #endif /* FSFW_STORAGEMANAGER_CONSTSTORAGEACCESSOR_H_ */ diff --git a/src/fsfw/storagemanager/LocalPool.cpp b/src/fsfw/storagemanager/LocalPool.cpp index c5e74e08..075de4b8 100644 --- a/src/fsfw/storagemanager/LocalPool.cpp +++ b/src/fsfw/storagemanager/LocalPool.cpp @@ -1,370 +1,340 @@ -#include "fsfw/FSFW.h" #include "fsfw/storagemanager/LocalPool.h" -#include "fsfw/objectmanager/ObjectManager.h" - #include -LocalPool::LocalPool(object_id_t setObjectId, const LocalPoolConfig& poolConfig, - bool registered, bool spillsToHigherPools): - SystemObject(setObjectId, registered), - NUMBER_OF_SUBPOOLS(poolConfig.size()), - spillsToHigherPools(spillsToHigherPools) { - if(NUMBER_OF_SUBPOOLS == 0) { +#include "fsfw/FSFW.h" +#include "fsfw/objectmanager/ObjectManager.h" + +LocalPool::LocalPool(object_id_t setObjectId, const LocalPoolConfig& poolConfig, bool registered, + bool spillsToHigherPools) + : SystemObject(setObjectId, registered), + NUMBER_OF_SUBPOOLS(poolConfig.size()), + spillsToHigherPools(spillsToHigherPools) { + if (NUMBER_OF_SUBPOOLS == 0) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "LocalPool::LocalPool: Passed pool configuration is " - << " invalid!" << std::endl; + sif::error << "LocalPool::LocalPool: Passed pool configuration is " + << " invalid!" << std::endl; #endif - } - max_subpools_t index = 0; - for (const auto& currentPoolConfig: poolConfig) { - this->numberOfElements[index] = currentPoolConfig.first; - this->elementSizes[index] = currentPoolConfig.second; - store[index] = std::vector( - numberOfElements[index] * elementSizes[index]); - sizeLists[index] = std::vector(numberOfElements[index]); - for(auto& size: sizeLists[index]) { - size = STORAGE_FREE; - } - index++; - } + } + max_subpools_t index = 0; + for (const auto& currentPoolConfig : poolConfig) { + this->numberOfElements[index] = currentPoolConfig.first; + this->elementSizes[index] = currentPoolConfig.second; + store[index] = std::vector(numberOfElements[index] * elementSizes[index]); + sizeLists[index] = std::vector(numberOfElements[index]); + for (auto& size : sizeLists[index]) { + size = STORAGE_FREE; + } + index++; + } } LocalPool::~LocalPool(void) {} - -ReturnValue_t LocalPool::addData(store_address_t* storageId, - const uint8_t* data, size_t size, bool ignoreFault) { - ReturnValue_t status = reserveSpace(size, storageId, ignoreFault); - if (status == RETURN_OK) { - write(*storageId, data, size); - } - return status; +ReturnValue_t LocalPool::addData(store_address_t* storageId, const uint8_t* data, size_t size, + bool ignoreFault) { + ReturnValue_t status = reserveSpace(size, storageId, ignoreFault); + if (status == RETURN_OK) { + write(*storageId, data, size); + } + return status; } -ReturnValue_t LocalPool::getData(store_address_t packetId, - const uint8_t **packetPtr, size_t *size) { - uint8_t* tempData = nullptr; - ReturnValue_t status = modifyData(packetId, &tempData, size); - *packetPtr = tempData; - return status; +ReturnValue_t LocalPool::getData(store_address_t packetId, const uint8_t** packetPtr, + size_t* size) { + uint8_t* tempData = nullptr; + ReturnValue_t status = modifyData(packetId, &tempData, size); + *packetPtr = tempData; + return status; } -ReturnValue_t LocalPool::getData(store_address_t storeId, - ConstStorageAccessor& storeAccessor) { - uint8_t* tempData = nullptr; - ReturnValue_t status = modifyData(storeId, &tempData, - &storeAccessor.size_); - storeAccessor.assignStore(this); - storeAccessor.constDataPointer = tempData; - return status; +ReturnValue_t LocalPool::getData(store_address_t storeId, ConstStorageAccessor& storeAccessor) { + uint8_t* tempData = nullptr; + ReturnValue_t status = modifyData(storeId, &tempData, &storeAccessor.size_); + storeAccessor.assignStore(this); + storeAccessor.constDataPointer = tempData; + return status; } ConstAccessorPair LocalPool::getData(store_address_t storeId) { - uint8_t* tempData = nullptr; - ConstStorageAccessor constAccessor(storeId, this); - ReturnValue_t status = modifyData(storeId, &tempData, &constAccessor.size_); - constAccessor.constDataPointer = tempData; - return ConstAccessorPair(status, std::move(constAccessor)); + uint8_t* tempData = nullptr; + ConstStorageAccessor constAccessor(storeId, this); + ReturnValue_t status = modifyData(storeId, &tempData, &constAccessor.size_); + constAccessor.constDataPointer = tempData; + return ConstAccessorPair(status, std::move(constAccessor)); } -ReturnValue_t LocalPool::getFreeElement(store_address_t *storageId, - const size_t size, uint8_t **pData, bool ignoreFault) { - ReturnValue_t status = reserveSpace(size, storageId, ignoreFault); - if (status == RETURN_OK) { - *pData = &store[storageId->poolIndex][getRawPosition(*storageId)]; - } - else { - *pData = nullptr; - } - return status; +ReturnValue_t LocalPool::getFreeElement(store_address_t* storageId, const size_t size, + uint8_t** pData, bool ignoreFault) { + ReturnValue_t status = reserveSpace(size, storageId, ignoreFault); + if (status == RETURN_OK) { + *pData = &store[storageId->poolIndex][getRawPosition(*storageId)]; + } else { + *pData = nullptr; + } + return status; } - AccessorPair LocalPool::modifyData(store_address_t storeId) { - StorageAccessor accessor(storeId, this); - ReturnValue_t status = modifyData(storeId, &accessor.dataPointer, - &accessor.size_); - accessor.assignConstPointer(); - return AccessorPair(status, std::move(accessor)); + StorageAccessor accessor(storeId, this); + ReturnValue_t status = modifyData(storeId, &accessor.dataPointer, &accessor.size_); + accessor.assignConstPointer(); + return AccessorPair(status, std::move(accessor)); } -ReturnValue_t LocalPool::modifyData(store_address_t storeId, - StorageAccessor& storeAccessor) { - storeAccessor.assignStore(this); - ReturnValue_t status = modifyData(storeId, &storeAccessor.dataPointer, - &storeAccessor.size_); - storeAccessor.assignConstPointer(); - return status; +ReturnValue_t LocalPool::modifyData(store_address_t storeId, StorageAccessor& storeAccessor) { + storeAccessor.assignStore(this); + ReturnValue_t status = modifyData(storeId, &storeAccessor.dataPointer, &storeAccessor.size_); + storeAccessor.assignConstPointer(); + return status; } -ReturnValue_t LocalPool::modifyData(store_address_t storeId, - uint8_t **packetPtr, size_t *size) { - ReturnValue_t status = RETURN_FAILED; - if (storeId.poolIndex >= NUMBER_OF_SUBPOOLS) { - return ILLEGAL_STORAGE_ID; - } - if ((storeId.packetIndex >= numberOfElements[storeId.poolIndex])) { - return ILLEGAL_STORAGE_ID; - } +ReturnValue_t LocalPool::modifyData(store_address_t storeId, uint8_t** packetPtr, size_t* size) { + ReturnValue_t status = RETURN_FAILED; + if (storeId.poolIndex >= NUMBER_OF_SUBPOOLS) { + return ILLEGAL_STORAGE_ID; + } + if ((storeId.packetIndex >= numberOfElements[storeId.poolIndex])) { + return ILLEGAL_STORAGE_ID; + } - if (sizeLists[storeId.poolIndex][storeId.packetIndex] - != STORAGE_FREE) { - size_type packetPosition = getRawPosition(storeId); - *packetPtr = &store[storeId.poolIndex][packetPosition]; - *size = sizeLists[storeId.poolIndex][storeId.packetIndex]; - status = RETURN_OK; - } - else { - status = DATA_DOES_NOT_EXIST; - } - return status; + if (sizeLists[storeId.poolIndex][storeId.packetIndex] != STORAGE_FREE) { + size_type packetPosition = getRawPosition(storeId); + *packetPtr = &store[storeId.poolIndex][packetPosition]; + *size = sizeLists[storeId.poolIndex][storeId.packetIndex]; + status = RETURN_OK; + } else { + status = DATA_DOES_NOT_EXIST; + } + return status; } ReturnValue_t LocalPool::deleteData(store_address_t storeId) { #if FSFW_VERBOSE_PRINTOUT == 2 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "Delete: Pool: " << std::dec << storeId.poolIndex - << " Index: " << storeId.packetIndex << std::endl; + sif::debug << "Delete: Pool: " << std::dec << storeId.poolIndex + << " Index: " << storeId.packetIndex << std::endl; #endif #endif - ReturnValue_t status = RETURN_OK; - size_type pageSize = getSubpoolElementSize(storeId.poolIndex); - if ((pageSize != 0) and - (storeId.packetIndex < numberOfElements[storeId.poolIndex])) { - uint16_t packetPosition = getRawPosition(storeId); - uint8_t* ptr = &store[storeId.poolIndex][packetPosition]; - std::memset(ptr, 0, pageSize); - //Set free list - sizeLists[storeId.poolIndex][storeId.packetIndex] = STORAGE_FREE; - } - else { - //pool_index or packet_index is too large + ReturnValue_t status = RETURN_OK; + size_type pageSize = getSubpoolElementSize(storeId.poolIndex); + if ((pageSize != 0) and (storeId.packetIndex < numberOfElements[storeId.poolIndex])) { + uint16_t packetPosition = getRawPosition(storeId); + uint8_t* ptr = &store[storeId.poolIndex][packetPosition]; + std::memset(ptr, 0, pageSize); + // Set free list + sizeLists[storeId.poolIndex][storeId.packetIndex] = STORAGE_FREE; + } else { + // pool_index or packet_index is too large #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "LocalPool::deleteData: Illegal store ID, no deletion!" - << std::endl; + sif::error << "LocalPool::deleteData: Illegal store ID, no deletion!" << std::endl; #endif - status = ILLEGAL_STORAGE_ID; - } - return status; + status = ILLEGAL_STORAGE_ID; + } + return status; } -ReturnValue_t LocalPool::deleteData(uint8_t *ptr, size_t size, - store_address_t *storeId) { - store_address_t localId; - ReturnValue_t result = ILLEGAL_ADDRESS; - for (uint16_t n = 0; n < NUMBER_OF_SUBPOOLS; n++) { - //Not sure if new allocates all stores in order. so better be careful. - if ((store[n].data() <= ptr) and - (&store[n][numberOfElements[n]*elementSizes[n]] > ptr)) { - localId.poolIndex = n; - uint32_t deltaAddress = ptr - store[n].data(); - // Getting any data from the right "block" is ok. - // This is necessary, as IF's sometimes don't point to the first - // element of an object. - localId.packetIndex = deltaAddress / elementSizes[n]; - result = deleteData(localId); +ReturnValue_t LocalPool::deleteData(uint8_t* ptr, size_t size, store_address_t* storeId) { + store_address_t localId; + ReturnValue_t result = ILLEGAL_ADDRESS; + for (uint16_t n = 0; n < NUMBER_OF_SUBPOOLS; n++) { + // Not sure if new allocates all stores in order. so better be careful. + if ((store[n].data() <= ptr) and (&store[n][numberOfElements[n] * elementSizes[n]] > ptr)) { + localId.poolIndex = n; + uint32_t deltaAddress = ptr - store[n].data(); + // Getting any data from the right "block" is ok. + // This is necessary, as IF's sometimes don't point to the first + // element of an object. + localId.packetIndex = deltaAddress / elementSizes[n]; + result = deleteData(localId); #if FSFW_VERBOSE_PRINTOUT == 2 - if (deltaAddress % elementSizes[n] != 0) { + if (deltaAddress % elementSizes[n] != 0) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "LocalPool::deleteData: Address not aligned!" - << std::endl; + sif::error << "LocalPool::deleteData: Address not aligned!" << std::endl; #endif - } + } #endif - break; - } + break; } - if (storeId != nullptr) { - *storeId = localId; - } - return result; + } + if (storeId != nullptr) { + *storeId = localId; + } + return result; } - ReturnValue_t LocalPool::initialize() { - ReturnValue_t result = SystemObject::initialize(); - if (result != RETURN_OK) { - return result; - } - internalErrorReporter = ObjectManager::instance()->get( - objects::INTERNAL_ERROR_REPORTER); - if (internalErrorReporter == nullptr){ - return ObjectManagerIF::INTERNAL_ERR_REPORTER_UNINIT; - } + ReturnValue_t result = SystemObject::initialize(); + if (result != RETURN_OK) { + return result; + } + internalErrorReporter = + ObjectManager::instance()->get(objects::INTERNAL_ERROR_REPORTER); + if (internalErrorReporter == nullptr) { + return ObjectManagerIF::INTERNAL_ERR_REPORTER_UNINIT; + } - //Check if any pool size is large than the maximum allowed. - for (uint8_t count = 0; count < NUMBER_OF_SUBPOOLS; count++) { - if (elementSizes[count] >= STORAGE_FREE) { + // Check if any pool size is large than the maximum allowed. + for (uint8_t count = 0; count < NUMBER_OF_SUBPOOLS; count++) { + if (elementSizes[count] >= STORAGE_FREE) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "LocalPool::initialize: Pool is too large! " - "Max. allowed size is: " << (STORAGE_FREE - 1) << std::endl; + sif::error << "LocalPool::initialize: Pool is too large! " + "Max. allowed size is: " + << (STORAGE_FREE - 1) << std::endl; #endif - return StorageManagerIF::POOL_TOO_LARGE; - } + return StorageManagerIF::POOL_TOO_LARGE; } - return HasReturnvaluesIF::RETURN_OK; + } + return HasReturnvaluesIF::RETURN_OK; } void LocalPool::clearStore() { - for(auto& sizeList: sizeLists) { - for(auto& size: sizeList) { - size = STORAGE_FREE; - } -// std::memset(sizeList[index], 0xff, -// numberOfElements[index] * sizeof(size_type)); + for (auto& sizeList : sizeLists) { + for (auto& size : sizeList) { + size = STORAGE_FREE; } - + // std::memset(sizeList[index], 0xff, + // numberOfElements[index] * sizeof(size_type)); + } } -ReturnValue_t LocalPool::reserveSpace(const size_t size, - store_address_t *storeId, bool ignoreFault) { - ReturnValue_t status = getSubPoolIndex(size, &storeId->poolIndex); - if (status != RETURN_OK) { +ReturnValue_t LocalPool::reserveSpace(const size_t size, store_address_t* storeId, + bool ignoreFault) { + ReturnValue_t status = getSubPoolIndex(size, &storeId->poolIndex); + if (status != RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "LocalPool( " << std::hex << getObjectId() << std::dec - << " )::reserveSpace: Packet too large." << std::endl; + sif::error << "LocalPool( " << std::hex << getObjectId() << std::dec + << " )::reserveSpace: Packet too large." << std::endl; #endif - return status; + return status; + } + status = findEmpty(storeId->poolIndex, &storeId->packetIndex); + while (status != RETURN_OK && spillsToHigherPools) { + status = getSubPoolIndex(size, &storeId->poolIndex, storeId->poolIndex + 1); + if (status != RETURN_OK) { + // We don't find any fitting pool anymore. + break; } status = findEmpty(storeId->poolIndex, &storeId->packetIndex); - while (status != RETURN_OK && spillsToHigherPools) { - status = getSubPoolIndex(size, &storeId->poolIndex, storeId->poolIndex + 1); - if (status != RETURN_OK) { - //We don't find any fitting pool anymore. - break; - } - status = findEmpty(storeId->poolIndex, &storeId->packetIndex); - } - if (status == RETURN_OK) { + } + if (status == RETURN_OK) { #if FSFW_VERBOSE_PRINTOUT == 2 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "Reserve: Pool: " << std::dec - << storeId->poolIndex << " Index: " << storeId->packetIndex - << std::endl; + sif::debug << "Reserve: Pool: " << std::dec << storeId->poolIndex + << " Index: " << storeId->packetIndex << std::endl; #endif #endif - sizeLists[storeId->poolIndex][storeId->packetIndex] = size; + sizeLists[storeId->poolIndex][storeId->packetIndex] = size; + } else { + if ((not ignoreFault) and (internalErrorReporter != nullptr)) { + internalErrorReporter->storeFull(); } - else { - if ((not ignoreFault) and (internalErrorReporter != nullptr)) { - internalErrorReporter->storeFull(); - } - } - return status; + } + return status; } -void LocalPool::write(store_address_t storeId, const uint8_t *data, - size_t size) { - uint8_t* ptr = nullptr; - size_type packetPosition = getRawPosition(storeId); +void LocalPool::write(store_address_t storeId, const uint8_t* data, size_t size) { + uint8_t* ptr = nullptr; + size_type packetPosition = getRawPosition(storeId); - // Size was checked before calling this function. - ptr = &store[storeId.poolIndex][packetPosition]; - std::memcpy(ptr, data, size); - sizeLists[storeId.poolIndex][storeId.packetIndex] = size; + // Size was checked before calling this function. + ptr = &store[storeId.poolIndex][packetPosition]; + std::memcpy(ptr, data, size); + sizeLists[storeId.poolIndex][storeId.packetIndex] = size; } LocalPool::size_type LocalPool::getSubpoolElementSize(max_subpools_t subpoolIndex) { - if (subpoolIndex < NUMBER_OF_SUBPOOLS) { - return elementSizes[subpoolIndex]; - } - else { - return 0; - } + if (subpoolIndex < NUMBER_OF_SUBPOOLS) { + return elementSizes[subpoolIndex]; + } else { + return 0; + } } -void LocalPool::setToSpillToHigherPools(bool enable) { - this->spillsToHigherPools = enable; -} +void LocalPool::setToSpillToHigherPools(bool enable) { this->spillsToHigherPools = enable; } -ReturnValue_t LocalPool::getSubPoolIndex(size_t packetSize, uint16_t *subpoolIndex, - uint16_t startAtIndex) { - for (uint16_t n = startAtIndex; n < NUMBER_OF_SUBPOOLS; n++) { +ReturnValue_t LocalPool::getSubPoolIndex(size_t packetSize, uint16_t* subpoolIndex, + uint16_t startAtIndex) { + for (uint16_t n = startAtIndex; n < NUMBER_OF_SUBPOOLS; n++) { #if FSFW_VERBOSE_PRINTOUT == 2 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "LocalPool " << getObjectId() << "::getPoolIndex: Pool: " - << n << ", Element Size: " << elementSizes[n] << std::endl; + sif::debug << "LocalPool " << getObjectId() << "::getPoolIndex: Pool: " << n + << ", Element Size: " << elementSizes[n] << std::endl; #endif #endif - if (elementSizes[n] >= packetSize) { - *subpoolIndex = n; - return RETURN_OK; - } + if (elementSizes[n] >= packetSize) { + *subpoolIndex = n; + return RETURN_OK; } - return DATA_TOO_LARGE; + } + return DATA_TOO_LARGE; } LocalPool::size_type LocalPool::getRawPosition(store_address_t storeId) { - return storeId.packetIndex * elementSizes[storeId.poolIndex]; + return storeId.packetIndex * elementSizes[storeId.poolIndex]; } -ReturnValue_t LocalPool::findEmpty(n_pool_elem_t poolIndex, uint16_t *element) { - ReturnValue_t status = DATA_STORAGE_FULL; - for (uint16_t foundElement = 0; foundElement < numberOfElements[poolIndex]; - foundElement++) { - if (sizeLists[poolIndex][foundElement] == STORAGE_FREE) { - *element = foundElement; - status = RETURN_OK; - break; - } +ReturnValue_t LocalPool::findEmpty(n_pool_elem_t poolIndex, uint16_t* element) { + ReturnValue_t status = DATA_STORAGE_FULL; + for (uint16_t foundElement = 0; foundElement < numberOfElements[poolIndex]; foundElement++) { + if (sizeLists[poolIndex][foundElement] == STORAGE_FREE) { + *element = foundElement; + status = RETURN_OK; + break; } - return status; + } + return status; } size_t LocalPool::getTotalSize(size_t* additionalSize) { - size_t totalSize = 0; - size_t sizesSize = 0; - for(uint8_t idx = 0; idx < NUMBER_OF_SUBPOOLS; idx ++) { - totalSize += elementSizes[idx] * numberOfElements[idx]; - sizesSize += numberOfElements[idx] * sizeof(size_type); + size_t totalSize = 0; + size_t sizesSize = 0; + for (uint8_t idx = 0; idx < NUMBER_OF_SUBPOOLS; idx++) { + totalSize += elementSizes[idx] * numberOfElements[idx]; + sizesSize += numberOfElements[idx] * sizeof(size_type); + } + if (additionalSize != nullptr) { + *additionalSize = sizesSize; + } + return totalSize; +} + +void LocalPool::getFillCount(uint8_t* buffer, uint8_t* bytesWritten) { + if (bytesWritten == nullptr or buffer == nullptr) { + return; + } + + uint16_t reservedHits = 0; + uint8_t idx = 0; + uint16_t sum = 0; + for (; idx < NUMBER_OF_SUBPOOLS; idx++) { + for (const auto& size : sizeLists[idx]) { + if (size != STORAGE_FREE) { + reservedHits++; + } } - if(additionalSize != nullptr) { - *additionalSize = sizesSize; - } - return totalSize; + buffer[idx] = static_cast(reservedHits) / numberOfElements[idx] * 100; + *bytesWritten += 1; + sum += buffer[idx]; + reservedHits = 0; + } + buffer[idx] = sum / NUMBER_OF_SUBPOOLS; + *bytesWritten += 1; } -void LocalPool::getFillCount(uint8_t *buffer, uint8_t *bytesWritten) { - if(bytesWritten == nullptr or buffer == nullptr) { - return; - } +void LocalPool::clearSubPool(max_subpools_t subpoolIndex) { + if (subpoolIndex >= NUMBER_OF_SUBPOOLS) { + return; + } - uint16_t reservedHits = 0; - uint8_t idx = 0; - uint16_t sum = 0; - for(; idx < NUMBER_OF_SUBPOOLS; idx ++) { - for(const auto& size: sizeLists[idx]) { - if(size != STORAGE_FREE) { - reservedHits++; - } - } - buffer[idx] = static_cast(reservedHits) / - numberOfElements[idx] * 100; - *bytesWritten += 1; - sum += buffer[idx]; - reservedHits = 0; - } - buffer[idx] = sum / NUMBER_OF_SUBPOOLS; - *bytesWritten += 1; + // Mark the storage as free + for (auto& size : sizeLists[subpoolIndex]) { + size = STORAGE_FREE; + } + + // Set all the page content to 0. + std::memset(store[subpoolIndex].data(), 0, elementSizes[subpoolIndex]); } - -void LocalPool::clearSubPool(max_subpools_t subpoolIndex) { - if(subpoolIndex >= NUMBER_OF_SUBPOOLS) { - return; - } - - // Mark the storage as free - for(auto& size: sizeLists[subpoolIndex]) { - size = STORAGE_FREE; - } - - // Set all the page content to 0. - std::memset(store[subpoolIndex].data(), 0, elementSizes[subpoolIndex]); -} - -LocalPool::max_subpools_t LocalPool::getNumberOfSubPools() const { - return NUMBER_OF_SUBPOOLS; -} +LocalPool::max_subpools_t LocalPool::getNumberOfSubPools() const { return NUMBER_OF_SUBPOOLS; } diff --git a/src/fsfw/storagemanager/LocalPool.h b/src/fsfw/storagemanager/LocalPool.h index 383d8a94..01706e9c 100644 --- a/src/fsfw/storagemanager/LocalPool.h +++ b/src/fsfw/storagemanager/LocalPool.h @@ -1,19 +1,17 @@ #ifndef FSFW_STORAGEMANAGER_LOCALPOOL_H_ #define FSFW_STORAGEMANAGER_LOCALPOOL_H_ -#include "fsfw/storagemanager/StorageManagerIF.h" - -#include "fsfw/objectmanager/SystemObject.h" -#include "fsfw/objectmanager/ObjectManagerIF.h" -#include "fsfw/serviceinterface/ServiceInterfaceStream.h" -#include "fsfw/internalerror/InternalErrorReporterIF.h" -#include "fsfw/storagemanager/StorageAccessor.h" - -#include +#include #include #include -#include +#include +#include "fsfw/internalerror/InternalErrorReporterIF.h" +#include "fsfw/objectmanager/ObjectManagerIF.h" +#include "fsfw/objectmanager/SystemObject.h" +#include "fsfw/serviceinterface/ServiceInterfaceStream.h" +#include "fsfw/storagemanager/StorageAccessor.h" +#include "fsfw/storagemanager/StorageManagerIF.h" /** * @brief The LocalPool class provides an intermediate data storage with @@ -29,229 +27,215 @@ * It is possible to store empty packets in the pool. * The local pool is NOT thread-safe. */ -class LocalPool: public SystemObject, public StorageManagerIF { -public: - using pool_elem_size_t = size_type; - using n_pool_elem_t = uint16_t; - using LocalPoolCfgPair = std::pair; +class LocalPool : public SystemObject, public StorageManagerIF { + public: + using pool_elem_size_t = size_type; + using n_pool_elem_t = uint16_t; + using LocalPoolCfgPair = std::pair; - // The configuration needs to be provided with the pool sizes ascending - // but the number of pool elements as the first value is more intuitive. - // Therefore, a custom comparator was provided. - struct LocalPoolConfigCmp - { - bool operator ()(const LocalPoolCfgPair &a, - const LocalPoolCfgPair &b) const - { - if(a.second < b.second) { - return true; - } - else if(a.second > b.second) { - return false; - } - else { - if(a.first < b.first) { - return true; - } - else { - return false; - } - } - } - }; - using LocalPoolConfig = std::multiset; + // The configuration needs to be provided with the pool sizes ascending + // but the number of pool elements as the first value is more intuitive. + // Therefore, a custom comparator was provided. + struct LocalPoolConfigCmp { + bool operator()(const LocalPoolCfgPair& a, const LocalPoolCfgPair& b) const { + if (a.second < b.second) { + return true; + } else if (a.second > b.second) { + return false; + } else { + if (a.first < b.first) { + return true; + } else { + return false; + } + } + } + }; + using LocalPoolConfig = std::multiset; - /** - * @brief This is the default constructor for a pool manager instance. - * @details - * The pool is configured by passing a set of pairs into the constructor. - * The first value of that pair determines the number of one elements on - * the respective page of the pool while the second value determines how - * many elements with that size are created on that page. - * All regions are to zero on start up. - * @param setObjectId The object identifier to be set. This allows for - * multiple instances of LocalPool in the system. - * @param poolConfig - * This is a set of pairs to configure the number of pages in the pool, - * the size of an element on a page, the number of elements on a page - * and the total size of the pool at once while also implicitely - * sorting the pairs in the right order. - * @param registered - * Determines whether the pool is registered in the object manager or not. - * @param spillsToHigherPools A variable to determine whether - * higher n pools are used if the store is full. - */ - LocalPool(object_id_t setObjectId, const LocalPoolConfig& poolConfig, - bool registered = false, bool spillsToHigherPools = false); + /** + * @brief This is the default constructor for a pool manager instance. + * @details + * The pool is configured by passing a set of pairs into the constructor. + * The first value of that pair determines the number of one elements on + * the respective page of the pool while the second value determines how + * many elements with that size are created on that page. + * All regions are to zero on start up. + * @param setObjectId The object identifier to be set. This allows for + * multiple instances of LocalPool in the system. + * @param poolConfig + * This is a set of pairs to configure the number of pages in the pool, + * the size of an element on a page, the number of elements on a page + * and the total size of the pool at once while also implicitely + * sorting the pairs in the right order. + * @param registered + * Determines whether the pool is registered in the object manager or not. + * @param spillsToHigherPools A variable to determine whether + * higher n pools are used if the store is full. + */ + LocalPool(object_id_t setObjectId, const LocalPoolConfig& poolConfig, bool registered = false, + bool spillsToHigherPools = false); - void setToSpillToHigherPools(bool enable); + void setToSpillToHigherPools(bool enable); - /** - * @brief In the LocalPool's destructor all allocated memory is freed. - */ - virtual ~LocalPool(void); + /** + * @brief In the LocalPool's destructor all allocated memory is freed. + */ + virtual ~LocalPool(void); - /** - * Documentation: See StorageManagerIF.h - */ - ReturnValue_t addData(store_address_t* storeId, const uint8_t * data, - size_t size, bool ignoreFault = false) override; - ReturnValue_t getFreeElement(store_address_t* storeId,const size_t size, - uint8_t** pData, bool ignoreFault = false) override; + /** + * Documentation: See StorageManagerIF.h + */ + ReturnValue_t addData(store_address_t* storeId, const uint8_t* data, size_t size, + bool ignoreFault = false) override; + ReturnValue_t getFreeElement(store_address_t* storeId, const size_t size, uint8_t** pData, + bool ignoreFault = false) override; - ConstAccessorPair getData(store_address_t storeId) override; - ReturnValue_t getData(store_address_t storeId, - ConstStorageAccessor& constAccessor) override; - ReturnValue_t getData(store_address_t storeId, - const uint8_t** packet_ptr, size_t * size) override; + ConstAccessorPair getData(store_address_t storeId) override; + ReturnValue_t getData(store_address_t storeId, ConstStorageAccessor& constAccessor) override; + ReturnValue_t getData(store_address_t storeId, const uint8_t** packet_ptr, size_t* size) override; - AccessorPair modifyData(store_address_t storeId) override; - ReturnValue_t modifyData(store_address_t storeId, - StorageAccessor& storeAccessor) override; - ReturnValue_t modifyData(store_address_t storeId, uint8_t** packet_ptr, - size_t * size) override; + AccessorPair modifyData(store_address_t storeId) override; + ReturnValue_t modifyData(store_address_t storeId, StorageAccessor& storeAccessor) override; + ReturnValue_t modifyData(store_address_t storeId, uint8_t** packet_ptr, size_t* size) override; - virtual ReturnValue_t deleteData(store_address_t storeId) override; - virtual ReturnValue_t deleteData(uint8_t* ptr, size_t size, - store_address_t* storeId = nullptr) override; + virtual ReturnValue_t deleteData(store_address_t storeId) override; + virtual ReturnValue_t deleteData(uint8_t* ptr, size_t size, + store_address_t* storeId = nullptr) override; - /** - * Get the total size of allocated memory for pool data. - * There is an additional overhead of the sizes of elements which will - * be assigned to additionalSize - * @return - */ - size_t getTotalSize(size_t* additionalSize) override; + /** + * Get the total size of allocated memory for pool data. + * There is an additional overhead of the sizes of elements which will + * be assigned to additionalSize + * @return + */ + size_t getTotalSize(size_t* additionalSize) override; - /** - * Get the fill count of the pool. Each character inside the provided - * buffer will be assigned to a rounded percentage fill count for each - * page. The last written byte (at the index bytesWritten - 1) - * will contain the total fill count of the pool as a mean of the - * percentages of single pages. - * @param buffer - * @param maxSize - */ - void getFillCount(uint8_t* buffer, uint8_t* bytesWritten) override; + /** + * Get the fill count of the pool. Each character inside the provided + * buffer will be assigned to a rounded percentage fill count for each + * page. The last written byte (at the index bytesWritten - 1) + * will contain the total fill count of the pool as a mean of the + * percentages of single pages. + * @param buffer + * @param maxSize + */ + void getFillCount(uint8_t* buffer, uint8_t* bytesWritten) override; - void clearStore() override; - void clearSubPool(max_subpools_t poolIndex) override; + void clearStore() override; + void clearSubPool(max_subpools_t poolIndex) override; - ReturnValue_t initialize() override; + ReturnValue_t initialize() override; - /** - * Get number sub pools. Each pool has pages with a specific bucket size. - * @return - */ - max_subpools_t getNumberOfSubPools() const override; -protected: - /** - * With this helper method, a free element of @c size is reserved. - * @param size The minimum packet size that shall be reserved. - * @param[out] address Storage ID of the reserved data. - * @return - #RETURN_OK on success, - * - the return codes of #getPoolIndex or #findEmpty otherwise. - */ - virtual ReturnValue_t reserveSpace(const size_t size, - store_address_t* address, bool ignoreFault); + /** + * Get number sub pools. Each pool has pages with a specific bucket size. + * @return + */ + max_subpools_t getNumberOfSubPools() const override; -private: + protected: + /** + * With this helper method, a free element of @c size is reserved. + * @param size The minimum packet size that shall be reserved. + * @param[out] address Storage ID of the reserved data. + * @return - #RETURN_OK on success, + * - the return codes of #getPoolIndex or #findEmpty otherwise. + */ + virtual ReturnValue_t reserveSpace(const size_t size, store_address_t* address, bool ignoreFault); - /** - * @brief This definition generally sets the number of - * different sized pools. It is derived from the number of pairs - * inside the LocalPoolConfig set on object creation. - * @details - * This must be less than the maximum number of pools (currently 0xff). - */ - const max_subpools_t NUMBER_OF_SUBPOOLS; + private: + /** + * @brief This definition generally sets the number of + * different sized pools. It is derived from the number of pairs + * inside the LocalPoolConfig set on object creation. + * @details + * This must be less than the maximum number of pools (currently 0xff). + */ + const max_subpools_t NUMBER_OF_SUBPOOLS; - /** - * Indicates that this element is free. - * This value limits the maximum size of a pool. - * Change to larger data type if increase is required. - */ - static const size_type STORAGE_FREE = std::numeric_limits::max(); - /** - * @brief In this array, the element sizes of each pool is stored. - * @details The sizes are maintained for internal pool management. The sizes - * must be set in ascending order on construction. - */ - std::vector elementSizes = - std::vector(NUMBER_OF_SUBPOOLS); - /** - * @brief n_elements stores the number of elements per pool. - * @details These numbers are maintained for internal pool management. - */ - std::vector numberOfElements = - std::vector(NUMBER_OF_SUBPOOLS); - /** - * @brief store represents the actual memory pool. - * @details It is an array of pointers to memory, which was allocated with - * a @c new call on construction. - */ - std::vector> store = - std::vector>(NUMBER_OF_SUBPOOLS); + /** + * Indicates that this element is free. + * This value limits the maximum size of a pool. + * Change to larger data type if increase is required. + */ + static const size_type STORAGE_FREE = std::numeric_limits::max(); + /** + * @brief In this array, the element sizes of each pool is stored. + * @details The sizes are maintained for internal pool management. The sizes + * must be set in ascending order on construction. + */ + std::vector elementSizes = std::vector(NUMBER_OF_SUBPOOLS); + /** + * @brief n_elements stores the number of elements per pool. + * @details These numbers are maintained for internal pool management. + */ + std::vector numberOfElements = std::vector(NUMBER_OF_SUBPOOLS); + /** + * @brief store represents the actual memory pool. + * @details It is an array of pointers to memory, which was allocated with + * a @c new call on construction. + */ + std::vector> store = std::vector>(NUMBER_OF_SUBPOOLS); - /** - * @brief The size_list attribute stores the size values of every pool element. - * @details As the number of elements is determined on construction, the size list - * is also dynamically allocated there. - */ - std::vector> sizeLists = - std::vector>(NUMBER_OF_SUBPOOLS); + /** + * @brief The size_list attribute stores the size values of every pool element. + * @details As the number of elements is determined on construction, the size list + * is also dynamically allocated there. + */ + std::vector> sizeLists = + std::vector>(NUMBER_OF_SUBPOOLS); - //! A variable to determine whether higher n pools are used if - //! the store is full. - bool spillsToHigherPools = false; - /** - * @brief This method safely stores the given data in the given packet_id. - * @details It also sets the size in size_list. The method does not perform - * any range checks, these are done in advance. - * @param packet_id The storage identifier in which the data shall be stored. - * @param data The data to be stored. - * @param size The size of the data to be stored. - */ - void write(store_address_t packetId, const uint8_t* data, size_t size); - /** - * @brief A helper method to read the element size of a certain pool. - * @param pool_index The pool in which to look. - * @return Returns the size of an element or 0. - */ - size_type getSubpoolElementSize(max_subpools_t subpoolIndex); + //! A variable to determine whether higher n pools are used if + //! the store is full. + bool spillsToHigherPools = false; + /** + * @brief This method safely stores the given data in the given packet_id. + * @details It also sets the size in size_list. The method does not perform + * any range checks, these are done in advance. + * @param packet_id The storage identifier in which the data shall be stored. + * @param data The data to be stored. + * @param size The size of the data to be stored. + */ + void write(store_address_t packetId, const uint8_t* data, size_t size); + /** + * @brief A helper method to read the element size of a certain pool. + * @param pool_index The pool in which to look. + * @return Returns the size of an element or 0. + */ + size_type getSubpoolElementSize(max_subpools_t subpoolIndex); - /** - * @brief This helper method looks up a fitting pool for a given size. - * @details The pools are looked up in ascending order, so the first that - * fits is used. - * @param packet_size The size of the data to be stored. - * @param[out] poolIndex The fitting pool index found. - * @return - @c RETURN_OK on success, - * - @c DATA_TOO_LARGE otherwise. - */ - ReturnValue_t getSubPoolIndex(size_t packetSize, uint16_t* subpoolIndex, - uint16_t startAtIndex = 0); - /** - * @brief This helper method calculates the true array position in store - * of a given packet id. - * @details The method does not perform any range checks, these are done in - * advance. - * @param packet_id The packet id to look up. - * @return Returns the position of the data in store. - */ - size_type getRawPosition(store_address_t storeId); - /** - * @brief This is a helper method to find an empty element in a given pool. - * @details The method searches size_list for the first empty element, so - * duration grows with the fill level of the pool. - * @param pool_index The pool in which the search is performed. - * @param[out] element The first found element in the pool. - * @return - #RETURN_OK on success, - * - #DATA_STORAGE_FULL if the store is full - */ - ReturnValue_t findEmpty(n_pool_elem_t poolIndex, uint16_t* element); + /** + * @brief This helper method looks up a fitting pool for a given size. + * @details The pools are looked up in ascending order, so the first that + * fits is used. + * @param packet_size The size of the data to be stored. + * @param[out] poolIndex The fitting pool index found. + * @return - @c RETURN_OK on success, + * - @c DATA_TOO_LARGE otherwise. + */ + ReturnValue_t getSubPoolIndex(size_t packetSize, uint16_t* subpoolIndex, + uint16_t startAtIndex = 0); + /** + * @brief This helper method calculates the true array position in store + * of a given packet id. + * @details The method does not perform any range checks, these are done in + * advance. + * @param packet_id The packet id to look up. + * @return Returns the position of the data in store. + */ + size_type getRawPosition(store_address_t storeId); + /** + * @brief This is a helper method to find an empty element in a given pool. + * @details The method searches size_list for the first empty element, so + * duration grows with the fill level of the pool. + * @param pool_index The pool in which the search is performed. + * @param[out] element The first found element in the pool. + * @return - #RETURN_OK on success, + * - #DATA_STORAGE_FULL if the store is full + */ + ReturnValue_t findEmpty(n_pool_elem_t poolIndex, uint16_t* element); - InternalErrorReporterIF *internalErrorReporter = nullptr; + InternalErrorReporterIF* internalErrorReporter = nullptr; }; #endif /* FSFW_STORAGEMANAGER_LOCALPOOL_H_ */ diff --git a/src/fsfw/storagemanager/PoolManager.cpp b/src/fsfw/storagemanager/PoolManager.cpp index 073371ad..6ff00360 100644 --- a/src/fsfw/storagemanager/PoolManager.cpp +++ b/src/fsfw/storagemanager/PoolManager.cpp @@ -1,63 +1,44 @@ -#include "fsfw/FSFW.h" #include "fsfw/storagemanager/PoolManager.h" +#include "fsfw/FSFW.h" -PoolManager::PoolManager(object_id_t setObjectId, - const LocalPoolConfig& localPoolConfig): - LocalPool(setObjectId, localPoolConfig, true) { - mutex = MutexFactory::instance()->createMutex(); +PoolManager::PoolManager(object_id_t setObjectId, const LocalPoolConfig& localPoolConfig) + : LocalPool(setObjectId, localPoolConfig, true) { + mutex = MutexFactory::instance()->createMutex(); } +PoolManager::~PoolManager(void) { MutexFactory::instance()->deleteMutex(mutex); } -PoolManager::~PoolManager(void) { - MutexFactory::instance()->deleteMutex(mutex); +ReturnValue_t PoolManager::reserveSpace(const size_t size, store_address_t* address, + bool ignoreFault) { + MutexGuard mutexHelper(mutex, MutexIF::TimeoutType::WAITING, mutexTimeoutMs); + ReturnValue_t status = LocalPool::reserveSpace(size, address, ignoreFault); + return status; } - -ReturnValue_t PoolManager::reserveSpace(const size_t size, - store_address_t* address, bool ignoreFault) { - MutexGuard mutexHelper(mutex, MutexIF::TimeoutType::WAITING, - mutexTimeoutMs); - ReturnValue_t status = LocalPool::reserveSpace(size, - address,ignoreFault); - return status; -} - - -ReturnValue_t PoolManager::deleteData( - store_address_t storeId) { +ReturnValue_t PoolManager::deleteData(store_address_t storeId) { #if FSFW_VERBOSE_PRINTOUT == 2 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "PoolManager( " << translateObject(getObjectId()) << - " )::deleteData from store " << storeId.poolIndex << - ". id is "<< storeId.packetIndex << std::endl; + sif::debug << "PoolManager( " << translateObject(getObjectId()) << " )::deleteData from store " + << storeId.poolIndex << ". id is " << storeId.packetIndex << std::endl; #endif #endif - MutexGuard mutexHelper(mutex, MutexIF::TimeoutType::WAITING, - mutexTimeoutMs); - return LocalPool::deleteData(storeId); + MutexGuard mutexHelper(mutex, MutexIF::TimeoutType::WAITING, mutexTimeoutMs); + return LocalPool::deleteData(storeId); } - -ReturnValue_t PoolManager::deleteData(uint8_t* buffer, - size_t size, store_address_t* storeId) { - MutexGuard mutexHelper(mutex, MutexIF::TimeoutType::WAITING, 20); - ReturnValue_t status = LocalPool::deleteData(buffer, - size, storeId); - return status; +ReturnValue_t PoolManager::deleteData(uint8_t* buffer, size_t size, store_address_t* storeId) { + MutexGuard mutexHelper(mutex, MutexIF::TimeoutType::WAITING, 20); + ReturnValue_t status = LocalPool::deleteData(buffer, size, storeId); + return status; } - -void PoolManager::setMutexTimeout( - uint32_t mutexTimeoutMs) { - this->mutexTimeoutMs = mutexTimeoutMs; +void PoolManager::setMutexTimeout(uint32_t mutexTimeoutMs) { + this->mutexTimeoutMs = mutexTimeoutMs; } -ReturnValue_t PoolManager::lockMutex(MutexIF::TimeoutType timeoutType, - uint32_t timeoutMs) { - return mutex->lockMutex(timeoutType, timeoutMs); +ReturnValue_t PoolManager::lockMutex(MutexIF::TimeoutType timeoutType, uint32_t timeoutMs) { + return mutex->lockMutex(timeoutType, timeoutMs); } -ReturnValue_t PoolManager::unlockMutex() { - return mutex->unlockMutex(); -} +ReturnValue_t PoolManager::unlockMutex() { return mutex->unlockMutex(); } diff --git a/src/fsfw/storagemanager/PoolManager.h b/src/fsfw/storagemanager/PoolManager.h index 4dde3a23..0951a518 100644 --- a/src/fsfw/storagemanager/PoolManager.h +++ b/src/fsfw/storagemanager/PoolManager.h @@ -1,10 +1,9 @@ #ifndef FSFW_STORAGEMANAGER_POOLMANAGER_H_ #define FSFW_STORAGEMANAGER_POOLMANAGER_H_ +#include "../ipc/MutexGuard.h" #include "LocalPool.h" #include "StorageAccessor.h" -#include "../ipc/MutexGuard.h" - /** * @brief The PoolManager class provides an intermediate data storage with @@ -20,56 +19,55 @@ * recommended to use the LocalPool class instead). * @author Bastian Baetz */ -class PoolManager: public LocalPool { -public: - PoolManager(object_id_t setObjectId, const LocalPoolConfig& poolConfig); +class PoolManager : public LocalPool { + public: + PoolManager(object_id_t setObjectId, const LocalPoolConfig& poolConfig); - /** - * @brief In the PoolManager's destructor all allocated memory - * is freed. - */ - virtual ~PoolManager(); + /** + * @brief In the PoolManager's destructor all allocated memory + * is freed. + */ + virtual ~PoolManager(); - /** - * Set the default mutex timeout for internal calls. - * @param mutexTimeoutMs - */ - void setMutexTimeout(uint32_t mutexTimeoutMs); + /** + * Set the default mutex timeout for internal calls. + * @param mutexTimeoutMs + */ + void setMutexTimeout(uint32_t mutexTimeoutMs); - /** - * @brief LocalPool overrides for thread-safety. Decorator function - * which wraps LocalPool calls with a mutex protection. - */ - ReturnValue_t deleteData(store_address_t) override; - ReturnValue_t deleteData(uint8_t* buffer, size_t size, - store_address_t* storeId = nullptr) override; + /** + * @brief LocalPool overrides for thread-safety. Decorator function + * which wraps LocalPool calls with a mutex protection. + */ + ReturnValue_t deleteData(store_address_t) override; + ReturnValue_t deleteData(uint8_t* buffer, size_t size, + store_address_t* storeId = nullptr) override; - /** - * The developer is allowed to lock the mutex in case the lock needs - * to persist beyond the function calls which are not protected by the - * class. - * @param timeoutType - * @param timeoutMs - * @return - */ - ReturnValue_t lockMutex(MutexIF::TimeoutType timeoutType, - uint32_t timeoutMs); - ReturnValue_t unlockMutex(); + /** + * The developer is allowed to lock the mutex in case the lock needs + * to persist beyond the function calls which are not protected by the + * class. + * @param timeoutType + * @param timeoutMs + * @return + */ + ReturnValue_t lockMutex(MutexIF::TimeoutType timeoutType, uint32_t timeoutMs); + ReturnValue_t unlockMutex(); -protected: - //! Default mutex timeout value to prevent permanent blocking. - uint32_t mutexTimeoutMs = 20; + protected: + //! Default mutex timeout value to prevent permanent blocking. + uint32_t mutexTimeoutMs = 20; - ReturnValue_t reserveSpace(const size_t size, store_address_t* address, - bool ignoreFault) override; + ReturnValue_t reserveSpace(const size_t size, store_address_t* address, + bool ignoreFault) override; - /** - * @brief The mutex is created in the constructor and makes - * access mutual exclusive. - * @details Locking and unlocking is done during searching for free slots - * and deleting existing slots. - */ - MutexIF* mutex; + /** + * @brief The mutex is created in the constructor and makes + * access mutual exclusive. + * @details Locking and unlocking is done during searching for free slots + * and deleting existing slots. + */ + MutexIF* mutex; }; #endif /* FSFW_STORAGEMANAGER_POOLMANAGER_H_ */ diff --git a/src/fsfw/storagemanager/StorageAccessor.cpp b/src/fsfw/storagemanager/StorageAccessor.cpp index 95f61a75..e2b083b2 100644 --- a/src/fsfw/storagemanager/StorageAccessor.cpp +++ b/src/fsfw/storagemanager/StorageAccessor.cpp @@ -1,80 +1,71 @@ #include "fsfw/storagemanager/StorageAccessor.h" -#include "fsfw/storagemanager/StorageManagerIF.h" - -#include "fsfw/serviceinterface/ServiceInterface.h" #include -StorageAccessor::StorageAccessor(store_address_t storeId): - ConstStorageAccessor(storeId) { -} +#include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/storagemanager/StorageManagerIF.h" -StorageAccessor::StorageAccessor(store_address_t storeId, - StorageManagerIF* store): - ConstStorageAccessor(storeId, store) { -} +StorageAccessor::StorageAccessor(store_address_t storeId) : ConstStorageAccessor(storeId) {} -StorageAccessor& StorageAccessor::operator =( - StorageAccessor&& other) { - // Call the parent move assignment and also assign own member. - dataPointer = other.dataPointer; - StorageAccessor::operator=(std::move(other)); - return * this; +StorageAccessor::StorageAccessor(store_address_t storeId, StorageManagerIF* store) + : ConstStorageAccessor(storeId, store) {} + +StorageAccessor& StorageAccessor::operator=(StorageAccessor&& other) { + // Call the parent move assignment and also assign own member. + dataPointer = other.dataPointer; + StorageAccessor::operator=(std::move(other)); + return *this; } // Call the parent move ctor and also transfer own member. -StorageAccessor::StorageAccessor(StorageAccessor&& other): - ConstStorageAccessor(std::move(other)), dataPointer(other.dataPointer) { -} +StorageAccessor::StorageAccessor(StorageAccessor&& other) + : ConstStorageAccessor(std::move(other)), dataPointer(other.dataPointer) {} -ReturnValue_t StorageAccessor::getDataCopy(uint8_t *pointer, size_t maxSize) { - if(internalState == AccessState::UNINIT) { +ReturnValue_t StorageAccessor::getDataCopy(uint8_t* pointer, size_t maxSize) { + if (internalState == AccessState::UNINIT) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "StorageAccessor: Not initialized!" << std::endl; + sif::warning << "StorageAccessor: Not initialized!" << std::endl; #endif - return HasReturnvaluesIF::RETURN_FAILED; - } - if(size_ > maxSize) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if (size_ > maxSize) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "StorageAccessor: Supplied buffer not large " - "enough" << std::endl; + sif::error << "StorageAccessor: Supplied buffer not large " + "enough" + << std::endl; #endif - return HasReturnvaluesIF::RETURN_FAILED; - } - std::copy(dataPointer, dataPointer + size_, pointer); - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_FAILED; + } + std::copy(dataPointer, dataPointer + size_, pointer); + return HasReturnvaluesIF::RETURN_OK; } uint8_t* StorageAccessor::data() { - if(internalState == AccessState::UNINIT) { + if (internalState == AccessState::UNINIT) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "StorageAccessor: Not initialized!" << std::endl; + sif::warning << "StorageAccessor: Not initialized!" << std::endl; #endif - } - return dataPointer; + } + return dataPointer; } -ReturnValue_t StorageAccessor::write(uint8_t *data, size_t size, - uint16_t offset) { - if(internalState == AccessState::UNINIT) { +ReturnValue_t StorageAccessor::write(uint8_t* data, size_t size, uint16_t offset) { + if (internalState == AccessState::UNINIT) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "StorageAccessor: Not initialized!" << std::endl; + sif::warning << "StorageAccessor: Not initialized!" << std::endl; #endif - return HasReturnvaluesIF::RETURN_FAILED; - } - if(offset + size > size_) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if (offset + size > size_) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "StorageAccessor: Data too large for pool " - "entry!" << std::endl; + sif::error << "StorageAccessor: Data too large for pool " + "entry!" + << std::endl; #endif - return HasReturnvaluesIF::RETURN_FAILED; - } - std::copy(data, data + size, dataPointer + offset); - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_FAILED; + } + std::copy(data, data + size, dataPointer + offset); + return HasReturnvaluesIF::RETURN_OK; } -void StorageAccessor::assignConstPointer() { - constDataPointer = dataPointer; -} - - +void StorageAccessor::assignConstPointer() { constDataPointer = dataPointer; } diff --git a/src/fsfw/storagemanager/StorageAccessor.h b/src/fsfw/storagemanager/StorageAccessor.h index d5b383eb..5e8b25e4 100644 --- a/src/fsfw/storagemanager/StorageAccessor.h +++ b/src/fsfw/storagemanager/StorageAccessor.h @@ -8,36 +8,36 @@ class StorageManagerIF; /** * @brief Child class for modifyable data. Also has a normal pointer member. */ -class StorageAccessor: public ConstStorageAccessor { - //! StorageManager classes have exclusive access to private variables. - friend class PoolManager; - friend class LocalPool; -public: - StorageAccessor(store_address_t storeId); - StorageAccessor(store_address_t storeId, StorageManagerIF* store); +class StorageAccessor : public ConstStorageAccessor { + //! StorageManager classes have exclusive access to private variables. + friend class PoolManager; + friend class LocalPool; - /** - * @brief Move ctor and move assignment allow returning accessors as - * a returnvalue. They prevent resource being freed prematurely. - * See: https://github.com/MicrosoftDocs/cpp-docs/blob/master/docs/cpp/ - * move-constructors-and-move-assignment-operators-cpp.md - * @param - * @return - */ - StorageAccessor& operator=(StorageAccessor&&); - StorageAccessor(StorageAccessor&&); + public: + StorageAccessor(store_address_t storeId); + StorageAccessor(store_address_t storeId, StorageManagerIF* store); - ReturnValue_t write(uint8_t *data, size_t size, - uint16_t offset = 0); - uint8_t* data(); - ReturnValue_t getDataCopy(uint8_t *pointer, size_t maxSize) override; + /** + * @brief Move ctor and move assignment allow returning accessors as + * a returnvalue. They prevent resource being freed prematurely. + * See: https://github.com/MicrosoftDocs/cpp-docs/blob/master/docs/cpp/ + * move-constructors-and-move-assignment-operators-cpp.md + * @param + * @return + */ + StorageAccessor& operator=(StorageAccessor&&); + StorageAccessor(StorageAccessor&&); -private: - //! Non-const pointer for modifyable data. - uint8_t* dataPointer = nullptr; - //! For modifyable data, the const pointer is assigned to the normal - //! pointer by the pool manager so both access functions can be used safely - void assignConstPointer(); + ReturnValue_t write(uint8_t* data, size_t size, uint16_t offset = 0); + uint8_t* data(); + ReturnValue_t getDataCopy(uint8_t* pointer, size_t maxSize) override; + + private: + //! Non-const pointer for modifyable data. + uint8_t* dataPointer = nullptr; + //! For modifyable data, the const pointer is assigned to the normal + //! pointer by the pool manager so both access functions can be used safely + void assignConstPointer(); }; #endif /* FSFW_STORAGEMANAGER_STORAGEACCESSOR_H_ */ diff --git a/src/fsfw/storagemanager/StorageManagerIF.h b/src/fsfw/storagemanager/StorageManagerIF.h index da7ce01d..375fc7cc 100644 --- a/src/fsfw/storagemanager/StorageManagerIF.h +++ b/src/fsfw/storagemanager/StorageManagerIF.h @@ -1,14 +1,13 @@ #ifndef FSFW_STORAGEMANAGER_STORAGEMANAGERIF_H_ #define FSFW_STORAGEMANAGER_STORAGEMANAGERIF_H_ -#include "StorageAccessor.h" -#include "storeAddress.h" +#include +#include #include "../events/Event.h" #include "../returnvalues/HasReturnvaluesIF.h" - -#include -#include +#include "StorageAccessor.h" +#include "storeAddress.h" using AccessorPair = std::pair; using ConstAccessorPair = std::pair; @@ -27,173 +26,173 @@ using ConstAccessorPair = std::pair; * @date 18.09.2012 */ class StorageManagerIF : public HasReturnvaluesIF { -public: - using size_type = size_t; - using max_subpools_t = uint8_t; + public: + using size_type = size_t; + using max_subpools_t = uint8_t; - static const uint8_t INTERFACE_ID = CLASS_ID::STORAGE_MANAGER_IF; //!< The unique ID for return codes for this interface. - static const ReturnValue_t DATA_TOO_LARGE = MAKE_RETURN_CODE(1); //!< This return code indicates that the data to be stored is too large for the store. - static const ReturnValue_t DATA_STORAGE_FULL = MAKE_RETURN_CODE(2); //!< This return code indicates that a data storage is full. - static const ReturnValue_t ILLEGAL_STORAGE_ID = MAKE_RETURN_CODE(3); //!< This return code indicates that data was requested with an illegal storage ID. - static const ReturnValue_t DATA_DOES_NOT_EXIST = MAKE_RETURN_CODE(4); //!< This return code indicates that the requested ID was valid, but no data is stored there. - static const ReturnValue_t ILLEGAL_ADDRESS = MAKE_RETURN_CODE(5); - static const ReturnValue_t POOL_TOO_LARGE = MAKE_RETURN_CODE(6); //!< Pool size too large on initialization. + static const uint8_t INTERFACE_ID = + CLASS_ID::STORAGE_MANAGER_IF; //!< The unique ID for return codes for this interface. + static const ReturnValue_t DATA_TOO_LARGE = MAKE_RETURN_CODE( + 1); //!< This return code indicates that the data to be stored is too large for the store. + static const ReturnValue_t DATA_STORAGE_FULL = + MAKE_RETURN_CODE(2); //!< This return code indicates that a data storage is full. + static const ReturnValue_t ILLEGAL_STORAGE_ID = MAKE_RETURN_CODE( + 3); //!< This return code indicates that data was requested with an illegal storage ID. + static const ReturnValue_t DATA_DOES_NOT_EXIST = + MAKE_RETURN_CODE(4); //!< This return code indicates that the requested ID was valid, but no + //!< data is stored there. + static const ReturnValue_t ILLEGAL_ADDRESS = MAKE_RETURN_CODE(5); + static const ReturnValue_t POOL_TOO_LARGE = + MAKE_RETURN_CODE(6); //!< Pool size too large on initialization. - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::OBSW; - static const Event GET_DATA_FAILED = MAKE_EVENT(0, severity::LOW); - static const Event STORE_DATA_FAILED = MAKE_EVENT(1, severity::LOW); + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::OBSW; + static const Event GET_DATA_FAILED = MAKE_EVENT(0, severity::LOW); + static const Event STORE_DATA_FAILED = MAKE_EVENT(1, severity::LOW); - //!< Indicates an invalid (i.e unused) storage address. - static const uint32_t INVALID_ADDRESS = 0xFFFFFFFF; + //!< Indicates an invalid (i.e unused) storage address. + static const uint32_t INVALID_ADDRESS = 0xFFFFFFFF; - /** - * @brief This is the empty virtual destructor as required for C++ interfaces. - */ - virtual ~StorageManagerIF() { - } - ; - /** - * @brief With addData, a free storage position is allocated and data - * stored there. - * @details During the allocation, the StorageManager is blocked. - * @param storageId A pointer to the storageId to retrieve. - * @param data The data to be stored in the StorageManager. - * @param size The amount of data to be stored. - * @return Returns @li RETURN_OK if data was added. - * @li RETURN_FAILED if data could not be added. - * storageId is unchanged then. - */ - virtual ReturnValue_t addData(store_address_t* storageId, - const uint8_t * data, size_t size, bool ignoreFault = false) = 0; - /** - * @brief With deleteData, the storageManager frees the memory region - * identified by packet_id. - * @param packet_id The identifier of the memory region to be freed. - * @return @li RETURN_OK on success. - * @li RETURN_FAILED if deletion did not work - * (e.g. an illegal packet_id was passed). - */ - virtual ReturnValue_t deleteData(store_address_t packet_id) = 0; - /** - * @brief Another deleteData which uses the pointer and size of the - * stored data to delete the content. - * @param buffer Pointer to the data. - * @param size Size of data to be stored. - * @param storeId Store id of the deleted element (optional) - * @return @li RETURN_OK on success. - * @li failure code if deletion did not work - */ - virtual ReturnValue_t deleteData(uint8_t* buffer, size_t size, - store_address_t* storeId = nullptr) = 0; + /** + * @brief This is the empty virtual destructor as required for C++ interfaces. + */ + virtual ~StorageManagerIF(){}; + /** + * @brief With addData, a free storage position is allocated and data + * stored there. + * @details During the allocation, the StorageManager is blocked. + * @param storageId A pointer to the storageId to retrieve. + * @param data The data to be stored in the StorageManager. + * @param size The amount of data to be stored. + * @return Returns @li RETURN_OK if data was added. + * @li RETURN_FAILED if data could not be added. + * storageId is unchanged then. + */ + virtual ReturnValue_t addData(store_address_t* storageId, const uint8_t* data, size_t size, + bool ignoreFault = false) = 0; + /** + * @brief With deleteData, the storageManager frees the memory region + * identified by packet_id. + * @param packet_id The identifier of the memory region to be freed. + * @return @li RETURN_OK on success. + * @li RETURN_FAILED if deletion did not work + * (e.g. an illegal packet_id was passed). + */ + virtual ReturnValue_t deleteData(store_address_t packet_id) = 0; + /** + * @brief Another deleteData which uses the pointer and size of the + * stored data to delete the content. + * @param buffer Pointer to the data. + * @param size Size of data to be stored. + * @param storeId Store id of the deleted element (optional) + * @return @li RETURN_OK on success. + * @li failure code if deletion did not work + */ + virtual ReturnValue_t deleteData(uint8_t* buffer, size_t size, + store_address_t* storeId = nullptr) = 0; + /** + * @brief Access the data by supplying a store ID. + * @details + * A pair consisting of the retrieval result and an instance of a + * ConstStorageAccessor class is returned + * @param storeId + * @return Pair of return value and a ConstStorageAccessor instance + */ + virtual ConstAccessorPair getData(store_address_t storeId) = 0; - /** - * @brief Access the data by supplying a store ID. - * @details - * A pair consisting of the retrieval result and an instance of a - * ConstStorageAccessor class is returned - * @param storeId - * @return Pair of return value and a ConstStorageAccessor instance - */ - virtual ConstAccessorPair getData(store_address_t storeId) = 0; + /** + * @brief Access the data by supplying a store ID and a helper + * instance + * @param storeId + * @param constAccessor Wrapper function to access store data. + * @return + */ + virtual ReturnValue_t getData(store_address_t storeId, ConstStorageAccessor& constAccessor) = 0; - /** - * @brief Access the data by supplying a store ID and a helper - * instance - * @param storeId - * @param constAccessor Wrapper function to access store data. - * @return - */ - virtual ReturnValue_t getData(store_address_t storeId, - ConstStorageAccessor& constAccessor) = 0; + /** + * @brief getData returns an address to data and the size of the data + * for a given packet_id. + * @param packet_id The id of the data to be returned + * @param packet_ptr The passed pointer address is set to the the memory + * position + * @param size The exact size of the stored data is returned here. + * @return @li RETURN_OK on success. + * @li RETURN_FAILED if fetching data did not work + * (e.g. an illegal packet_id was passed). + */ + virtual ReturnValue_t getData(store_address_t packet_id, const uint8_t** packet_ptr, + size_t* size) = 0; + /** + * Modify data by supplying a store ID + * @param storeId + * @return Pair of return value and StorageAccessor helper + */ + virtual AccessorPair modifyData(store_address_t storeId) = 0; - /** - * @brief getData returns an address to data and the size of the data - * for a given packet_id. - * @param packet_id The id of the data to be returned - * @param packet_ptr The passed pointer address is set to the the memory - * position - * @param size The exact size of the stored data is returned here. - * @return @li RETURN_OK on success. - * @li RETURN_FAILED if fetching data did not work - * (e.g. an illegal packet_id was passed). - */ - virtual ReturnValue_t getData(store_address_t packet_id, - const uint8_t** packet_ptr, size_t* size) = 0; + /** + * Modify data by supplying a store ID and a StorageAccessor helper instance. + * @param storeId + * @param accessor Helper class to access the modifiable data. + * @return + */ + virtual ReturnValue_t modifyData(store_address_t storeId, StorageAccessor& accessor) = 0; + /** + * Get pointer and size of modifiable data by supplying the storeId + * @param packet_id + * @param packet_ptr [out] Pointer to pointer of data to set + * @param size [out] Pointer to size to set + * @return + */ + virtual ReturnValue_t modifyData(store_address_t packet_id, uint8_t** packet_ptr, + size_t* size) = 0; + /** + * This method reserves an element of @c size. + * + * It returns the packet id of this element as well as a direct pointer to the + * data of the element. It must be assured that exactly @c size data is + * written to p_data! + * @param storageId A pointer to the storageId to retrieve. + * @param size The size of the space to be reserved. + * @param p_data A pointer to the element data is returned here. + * @return Returns @li RETURN_OK if data was added. + * @li RETURN_FAILED if data could not be added. + * storageId is unchanged then. + */ + virtual ReturnValue_t getFreeElement(store_address_t* storageId, const size_t size, + uint8_t** p_data, bool ignoreFault = false) = 0; - /** - * Modify data by supplying a store ID - * @param storeId - * @return Pair of return value and StorageAccessor helper - */ - virtual AccessorPair modifyData(store_address_t storeId) = 0; + /** + * Clears the whole store. + * Use with care! + */ + virtual void clearStore() = 0; - /** - * Modify data by supplying a store ID and a StorageAccessor helper instance. - * @param storeId - * @param accessor Helper class to access the modifiable data. - * @return - */ - virtual ReturnValue_t modifyData(store_address_t storeId, - StorageAccessor& accessor) = 0; + /** + * Clears a pool in the store with the given pool index. Use with care! + * @param pageIndex + */ + virtual void clearSubPool(uint8_t poolIndex) = 0; - /** - * Get pointer and size of modifiable data by supplying the storeId - * @param packet_id - * @param packet_ptr [out] Pointer to pointer of data to set - * @param size [out] Pointer to size to set - * @return - */ - virtual ReturnValue_t modifyData(store_address_t packet_id, - uint8_t** packet_ptr, size_t* size) = 0; - /** - * This method reserves an element of @c size. - * - * It returns the packet id of this element as well as a direct pointer to the - * data of the element. It must be assured that exactly @c size data is - * written to p_data! - * @param storageId A pointer to the storageId to retrieve. - * @param size The size of the space to be reserved. - * @param p_data A pointer to the element data is returned here. - * @return Returns @li RETURN_OK if data was added. - * @li RETURN_FAILED if data could not be added. - * storageId is unchanged then. - */ - virtual ReturnValue_t getFreeElement(store_address_t* storageId, - const size_t size, uint8_t** p_data, bool ignoreFault = false ) = 0; + /** + * Get the fill count of the pool. Each character inside the provided + * buffer will be assigned to a rounded percentage fill count for each + * page. The last written byte (at the index bytesWritten - 1) + * will contain the total fill count of the pool as a mean of the + * percentages of single pages. + * @param buffer + * @param maxSize + */ + virtual void getFillCount(uint8_t* buffer, uint8_t* bytesWritten) = 0; - /** - * Clears the whole store. - * Use with care! - */ - virtual void clearStore() = 0; + virtual size_t getTotalSize(size_t* additionalSize) = 0; - /** - * Clears a pool in the store with the given pool index. Use with care! - * @param pageIndex - */ - virtual void clearSubPool(uint8_t poolIndex) = 0; - - /** - * Get the fill count of the pool. Each character inside the provided - * buffer will be assigned to a rounded percentage fill count for each - * page. The last written byte (at the index bytesWritten - 1) - * will contain the total fill count of the pool as a mean of the - * percentages of single pages. - * @param buffer - * @param maxSize - */ - virtual void getFillCount(uint8_t* buffer, uint8_t* bytesWritten) = 0; - - virtual size_t getTotalSize(size_t* additionalSize) = 0; - - /** - * Get number of pools. - * @return - */ - virtual max_subpools_t getNumberOfSubPools() const = 0; + /** + * Get number of pools. + * @return + */ + virtual max_subpools_t getNumberOfSubPools() const = 0; }; #endif /* FSFW_STORAGEMANAGER_STORAGEMANAGERIF_H_ */ diff --git a/src/fsfw/storagemanager/storeAddress.h b/src/fsfw/storagemanager/storeAddress.h index ea72f6f8..41f70573 100644 --- a/src/fsfw/storagemanager/storeAddress.h +++ b/src/fsfw/storagemanager/storeAddress.h @@ -13,48 +13,45 @@ static constexpr uint32_t INVALID_STORE_ADDRESS = 0xffffffff; * a structured part to use it in pool-like stores. */ union store_address_t { + /** + * Default Constructor, initializing to INVALID_ADDRESS + */ + store_address_t() : raw(storeId::INVALID_STORE_ADDRESS) {} + /** + * Constructor to create an address object using the raw address + * + * @param rawAddress + */ + store_address_t(uint32_t rawAddress) : raw(rawAddress) {} - /** - * Default Constructor, initializing to INVALID_ADDRESS - */ - store_address_t(): raw(storeId::INVALID_STORE_ADDRESS){} - /** - * Constructor to create an address object using the raw address - * - * @param rawAddress - */ - store_address_t(uint32_t rawAddress):raw(rawAddress){} + /** + * Constructor to create an address object using pool + * and packet indices + * + * @param poolIndex + * @param packetIndex + */ + store_address_t(uint16_t poolIndex, uint16_t packetIndex) + : poolIndex(poolIndex), packetIndex(packetIndex) {} + /** + * A structure with two elements to access the store address pool-like. + */ + struct { + /** + * The index in which pool the packet lies. + */ + uint16_t poolIndex; + /** + * The position in the chosen pool. + */ + uint16_t packetIndex; + }; + /** + * Alternative access to the raw value. + */ + uint32_t raw; - /** - * Constructor to create an address object using pool - * and packet indices - * - * @param poolIndex - * @param packetIndex - */ - store_address_t(uint16_t poolIndex, uint16_t packetIndex): - poolIndex(poolIndex), packetIndex(packetIndex){} - /** - * A structure with two elements to access the store address pool-like. - */ - struct { - /** - * The index in which pool the packet lies. - */ - uint16_t poolIndex; - /** - * The position in the chosen pool. - */ - uint16_t packetIndex; - }; - /** - * Alternative access to the raw value. - */ - uint32_t raw; - - bool operator==(const store_address_t& other) const { - return raw == other.raw; - } + bool operator==(const store_address_t& other) const { return raw == other.raw; } }; #endif /* FSFW_STORAGEMANAGER_STOREADDRESS_H_ */ diff --git a/src/fsfw/subsystem/Subsystem.cpp b/src/fsfw/subsystem/Subsystem.cpp index 0c8e3f35..a837bf83 100644 --- a/src/fsfw/subsystem/Subsystem.cpp +++ b/src/fsfw/subsystem/Subsystem.cpp @@ -1,661 +1,607 @@ #include "fsfw/subsystem/Subsystem.h" +#include + #include "fsfw/health/HealthMessage.h" #include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/serialize/SerialArrayListAdapter.h" #include "fsfw/serialize/SerialFixedArrayListAdapter.h" -#include "fsfw/serialize/SerializeElement.h" #include "fsfw/serialize/SerialLinkedListAdapter.h" +#include "fsfw/serialize/SerializeElement.h" -#include - -Subsystem::Subsystem(object_id_t setObjectId, object_id_t parent, - uint32_t maxNumberOfSequences, uint32_t maxNumberOfTables) : - SubsystemBase(setObjectId, parent, 0), isInTransition(false), - childrenChangedHealth(false), currentTargetTable(), - targetSubmode(SUBMODE_NONE), currentSequenceIterator(), - modeTables(maxNumberOfTables), modeSequences(maxNumberOfSequences) {} +Subsystem::Subsystem(object_id_t setObjectId, object_id_t parent, uint32_t maxNumberOfSequences, + uint32_t maxNumberOfTables) + : SubsystemBase(setObjectId, parent, 0), + isInTransition(false), + childrenChangedHealth(false), + currentTargetTable(), + targetSubmode(SUBMODE_NONE), + currentSequenceIterator(), + modeTables(maxNumberOfTables), + modeSequences(maxNumberOfSequences) {} Subsystem::~Subsystem() {} ReturnValue_t Subsystem::checkSequence(HybridIterator iter, - Mode_t fallbackSequence) { + Mode_t fallbackSequence) { + // only check for existence, checking the fallback would lead to a (possibly infinite) recursion. + // the fallback sequence will be checked when it is needed. + if (!existsModeSequence(fallbackSequence)) { + return FALLBACK_SEQUENCE_DOES_NOT_EXIST; + } - //only check for existence, checking the fallback would lead to a (possibly infinite) recursion. - //the fallback sequence will be checked when it is needed. - if (!existsModeSequence(fallbackSequence)) { - return FALLBACK_SEQUENCE_DOES_NOT_EXIST; - } + if (iter.value == NULL) { + return NO_TARGET_TABLE; + } - if (iter.value == NULL) { - return NO_TARGET_TABLE; - } - - for (; iter.value != NULL; ++iter) { - if (!existsModeTable(iter->getTableId())) { - return TABLE_DOES_NOT_EXIST; - } else { - ReturnValue_t result = checkTable(getTable(iter->getTableId())); - if (result != RETURN_OK) { - return result; - } - } - } - return RETURN_OK; + for (; iter.value != NULL; ++iter) { + if (!existsModeTable(iter->getTableId())) { + return TABLE_DOES_NOT_EXIST; + } else { + ReturnValue_t result = checkTable(getTable(iter->getTableId())); + if (result != RETURN_OK) { + return result; + } + } + } + return RETURN_OK; } ReturnValue_t Subsystem::checkSequence(Mode_t sequence) { - if (!existsModeSequence(sequence)) { - return SEQUENCE_DOES_NOT_EXIST; - } - HybridIterator iter = getSequence(sequence); - return checkSequence(iter, getFallbackSequence(sequence)); + if (!existsModeSequence(sequence)) { + return SEQUENCE_DOES_NOT_EXIST; + } + HybridIterator iter = getSequence(sequence); + return checkSequence(iter, getFallbackSequence(sequence)); } -bool Subsystem::existsModeSequence(Mode_t id) { - return modeSequences.exists(id) == RETURN_OK; -} +bool Subsystem::existsModeSequence(Mode_t id) { return modeSequences.exists(id) == RETURN_OK; } -bool Subsystem::existsModeTable(Mode_t id) { - return modeTables.exists(id) == RETURN_OK; -} +bool Subsystem::existsModeTable(Mode_t id) { return modeTables.exists(id) == RETURN_OK; } HybridIterator Subsystem::getCurrentTable() { - return getTable(currentSequenceIterator->getTableId()); + return getTable(currentSequenceIterator->getTableId()); } void Subsystem::performChildOperation() { - if (isInTransition) { - if (commandsOutstanding <= 0) { //all children of the current table were commanded and replied - if (currentSequenceIterator.value == NULL) { //we're through with this sequence - if (checkStateAgainstTable(currentTargetTable, targetSubmode) - == RETURN_OK) { - setMode(targetMode, targetSubmode); - isInTransition = false; - return; - } else { - transitionFailed(TARGET_TABLE_NOT_REACHED, - getSequence(targetMode)->getTableId()); - return; - } - } - if (currentSequenceIterator->checkSuccess()) { - if (checkStateAgainstTable(getCurrentTable(), targetSubmode) - != RETURN_OK) { - transitionFailed(TABLE_CHECK_FAILED, - currentSequenceIterator->getTableId()); - return; - } - } - if (currentSequenceIterator->getWaitSeconds() != 0) { - if (uptimeStartTable == 0) { - Clock::getUptime(&uptimeStartTable); - return; - } else { - uint32_t uptimeNow; - Clock::getUptime(&uptimeNow); - if ((uptimeNow - uptimeStartTable) - < (currentSequenceIterator->getWaitSeconds() * 1000)) { - return; - } - } - } - uptimeStartTable = 0; - //next Table, but only if there is one - if ((++currentSequenceIterator).value != NULL) { //we're through with this sequence - executeTable(getCurrentTable(), targetSubmode); - } - } - } else { - if (childrenChangedHealth) { - triggerEvent(CHILD_CHANGED_HEALTH, 0, 0); - childrenChangedHealth = false; - startTransition(mode, submode); - } else if (childrenChangedMode) { - if (checkStateAgainstTable(currentTargetTable, submode) - != RETURN_OK) { - triggerEvent(CANT_KEEP_MODE, mode, submode); - cantKeepMode(); - } - } - } + if (isInTransition) { + if (commandsOutstanding <= 0) { // all children of the current table were commanded and replied + if (currentSequenceIterator.value == NULL) { // we're through with this sequence + if (checkStateAgainstTable(currentTargetTable, targetSubmode) == RETURN_OK) { + setMode(targetMode, targetSubmode); + isInTransition = false; + return; + } else { + transitionFailed(TARGET_TABLE_NOT_REACHED, getSequence(targetMode)->getTableId()); + return; + } + } + if (currentSequenceIterator->checkSuccess()) { + if (checkStateAgainstTable(getCurrentTable(), targetSubmode) != RETURN_OK) { + transitionFailed(TABLE_CHECK_FAILED, currentSequenceIterator->getTableId()); + return; + } + } + if (currentSequenceIterator->getWaitSeconds() != 0) { + if (uptimeStartTable == 0) { + Clock::getUptime(&uptimeStartTable); + return; + } else { + uint32_t uptimeNow; + Clock::getUptime(&uptimeNow); + if ((uptimeNow - uptimeStartTable) < (currentSequenceIterator->getWaitSeconds() * 1000)) { + return; + } + } + } + uptimeStartTable = 0; + // next Table, but only if there is one + if ((++currentSequenceIterator).value != NULL) { // we're through with this sequence + executeTable(getCurrentTable(), targetSubmode); + } + } + } else { + if (childrenChangedHealth) { + triggerEvent(CHILD_CHANGED_HEALTH, 0, 0); + childrenChangedHealth = false; + startTransition(mode, submode); + } else if (childrenChangedMode) { + if (checkStateAgainstTable(currentTargetTable, submode) != RETURN_OK) { + triggerEvent(CANT_KEEP_MODE, mode, submode); + cantKeepMode(); + } + } + } } HybridIterator Subsystem::getSequence(Mode_t id) { - SequenceInfo *sequenceInfo = modeSequences.findValue(id); - if (sequenceInfo->entries.islinked) { - return HybridIterator( - sequenceInfo->entries.firstLinkedElement); - } else { - return HybridIterator( - sequenceInfo->entries.array->front(), - sequenceInfo->entries.array->back()); - } + SequenceInfo *sequenceInfo = modeSequences.findValue(id); + if (sequenceInfo->entries.islinked) { + return HybridIterator(sequenceInfo->entries.firstLinkedElement); + } else { + return HybridIterator(sequenceInfo->entries.array->front(), + sequenceInfo->entries.array->back()); + } } HybridIterator Subsystem::getTable(Mode_t id) { - EntryPointer *entry = modeTables.findValue(id); - if (entry->islinked) { - return HybridIterator(entry->firstLinkedElement); - } else { - return HybridIterator(entry->array->front(), - entry->array->back()); - } + EntryPointer *entry = modeTables.findValue(id); + if (entry->islinked) { + return HybridIterator(entry->firstLinkedElement); + } else { + return HybridIterator(entry->array->front(), entry->array->back()); + } } ReturnValue_t Subsystem::handleCommandMessage(CommandMessage *message) { - switch (message->getCommand()) { - case HealthMessage::HEALTH_INFO: { - HealthState health = HealthMessage::getHealth(message); - if (health != EXTERNAL_CONTROL) { - //Ignore external control, as it has an effect only if the mode changes, - //which is communicated with an additional mode info event. - childrenChangedHealth = true; - } - } - break; - case ModeSequenceMessage::ADD_SEQUENCE: { - FixedArrayList sequence; - const uint8_t *pointer; - size_t sizeRead; - ReturnValue_t result = IPCStore->getData( - ModeSequenceMessage::getStoreAddress(message), &pointer, - &sizeRead); - if (result == RETURN_OK) { - Mode_t fallbackId; - size_t size = sizeRead; - result = SerializeAdapter::deSerialize(&fallbackId, &pointer, &size, - SerializeIF::Endianness::BIG); - if (result == RETURN_OK) { - result = SerialArrayListAdapter::deSerialize( - &sequence, &pointer, &size, - SerializeIF::Endianness::BIG); - if (result == RETURN_OK) { - result = addSequence(&sequence, - ModeSequenceMessage::getSequenceId(message), - fallbackId); - } - } - IPCStore->deleteData(ModeSequenceMessage::getStoreAddress(message)); - } - replyToCommand(result, 0); - } - break; - case ModeSequenceMessage::ADD_TABLE: { - FixedArrayList table; - const uint8_t *pointer; - size_t sizeRead; - ReturnValue_t result = IPCStore->getData( - ModeSequenceMessage::getStoreAddress(message), &pointer, - &sizeRead); - if (result == RETURN_OK) { - size_t size = sizeRead; - result = SerialArrayListAdapter::deSerialize(&table, - &pointer, &size, SerializeIF::Endianness::BIG); - if (result == RETURN_OK) { - result = addTable(&table, - ModeSequenceMessage::getSequenceId(message)); - } - IPCStore->deleteData(ModeSequenceMessage::getStoreAddress(message)); - } - replyToCommand(result, 0); + switch (message->getCommand()) { + case HealthMessage::HEALTH_INFO: { + HealthState health = HealthMessage::getHealth(message); + if (health != EXTERNAL_CONTROL) { + // Ignore external control, as it has an effect only if the mode changes, + // which is communicated with an additional mode info event. + childrenChangedHealth = true; + } + } break; + case ModeSequenceMessage::ADD_SEQUENCE: { + FixedArrayList sequence; + const uint8_t *pointer; + size_t sizeRead; + ReturnValue_t result = + IPCStore->getData(ModeSequenceMessage::getStoreAddress(message), &pointer, &sizeRead); + if (result == RETURN_OK) { + Mode_t fallbackId; + size_t size = sizeRead; + result = SerializeAdapter::deSerialize(&fallbackId, &pointer, &size, + SerializeIF::Endianness::BIG); + if (result == RETURN_OK) { + result = SerialArrayListAdapter::deSerialize(&sequence, &pointer, &size, + SerializeIF::Endianness::BIG); + if (result == RETURN_OK) { + result = + addSequence(&sequence, ModeSequenceMessage::getSequenceId(message), fallbackId); + } + } + IPCStore->deleteData(ModeSequenceMessage::getStoreAddress(message)); + } + replyToCommand(result, 0); + } break; + case ModeSequenceMessage::ADD_TABLE: { + FixedArrayList table; + const uint8_t *pointer; + size_t sizeRead; + ReturnValue_t result = + IPCStore->getData(ModeSequenceMessage::getStoreAddress(message), &pointer, &sizeRead); + if (result == RETURN_OK) { + size_t size = sizeRead; + result = SerialArrayListAdapter::deSerialize(&table, &pointer, &size, + SerializeIF::Endianness::BIG); + if (result == RETURN_OK) { + result = addTable(&table, ModeSequenceMessage::getSequenceId(message)); + } + IPCStore->deleteData(ModeSequenceMessage::getStoreAddress(message)); + } + replyToCommand(result, 0); - } - break; - case ModeSequenceMessage::DELETE_SEQUENCE:{ - if (isInTransition) { - replyToCommand(IN_TRANSITION, 0); - break; - } - ReturnValue_t result = deleteSequence(ModeSequenceMessage::getSequenceId(message)); - replyToCommand(result, 0); - } - break; - case ModeSequenceMessage::DELETE_TABLE:{ - if (isInTransition) { - replyToCommand(IN_TRANSITION, 0); - break; - } - ReturnValue_t result = deleteTable(ModeSequenceMessage::getTableId(message)); - replyToCommand(result, 0); - } - break; - case ModeSequenceMessage::LIST_SEQUENCES: { - SerialFixedArrayListAdapter sequences; - FixedMap::Iterator iter; - for (iter = modeSequences.begin(); iter != modeSequences.end(); - ++iter) { - sequences.insert(iter.value->first); - } - SerializeIF *pointer = &sequences; - sendSerializablesAsCommandMessage(ModeSequenceMessage::SEQUENCE_LIST, - &pointer, 1); - } - break; - case ModeSequenceMessage::LIST_TABLES: { - SerialFixedArrayListAdapter tables; - FixedMap::Iterator iter; - for (iter = modeTables.begin(); iter != modeTables.end(); ++iter) { - tables.insert(iter.value->first); - } - SerializeIF *pointer = &tables; - sendSerializablesAsCommandMessage(ModeSequenceMessage::TABLE_LIST, - &pointer, 1); - } - break; - case ModeSequenceMessage::READ_SEQUENCE: { - ReturnValue_t result; - Mode_t sequence = ModeSequenceMessage::getSequenceId(message); - SequenceInfo *sequenceInfo = NULL; - result = modeSequences.find(sequence, &sequenceInfo); - if (result != RETURN_OK) { - replyToCommand(result, 0); - } + } break; + case ModeSequenceMessage::DELETE_SEQUENCE: { + if (isInTransition) { + replyToCommand(IN_TRANSITION, 0); + break; + } + ReturnValue_t result = deleteSequence(ModeSequenceMessage::getSequenceId(message)); + replyToCommand(result, 0); + } break; + case ModeSequenceMessage::DELETE_TABLE: { + if (isInTransition) { + replyToCommand(IN_TRANSITION, 0); + break; + } + ReturnValue_t result = deleteTable(ModeSequenceMessage::getTableId(message)); + replyToCommand(result, 0); + } break; + case ModeSequenceMessage::LIST_SEQUENCES: { + SerialFixedArrayListAdapter sequences; + FixedMap::Iterator iter; + for (iter = modeSequences.begin(); iter != modeSequences.end(); ++iter) { + sequences.insert(iter.value->first); + } + SerializeIF *pointer = &sequences; + sendSerializablesAsCommandMessage(ModeSequenceMessage::SEQUENCE_LIST, &pointer, 1); + } break; + case ModeSequenceMessage::LIST_TABLES: { + SerialFixedArrayListAdapter tables; + FixedMap::Iterator iter; + for (iter = modeTables.begin(); iter != modeTables.end(); ++iter) { + tables.insert(iter.value->first); + } + SerializeIF *pointer = &tables; + sendSerializablesAsCommandMessage(ModeSequenceMessage::TABLE_LIST, &pointer, 1); + } break; + case ModeSequenceMessage::READ_SEQUENCE: { + ReturnValue_t result; + Mode_t sequence = ModeSequenceMessage::getSequenceId(message); + SequenceInfo *sequenceInfo = NULL; + result = modeSequences.find(sequence, &sequenceInfo); + if (result != RETURN_OK) { + replyToCommand(result, 0); + } - SerializeIF *elements[3]; - SerializeElement sequenceId(sequence); - SerializeElement fallbackSequenceId( - getFallbackSequence(sequence)); + SerializeIF *elements[3]; + SerializeElement sequenceId(sequence); + SerializeElement fallbackSequenceId(getFallbackSequence(sequence)); - elements[0] = &sequenceId; - elements[1] = &fallbackSequenceId; + elements[0] = &sequenceId; + elements[1] = &fallbackSequenceId; - if (sequenceInfo->entries.islinked) { - SerialLinkedListAdapter list( - sequenceInfo->entries.firstLinkedElement, true); - elements[2] = &list; - sendSerializablesAsCommandMessage(ModeSequenceMessage::SEQUENCE, - elements, 3); - } else { - SerialArrayListAdapter serializableArray( - sequenceInfo->entries.array); + if (sequenceInfo->entries.islinked) { + SerialLinkedListAdapter list(sequenceInfo->entries.firstLinkedElement, true); + elements[2] = &list; + sendSerializablesAsCommandMessage(ModeSequenceMessage::SEQUENCE, elements, 3); + } else { + SerialArrayListAdapter serializableArray(sequenceInfo->entries.array); - elements[2] = &serializableArray; - sendSerializablesAsCommandMessage(ModeSequenceMessage::SEQUENCE, - elements, 3); - } - } - break; - case ModeSequenceMessage::READ_TABLE: { - ReturnValue_t result; - Mode_t table = ModeSequenceMessage::getSequenceId(message); - EntryPointer *entry = NULL; - result = modeTables.find(table, &entry); - if (result != RETURN_OK) { - replyToCommand(result, 0); - } + elements[2] = &serializableArray; + sendSerializablesAsCommandMessage(ModeSequenceMessage::SEQUENCE, elements, 3); + } + } break; + case ModeSequenceMessage::READ_TABLE: { + ReturnValue_t result; + Mode_t table = ModeSequenceMessage::getSequenceId(message); + EntryPointer *entry = NULL; + result = modeTables.find(table, &entry); + if (result != RETURN_OK) { + replyToCommand(result, 0); + } - SerializeIF *elements[2]; - SerializeElement tableId(table); + SerializeIF *elements[2]; + SerializeElement tableId(table); - elements[0] = &tableId; + elements[0] = &tableId; - if (entry->islinked) { - SerialLinkedListAdapter list( - entry->firstLinkedElement, true); - elements[1] = &list; - sendSerializablesAsCommandMessage(ModeSequenceMessage::TABLE, - elements, 2); - } else { - SerialArrayListAdapter serializableArray( - entry->array); - elements[1] = &serializableArray; - sendSerializablesAsCommandMessage(ModeSequenceMessage::TABLE, - elements, 2); - } - } - break; - case ModeSequenceMessage::READ_FREE_SEQUENCE_SLOTS: { - uint32_t freeSlots = modeSequences.maxSize() - modeSequences.size(); - CommandMessage reply; - ModeSequenceMessage::setModeSequenceMessage(&reply, - ModeSequenceMessage::FREE_SEQUENCE_SLOTS, freeSlots); - commandQueue->reply(&reply); - } - break; - case ModeSequenceMessage::READ_FREE_TABLE_SLOTS: { - uint32_t free = modeTables.maxSize() - modeTables.size(); - CommandMessage reply; - ModeSequenceMessage::setModeSequenceMessage(&reply, - ModeSequenceMessage::FREE_TABLE_SLOTS, free); - commandQueue->reply(&reply); - } - break; - default: - return RETURN_FAILED; - } - return RETURN_OK; + if (entry->islinked) { + SerialLinkedListAdapter list(entry->firstLinkedElement, true); + elements[1] = &list; + sendSerializablesAsCommandMessage(ModeSequenceMessage::TABLE, elements, 2); + } else { + SerialArrayListAdapter serializableArray(entry->array); + elements[1] = &serializableArray; + sendSerializablesAsCommandMessage(ModeSequenceMessage::TABLE, elements, 2); + } + } break; + case ModeSequenceMessage::READ_FREE_SEQUENCE_SLOTS: { + uint32_t freeSlots = modeSequences.maxSize() - modeSequences.size(); + CommandMessage reply; + ModeSequenceMessage::setModeSequenceMessage(&reply, ModeSequenceMessage::FREE_SEQUENCE_SLOTS, + freeSlots); + commandQueue->reply(&reply); + } break; + case ModeSequenceMessage::READ_FREE_TABLE_SLOTS: { + uint32_t free = modeTables.maxSize() - modeTables.size(); + CommandMessage reply; + ModeSequenceMessage::setModeSequenceMessage(&reply, ModeSequenceMessage::FREE_TABLE_SLOTS, + free); + commandQueue->reply(&reply); + } break; + default: + return RETURN_FAILED; + } + return RETURN_OK; } void Subsystem::replyToCommand(ReturnValue_t status, uint32_t parameter) { - if (status == RETURN_OK) { - CommandMessage reply(CommandMessage::REPLY_COMMAND_OK, 0, 0); - commandQueue->reply(&reply); - } else { - CommandMessage reply(CommandMessage::REPLY_REJECTED, status, 0); - commandQueue->reply(&reply); - } + if (status == RETURN_OK) { + CommandMessage reply(CommandMessage::REPLY_COMMAND_OK, 0, 0); + commandQueue->reply(&reply); + } else { + CommandMessage reply(CommandMessage::REPLY_REJECTED, status, 0); + commandQueue->reply(&reply); + } } -ReturnValue_t Subsystem::addSequence(ArrayList *sequence, - Mode_t id, Mode_t fallbackSequence, bool inStore, bool preInit) { +ReturnValue_t Subsystem::addSequence(ArrayList *sequence, Mode_t id, + Mode_t fallbackSequence, bool inStore, bool preInit) { + ReturnValue_t result; - ReturnValue_t result; + // Before initialize() is called, tables must not be checked as the + // children are not added yet. + // Sequences added before are checked by initialize() + if (!preInit) { + result = checkSequence(HybridIterator(sequence->front(), sequence->back()), + fallbackSequence); + if (result != RETURN_OK) { + return result; + } + } - //Before initialize() is called, tables must not be checked as the - //children are not added yet. - //Sequences added before are checked by initialize() - if (!preInit) { - result = checkSequence( - HybridIterator(sequence->front(), - sequence->back()), fallbackSequence); - if (result != RETURN_OK) { - return result; - } - } + SequenceInfo info; - SequenceInfo info; + info.fallbackSequence = fallbackSequence; - info.fallbackSequence = fallbackSequence; + info.entries.islinked = inStore; + info.entries.array = sequence; - info.entries.islinked = inStore; - info.entries.array = sequence; + result = modeSequences.insert(id, info); - result = modeSequences.insert(id, info); + if (result != RETURN_OK) { + return result; + } - if (result != RETURN_OK) { - return result; - } - - if (inStore) { + if (inStore) { #if FSFW_USE_MODESTORE == 1 - result = modeStore->storeArray(sequence, - &(modeSequences.find(id)->entries.firstLinkedElement)); - if (result != RETURN_OK) { - modeSequences.erase(id); - } + result = modeStore->storeArray(sequence, &(modeSequences.find(id)->entries.firstLinkedElement)); + if (result != RETURN_OK) { + modeSequences.erase(id); + } #else - modeSequences.erase(id); - return RETURN_FAILED; + modeSequences.erase(id); + return RETURN_FAILED; #endif - } - - return result; + } + return result; } -ReturnValue_t Subsystem::addTable(ArrayList *table, Mode_t id, - bool inStore, bool preInit) { +ReturnValue_t Subsystem::addTable(ArrayList *table, Mode_t id, bool inStore, + bool preInit) { + ReturnValue_t result; - ReturnValue_t result; + // Before initialize() is called, tables must not be checked as the children + // are not added yet. Tables added before are checked by initialize() + if (!preInit) { + result = checkTable(HybridIterator(table->front(), table->back())); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + } - //Before initialize() is called, tables must not be checked as the children - //are not added yet. Tables added before are checked by initialize() - if (!preInit) { - result = checkTable( - HybridIterator(table->front(), table->back())); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - } + EntryPointer pointer; - EntryPointer pointer; + pointer.islinked = inStore; + pointer.array = table; - pointer.islinked = inStore; - pointer.array = table; + result = modeTables.insert(id, pointer); - result = modeTables.insert(id, pointer); + if (result != RETURN_OK) { + return result; + } - if (result != RETURN_OK) { - return result; - } - - if (inStore) { + if (inStore) { #if FSFW_USE_MODESTORE == 1 - result = modeStore->storeArray(table, - &(modeTables.find(id)->firstLinkedElement)); - if (result != RETURN_OK) { - modeTables.erase(id); - } + result = modeStore->storeArray(table, &(modeTables.find(id)->firstLinkedElement)); + if (result != RETURN_OK) { + modeTables.erase(id); + } #else - modeTables.erase(id); - return RETURN_FAILED; + modeTables.erase(id); + return RETURN_FAILED; #endif - } - return result; + } + return result; } ReturnValue_t Subsystem::deleteSequence(Mode_t id) { + if (isFallbackSequence(id)) { + return IS_FALLBACK_SEQUENCE; + } - if (isFallbackSequence(id)) { - return IS_FALLBACK_SEQUENCE; - } - - SequenceInfo *sequenceInfo; - ReturnValue_t result; - result = modeSequences.find(id, &sequenceInfo); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if (!sequenceInfo->entries.islinked) { - return ACCESS_DENIED; - } + SequenceInfo *sequenceInfo; + ReturnValue_t result; + result = modeSequences.find(id, &sequenceInfo); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (!sequenceInfo->entries.islinked) { + return ACCESS_DENIED; + } #if FSFW_USE_MODESTORE == 1 - modeStore->deleteList(sequenceInfo->entries.firstLinkedElement); + modeStore->deleteList(sequenceInfo->entries.firstLinkedElement); #endif - modeSequences.erase(id); - return RETURN_OK; + modeSequences.erase(id); + return RETURN_OK; } ReturnValue_t Subsystem::deleteTable(Mode_t id) { + if (isTableUsed(id)) { + return TABLE_IN_USE; + } - if (isTableUsed(id)) { - return TABLE_IN_USE; - } - - EntryPointer *pointer; - ReturnValue_t result; - result = modeTables.find(id, &pointer); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if (!pointer->islinked) { - return ACCESS_DENIED; - } + EntryPointer *pointer; + ReturnValue_t result; + result = modeTables.find(id, &pointer); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (!pointer->islinked) { + return ACCESS_DENIED; + } #if FSFW_USE_MODESTORE == 1 - modeStore->deleteList(pointer->firstLinkedElement); + modeStore->deleteList(pointer->firstLinkedElement); #endif - modeSequences.erase(id); - return RETURN_OK; + modeSequences.erase(id); + return RETURN_OK; } ReturnValue_t Subsystem::initialize() { - ReturnValue_t result = SubsystemBase::initialize(); + ReturnValue_t result = SubsystemBase::initialize(); - if (result != RETURN_OK) { - return result; - } + if (result != RETURN_OK) { + return result; + } - IPCStore = ObjectManager::instance()->get(objects::IPC_STORE); - if (IPCStore == NULL) { - return RETURN_FAILED; - } + IPCStore = ObjectManager::instance()->get(objects::IPC_STORE); + if (IPCStore == NULL) { + return RETURN_FAILED; + } #if FSFW_USE_MODESTORE == 1 - modeStore = ObjectManager::instance()->get(objects::MODE_STORE); + modeStore = ObjectManager::instance()->get(objects::MODE_STORE); - if (modeStore == nullptr) { - return RETURN_FAILED; - } + if (modeStore == nullptr) { + return RETURN_FAILED; + } #endif - if ((modeSequences.maxSize() > MAX_NUMBER_OF_TABLES_OR_SEQUENCES) - || (modeTables.maxSize() > MAX_NUMBER_OF_TABLES_OR_SEQUENCES)) { - return TABLE_OR_SEQUENCE_LENGTH_INVALID; - } + if ((modeSequences.maxSize() > MAX_NUMBER_OF_TABLES_OR_SEQUENCES) || + (modeTables.maxSize() > MAX_NUMBER_OF_TABLES_OR_SEQUENCES)) { + return TABLE_OR_SEQUENCE_LENGTH_INVALID; + } - mode = initialMode; + mode = initialMode; - return RETURN_OK; + return RETURN_OK; } MessageQueueId_t Subsystem::getSequenceCommandQueue() const { - return SubsystemBase::getCommandQueue(); + return SubsystemBase::getCommandQueue(); } ReturnValue_t Subsystem::checkModeCommand(Mode_t mode, Submode_t submode, - uint32_t *msToReachTheMode) { - //Need to accept all submodes to be able to inherit submodes -// if (submode != SUBMODE_NONE) { -// return INVALID_SUBMODE; -// } + uint32_t *msToReachTheMode) { + // Need to accept all submodes to be able to inherit submodes + // if (submode != SUBMODE_NONE) { + // return INVALID_SUBMODE; + // } - if (isInTransition && (mode != getFallbackSequence(targetMode))) { - return HasModesIF::IN_TRANSITION; - } else { - return checkSequence(mode); - } + if (isInTransition && (mode != getFallbackSequence(targetMode))) { + return HasModesIF::IN_TRANSITION; + } else { + return checkSequence(mode); + } } void Subsystem::startTransition(Mode_t sequence, Submode_t submode) { - if (modeHelper.isForced()) { - triggerEvent(FORCING_MODE, sequence, submode); - } else { - triggerEvent(CHANGING_MODE, sequence, submode); - } - targetMode = sequence; - targetSubmode = submode; - isInTransition = true; - commandsOutstanding = 0; - currentSequenceIterator = getSequence(sequence); + if (modeHelper.isForced()) { + triggerEvent(FORCING_MODE, sequence, submode); + } else { + triggerEvent(CHANGING_MODE, sequence, submode); + } + targetMode = sequence; + targetSubmode = submode; + isInTransition = true; + commandsOutstanding = 0; + currentSequenceIterator = getSequence(sequence); - currentTargetTable = getTable(currentSequenceIterator->getTableId()); + currentTargetTable = getTable(currentSequenceIterator->getTableId()); - ++currentSequenceIterator; + ++currentSequenceIterator; - if (currentSequenceIterator.value != NULL) { - executeTable(getCurrentTable(), targetSubmode); - } + if (currentSequenceIterator.value != NULL) { + executeTable(getCurrentTable(), targetSubmode); + } } Mode_t Subsystem::getFallbackSequence(Mode_t sequence) { - for (FixedMap::Iterator iter = modeSequences.begin(); - iter != modeSequences.end(); ++iter) { - if (iter.value->first == sequence) { - return iter->second.fallbackSequence; - } - } - return -1; + for (FixedMap::Iterator iter = modeSequences.begin(); + iter != modeSequences.end(); ++iter) { + if (iter.value->first == sequence) { + return iter->second.fallbackSequence; + } + } + return -1; } bool Subsystem::isFallbackSequence(Mode_t SequenceId) { - for (FixedMap::Iterator iter = modeSequences.begin(); - iter != modeSequences.end(); iter++) { - if (iter->second.fallbackSequence == SequenceId) { - return true; - } - } - return false; + for (FixedMap::Iterator iter = modeSequences.begin(); + iter != modeSequences.end(); iter++) { + if (iter->second.fallbackSequence == SequenceId) { + return true; + } + } + return false; } bool Subsystem::isTableUsed(Mode_t tableId) { - for (FixedMap::Iterator sequence = - modeSequences.begin(); sequence != modeSequences.end(); - sequence++) { - HybridIterator sequenceIterator = getSequence( - sequence.value->first); - while (sequenceIterator.value != NULL) { - if (sequenceIterator->getTableId() == tableId) { - return true; - } - ++sequenceIterator; - } - } - return false; + for (FixedMap::Iterator sequence = modeSequences.begin(); + sequence != modeSequences.end(); sequence++) { + HybridIterator sequenceIterator = getSequence(sequence.value->first); + while (sequenceIterator.value != NULL) { + if (sequenceIterator->getTableId() == tableId) { + return true; + } + ++sequenceIterator; + } + } + return false; } -void Subsystem::transitionFailed(ReturnValue_t failureCode, - uint32_t parameter) { - triggerEvent(MODE_TRANSITION_FAILED, failureCode, parameter); - if (mode == targetMode) { - //already tried going back to the current mode - //go into fallback mode, also set current mode to fallback mode, - //so we come here at the next fail - modeHelper.setForced(true); - ReturnValue_t result; - if ((result = checkSequence(getFallbackSequence(mode))) != RETURN_OK) { - triggerEvent(FALLBACK_FAILED, result, getFallbackSequence(mode)); - //keep still and allow arbitrary mode commands to recover - isInTransition = false; - return; - } - mode = getFallbackSequence(mode); - startTransition(mode, submode); - } else { - //try to go back to the current mode - startTransition(mode, submode); - } +void Subsystem::transitionFailed(ReturnValue_t failureCode, uint32_t parameter) { + triggerEvent(MODE_TRANSITION_FAILED, failureCode, parameter); + if (mode == targetMode) { + // already tried going back to the current mode + // go into fallback mode, also set current mode to fallback mode, + // so we come here at the next fail + modeHelper.setForced(true); + ReturnValue_t result; + if ((result = checkSequence(getFallbackSequence(mode))) != RETURN_OK) { + triggerEvent(FALLBACK_FAILED, result, getFallbackSequence(mode)); + // keep still and allow arbitrary mode commands to recover + isInTransition = false; + return; + } + mode = getFallbackSequence(mode); + startTransition(mode, submode); + } else { + // try to go back to the current mode + startTransition(mode, submode); + } } -void Subsystem::sendSerializablesAsCommandMessage(Command_t command, - SerializeIF **elements, uint8_t count) { - ReturnValue_t result; - size_t maxSize = 0; - for (uint8_t i = 0; i < count; i++) { - maxSize += elements[i]->getSerializedSize(); - } - uint8_t *storeBuffer; - store_address_t address; - size_t size = 0; +void Subsystem::sendSerializablesAsCommandMessage(Command_t command, SerializeIF **elements, + uint8_t count) { + ReturnValue_t result; + size_t maxSize = 0; + for (uint8_t i = 0; i < count; i++) { + maxSize += elements[i]->getSerializedSize(); + } + uint8_t *storeBuffer; + store_address_t address; + size_t size = 0; - result = IPCStore->getFreeElement(&address, maxSize, &storeBuffer); - if (result != HasReturnvaluesIF::RETURN_OK) { - replyToCommand(result, 0); - return; - } - for (uint8_t i = 0; i < count; i++) { - elements[i]->serialize(&storeBuffer, &size, maxSize, - SerializeIF::Endianness::BIG); - } - CommandMessage reply; - ModeSequenceMessage::setModeSequenceMessage(&reply, command, address); - if (commandQueue->reply(&reply) != RETURN_OK) { - IPCStore->deleteData(address); - } + result = IPCStore->getFreeElement(&address, maxSize, &storeBuffer); + if (result != HasReturnvaluesIF::RETURN_OK) { + replyToCommand(result, 0); + return; + } + for (uint8_t i = 0; i < count; i++) { + elements[i]->serialize(&storeBuffer, &size, maxSize, SerializeIF::Endianness::BIG); + } + CommandMessage reply; + ModeSequenceMessage::setModeSequenceMessage(&reply, command, address); + if (commandQueue->reply(&reply) != RETURN_OK) { + IPCStore->deleteData(address); + } } ReturnValue_t Subsystem::checkObjectConnections() { - ReturnValue_t result = RETURN_OK; - for (FixedMap::Iterator iter = modeSequences.begin(); - iter != modeSequences.end(); iter++) { - result = checkSequence(iter.value->first); - if (result != RETURN_OK) { - return result; - } - - } - return RETURN_OK; + ReturnValue_t result = RETURN_OK; + for (FixedMap::Iterator iter = modeSequences.begin(); + iter != modeSequences.end(); iter++) { + result = checkSequence(iter.value->first); + if (result != RETURN_OK) { + return result; + } + } + return RETURN_OK; } -void Subsystem::setInitialMode(Mode_t mode) { - initialMode = mode; -} +void Subsystem::setInitialMode(Mode_t mode) { initialMode = mode; } void Subsystem::cantKeepMode() { - ReturnValue_t result; - if ((result = checkSequence(getFallbackSequence(mode))) != RETURN_OK) { - triggerEvent(FALLBACK_FAILED, result, getFallbackSequence(mode)); - return; - } + ReturnValue_t result; + if ((result = checkSequence(getFallbackSequence(mode))) != RETURN_OK) { + triggerEvent(FALLBACK_FAILED, result, getFallbackSequence(mode)); + return; + } - modeHelper.setForced(true); + modeHelper.setForced(true); - //already set the mode, so that we do not try to go back in our old mode - //when the transition fails - mode = getFallbackSequence(mode); - //SHOULDDO: We should store submodes for fallback sequence as well, - //otherwise we should get rid of submodes completely. - startTransition(mode, SUBMODE_NONE); + // already set the mode, so that we do not try to go back in our old mode + // when the transition fails + mode = getFallbackSequence(mode); + // SHOULDDO: We should store submodes for fallback sequence as well, + // otherwise we should get rid of submodes completely. + startTransition(mode, SUBMODE_NONE); } diff --git a/src/fsfw/subsystem/Subsystem.h b/src/fsfw/subsystem/Subsystem.h index 69563643..2c78c8cd 100644 --- a/src/fsfw/subsystem/Subsystem.h +++ b/src/fsfw/subsystem/Subsystem.h @@ -1,172 +1,166 @@ #ifndef FSFW_SUBSYSTEM_SUBSYSTEM_H_ #define FSFW_SUBSYSTEM_SUBSYSTEM_H_ -#include "SubsystemBase.h" -#include "modes/ModeDefinitions.h" +#include #include "../container/FixedArrayList.h" #include "../container/FixedMap.h" #include "../container/HybridIterator.h" #include "../container/SinglyLinkedList.h" #include "../serialize/SerialArrayListAdapter.h" - -#include +#include "SubsystemBase.h" +#include "modes/ModeDefinitions.h" /** * @brief TODO: documentation missing * @details */ -class Subsystem: public SubsystemBase, public HasModeSequenceIF { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::SUBSYSTEM; - static const ReturnValue_t SEQUENCE_ALREADY_EXISTS = MAKE_RETURN_CODE(0x01); - static const ReturnValue_t TABLE_ALREADY_EXISTS = MAKE_RETURN_CODE(0x02); - static const ReturnValue_t TABLE_DOES_NOT_EXIST = MAKE_RETURN_CODE(0x03); - static const ReturnValue_t TABLE_OR_SEQUENCE_LENGTH_INVALID = MAKE_RETURN_CODE(0x04); - static const ReturnValue_t SEQUENCE_DOES_NOT_EXIST = MAKE_RETURN_CODE(0x05); - static const ReturnValue_t TABLE_CONTAINS_INVALID_OBJECT_ID = - MAKE_RETURN_CODE(0x06); - static const ReturnValue_t FALLBACK_SEQUENCE_DOES_NOT_EXIST = - MAKE_RETURN_CODE(0x07); - static const ReturnValue_t NO_TARGET_TABLE = MAKE_RETURN_CODE(0x08); - static const ReturnValue_t SEQUENCE_OR_TABLE_TOO_LONG = MAKE_RETURN_CODE(0x09); - static const ReturnValue_t IS_FALLBACK_SEQUENCE = MAKE_RETURN_CODE(0x0B); - static const ReturnValue_t ACCESS_DENIED = MAKE_RETURN_CODE(0x0C); - static const ReturnValue_t TABLE_IN_USE = MAKE_RETURN_CODE(0x0E); +class Subsystem : public SubsystemBase, public HasModeSequenceIF { + public: + static const uint8_t INTERFACE_ID = CLASS_ID::SUBSYSTEM; + static const ReturnValue_t SEQUENCE_ALREADY_EXISTS = MAKE_RETURN_CODE(0x01); + static const ReturnValue_t TABLE_ALREADY_EXISTS = MAKE_RETURN_CODE(0x02); + static const ReturnValue_t TABLE_DOES_NOT_EXIST = MAKE_RETURN_CODE(0x03); + static const ReturnValue_t TABLE_OR_SEQUENCE_LENGTH_INVALID = MAKE_RETURN_CODE(0x04); + static const ReturnValue_t SEQUENCE_DOES_NOT_EXIST = MAKE_RETURN_CODE(0x05); + static const ReturnValue_t TABLE_CONTAINS_INVALID_OBJECT_ID = MAKE_RETURN_CODE(0x06); + static const ReturnValue_t FALLBACK_SEQUENCE_DOES_NOT_EXIST = MAKE_RETURN_CODE(0x07); + static const ReturnValue_t NO_TARGET_TABLE = MAKE_RETURN_CODE(0x08); + static const ReturnValue_t SEQUENCE_OR_TABLE_TOO_LONG = MAKE_RETURN_CODE(0x09); + static const ReturnValue_t IS_FALLBACK_SEQUENCE = MAKE_RETURN_CODE(0x0B); + static const ReturnValue_t ACCESS_DENIED = MAKE_RETURN_CODE(0x0C); + static const ReturnValue_t TABLE_IN_USE = MAKE_RETURN_CODE(0x0E); - static const ReturnValue_t TARGET_TABLE_NOT_REACHED = MAKE_RETURN_CODE(0xA1); - static const ReturnValue_t TABLE_CHECK_FAILED = MAKE_RETURN_CODE(0xA2); + static const ReturnValue_t TARGET_TABLE_NOT_REACHED = MAKE_RETURN_CODE(0xA1); + static const ReturnValue_t TABLE_CHECK_FAILED = MAKE_RETURN_CODE(0xA2); - /** - * TODO: Doc for constructor - * @param setObjectId - * @param parent - * @param maxNumberOfSequences - * @param maxNumberOfTables - */ - Subsystem(object_id_t setObjectId, object_id_t parent, - uint32_t maxNumberOfSequences, uint32_t maxNumberOfTables); - virtual ~Subsystem(); + /** + * TODO: Doc for constructor + * @param setObjectId + * @param parent + * @param maxNumberOfSequences + * @param maxNumberOfTables + */ + Subsystem(object_id_t setObjectId, object_id_t parent, uint32_t maxNumberOfSequences, + uint32_t maxNumberOfTables); + virtual ~Subsystem(); - ReturnValue_t addSequence(ArrayList* sequence, Mode_t id, - Mode_t fallbackSequence, bool inStore = true, bool preInit = true); + ReturnValue_t addSequence(ArrayList *sequence, Mode_t id, Mode_t fallbackSequence, + bool inStore = true, bool preInit = true); - ReturnValue_t addTable(ArrayList *table, Mode_t id, - bool inStore = true, bool preInit = true); + ReturnValue_t addTable(ArrayList *table, Mode_t id, bool inStore = true, + bool preInit = true); - void setInitialMode(Mode_t mode); + void setInitialMode(Mode_t mode); - virtual ReturnValue_t initialize() override; + virtual ReturnValue_t initialize() override; - virtual ReturnValue_t checkObjectConnections() override; + virtual ReturnValue_t checkObjectConnections() override; - virtual MessageQueueId_t getSequenceCommandQueue() const override; + virtual MessageQueueId_t getSequenceCommandQueue() const override; -protected: + protected: + struct EntryPointer { + bool islinked; + union { + ModeListEntry *firstLinkedElement; + ArrayList *array; + }; + }; - struct EntryPointer { - bool islinked; - union { - ModeListEntry *firstLinkedElement; - ArrayList *array; - }; - }; + struct SequenceInfo { + Mode_t fallbackSequence; + EntryPointer entries; + }; - struct SequenceInfo { - Mode_t fallbackSequence; - EntryPointer entries; - }; + static const uint8_t MAX_NUMBER_OF_TABLES_OR_SEQUENCES = 70; - static const uint8_t MAX_NUMBER_OF_TABLES_OR_SEQUENCES = 70; + static const uint8_t MAX_LENGTH_OF_TABLE_OR_SEQUENCE = 20; - static const uint8_t MAX_LENGTH_OF_TABLE_OR_SEQUENCE = 20; + bool isInTransition; - bool isInTransition; + bool childrenChangedHealth; - bool childrenChangedHealth; + uint32_t uptimeStartTable = 0; - uint32_t uptimeStartTable = 0; + HybridIterator currentTargetTable; - HybridIterator currentTargetTable; + Mode_t targetMode = 0; - Mode_t targetMode = 0; + Submode_t targetSubmode; - Submode_t targetSubmode; + Mode_t initialMode = 0; - Mode_t initialMode = 0; + HybridIterator currentSequenceIterator; - HybridIterator currentSequenceIterator; + FixedMap modeTables; - FixedMap modeTables; + FixedMap modeSequences; - FixedMap modeSequences; - - StorageManagerIF *IPCStore = nullptr; + StorageManagerIF *IPCStore = nullptr; #if FSFW_USE_MODESTORE == 1 - ModeStoreIF *modeStore = nullptr; + ModeStoreIF *modeStore = nullptr; #endif - bool existsModeSequence(Mode_t id); + bool existsModeSequence(Mode_t id); - HybridIterator getSequence(Mode_t id); + HybridIterator getSequence(Mode_t id); - bool existsModeTable(Mode_t id); + bool existsModeTable(Mode_t id); - HybridIterator getTable(Mode_t id); + HybridIterator getTable(Mode_t id); - HybridIterator getCurrentTable(); + HybridIterator getCurrentTable(); - /** - * DO NOT USE ON NON EXISTING SEQUENCE - * - * @param a sequence - * @return the fallback sequence's Id - */ - Mode_t getFallbackSequence(Mode_t sequence); + /** + * DO NOT USE ON NON EXISTING SEQUENCE + * + * @param a sequence + * @return the fallback sequence's Id + */ + Mode_t getFallbackSequence(Mode_t sequence); - void replyToCommand(ReturnValue_t status, uint32_t parameter); + void replyToCommand(ReturnValue_t status, uint32_t parameter); - ReturnValue_t deleteSequence(Mode_t id); + ReturnValue_t deleteSequence(Mode_t id); - ReturnValue_t deleteTable(Mode_t id); + ReturnValue_t deleteTable(Mode_t id); - virtual void performChildOperation(); + virtual void performChildOperation(); - virtual ReturnValue_t handleCommandMessage(CommandMessage *message); + virtual ReturnValue_t handleCommandMessage(CommandMessage *message); - bool isFallbackSequence(Mode_t SequenceId); + bool isFallbackSequence(Mode_t SequenceId); - bool isTableUsed(Mode_t tableId); + bool isTableUsed(Mode_t tableId); - virtual ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, - uint32_t *msToReachTheMode); + virtual ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, + uint32_t *msToReachTheMode); - virtual void startTransition(Mode_t mode, Submode_t submode); + virtual void startTransition(Mode_t mode, Submode_t submode); - void sendSerializablesAsCommandMessage(Command_t command, - SerializeIF **elements, uint8_t count); + void sendSerializablesAsCommandMessage(Command_t command, SerializeIF **elements, uint8_t count); - void transitionFailed(ReturnValue_t failureCode, uint32_t parameter); + void transitionFailed(ReturnValue_t failureCode, uint32_t parameter); - void cantKeepMode(); + void cantKeepMode(); - /** - * @brief Checks whether a sequence, identified by a mode. - * @param sequence - * @return - */ - ReturnValue_t checkSequence(Mode_t sequence); + /** + * @brief Checks whether a sequence, identified by a mode. + * @param sequence + * @return + */ + ReturnValue_t checkSequence(Mode_t sequence); - /** - * @brief Checks whether a sequence, identified by a mode list iterator - * and a fallback sequence. Iterator needs to point to a valid - * sequence. - * @param iter - * @return - */ - ReturnValue_t checkSequence(HybridIterator iter, - Mode_t fallbackSequence); + /** + * @brief Checks whether a sequence, identified by a mode list iterator + * and a fallback sequence. Iterator needs to point to a valid + * sequence. + * @param iter + * @return + */ + ReturnValue_t checkSequence(HybridIterator iter, Mode_t fallbackSequence); }; #endif /* FSFW_SUBSYSTEM_SUBSYSTEM_H_ */ diff --git a/src/fsfw/subsystem/SubsystemBase.cpp b/src/fsfw/subsystem/SubsystemBase.cpp index afcd43ad..104db3c3 100644 --- a/src/fsfw/subsystem/SubsystemBase.cpp +++ b/src/fsfw/subsystem/SubsystemBase.cpp @@ -1,356 +1,326 @@ #include "fsfw/subsystem/SubsystemBase.h" -#include "fsfw/serviceinterface/ServiceInterface.h" -#include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/ipc/QueueFactory.h" +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/serviceinterface/ServiceInterface.h" -SubsystemBase::SubsystemBase(object_id_t setObjectId, object_id_t parent, - Mode_t initialMode, uint16_t commandQueueDepth) : - SystemObject(setObjectId), mode(initialMode), - commandQueue(QueueFactory::instance()->createMessageQueue( - commandQueueDepth, CommandMessage::MAX_MESSAGE_SIZE)), - healthHelper(this, setObjectId), modeHelper(this), parentId(parent) { -} +SubsystemBase::SubsystemBase(object_id_t setObjectId, object_id_t parent, Mode_t initialMode, + uint16_t commandQueueDepth) + : SystemObject(setObjectId), + mode(initialMode), + commandQueue(QueueFactory::instance()->createMessageQueue(commandQueueDepth, + CommandMessage::MAX_MESSAGE_SIZE)), + healthHelper(this, setObjectId), + modeHelper(this), + parentId(parent) {} -SubsystemBase::~SubsystemBase() { - QueueFactory::instance()->deleteMessageQueue(commandQueue); - -} +SubsystemBase::~SubsystemBase() { QueueFactory::instance()->deleteMessageQueue(commandQueue); } ReturnValue_t SubsystemBase::registerChild(object_id_t objectId) { - ChildInfo info; + ChildInfo info; - HasModesIF *child = ObjectManager::instance()->get(objectId); - // This is a rather ugly hack to have the changedHealth info for all - // children available. - HasHealthIF* healthChild = ObjectManager::instance()->get(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 - } + HasModesIF* child = ObjectManager::instance()->get(objectId); + // This is a rather ugly hack to have the changedHealth info for all + // children available. + HasHealthIF* healthChild = ObjectManager::instance()->get(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; + info.submode = SUBMODE_NONE; + info.healthChanged = false; - auto resultPair = childrenMap.emplace(objectId, info); - if (not resultPair.second) { - return COULD_NOT_INSERT_CHILD; - } - return RETURN_OK; + auto resultPair = childrenMap.emplace(objectId, info); + if (not resultPair.second) { + return COULD_NOT_INSERT_CHILD; + } + return RETURN_OK; } -ReturnValue_t SubsystemBase::checkStateAgainstTable( - HybridIterator tableIter, Submode_t targetSubmode) { +ReturnValue_t SubsystemBase::checkStateAgainstTable(HybridIterator tableIter, + Submode_t targetSubmode) { + std::map::iterator childIter; - std::map::iterator childIter; + for (; tableIter.value != NULL; ++tableIter) { + object_id_t object = tableIter.value->getObject(); - for (; tableIter.value != NULL; ++tableIter) { - object_id_t object = tableIter.value->getObject(); + if ((childIter = childrenMap.find(object)) == childrenMap.end()) { + return RETURN_FAILED; + } - if ((childIter = childrenMap.find(object)) == childrenMap.end()) { - return RETURN_FAILED; - } + if (childIter->second.mode != tableIter.value->getMode()) { + return RETURN_FAILED; + } - if (childIter->second.mode != tableIter.value->getMode()) { - return RETURN_FAILED; - } + Submode_t submodeToCheckAgainst = tableIter.value->getSubmode(); + if (tableIter.value->inheritSubmode()) { + submodeToCheckAgainst = targetSubmode; + } - Submode_t submodeToCheckAgainst = tableIter.value->getSubmode(); - if (tableIter.value->inheritSubmode()) { - submodeToCheckAgainst = targetSubmode; - } - - if (childIter->second.submode != submodeToCheckAgainst) { - return RETURN_FAILED; - } - } - return RETURN_OK; + if (childIter->second.submode != submodeToCheckAgainst) { + return RETURN_FAILED; + } + } + return RETURN_OK; } -void SubsystemBase::executeTable(HybridIterator tableIter, - Submode_t targetSubmode) { - CommandMessage command; +void SubsystemBase::executeTable(HybridIterator tableIter, Submode_t targetSubmode) { + CommandMessage command; - std::map::iterator iter; + std::map::iterator iter; - commandsOutstanding = 0; + commandsOutstanding = 0; - for (; tableIter.value != nullptr; ++tableIter) { - object_id_t object = tableIter.value->getObject(); - if ((iter = childrenMap.find(object)) == childrenMap.end()) { - //illegal table entry, should only happen due to misconfigured mode table + for (; tableIter.value != nullptr; ++tableIter) { + object_id_t object = tableIter.value->getObject(); + if ((iter = childrenMap.find(object)) == childrenMap.end()) { + // illegal table entry, should only happen due to misconfigured mode table #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << std::hex << getObjectId() << ": invalid mode table entry" - << std::endl; + sif::debug << std::hex << getObjectId() << ": invalid mode table entry" << std::endl; #endif - continue; - } + continue; + } - Submode_t submodeToCommand = tableIter.value->getSubmode(); - if (tableIter.value->inheritSubmode()) { - submodeToCommand = targetSubmode; - } + Submode_t submodeToCommand = tableIter.value->getSubmode(); + if (tableIter.value->inheritSubmode()) { + submodeToCommand = targetSubmode; + } - if (healthHelper.healthTable->hasHealth(object)) { - if (healthHelper.healthTable->isFaulty(object)) { - ModeMessage::setModeMessage(&command, - ModeMessage::CMD_MODE_COMMAND, HasModesIF::MODE_OFF, - SUBMODE_NONE); - } else { - if (modeHelper.isForced()) { - ModeMessage::setModeMessage(&command, - ModeMessage::CMD_MODE_COMMAND_FORCED, - tableIter.value->getMode(), submodeToCommand); - } else { - if (healthHelper.healthTable->isCommandable(object)) { - ModeMessage::setModeMessage(&command, - ModeMessage::CMD_MODE_COMMAND, - tableIter.value->getMode(), submodeToCommand); - } else { - continue; - } - } - } - } else { - ModeMessage::setModeMessage(&command, ModeMessage::CMD_MODE_COMMAND, - tableIter.value->getMode(), submodeToCommand); - } - - if ((iter->second.mode == ModeMessage::getMode(&command)) - && (iter->second.submode == ModeMessage::getSubmode(&command)) - && !modeHelper.isForced()) { - continue; //don't send redundant mode commands (produces event spam), but still command if mode is forced to reach lower levels - } - ReturnValue_t result = commandQueue->sendMessage( - iter->second.commandQueue, &command); - if (result == RETURN_OK) { - ++commandsOutstanding; - } - } + if (healthHelper.healthTable->hasHealth(object)) { + if (healthHelper.healthTable->isFaulty(object)) { + ModeMessage::setModeMessage(&command, ModeMessage::CMD_MODE_COMMAND, HasModesIF::MODE_OFF, + SUBMODE_NONE); + } else { + if (modeHelper.isForced()) { + ModeMessage::setModeMessage(&command, ModeMessage::CMD_MODE_COMMAND_FORCED, + tableIter.value->getMode(), submodeToCommand); + } else { + if (healthHelper.healthTable->isCommandable(object)) { + ModeMessage::setModeMessage(&command, ModeMessage::CMD_MODE_COMMAND, + tableIter.value->getMode(), submodeToCommand); + } else { + continue; + } + } + } + } else { + ModeMessage::setModeMessage(&command, ModeMessage::CMD_MODE_COMMAND, + tableIter.value->getMode(), submodeToCommand); + } + if ((iter->second.mode == ModeMessage::getMode(&command)) && + (iter->second.submode == ModeMessage::getSubmode(&command)) && !modeHelper.isForced()) { + continue; // don't send redundant mode commands (produces event spam), but still command if + // mode is forced to reach lower levels + } + ReturnValue_t result = commandQueue->sendMessage(iter->second.commandQueue, &command); + if (result == RETURN_OK) { + ++commandsOutstanding; + } + } } -ReturnValue_t SubsystemBase::updateChildMode(MessageQueueId_t queue, - Mode_t mode, Submode_t submode) { - std::map::iterator iter; +ReturnValue_t SubsystemBase::updateChildMode(MessageQueueId_t queue, Mode_t mode, + Submode_t submode) { + std::map::iterator iter; - for (iter = childrenMap.begin(); iter != childrenMap.end(); iter++) { - if (iter->second.commandQueue == queue) { - iter->second.mode = mode; - iter->second.submode = submode; - return RETURN_OK; - } - } - return CHILD_NOT_FOUND; + for (iter = childrenMap.begin(); iter != childrenMap.end(); iter++) { + if (iter->second.commandQueue == queue) { + iter->second.mode = mode; + iter->second.submode = submode; + return RETURN_OK; + } + } + return CHILD_NOT_FOUND; } -ReturnValue_t SubsystemBase::updateChildChangedHealth(MessageQueueId_t queue, -bool changedHealth) { - for (auto iter = childrenMap.begin(); iter != childrenMap.end(); iter++) { - if (iter->second.commandQueue == queue) { - iter->second.healthChanged = changedHealth; - return RETURN_OK; - } - } - return CHILD_NOT_FOUND; +ReturnValue_t SubsystemBase::updateChildChangedHealth(MessageQueueId_t queue, bool changedHealth) { + for (auto iter = childrenMap.begin(); iter != childrenMap.end(); iter++) { + if (iter->second.commandQueue == queue) { + iter->second.healthChanged = changedHealth; + return RETURN_OK; + } + } + return CHILD_NOT_FOUND; } -MessageQueueId_t SubsystemBase::getCommandQueue() const { - return commandQueue->getId(); -} +MessageQueueId_t SubsystemBase::getCommandQueue() const { return commandQueue->getId(); } ReturnValue_t SubsystemBase::initialize() { - MessageQueueId_t parentQueue = MessageQueueIF::NO_QUEUE; - ReturnValue_t result = SystemObject::initialize(); + MessageQueueId_t parentQueue = MessageQueueIF::NO_QUEUE; + ReturnValue_t result = SystemObject::initialize(); - if (result != RETURN_OK) { - return result; - } + if (result != RETURN_OK) { + return result; + } - if (parentId != objects::NO_OBJECT) { - SubsystemBase *parent = ObjectManager::instance()->get(parentId); - if (parent == nullptr) { - return RETURN_FAILED; - } - parentQueue = parent->getCommandQueue(); + if (parentId != objects::NO_OBJECT) { + SubsystemBase* parent = ObjectManager::instance()->get(parentId); + if (parent == nullptr) { + return RETURN_FAILED; + } + parentQueue = parent->getCommandQueue(); - parent->registerChild(getObjectId()); - } + parent->registerChild(getObjectId()); + } - result = healthHelper.initialize(parentQueue); + result = healthHelper.initialize(parentQueue); - if (result != RETURN_OK) { - return result; - } + if (result != RETURN_OK) { + return result; + } - result = modeHelper.initialize(parentQueue); + result = modeHelper.initialize(parentQueue); - if (result != RETURN_OK) { - return result; - } + if (result != RETURN_OK) { + return result; + } - return RETURN_OK; + return RETURN_OK; } ReturnValue_t SubsystemBase::performOperation(uint8_t opCode) { + childrenChangedMode = false; - childrenChangedMode = false; + checkCommandQueue(); - checkCommandQueue(); + performChildOperation(); - performChildOperation(); - - return RETURN_OK; + return RETURN_OK; } ReturnValue_t SubsystemBase::handleModeReply(CommandMessage* message) { - switch (message->getCommand()) { - case ModeMessage::REPLY_MODE_INFO: - updateChildMode(message->getSender(), ModeMessage::getMode(message), - ModeMessage::getSubmode(message)); - childrenChangedMode = true; - return RETURN_OK; - case ModeMessage::REPLY_MODE_REPLY: - case ModeMessage::REPLY_WRONG_MODE_REPLY: - updateChildMode(message->getSender(), ModeMessage::getMode(message), - ModeMessage::getSubmode(message)); - childrenChangedMode = true; - commandsOutstanding--; - return RETURN_OK; - case ModeMessage::REPLY_CANT_REACH_MODE: - commandsOutstanding--; - { - for (auto iter = childrenMap.begin(); iter != childrenMap.end(); - iter++) { - if (iter->second.commandQueue == message->getSender()) { - triggerEvent(MODE_CMD_REJECTED, iter->first, - message->getParameter()); - } - } - } - return RETURN_OK; -// case ModeMessage::CMD_MODE_COMMAND: -// handleCommandedMode(message); -// return RETURN_OK; -// case ModeMessage::CMD_MODE_ANNOUNCE: -// triggerEvent(MODE_INFO, mode, submode); -// return RETURN_OK; -// case ModeMessage::CMD_MODE_ANNOUNCE_RECURSIVELY: -// triggerEvent(MODE_INFO, mode, submode); -// commandAllChildren(message); -// return RETURN_OK; - default: - return RETURN_FAILED; - } + switch (message->getCommand()) { + case ModeMessage::REPLY_MODE_INFO: + updateChildMode(message->getSender(), ModeMessage::getMode(message), + ModeMessage::getSubmode(message)); + childrenChangedMode = true; + return RETURN_OK; + case ModeMessage::REPLY_MODE_REPLY: + case ModeMessage::REPLY_WRONG_MODE_REPLY: + updateChildMode(message->getSender(), ModeMessage::getMode(message), + ModeMessage::getSubmode(message)); + childrenChangedMode = true; + commandsOutstanding--; + return RETURN_OK; + case ModeMessage::REPLY_CANT_REACH_MODE: + commandsOutstanding--; + { + for (auto iter = childrenMap.begin(); iter != childrenMap.end(); iter++) { + if (iter->second.commandQueue == message->getSender()) { + triggerEvent(MODE_CMD_REJECTED, iter->first, message->getParameter()); + } + } + } + return RETURN_OK; + // case ModeMessage::CMD_MODE_COMMAND: + // handleCommandedMode(message); + // return RETURN_OK; + // case ModeMessage::CMD_MODE_ANNOUNCE: + // triggerEvent(MODE_INFO, mode, submode); + // return RETURN_OK; + // case ModeMessage::CMD_MODE_ANNOUNCE_RECURSIVELY: + // triggerEvent(MODE_INFO, mode, submode); + // commandAllChildren(message); + // return RETURN_OK; + default: + return RETURN_FAILED; + } } -ReturnValue_t SubsystemBase::checkTable( - HybridIterator tableIter) { - for (; tableIter.value != NULL; ++tableIter) { - if (childrenMap.find(tableIter.value->getObject()) - == childrenMap.end()) { - return TABLE_CONTAINS_INVALID_OBJECT_ID; - } - } - return RETURN_OK; +ReturnValue_t SubsystemBase::checkTable(HybridIterator tableIter) { + for (; tableIter.value != NULL; ++tableIter) { + if (childrenMap.find(tableIter.value->getObject()) == childrenMap.end()) { + return TABLE_CONTAINS_INVALID_OBJECT_ID; + } + } + return RETURN_OK; } -void SubsystemBase::replyToCommand(CommandMessage* message) { - commandQueue->reply(message); -} +void SubsystemBase::replyToCommand(CommandMessage* message) { commandQueue->reply(message); } void SubsystemBase::setMode(Mode_t newMode, Submode_t newSubmode) { - modeHelper.modeChanged(newMode, newSubmode); - mode = newMode; - submode = newSubmode; - modeChanged(); - announceMode(false); + modeHelper.modeChanged(newMode, newSubmode); + mode = newMode; + submode = newSubmode; + modeChanged(); + announceMode(false); } -void SubsystemBase::setMode(Mode_t newMode) { - setMode(newMode, submode); -} +void SubsystemBase::setMode(Mode_t newMode) { setMode(newMode, submode); } void SubsystemBase::commandAllChildren(CommandMessage* message) { - std::map::iterator iter; - for (iter = childrenMap.begin(); iter != childrenMap.end(); ++iter) { - commandQueue->sendMessage(iter->second.commandQueue, message); - } + std::map::iterator iter; + for (iter = childrenMap.begin(); iter != childrenMap.end(); ++iter) { + commandQueue->sendMessage(iter->second.commandQueue, message); + } } void SubsystemBase::getMode(Mode_t* mode, Submode_t* submode) { - *mode = this->mode; - *submode = this->submode; + *mode = this->mode; + *submode = this->submode; } -void SubsystemBase::setToExternalControl() { - healthHelper.setHealth(EXTERNAL_CONTROL); -} +void SubsystemBase::setToExternalControl() { healthHelper.setHealth(EXTERNAL_CONTROL); } void SubsystemBase::announceMode(bool recursive) { - triggerEvent(MODE_INFO, mode, submode); - if (recursive) { - CommandMessage command; - ModeMessage::setModeMessage(&command, - ModeMessage::CMD_MODE_ANNOUNCE_RECURSIVELY, 0, 0); - commandAllChildren(&command); - } + triggerEvent(MODE_INFO, mode, submode); + if (recursive) { + CommandMessage command; + ModeMessage::setModeMessage(&command, ModeMessage::CMD_MODE_ANNOUNCE_RECURSIVELY, 0, 0); + commandAllChildren(&command); + } } void SubsystemBase::checkCommandQueue() { - ReturnValue_t result; - CommandMessage command; + ReturnValue_t result; + CommandMessage command; - for (result = commandQueue->receiveMessage(&command); result == RETURN_OK; - result = commandQueue->receiveMessage(&command)) { + for (result = commandQueue->receiveMessage(&command); result == RETURN_OK; + result = commandQueue->receiveMessage(&command)) { + result = healthHelper.handleHealthCommand(&command); + if (result == RETURN_OK) { + continue; + } - result = healthHelper.handleHealthCommand(&command); - if (result == RETURN_OK) { - continue; - } + result = modeHelper.handleModeCommand(&command); + if (result == RETURN_OK) { + continue; + } - result = modeHelper.handleModeCommand(&command); - if (result == RETURN_OK) { - continue; - } + result = handleModeReply(&command); + if (result == RETURN_OK) { + continue; + } - result = handleModeReply(&command); - if (result == RETURN_OK) { - continue; - } - - result = handleCommandMessage(&command); - if (result != RETURN_OK) { - CommandMessage reply; - reply.setReplyRejected(CommandMessage::UNKNOWN_COMMAND, - command.getCommand()); - replyToCommand(&reply); - } - } + result = handleCommandMessage(&command); + if (result != RETURN_OK) { + CommandMessage reply; + reply.setReplyRejected(CommandMessage::UNKNOWN_COMMAND, command.getCommand()); + replyToCommand(&reply); + } + } } ReturnValue_t SubsystemBase::setHealth(HealthState health) { - switch (health) { - case HEALTHY: - case EXTERNAL_CONTROL: - healthHelper.setHealth(health); - return RETURN_OK; - default: - return INVALID_HEALTH_STATE; - } + switch (health) { + case HEALTHY: + case EXTERNAL_CONTROL: + healthHelper.setHealth(health); + return RETURN_OK; + default: + return INVALID_HEALTH_STATE; + } } -HasHealthIF::HealthState SubsystemBase::getHealth() { - return healthHelper.getHealth(); -} - -void SubsystemBase::modeChanged() { -} +HasHealthIF::HealthState SubsystemBase::getHealth() { return healthHelper.getHealth(); } +void SubsystemBase::modeChanged() {} diff --git a/src/fsfw/subsystem/SubsystemBase.h b/src/fsfw/subsystem/SubsystemBase.h index a1de077d..8cfd5be0 100644 --- a/src/fsfw/subsystem/SubsystemBase.h +++ b/src/fsfw/subsystem/SubsystemBase.h @@ -1,142 +1,139 @@ #ifndef FSFW_SUBSYSTEM_SUBSYSTEMBASE_H_ #define FSFW_SUBSYSTEM_SUBSYSTEMBASE_H_ -#include "modes/HasModeSequenceIF.h" +#include #include "../container/HybridIterator.h" #include "../health/HasHealthIF.h" #include "../health/HealthHelper.h" +#include "../ipc/MessageQueueIF.h" #include "../modes/HasModesIF.h" #include "../objectmanager/SystemObject.h" #include "../returnvalues/HasReturnvaluesIF.h" #include "../tasks/ExecutableObjectIF.h" -#include "../ipc/MessageQueueIF.h" -#include +#include "modes/HasModeSequenceIF.h" /** * @defgroup subsystems Subsystem Objects * Contains all Subsystem and Assemblies */ -class SubsystemBase: public SystemObject, - public HasModesIF, - public HasHealthIF, - public HasReturnvaluesIF, - public ExecutableObjectIF { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::SUBSYSTEM_BASE; - static const ReturnValue_t CHILD_NOT_FOUND = MAKE_RETURN_CODE(0x01); - static const ReturnValue_t CHILD_INFO_UPDATED = MAKE_RETURN_CODE(0x02); - static const ReturnValue_t CHILD_DOESNT_HAVE_MODES = MAKE_RETURN_CODE(0x03); - 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); +class SubsystemBase : public SystemObject, + public HasModesIF, + public HasHealthIF, + public HasReturnvaluesIF, + public ExecutableObjectIF { + public: + static const uint8_t INTERFACE_ID = CLASS_ID::SUBSYSTEM_BASE; + static const ReturnValue_t CHILD_NOT_FOUND = MAKE_RETURN_CODE(0x01); + static const ReturnValue_t CHILD_INFO_UPDATED = MAKE_RETURN_CODE(0x02); + static const ReturnValue_t CHILD_DOESNT_HAVE_MODES = MAKE_RETURN_CODE(0x03); + 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); - SubsystemBase(object_id_t setObjectId, object_id_t parent, - Mode_t initialMode = 0, uint16_t commandQueueDepth = 8); - virtual ~SubsystemBase(); + SubsystemBase(object_id_t setObjectId, object_id_t parent, Mode_t initialMode = 0, + uint16_t commandQueueDepth = 8); + virtual ~SubsystemBase(); - virtual MessageQueueId_t getCommandQueue() const override; + virtual MessageQueueId_t getCommandQueue() const override; - /** - * Function to register the child objects. - * Performs a checks if the child does implement HasHealthIF and/or HasModesIF - * - * Also adds them to the internal childrenMap. - * - * @param objectId - * @return RETURN_OK if successful - * 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 - */ - ReturnValue_t registerChild(object_id_t objectId); + /** + * Function to register the child objects. + * Performs a checks if the child does implement HasHealthIF and/or HasModesIF + * + * Also adds them to the internal childrenMap. + * + * @param objectId + * @return RETURN_OK if successful + * 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 + */ + ReturnValue_t registerChild(object_id_t objectId); - virtual ReturnValue_t initialize() override; + virtual ReturnValue_t initialize() override; - virtual ReturnValue_t performOperation(uint8_t opCode) override; + virtual ReturnValue_t performOperation(uint8_t opCode) override; - virtual ReturnValue_t setHealth(HealthState health) override; + virtual ReturnValue_t setHealth(HealthState health) override; - virtual HasHealthIF::HealthState getHealth() override; + virtual HasHealthIF::HealthState getHealth() override; -protected: - struct ChildInfo { - MessageQueueId_t commandQueue; - Mode_t mode; - Submode_t submode; - bool healthChanged; - }; + protected: + struct ChildInfo { + MessageQueueId_t commandQueue; + Mode_t mode; + Submode_t submode; + bool healthChanged; + }; - Mode_t mode; + Mode_t mode; - Submode_t submode = SUBMODE_NONE; + Submode_t submode = SUBMODE_NONE; - bool childrenChangedMode = false; + bool childrenChangedMode = false; - /** - * Always check this against <=0, so you are robust against too many replies - */ - int32_t commandsOutstanding = 0; + /** + * Always check this against <=0, so you are robust against too many replies + */ + int32_t commandsOutstanding = 0; - MessageQueueIF* commandQueue = nullptr; + MessageQueueIF *commandQueue = nullptr; - HealthHelper healthHelper; + HealthHelper healthHelper; - ModeHelper modeHelper; + ModeHelper modeHelper; - const object_id_t parentId; + const object_id_t parentId; - typedef std::map ChildrenMap; - ChildrenMap childrenMap; + typedef std::map ChildrenMap; + ChildrenMap childrenMap; - void checkCommandQueue(); + void checkCommandQueue(); - /** - * We need to know the target Submode, as children are able to inherit the submode - */ - ReturnValue_t checkStateAgainstTable( - HybridIterator tableIter, Submode_t targetSubmode); + /** + * We need to know the target Submode, as children are able to inherit the submode + */ + ReturnValue_t checkStateAgainstTable(HybridIterator tableIter, + Submode_t targetSubmode); - /** - * 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 - */ - void executeTable(HybridIterator tableIter, - Submode_t targetSubmode = SUBMODE_NONE); + /** + * 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 + */ + void executeTable(HybridIterator tableIter, + 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 updateChildChangedHealth(MessageQueueId_t queue, - bool changedHealth = true); + ReturnValue_t updateChildChangedHealth(MessageQueueId_t queue, bool changedHealth = true); - virtual ReturnValue_t handleModeReply(CommandMessage *message); + virtual ReturnValue_t handleModeReply(CommandMessage *message); - void commandAllChildren(CommandMessage *message); + void commandAllChildren(CommandMessage *message); - ReturnValue_t checkTable(HybridIterator tableIter); + ReturnValue_t checkTable(HybridIterator tableIter); - void replyToCommand(CommandMessage *message); + void replyToCommand(CommandMessage *message); - void setMode(Mode_t newMode, Submode_t newSubmode); + void setMode(Mode_t newMode, Submode_t newSubmode); - void setMode(Mode_t newMode); + void setMode(Mode_t newMode); - virtual ReturnValue_t handleCommandMessage(CommandMessage *message) = 0; + virtual ReturnValue_t handleCommandMessage(CommandMessage *message) = 0; - virtual void performChildOperation() = 0; + virtual void performChildOperation() = 0; - virtual ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, - uint32_t *msToReachTheMode) = 0; + virtual ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, + uint32_t *msToReachTheMode) = 0; - virtual void startTransition(Mode_t mode, Submode_t submode) = 0; + virtual void startTransition(Mode_t mode, Submode_t submode) = 0; - virtual void getMode(Mode_t *mode, Submode_t *submode); + virtual void getMode(Mode_t *mode, Submode_t *submode); - virtual void setToExternalControl(); + virtual void setToExternalControl(); - virtual void announceMode(bool recursive); + virtual void announceMode(bool recursive); - virtual void modeChanged(); + virtual void modeChanged(); }; #endif /* FSFW_SUBSYSTEM_SUBSYSTEMBASE_H_ */ diff --git a/src/fsfw/subsystem/modes/HasModeSequenceIF.h b/src/fsfw/subsystem/modes/HasModeSequenceIF.h index 70b1667e..cf9b9111 100644 --- a/src/fsfw/subsystem/modes/HasModeSequenceIF.h +++ b/src/fsfw/subsystem/modes/HasModeSequenceIF.h @@ -5,16 +5,11 @@ #include "ModeSequenceMessage.h" #include "ModeStoreIF.h" - class HasModeSequenceIF { -public: - virtual ~HasModeSequenceIF() { - - } - - virtual MessageQueueId_t getSequenceCommandQueue() const = 0; + public: + virtual ~HasModeSequenceIF() {} + virtual MessageQueueId_t getSequenceCommandQueue() const = 0; }; - #endif /* HASMODESEQUENCEIF_H_ */ diff --git a/src/fsfw/subsystem/modes/ModeDefinitions.h b/src/fsfw/subsystem/modes/ModeDefinitions.h index 13a780ee..9a6b8e31 100644 --- a/src/fsfw/subsystem/modes/ModeDefinitions.h +++ b/src/fsfw/subsystem/modes/ModeDefinitions.h @@ -3,147 +3,110 @@ #include "../../modes/HasModesIF.h" #include "../../objectmanager/SystemObjectIF.h" -#include "../../serialize/SerializeIF.h" #include "../../serialize/SerialLinkedListAdapter.h" +#include "../../serialize/SerializeIF.h" -class ModeListEntry: public SerializeIF, public LinkedElement { -public: - ModeListEntry(): LinkedElement(this) {} +class ModeListEntry : public SerializeIF, public LinkedElement { + public: + ModeListEntry() : LinkedElement(this) {} - uint32_t value1 = 0; - uint32_t value2 = 0; - uint8_t value3 = 0; - uint8_t value4 = 0; + uint32_t value1 = 0; + uint32_t value2 = 0; + uint8_t value3 = 0; + uint8_t value4 = 0; - virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const { + virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const { + ReturnValue_t result; - ReturnValue_t result; + result = SerializeAdapter::serialize(&value1, buffer, size, maxSize, streamEndianness); - result = SerializeAdapter::serialize(&value1, buffer, size, - maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::serialize(&value2, buffer, size, maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::serialize(&value2, buffer, size, - maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::serialize(&value3, buffer, size, maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::serialize(&value3, buffer, size, - maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + result = SerializeAdapter::serialize(&value4, buffer, size, maxSize, streamEndianness); - result = SerializeAdapter::serialize(&value4, buffer, size, - maxSize, streamEndianness); + return result; + } - return result; + virtual size_t getSerializedSize() const { + return sizeof(value1) + sizeof(value2) + sizeof(value3) + sizeof(value4); + } - } + virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + Endianness streamEndianness) { + ReturnValue_t result; - virtual size_t getSerializedSize() const { - return sizeof(value1) + sizeof(value2) + sizeof(value3) + sizeof(value4); - } + result = SerializeAdapter::deSerialize(&value1, buffer, size, streamEndianness); - virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) { - ReturnValue_t result; + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::deSerialize(&value2, buffer, size, streamEndianness); - result = SerializeAdapter::deSerialize(&value1, buffer, size, - streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::deSerialize(&value3, buffer, size, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::deSerialize(&value2, buffer, size, - streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::deSerialize(&value4, buffer, size, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::deSerialize(&value3, buffer, size, - streamEndianness); + return result; + } - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::deSerialize(&value4, buffer, size, - streamEndianness); + // for Sequences + Mode_t getTableId() const { return value1; } - return result; - } + void setTableId(Mode_t tableId) { this->value1 = tableId; } - //for Sequences - Mode_t getTableId() const { - return value1; - } + uint8_t getWaitSeconds() const { return value2; } - void setTableId(Mode_t tableId) { - this->value1 = tableId; - } + void setWaitSeconds(uint8_t waitSeconds) { this->value2 = waitSeconds; } - uint8_t getWaitSeconds() const { - return value2; - } + bool checkSuccess() const { return value3 == 1; } - void setWaitSeconds(uint8_t waitSeconds) { - this->value2 = waitSeconds; - } + void setCheckSuccess(bool checkSuccess) { this->value3 = checkSuccess; } - bool checkSuccess() const { - return value3 == 1; - } + // for Tables + object_id_t getObject() const { return value1; } - void setCheckSuccess(bool checkSuccess) { - this->value3 = checkSuccess; - } + void setObject(object_id_t object) { this->value1 = object; } - //for Tables - object_id_t getObject() const { - return value1; - } + Mode_t getMode() const { return value2; } - void setObject(object_id_t object) { - this->value1 = object; - } + void setMode(Mode_t mode) { this->value2 = mode; } - Mode_t getMode() const { - return value2; - } + Submode_t getSubmode() const { return value3; } - void setMode(Mode_t mode) { - this->value2 = mode; - } + void setSubmode(Submode_t submode) { this->value3 = submode; } - Submode_t getSubmode() const { - return value3; - } + bool inheritSubmode() const { return value4 == 1; } - void setSubmode(Submode_t submode) { - this->value3 = submode; - } + void setInheritSubmode(bool inherit) { + if (inherit) { + value4 = 1; + } else { + value4 = 0; + } + } - bool inheritSubmode() const { - return value4 == 1; - } - - void setInheritSubmode(bool inherit){ - if (inherit){ - value4 = 1; - } else { - value4 = 0; - } - } - - bool operator==(ModeListEntry other) { - return ((value1 == other.value1) && (value2 == other.value2) - && (value3 == other.value3)); - } + bool operator==(ModeListEntry other) { + return ((value1 == other.value1) && (value2 == other.value2) && (value3 == other.value3)); + } }; #endif /* FSFW_SUBSYSTEM_MODES_MODEDEFINITIONS_H_ */ diff --git a/src/fsfw/subsystem/modes/ModeSequenceMessage.cpp b/src/fsfw/subsystem/modes/ModeSequenceMessage.cpp index d7570276..a7e0c579 100644 --- a/src/fsfw/subsystem/modes/ModeSequenceMessage.cpp +++ b/src/fsfw/subsystem/modes/ModeSequenceMessage.cpp @@ -3,74 +3,72 @@ #include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/storagemanager/StorageManagerIF.h" -void ModeSequenceMessage::setModeSequenceMessage(CommandMessage* message, - Command_t command, Mode_t sequence, store_address_t storeAddress) { - message->setCommand(command); - message->setParameter(storeAddress.raw); - message->setParameter2(sequence); +void ModeSequenceMessage::setModeSequenceMessage(CommandMessage* message, Command_t command, + Mode_t sequence, store_address_t storeAddress) { + message->setCommand(command); + message->setParameter(storeAddress.raw); + message->setParameter2(sequence); } -void ModeSequenceMessage::setModeSequenceMessage(CommandMessage* message, - Command_t command, Mode_t sequence) { - message->setCommand(command); - message->setParameter2(sequence); +void ModeSequenceMessage::setModeSequenceMessage(CommandMessage* message, Command_t command, + Mode_t sequence) { + message->setCommand(command); + message->setParameter2(sequence); } -void ModeSequenceMessage::setModeSequenceMessage(CommandMessage* message, - Command_t command, store_address_t storeAddress) { - message->setCommand(command); - message->setParameter(storeAddress.raw); +void ModeSequenceMessage::setModeSequenceMessage(CommandMessage* message, Command_t command, + store_address_t storeAddress) { + message->setCommand(command); + message->setParameter(storeAddress.raw); } -store_address_t ModeSequenceMessage::getStoreAddress( - const CommandMessage* message) { - store_address_t address; - address.raw = message->getParameter(); - return address; +store_address_t ModeSequenceMessage::getStoreAddress(const CommandMessage* message) { + store_address_t address; + address.raw = message->getParameter(); + return address; } Mode_t ModeSequenceMessage::getSequenceId(const CommandMessage* message) { - return message->getParameter2(); + return message->getParameter2(); } Mode_t ModeSequenceMessage::getTableId(const CommandMessage* message) { - return message->getParameter2(); + return message->getParameter2(); } - uint32_t ModeSequenceMessage::getNumber(const CommandMessage* message) { - return message->getParameter2(); + return message->getParameter2(); } -void ModeSequenceMessage::clear(CommandMessage *message) { - switch (message->getCommand()) { - case ADD_SEQUENCE: - case ADD_TABLE: - case SEQUENCE_LIST: - case TABLE_LIST: - case TABLE: - case SEQUENCE: { - StorageManagerIF *ipcStore = ObjectManager::instance()->get( - objects::IPC_STORE); - if (ipcStore != nullptr){ - ipcStore->deleteData(ModeSequenceMessage::getStoreAddress(message)); - } - } - /* NO BREAK falls through*/ - case DELETE_SEQUENCE: - case DELETE_TABLE: - case READ_SEQUENCE: - case READ_TABLE: - case LIST_SEQUENCES: - case LIST_TABLES: - case READ_FREE_SEQUENCE_SLOTS: - case FREE_SEQUENCE_SLOTS: - case READ_FREE_TABLE_SLOTS: - case FREE_TABLE_SLOTS: - default: - message->setCommand(CommandMessage::CMD_NONE); - message->setParameter(0); - message->setParameter2(0); - break; - } +void ModeSequenceMessage::clear(CommandMessage* message) { + switch (message->getCommand()) { + case ADD_SEQUENCE: + case ADD_TABLE: + case SEQUENCE_LIST: + case TABLE_LIST: + case TABLE: + case SEQUENCE: { + StorageManagerIF* ipcStore = + ObjectManager::instance()->get(objects::IPC_STORE); + if (ipcStore != nullptr) { + ipcStore->deleteData(ModeSequenceMessage::getStoreAddress(message)); + } + } + /* NO BREAK falls through*/ + case DELETE_SEQUENCE: + case DELETE_TABLE: + case READ_SEQUENCE: + case READ_TABLE: + case LIST_SEQUENCES: + case LIST_TABLES: + case READ_FREE_SEQUENCE_SLOTS: + case FREE_SEQUENCE_SLOTS: + case READ_FREE_TABLE_SLOTS: + case FREE_TABLE_SLOTS: + default: + message->setCommand(CommandMessage::CMD_NONE); + message->setParameter(0); + message->setParameter2(0); + break; + } } diff --git a/src/fsfw/subsystem/modes/ModeSequenceMessage.h b/src/fsfw/subsystem/modes/ModeSequenceMessage.h index 0dbe7ffb..4c238db0 100644 --- a/src/fsfw/subsystem/modes/ModeSequenceMessage.h +++ b/src/fsfw/subsystem/modes/ModeSequenceMessage.h @@ -2,49 +2,46 @@ #define FSFW_SUBSYSTEM_MODES_MODESEQUENCEMESSAGE_H_ #include "ModeDefinitions.h" - #include "fsfw/ipc/CommandMessage.h" #include "fsfw/storagemanager/StorageManagerIF.h" - class ModeSequenceMessage { -public: - static const uint8_t MESSAGE_ID = messagetypes::MODE_SEQUENCE; + public: + static const uint8_t MESSAGE_ID = messagetypes::MODE_SEQUENCE; - static const Command_t ADD_SEQUENCE = MAKE_COMMAND_ID(0x01); - static const Command_t ADD_TABLE = MAKE_COMMAND_ID(0x02); - static const Command_t DELETE_SEQUENCE = MAKE_COMMAND_ID(0x03); - static const Command_t DELETE_TABLE = MAKE_COMMAND_ID(0x04); - static const Command_t READ_SEQUENCE = MAKE_COMMAND_ID(0x05); - static const Command_t READ_TABLE = MAKE_COMMAND_ID(0x06); - static const Command_t LIST_SEQUENCES = MAKE_COMMAND_ID(0x07); - static const Command_t LIST_TABLES = MAKE_COMMAND_ID(0x08); - static const Command_t SEQUENCE_LIST = MAKE_COMMAND_ID(0x09); - static const Command_t TABLE_LIST = MAKE_COMMAND_ID(0x0A); - static const Command_t TABLE = MAKE_COMMAND_ID(0x0B); - static const Command_t SEQUENCE = MAKE_COMMAND_ID(0x0C); - static const Command_t READ_FREE_SEQUENCE_SLOTS = MAKE_COMMAND_ID(0x0D); - static const Command_t FREE_SEQUENCE_SLOTS = MAKE_COMMAND_ID(0x0E); - static const Command_t READ_FREE_TABLE_SLOTS = MAKE_COMMAND_ID(0x0F); - static const Command_t FREE_TABLE_SLOTS = MAKE_COMMAND_ID(0x10); + static const Command_t ADD_SEQUENCE = MAKE_COMMAND_ID(0x01); + static const Command_t ADD_TABLE = MAKE_COMMAND_ID(0x02); + static const Command_t DELETE_SEQUENCE = MAKE_COMMAND_ID(0x03); + static const Command_t DELETE_TABLE = MAKE_COMMAND_ID(0x04); + static const Command_t READ_SEQUENCE = MAKE_COMMAND_ID(0x05); + static const Command_t READ_TABLE = MAKE_COMMAND_ID(0x06); + static const Command_t LIST_SEQUENCES = MAKE_COMMAND_ID(0x07); + static const Command_t LIST_TABLES = MAKE_COMMAND_ID(0x08); + static const Command_t SEQUENCE_LIST = MAKE_COMMAND_ID(0x09); + static const Command_t TABLE_LIST = MAKE_COMMAND_ID(0x0A); + static const Command_t TABLE = MAKE_COMMAND_ID(0x0B); + static const Command_t SEQUENCE = MAKE_COMMAND_ID(0x0C); + static const Command_t READ_FREE_SEQUENCE_SLOTS = MAKE_COMMAND_ID(0x0D); + static const Command_t FREE_SEQUENCE_SLOTS = MAKE_COMMAND_ID(0x0E); + static const Command_t READ_FREE_TABLE_SLOTS = MAKE_COMMAND_ID(0x0F); + static const Command_t FREE_TABLE_SLOTS = MAKE_COMMAND_ID(0x10); - static void setModeSequenceMessage(CommandMessage *message, - Command_t command, Mode_t sequenceOrTable, - store_address_t storeAddress); - static void setModeSequenceMessage(CommandMessage *message, - Command_t command, Mode_t sequenceOrTable); - static void setModeSequenceMessage(CommandMessage *message, - Command_t command, store_address_t storeAddress); + static void setModeSequenceMessage(CommandMessage *message, Command_t command, + Mode_t sequenceOrTable, store_address_t storeAddress); + static void setModeSequenceMessage(CommandMessage *message, Command_t command, + Mode_t sequenceOrTable); + static void setModeSequenceMessage(CommandMessage *message, Command_t command, + store_address_t storeAddress); - static store_address_t getStoreAddress(const CommandMessage *message); - static Mode_t getSequenceId(const CommandMessage *message); - static Mode_t getTableId(const CommandMessage *message); - static uint32_t getNumber(const CommandMessage *message); + static store_address_t getStoreAddress(const CommandMessage *message); + static Mode_t getSequenceId(const CommandMessage *message); + static Mode_t getTableId(const CommandMessage *message); + static uint32_t getNumber(const CommandMessage *message); - static void clear(CommandMessage *message); + static void clear(CommandMessage *message); -private: - ModeSequenceMessage(); + private: + ModeSequenceMessage(); }; #endif /* FSFW_SUBSYSTEM_MODES_MODESEQUENCEMESSAGE_H_ */ diff --git a/src/fsfw/subsystem/modes/ModeStore.cpp b/src/fsfw/subsystem/modes/ModeStore.cpp index e28bbc4f..c70b5e21 100644 --- a/src/fsfw/subsystem/modes/ModeStore.cpp +++ b/src/fsfw/subsystem/modes/ModeStore.cpp @@ -4,125 +4,120 @@ // USE_MODESTORE could be part of the new FSFWConfig.h file. #if FSFW_USE_MODESTORE == 1 -ModeStore::ModeStore(object_id_t objectId, uint32_t slots) : - SystemObject(objectId), store(slots), emptySlot(store.front()) { - mutex = MutexFactory::instance()->createMutex();; - OSAL::createMutex(objectId + 1, mutex); - clear(); +ModeStore::ModeStore(object_id_t objectId, uint32_t slots) + : SystemObject(objectId), store(slots), emptySlot(store.front()) { + mutex = MutexFactory::instance()->createMutex(); + ; + OSAL::createMutex(objectId + 1, mutex); + clear(); } -ModeStore::~ModeStore() { - delete mutex; -} +ModeStore::~ModeStore() { delete mutex; } uint32_t ModeStore::getFreeSlots() { - OSAL::lockMutex(mutex, OSAL::NO_TIMEOUT); - uint32_t count = 0; - ArrayList::Iterator iter; - for (iter = store.begin(); iter != store.end(); ++iter) { - if (iter->getNext() == emptySlot) { - ++count; - } - } - OSAL::unlockMutex(mutex); - return count; + OSAL::lockMutex(mutex, OSAL::NO_TIMEOUT); + uint32_t count = 0; + ArrayList::Iterator iter; + for (iter = store.begin(); iter != store.end(); ++iter) { + if (iter->getNext() == emptySlot) { + ++count; + } + } + OSAL::unlockMutex(mutex); + return count; } ReturnValue_t ModeStore::storeArray(ArrayList* sequence, - ModeListEntry** storedFirstEntry) { - if (sequence->size == 0) { - return CANT_STORE_EMPTY; - } - OSAL::lockMutex(mutex, OSAL::NO_TIMEOUT); - *storedFirstEntry = findEmptySlotNoLock(store.front()); + ModeListEntry** storedFirstEntry) { + if (sequence->size == 0) { + return CANT_STORE_EMPTY; + } + OSAL::lockMutex(mutex, OSAL::NO_TIMEOUT); + *storedFirstEntry = findEmptySlotNoLock(store.front()); - ModeListEntry* pointer = - *storedFirstEntry; - pointer->setNext(pointer); + ModeListEntry* pointer = *storedFirstEntry; + pointer->setNext(pointer); - ArrayList::Iterator iter; - for (iter = sequence->begin(); iter != sequence->end(); ++iter) { - //SHOULDDO: I need to check this in detail. What is the idea? Why does it not work? - pointer = pointer->getNext()->value; - if (pointer == NULL) { - deleteListNoLock(*storedFirstEntry); - OSAL::unlockMutex(mutex); - return TOO_MANY_ELEMENTS; - } - pointer->value->value1 = iter->value1; - pointer->value->value2 = iter->value2; - pointer->value->value3 = iter->value3; - pointer->setNext(findEmptySlotNoLock(pointer + 1)); - } - pointer->setNext(NULL); - OSAL::unlockMutex(mutex); - return HasReturnvaluesIF::RETURN_OK; + ArrayList::Iterator iter; + for (iter = sequence->begin(); iter != sequence->end(); ++iter) { + // SHOULDDO: I need to check this in detail. What is the idea? Why does it not work? + pointer = pointer->getNext()->value; + if (pointer == NULL) { + deleteListNoLock(*storedFirstEntry); + OSAL::unlockMutex(mutex); + return TOO_MANY_ELEMENTS; + } + pointer->value->value1 = iter->value1; + pointer->value->value2 = iter->value2; + pointer->value->value3 = iter->value3; + pointer->setNext(findEmptySlotNoLock(pointer + 1)); + } + pointer->setNext(NULL); + OSAL::unlockMutex(mutex); + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t ModeStore::deleteList(ModeListEntry* sequence) { - ReturnValue_t result = isValidEntry(sequence); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - OSAL::lockMutex(mutex, OSAL::NO_TIMEOUT); - deleteListNoLock(sequence); - OSAL::unlockMutex(mutex); - return HasReturnvaluesIF::RETURN_OK; + ReturnValue_t result = isValidEntry(sequence); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + OSAL::lockMutex(mutex, OSAL::NO_TIMEOUT); + deleteListNoLock(sequence); + OSAL::unlockMutex(mutex); + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t ModeStore::readList(ModeListEntry* sequence, - ArrayList* into) { - ReturnValue_t result = isValidEntry(sequence); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - OSAL::lockMutex(mutex, OSAL::NO_TIMEOUT); - result = into->insert(*sequence->value); - while ((result == HasReturnvaluesIF::RETURN_OK) && (sequence->getNext() != NULL)) { - result = into->insert(*sequence->value); - sequence = sequence->getNext()->value; - } - OSAL::unlockMutex(mutex); - return result; +ReturnValue_t ModeStore::readList(ModeListEntry* sequence, ArrayList* into) { + ReturnValue_t result = isValidEntry(sequence); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + OSAL::lockMutex(mutex, OSAL::NO_TIMEOUT); + result = into->insert(*sequence->value); + while ((result == HasReturnvaluesIF::RETURN_OK) && (sequence->getNext() != NULL)) { + result = into->insert(*sequence->value); + sequence = sequence->getNext()->value; + } + OSAL::unlockMutex(mutex); + return result; } void ModeStore::clear() { - OSAL::lockMutex(mutex, OSAL::NO_TIMEOUT); - store.size = store.maxSize(); - ArrayList::Iterator iter; - for (iter = store.begin(); iter != store.end(); ++iter) { - iter->setNext(emptySlot); - } - OSAL::unlockMutex(mutex); + OSAL::lockMutex(mutex, OSAL::NO_TIMEOUT); + store.size = store.maxSize(); + ArrayList::Iterator iter; + for (iter = store.begin(); iter != store.end(); ++iter) { + iter->setNext(emptySlot); + } + OSAL::unlockMutex(mutex); } ModeListEntry* ModeStore::findEmptySlotNoLock(ModeListEntry* startFrom) { - ArrayList::Iterator iter( - startFrom); - for (; iter != store.end(); ++iter) { - if (iter.value->getNext() == emptySlot) { - OSAL::unlockMutex(mutex); - return iter.value; - } - } - return NULL; + ArrayList::Iterator iter(startFrom); + for (; iter != store.end(); ++iter) { + if (iter.value->getNext() == emptySlot) { + OSAL::unlockMutex(mutex); + return iter.value; + } + } + return NULL; } void ModeStore::deleteListNoLock(ModeListEntry* sequence) { - ModeListEntry* next = sequence; - while (next != NULL) { - next = sequence->getNext()->value; - sequence->setNext(emptySlot); - sequence = next; - } + ModeListEntry* next = sequence; + while (next != NULL) { + next = sequence->getNext()->value; + sequence->setNext(emptySlot); + sequence = next; + } } ReturnValue_t ModeStore::isValidEntry(ModeListEntry* sequence) { - if ((sequence < store.front()) || (sequence > store.back()) - || sequence->getNext() == emptySlot) { - return INVALID_ENTRY; - } - return HasReturnvaluesIF::RETURN_OK; + if ((sequence < store.front()) || (sequence > store.back()) || sequence->getNext() == emptySlot) { + return INVALID_ENTRY; + } + return HasReturnvaluesIF::RETURN_OK; } #endif diff --git a/src/fsfw/subsystem/modes/ModeStore.h b/src/fsfw/subsystem/modes/ModeStore.h index a5cb4059..1f3d103e 100644 --- a/src/fsfw/subsystem/modes/ModeStore.h +++ b/src/fsfw/subsystem/modes/ModeStore.h @@ -5,44 +5,37 @@ #if FSFW_USE_MODESTORE == 1 -#include "ModeStoreIF.h" - #include "../../container/ArrayList.h" #include "../../container/SinglyLinkedList.h" #include "../../objectmanager/SystemObject.h" +#include "ModeStoreIF.h" -class ModeStore: public ModeStoreIF, public SystemObject { -public: - ModeStore(object_id_t objectId, uint32_t slots); - virtual ~ModeStore(); +class ModeStore : public ModeStoreIF, public SystemObject { + public: + ModeStore(object_id_t objectId, uint32_t slots); + virtual ~ModeStore(); - virtual ReturnValue_t storeArray(ArrayList *sequence, - ModeListEntry **storedFirstEntry); + virtual ReturnValue_t storeArray(ArrayList *sequence, + ModeListEntry **storedFirstEntry); - virtual ReturnValue_t deleteList( - ModeListEntry *sequence); + virtual ReturnValue_t deleteList(ModeListEntry *sequence); - virtual ReturnValue_t readList( - ModeListEntry *sequence, - ArrayList *into); + virtual ReturnValue_t readList(ModeListEntry *sequence, ArrayList *into); - virtual uint32_t getFreeSlots(); + virtual uint32_t getFreeSlots(); -private: - MutexId_t* mutex; - ArrayList store; - ModeListEntry *emptySlot; + private: + MutexId_t *mutex; + ArrayList store; + ModeListEntry *emptySlot; - void clear(); - ModeListEntry* findEmptySlotNoLock( - ModeListEntry* startFrom); - void deleteListNoLock( - ModeListEntry *sequence); + void clear(); + ModeListEntry *findEmptySlotNoLock(ModeListEntry *startFrom); + void deleteListNoLock(ModeListEntry *sequence); - ReturnValue_t isValidEntry(ModeListEntry *sequence); + ReturnValue_t isValidEntry(ModeListEntry *sequence); }; #endif #endif /* FSFW_SUBSYSTEM_MODES_MODESTORE_H_ */ - diff --git a/src/fsfw/subsystem/modes/ModeStoreIF.h b/src/fsfw/subsystem/modes/ModeStoreIF.h index 9682501d..79215971 100644 --- a/src/fsfw/subsystem/modes/ModeStoreIF.h +++ b/src/fsfw/subsystem/modes/ModeStoreIF.h @@ -5,34 +5,28 @@ #if FSFW_USE_MODESTORE == 1 -#include "ModeDefinitions.h" - #include "../../container/ArrayList.h" #include "../../container/SinglyLinkedList.h" #include "../../returnvalues/HasReturnvaluesIF.h" +#include "ModeDefinitions.h" class ModeStoreIF { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::MODE_STORE_IF; - static const ReturnValue_t INVALID_ENTRY = MAKE_RETURN_CODE(0x02); - static const ReturnValue_t TOO_MANY_ELEMENTS = MAKE_RETURN_CODE(0x03); - static const ReturnValue_t CANT_STORE_EMPTY = MAKE_RETURN_CODE(0x04); + public: + static const uint8_t INTERFACE_ID = CLASS_ID::MODE_STORE_IF; + static const ReturnValue_t INVALID_ENTRY = MAKE_RETURN_CODE(0x02); + static const ReturnValue_t TOO_MANY_ELEMENTS = MAKE_RETURN_CODE(0x03); + static const ReturnValue_t CANT_STORE_EMPTY = MAKE_RETURN_CODE(0x04); - virtual ~ModeStoreIF() { + virtual ~ModeStoreIF() {} - } + virtual ReturnValue_t storeArray(ArrayList *sequence, + ModeListEntry **storedFirstEntry) = 0; - virtual ReturnValue_t storeArray(ArrayList *sequence, - ModeListEntry **storedFirstEntry) = 0; + virtual ReturnValue_t deleteList(ModeListEntry *sequence) = 0; - virtual ReturnValue_t deleteList( - ModeListEntry *sequence) = 0; + virtual ReturnValue_t readList(ModeListEntry *sequence, ArrayList *into) = 0; - virtual ReturnValue_t readList( - ModeListEntry *sequence, - ArrayList *into) = 0; - - virtual uint32_t getFreeSlots() = 0; + virtual uint32_t getFreeSlots() = 0; }; #endif diff --git a/src/fsfw/tasks/ExecutableObjectIF.h b/src/fsfw/tasks/ExecutableObjectIF.h index 06b837db..753a124f 100644 --- a/src/fsfw/tasks/ExecutableObjectIF.h +++ b/src/fsfw/tasks/ExecutableObjectIF.h @@ -3,9 +3,9 @@ class PeriodicTaskIF; -#include "../returnvalues/HasReturnvaluesIF.h" - #include + +#include "../returnvalues/HasReturnvaluesIF.h" /** * @brief The interface provides a method to execute objects within a task. * @details The performOperation method, that is required by the interface is @@ -13,41 +13,39 @@ class PeriodicTaskIF; * @author Bastian Baetz */ class ExecutableObjectIF { -public: - /** - * @brief This is the empty virtual destructor as required for C++ interfaces. - */ - virtual ~ExecutableObjectIF() { } - /** - * @brief The performOperation method is executed in a task. - * @details There are no restrictions for calls within this method, so any - * other member of the class can be used. - * @return Currently, the return value is ignored. - */ - virtual ReturnValue_t performOperation(uint8_t operationCode = 0) = 0; + public: + /** + * @brief This is the empty virtual destructor as required for C++ interfaces. + */ + virtual ~ExecutableObjectIF() {} + /** + * @brief The performOperation method is executed in a task. + * @details There are no restrictions for calls within this method, so any + * other member of the class can be used. + * @return Currently, the return value is ignored. + */ + virtual ReturnValue_t performOperation(uint8_t operationCode = 0) = 0; - /** - * @brief Function called during setup assignment of object to task - * @details - * Has to be called from the function that assigns the object to a task and - * enables the object implementation to overwrite this function and get - * a reference to the executing task - * @param task_ Pointer to the taskIF of this task - */ - virtual void setTaskIF(PeriodicTaskIF* task_) {}; + /** + * @brief Function called during setup assignment of object to task + * @details + * Has to be called from the function that assigns the object to a task and + * enables the object implementation to overwrite this function and get + * a reference to the executing task + * @param task_ Pointer to the taskIF of this task + */ + virtual void setTaskIF(PeriodicTaskIF* task_){}; - /** - * This function should be called after the object was assigned to a - * specific task. - * - * Example: Can be used to get task execution frequency. - * The task is created after initialize() and the object ctors have been - * called so the execution frequency can't be cached in initialize() - * @return - */ - virtual ReturnValue_t initializeAfterTaskCreation() { - return HasReturnvaluesIF::RETURN_OK; - } + /** + * This function should be called after the object was assigned to a + * specific task. + * + * Example: Can be used to get task execution frequency. + * The task is created after initialize() and the object ctors have been + * called so the execution frequency can't be cached in initialize() + * @return + */ + virtual ReturnValue_t initializeAfterTaskCreation() { return HasReturnvaluesIF::RETURN_OK; } }; #endif /* FRAMEWORK_TASKS_EXECUTABLEOBJECTIF_H_ */ diff --git a/src/fsfw/tasks/FixedSequenceSlot.cpp b/src/fsfw/tasks/FixedSequenceSlot.cpp index 9f617b58..e71135be 100644 --- a/src/fsfw/tasks/FixedSequenceSlot.cpp +++ b/src/fsfw/tasks/FixedSequenceSlot.cpp @@ -1,18 +1,18 @@ #include "fsfw/tasks/FixedSequenceSlot.h" -#include "fsfw/tasks/PeriodicTaskIF.h" #include -FixedSequenceSlot::FixedSequenceSlot(object_id_t handlerId, uint32_t setTime, - int8_t setSequenceId, ExecutableObjectIF* executableObject, - PeriodicTaskIF* executingTask) : handlerId(handlerId), - pollingTimeMs(setTime), opcode(setSequenceId) { - if(executableObject == nullptr) { - return; - } - this->executableObject = executableObject; - this->executableObject->setTaskIF(executingTask); +#include "fsfw/tasks/PeriodicTaskIF.h" + +FixedSequenceSlot::FixedSequenceSlot(object_id_t handlerId, uint32_t setTime, int8_t setSequenceId, + ExecutableObjectIF* executableObject, + PeriodicTaskIF* executingTask) + : handlerId(handlerId), pollingTimeMs(setTime), opcode(setSequenceId) { + if (executableObject == nullptr) { + return; + } + this->executableObject = executableObject; + this->executableObject->setTaskIF(executingTask); } FixedSequenceSlot::~FixedSequenceSlot() {} - diff --git a/src/fsfw/tasks/FixedSequenceSlot.h b/src/fsfw/tasks/FixedSequenceSlot.h index aea77dfe..5593a6aa 100644 --- a/src/fsfw/tasks/FixedSequenceSlot.h +++ b/src/fsfw/tasks/FixedSequenceSlot.h @@ -15,46 +15,44 @@ class PeriodicTaskIF; * @author baetz */ class FixedSequenceSlot { -public: - FixedSequenceSlot( object_id_t handlerId, uint32_t setTimeMs, - int8_t setSequenceId, ExecutableObjectIF* executableObject, - PeriodicTaskIF* executingTask); - virtual ~FixedSequenceSlot(); + public: + FixedSequenceSlot(object_id_t handlerId, uint32_t setTimeMs, int8_t setSequenceId, + ExecutableObjectIF* executableObject, PeriodicTaskIF* executingTask); + virtual ~FixedSequenceSlot(); - object_id_t handlerId; + object_id_t handlerId; - /** - * @brief Handler identifies which object is executed in this slot. - */ - ExecutableObjectIF* executableObject = nullptr; + /** + * @brief Handler identifies which object is executed in this slot. + */ + ExecutableObjectIF* executableObject = nullptr; - /** - * @brief This attribute defines when a device handler object is executed. - * @details - * The pollingTime attribute identifies the time the handler is - * executed in ms. It must be smaller than the period length of the - * polling sequence. - */ - uint32_t pollingTimeMs; + /** + * @brief This attribute defines when a device handler object is executed. + * @details + * The pollingTime attribute identifies the time the handler is + * executed in ms. It must be smaller than the period length of the + * polling sequence. + */ + uint32_t pollingTimeMs; - /** - * @brief This value defines the type of device communication. - * - * @details The state of this value decides what communication routine is - * called in the PST executable or the device handler object. - */ - uint8_t opcode; + /** + * @brief This value defines the type of device communication. + * + * @details The state of this value decides what communication routine is + * called in the PST executable or the device handler object. + */ + uint8_t opcode; - /** - * @brief Operator overload for the comparison operator to - * allow sorting by polling time. - * @param fixedSequenceSlot - * @return - */ - bool operator <(const FixedSequenceSlot & fixedSequenceSlot) const { - return pollingTimeMs < fixedSequenceSlot.pollingTimeMs; - } + /** + * @brief Operator overload for the comparison operator to + * allow sorting by polling time. + * @param fixedSequenceSlot + * @return + */ + bool operator<(const FixedSequenceSlot& fixedSequenceSlot) const { + return pollingTimeMs < fixedSequenceSlot.pollingTimeMs; + } }; - #endif /* FSFW_TASKS_FIXEDSEQUENCESLOT_H_ */ diff --git a/src/fsfw/tasks/FixedSlotSequence.cpp b/src/fsfw/tasks/FixedSlotSequence.cpp index 5e896af4..d4c67b4d 100644 --- a/src/fsfw/tasks/FixedSlotSequence.cpp +++ b/src/fsfw/tasks/FixedSlotSequence.cpp @@ -1,174 +1,166 @@ #include "fsfw/tasks/FixedSlotSequence.h" -#include "fsfw/tasks/FixedTimeslotTaskIF.h" -#include "fsfw/serviceinterface/ServiceInterface.h" + #include -FixedSlotSequence::FixedSlotSequence(uint32_t setLengthMs) : - lengthMs(setLengthMs) { - current = slotList.begin(); +#include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/tasks/FixedTimeslotTaskIF.h" + +FixedSlotSequence::FixedSlotSequence(uint32_t setLengthMs) : lengthMs(setLengthMs) { + current = slotList.begin(); } FixedSlotSequence::~FixedSlotSequence() { - // Call the destructor on each list entry. - slotList.clear(); + // Call the destructor on each list entry. + slotList.clear(); } void FixedSlotSequence::executeAndAdvance() { - current->executableObject->performOperation(current->opcode); -// if (returnValue != RETURN_OK) { -// this->sendErrorMessage( returnValue ); -// } - //Increment the polling Sequence iterator - this->current++; - //Set it to the beginning, if the list's end is reached. - if (this->current == this->slotList.end()) { - this->current = this->slotList.begin(); - } + current->executableObject->performOperation(current->opcode); + // if (returnValue != RETURN_OK) { + // this->sendErrorMessage( returnValue ); + // } + // Increment the polling Sequence iterator + this->current++; + // Set it to the beginning, if the list's end is reached. + if (this->current == this->slotList.end()) { + this->current = this->slotList.begin(); + } } uint32_t FixedSlotSequence::getIntervalToNextSlotMs() { - uint32_t oldTime; - SlotListIter slotListIter = current; - // Get the pollingTimeMs of the current slot object. - oldTime = slotListIter->pollingTimeMs; - // Advance to the next object. - slotListIter++; - // Find the next interval which is not 0. - while (slotListIter != slotList.end()) { - if (oldTime != slotListIter->pollingTimeMs) { - return slotListIter->pollingTimeMs - oldTime; - } else { - slotListIter++; - } - } - // If the list end is reached (this is definitely an interval != 0), - // the interval is calculated by subtracting the remaining time of the PST - // and adding the start time of the first handler in the list. - slotListIter = slotList.begin(); - return lengthMs - oldTime + slotListIter->pollingTimeMs; + uint32_t oldTime; + SlotListIter slotListIter = current; + // Get the pollingTimeMs of the current slot object. + oldTime = slotListIter->pollingTimeMs; + // Advance to the next object. + slotListIter++; + // Find the next interval which is not 0. + while (slotListIter != slotList.end()) { + if (oldTime != slotListIter->pollingTimeMs) { + return slotListIter->pollingTimeMs - oldTime; + } else { + slotListIter++; + } + } + // If the list end is reached (this is definitely an interval != 0), + // the interval is calculated by subtracting the remaining time of the PST + // and adding the start time of the first handler in the list. + slotListIter = slotList.begin(); + return lengthMs - oldTime + slotListIter->pollingTimeMs; } uint32_t FixedSlotSequence::getIntervalToPreviousSlotMs() { - uint32_t currentTime; - SlotListIter slotListIter = current; - // Get the pollingTimeMs of the current slot object. - currentTime = slotListIter->pollingTimeMs; + uint32_t currentTime; + SlotListIter slotListIter = current; + // Get the pollingTimeMs of the current slot object. + currentTime = slotListIter->pollingTimeMs; - //if it is the first slot, calculate difference to last slot - if (slotListIter == slotList.begin()){ - return lengthMs - (--slotList.end())->pollingTimeMs + currentTime; - } - // get previous slot - slotListIter--; + // if it is the first slot, calculate difference to last slot + if (slotListIter == slotList.begin()) { + return lengthMs - (--slotList.end())->pollingTimeMs + currentTime; + } + // get previous slot + slotListIter--; - return currentTime - slotListIter->pollingTimeMs; + return currentTime - slotListIter->pollingTimeMs; } bool FixedSlotSequence::slotFollowsImmediately() { - uint32_t currentTime = current->pollingTimeMs; - SlotListIter fixedSequenceIter = this->current; - // Get the pollingTimeMs of the current slot object. - if (fixedSequenceIter == slotList.begin()) - return false; - fixedSequenceIter--; - if (fixedSequenceIter->pollingTimeMs == currentTime) { - return true; - } else { - return false; - } + uint32_t currentTime = current->pollingTimeMs; + SlotListIter fixedSequenceIter = this->current; + // Get the pollingTimeMs of the current slot object. + if (fixedSequenceIter == slotList.begin()) return false; + fixedSequenceIter--; + if (fixedSequenceIter->pollingTimeMs == currentTime) { + return true; + } else { + return false; + } } -uint32_t FixedSlotSequence::getLengthMs() const { - return this->lengthMs; -} +uint32_t FixedSlotSequence::getLengthMs() const { return this->lengthMs; } -void FixedSlotSequence::addSlot(object_id_t componentId, uint32_t slotTimeMs, - int8_t executionStep, ExecutableObjectIF* executableObject, - PeriodicTaskIF* executingTask) { - this->slotList.insert(FixedSequenceSlot(componentId, slotTimeMs, - executionStep, executableObject, executingTask)); - this->current = slotList.begin(); +void FixedSlotSequence::addSlot(object_id_t componentId, uint32_t slotTimeMs, int8_t executionStep, + ExecutableObjectIF* executableObject, + PeriodicTaskIF* executingTask) { + this->slotList.insert( + FixedSequenceSlot(componentId, slotTimeMs, executionStep, executableObject, executingTask)); + this->current = slotList.begin(); } ReturnValue_t FixedSlotSequence::checkSequence() const { - if(slotList.empty()) { + if (slotList.empty()) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "FixedSlotSequence::checkSequence: Slot list is empty!" << std::endl; + sif::warning << "FixedSlotSequence::checkSequence: Slot list is empty!" << std::endl; #endif - return FixedTimeslotTaskIF::SLOT_LIST_EMPTY; - } + return FixedTimeslotTaskIF::SLOT_LIST_EMPTY; + } - if(customCheckFunction != nullptr) { - ReturnValue_t result = customCheckFunction(slotList); - if(result != HasReturnvaluesIF::RETURN_OK) { - // Continue for now but print error output. + if (customCheckFunction != nullptr) { + ReturnValue_t result = customCheckFunction(slotList); + if (result != HasReturnvaluesIF::RETURN_OK) { + // Continue for now but print error output. #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "FixedSlotSequence::checkSequence:" - << " Custom check failed!" << std::endl; + sif::error << "FixedSlotSequence::checkSequence:" + << " Custom check failed!" << std::endl; #endif - } - } + } + } - uint32_t errorCount = 0; - uint32_t time = 0; - for(const auto& slot: slotList) { - if (slot.executableObject == nullptr) { - errorCount++; - } - else if (slot.pollingTimeMs < time) { + uint32_t errorCount = 0; + uint32_t time = 0; + for (const auto& slot : slotList) { + if (slot.executableObject == nullptr) { + errorCount++; + } else if (slot.pollingTimeMs < time) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "FixedSlotSequence::checkSequence: Time: " - << slot.pollingTimeMs << " is smaller than previous with " - << time << std::endl; + sif::error << "FixedSlotSequence::checkSequence: Time: " << slot.pollingTimeMs + << " is smaller than previous with " << time << std::endl; #endif - errorCount++; - } - else { - // All ok, print slot. + errorCount++; + } else { + // All ok, print slot. #if FSFW_CPP_OSTREAM_ENABLED == 1 - //sif::info << "Current slot polling time: " << std::endl; - //sif::info << std::dec << slotIt->pollingTimeMs << std::endl; + // sif::info << "Current slot polling time: " << std::endl; + // sif::info << std::dec << slotIt->pollingTimeMs << std::endl; #endif - } - time = slot.pollingTimeMs; - - } + } + time = slot.pollingTimeMs; + } #if FSFW_CPP_OSTREAM_ENABLED == 1 - //sif::info << "Number of elements in slot list: " - // << slotList.size() << std::endl; + // sif::info << "Number of elements in slot list: " + // << slotList.size() << std::endl; #endif - if (errorCount > 0) { - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + if (errorCount > 0) { + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } - ReturnValue_t FixedSlotSequence::intializeSequenceAfterTaskCreation() const { - std::set uniqueObjects; - uint32_t count = 0; - for(const auto& slot: slotList) { - // Ensure that each unique object is initialized once. - if(uniqueObjects.find(slot.executableObject) == uniqueObjects.end()) { - ReturnValue_t result = - slot.executableObject->initializeAfterTaskCreation(); - if(result != HasReturnvaluesIF::RETURN_OK) { - count++; - } - uniqueObjects.emplace(slot.executableObject); - } + std::set uniqueObjects; + uint32_t count = 0; + for (const auto& slot : slotList) { + // Ensure that each unique object is initialized once. + if (uniqueObjects.find(slot.executableObject) == uniqueObjects.end()) { + ReturnValue_t result = slot.executableObject->initializeAfterTaskCreation(); + if (result != HasReturnvaluesIF::RETURN_OK) { + count++; + } + uniqueObjects.emplace(slot.executableObject); } - if (count > 0) { + } + if (count > 0) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "FixedSlotSequence::intializeSequenceAfterTaskCreation:" - "Counted " << count << " failed initializations!" << std::endl; + sif::error << "FixedSlotSequence::intializeSequenceAfterTaskCreation:" + "Counted " + << count << " failed initializations!" << std::endl; #endif - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } -void FixedSlotSequence::addCustomCheck(ReturnValue_t - (*customCheckFunction)(const SlotList&)) { - this->customCheckFunction = customCheckFunction; +void FixedSlotSequence::addCustomCheck(ReturnValue_t (*customCheckFunction)(const SlotList&)) { + this->customCheckFunction = customCheckFunction; } diff --git a/src/fsfw/tasks/FixedSlotSequence.h b/src/fsfw/tasks/FixedSlotSequence.h index 7f49ea0c..a287c5b2 100644 --- a/src/fsfw/tasks/FixedSlotSequence.h +++ b/src/fsfw/tasks/FixedSlotSequence.h @@ -1,11 +1,11 @@ #ifndef FSFW_TASKS_FIXEDSLOTSEQUENCE_H_ #define FSFW_TASKS_FIXEDSLOTSEQUENCE_H_ +#include + #include "FixedSequenceSlot.h" #include "fsfw/objectmanager/SystemObject.h" -#include - /** * @brief This class is the representation of a * Polling Sequence Table in software. @@ -27,157 +27,155 @@ * executing the executable object in the correct timeslot. */ class FixedSlotSequence { -public: - using SlotList = std::multiset; - using SlotListIter = std::multiset::iterator; + public: + using SlotList = std::multiset; + using SlotListIter = std::multiset::iterator; - /** - * @brief The constructor of the FixedSlotSequence object. - * @param setLength The period length, expressed in ms. - */ - FixedSlotSequence(uint32_t setLengthMs); + /** + * @brief The constructor of the FixedSlotSequence object. + * @param setLength The period length, expressed in ms. + */ + FixedSlotSequence(uint32_t setLengthMs); - /** - * @brief The destructor of the FixedSlotSequence object. - * @details - * The destructor frees all allocated memory by iterating through the - * slotList and deleting all allocated resources. - */ - virtual ~FixedSlotSequence(); + /** + * @brief The destructor of the FixedSlotSequence object. + * @details + * The destructor frees all allocated memory by iterating through the + * slotList and deleting all allocated resources. + */ + virtual ~FixedSlotSequence(); - /** - * @brief This is a method to add an PollingSlot object to slotList. - * - * @details - * Here, a polling slot object is added to the slot list. It is appended - * to the end of the list. The list is currently NOT reordered. - * Afterwards, the iterator current is set to the beginning of the list. - * @param handlerId ID of the object to add - * @param setTime - * Value between (0 to 1) * slotLengthMs, when a FixedTimeslotTask - * will be called inside the slot period. - * @param setSequenceId - * ID which can be used to distinguish different task operations. This - * value will be passed to the executable function. - * @param - * @param - */ - void addSlot(object_id_t handlerId, uint32_t setTime, int8_t setSequenceId, - ExecutableObjectIF* executableObject, - PeriodicTaskIF* executingTask); + /** + * @brief This is a method to add an PollingSlot object to slotList. + * + * @details + * Here, a polling slot object is added to the slot list. It is appended + * to the end of the list. The list is currently NOT reordered. + * Afterwards, the iterator current is set to the beginning of the list. + * @param handlerId ID of the object to add + * @param setTime + * Value between (0 to 1) * slotLengthMs, when a FixedTimeslotTask + * will be called inside the slot period. + * @param setSequenceId + * ID which can be used to distinguish different task operations. This + * value will be passed to the executable function. + * @param + * @param + */ + void addSlot(object_id_t handlerId, uint32_t setTime, int8_t setSequenceId, + ExecutableObjectIF* executableObject, PeriodicTaskIF* executingTask); - /** - * @brief Checks if the current slot shall be executed immediately - * after the one before. - * @details - * This allows to distinguish between grouped and separated handlers. - * @return - @c true if the slot has the same polling time as the previous - * - @c false else - */ - bool slotFollowsImmediately(); + /** + * @brief Checks if the current slot shall be executed immediately + * after the one before. + * @details + * This allows to distinguish between grouped and separated handlers. + * @return - @c true if the slot has the same polling time as the previous + * - @c false else + */ + bool slotFollowsImmediately(); - /** - * @brief This method returns the time until the next software - * component is invoked. - * - * @details - * This method is vitally important for the operation of the PST. - * By fetching the polling time of the current slot and that of the - * next one (or the first one, if the list end is reached) - * it calculates and returns the interval in milliseconds within - * which the handler execution shall take place. - * If the next slot has the same time as the current one, it is ignored - * until a slot with different time or the end of the PST is found. - */ - uint32_t getIntervalToNextSlotMs(); + /** + * @brief This method returns the time until the next software + * component is invoked. + * + * @details + * This method is vitally important for the operation of the PST. + * By fetching the polling time of the current slot and that of the + * next one (or the first one, if the list end is reached) + * it calculates and returns the interval in milliseconds within + * which the handler execution shall take place. + * If the next slot has the same time as the current one, it is ignored + * until a slot with different time or the end of the PST is found. + */ + uint32_t getIntervalToNextSlotMs(); - /** - * @brief This method returns the time difference between the current - * slot and the previous slot - * - * @details - * This method is vitally important for the operation of the PST. - * By fetching the polling time of the current slot and that of the previous - * one (or the last one, if the slot is the first one) it calculates and - * returns the interval in milliseconds that the handler execution shall - * be delayed. - */ - uint32_t getIntervalToPreviousSlotMs(); + /** + * @brief This method returns the time difference between the current + * slot and the previous slot + * + * @details + * This method is vitally important for the operation of the PST. + * By fetching the polling time of the current slot and that of the previous + * one (or the last one, if the slot is the first one) it calculates and + * returns the interval in milliseconds that the handler execution shall + * be delayed. + */ + uint32_t getIntervalToPreviousSlotMs(); - /** - * @brief This method returns the length of this FixedSlotSequence instance. - */ - uint32_t getLengthMs() const; + /** + * @brief This method returns the length of this FixedSlotSequence instance. + */ + uint32_t getLengthMs() const; - /** - * @brief The method to execute the device handler entered in the current - * PollingSlot object. - * - * @details - * Within this method the device handler object to be executed is chosen by - * looking up the handler address of the current slot in the handlerMap. - * Either the device handler's talkToInterface or its listenToInterface - * method is invoked, depending on the isTalking flag of the polling slot. - * After execution the iterator current is increased or, by reaching the - * end of slotList, reset to the beginning. - */ - void executeAndAdvance(); + /** + * @brief The method to execute the device handler entered in the current + * PollingSlot object. + * + * @details + * Within this method the device handler object to be executed is chosen by + * looking up the handler address of the current slot in the handlerMap. + * Either the device handler's talkToInterface or its listenToInterface + * method is invoked, depending on the isTalking flag of the polling slot. + * After execution the iterator current is increased or, by reaching the + * end of slotList, reset to the beginning. + */ + void executeAndAdvance(); - /** - * @brief An iterator that indicates the current polling slot to execute. - * - * @details This is an iterator for slotList and always points to the - * polling slot which is executed next. - */ - SlotListIter current; + /** + * @brief An iterator that indicates the current polling slot to execute. + * + * @details This is an iterator for slotList and always points to the + * polling slot which is executed next. + */ + SlotListIter current; - /** - * @brief Check and initialize slot list. - * @details - * Checks if timing is ok (must be ascending) and if all handlers were found. - * @return - * - SLOT_LIST_EMPTY if the slot list is empty - */ - ReturnValue_t checkSequence() const; + /** + * @brief Check and initialize slot list. + * @details + * Checks if timing is ok (must be ascending) and if all handlers were found. + * @return + * - SLOT_LIST_EMPTY if the slot list is empty + */ + ReturnValue_t checkSequence() const; - /** - * @brief A custom check can be injected for the respective slot list. - * @details - * This can be used by the developer to check the validity of a certain - * sequence. The function will be run in the #checkSequence function. - * The general check will be continued for now if the custom check function - * fails but a diagnostic debug output will be given. - * @param customCheckFunction - * - */ - void addCustomCheck(ReturnValue_t (*customCheckFunction)(const SlotList &)); + /** + * @brief A custom check can be injected for the respective slot list. + * @details + * This can be used by the developer to check the validity of a certain + * sequence. The function will be run in the #checkSequence function. + * The general check will be continued for now if the custom check function + * fails but a diagnostic debug output will be given. + * @param customCheckFunction + * + */ + void addCustomCheck(ReturnValue_t (*customCheckFunction)(const SlotList&)); - /** - * @brief Perform any initialization steps required after the executing - * task has been created. This function should be called from the - * executing task! - * @return - */ - ReturnValue_t intializeSequenceAfterTaskCreation() const; + /** + * @brief Perform any initialization steps required after the executing + * task has been created. This function should be called from the + * executing task! + * @return + */ + ReturnValue_t intializeSequenceAfterTaskCreation() const; -protected: + protected: + /** + * @brief This list contains all PollingSlot objects, defining order and + * execution time of the device handler objects. + * + * @details + * The slot list is a std:list object that contains all created + * PollingSlot instances. They are NOT ordered automatically, so by + * adding entries, the correct order needs to be ensured. By iterating + * through this list the polling sequence is executed. Two entries with + * identical polling times are executed immediately one after another. + */ + SlotList slotList; - /** - * @brief This list contains all PollingSlot objects, defining order and - * execution time of the device handler objects. - * - * @details - * The slot list is a std:list object that contains all created - * PollingSlot instances. They are NOT ordered automatically, so by - * adding entries, the correct order needs to be ensured. By iterating - * through this list the polling sequence is executed. Two entries with - * identical polling times are executed immediately one after another. - */ - SlotList slotList; + ReturnValue_t (*customCheckFunction)(const SlotList&) = nullptr; - ReturnValue_t (*customCheckFunction)(const SlotList&) = nullptr; - - uint32_t lengthMs; + uint32_t lengthMs; }; #endif /* FSFW_TASKS_FIXEDSLOTSEQUENCE_H_ */ diff --git a/src/fsfw/tasks/FixedTimeslotTaskIF.h b/src/fsfw/tasks/FixedTimeslotTaskIF.h index 605239a4..497db245 100644 --- a/src/fsfw/tasks/FixedTimeslotTaskIF.h +++ b/src/fsfw/tasks/FixedTimeslotTaskIF.h @@ -10,29 +10,27 @@ * This is the interface for a Fixed timeslot task */ class FixedTimeslotTaskIF : public PeriodicTaskIF { -public: - virtual ~FixedTimeslotTaskIF() {} + public: + virtual ~FixedTimeslotTaskIF() {} - static constexpr ReturnValue_t SLOT_LIST_EMPTY = HasReturnvaluesIF::makeReturnCode( - CLASS_ID::FIXED_SLOT_TASK_IF, 0); - /** - * Add an object with a slot time and the execution step to the task. - * The execution step will be passed to the object (e.g. as an operation - * code in #performOperation) - * @param componentId - * @param slotTimeMs - * @param executionStep - * @return - */ - virtual ReturnValue_t addSlot(object_id_t componentId, uint32_t slotTimeMs, - int8_t executionStep) = 0; - /** - * Check whether the sequence is valid and perform all other required - * initialization steps which are needed after task creation - */ - virtual ReturnValue_t checkSequence() const = 0; + static constexpr ReturnValue_t SLOT_LIST_EMPTY = + HasReturnvaluesIF::makeReturnCode(CLASS_ID::FIXED_SLOT_TASK_IF, 0); + /** + * Add an object with a slot time and the execution step to the task. + * The execution step will be passed to the object (e.g. as an operation + * code in #performOperation) + * @param componentId + * @param slotTimeMs + * @param executionStep + * @return + */ + virtual ReturnValue_t addSlot(object_id_t componentId, uint32_t slotTimeMs, + int8_t executionStep) = 0; + /** + * Check whether the sequence is valid and perform all other required + * initialization steps which are needed after task creation + */ + virtual ReturnValue_t checkSequence() const = 0; }; - - #endif /* FRAMEWORK_TASKS_FIXEDTIMESLOTTASKIF_H_ */ diff --git a/src/fsfw/tasks/PeriodicTaskIF.h b/src/fsfw/tasks/PeriodicTaskIF.h index 4df37645..a8a51229 100644 --- a/src/fsfw/tasks/PeriodicTaskIF.h +++ b/src/fsfw/tasks/PeriodicTaskIF.h @@ -1,49 +1,49 @@ #ifndef FRAMEWORK_TASK_PERIODICTASKIF_H_ #define FRAMEWORK_TASK_PERIODICTASKIF_H_ +#include + #include "../objectmanager/SystemObjectIF.h" #include "../timemanager/Clock.h" -#include class ExecutableObjectIF; /** * New version of TaskIF * Follows RAII principles, i.e. there's no create or delete method. * Minimalistic. -*/ + */ class PeriodicTaskIF { -public: - static const size_t MINIMUM_STACK_SIZE; - /** - * @brief A virtual destructor as it is mandatory for interfaces. - */ - virtual ~PeriodicTaskIF() { } - /** - * @brief With the startTask method, a created task can be started - * for the first time. - */ - virtual ReturnValue_t startTask() = 0; + public: + static const size_t MINIMUM_STACK_SIZE; + /** + * @brief A virtual destructor as it is mandatory for interfaces. + */ + virtual ~PeriodicTaskIF() {} + /** + * @brief With the startTask method, a created task can be started + * for the first time. + */ + virtual ReturnValue_t startTask() = 0; - /** - * Add a component (object) to a periodic task. The pointer to the - * task can be set optionally - * @param object - * Add an object to the task. The most important case is to add an - * executable object with a function which will be called regularly - * (see ExecutableObjectIF) - * @param setTaskIF - * Can be used to specify whether the task object pointer is passed - * to the component. - * @return - */ - virtual ReturnValue_t addComponent(object_id_t object) { - return HasReturnvaluesIF::RETURN_FAILED; - }; + /** + * Add a component (object) to a periodic task. The pointer to the + * task can be set optionally + * @param object + * Add an object to the task. The most important case is to add an + * executable object with a function which will be called regularly + * (see ExecutableObjectIF) + * @param setTaskIF + * Can be used to specify whether the task object pointer is passed + * to the component. + * @return + */ + virtual ReturnValue_t addComponent(object_id_t object) { + return HasReturnvaluesIF::RETURN_FAILED; + }; - virtual ReturnValue_t sleepFor(uint32_t ms) = 0; + virtual ReturnValue_t sleepFor(uint32_t ms) = 0; - virtual uint32_t getPeriodMs() const = 0; + virtual uint32_t getPeriodMs() const = 0; }; - #endif /* PERIODICTASKIF_H_ */ diff --git a/src/fsfw/tasks/SemaphoreFactory.h b/src/fsfw/tasks/SemaphoreFactory.h index 2df7d53f..936ee46b 100644 --- a/src/fsfw/tasks/SemaphoreFactory.h +++ b/src/fsfw/tasks/SemaphoreFactory.h @@ -9,42 +9,42 @@ * interface, but also is the base class for a singleton. */ class SemaphoreFactory { -public: - virtual ~SemaphoreFactory(); - /** - * Returns the single instance of SemaphoreFactory. - * The implementation of #instance is found in its subclasses. - * Thus, we choose link-time variability of the instance. - */ - static SemaphoreFactory* instance(); + public: + virtual ~SemaphoreFactory(); + /** + * Returns the single instance of SemaphoreFactory. + * The implementation of #instance is found in its subclasses. + * Thus, we choose link-time variability of the instance. + */ + static SemaphoreFactory* instance(); - /** - * Create a binary semaphore. - * Creator function for a binary semaphore which may only be acquired once - * @param argument Can be used to pass implementation specific information. - * @return Pointer to newly created semaphore class instance. - */ - SemaphoreIF* createBinarySemaphore(uint32_t arguments = 0); - /** - * Create a counting semaphore. - * Creator functons for a counting semaphore which may be acquired multiple - * times. - * @param count Semaphore can be taken count times. - * @param initCount Initial count value. - * @param argument Can be used to pass implementation specific information. - * @return - */ - SemaphoreIF* createCountingSemaphore(const uint8_t maxCount, - uint8_t initCount, uint32_t arguments = 0); + /** + * Create a binary semaphore. + * Creator function for a binary semaphore which may only be acquired once + * @param argument Can be used to pass implementation specific information. + * @return Pointer to newly created semaphore class instance. + */ + SemaphoreIF* createBinarySemaphore(uint32_t arguments = 0); + /** + * Create a counting semaphore. + * Creator functons for a counting semaphore which may be acquired multiple + * times. + * @param count Semaphore can be taken count times. + * @param initCount Initial count value. + * @param argument Can be used to pass implementation specific information. + * @return + */ + SemaphoreIF* createCountingSemaphore(const uint8_t maxCount, uint8_t initCount, + uint32_t arguments = 0); - void deleteSemaphore(SemaphoreIF* semaphore); + void deleteSemaphore(SemaphoreIF* semaphore); -private: - /** - * External instantiation is not allowed. - */ - SemaphoreFactory(); - static SemaphoreFactory* factoryInstance; + private: + /** + * External instantiation is not allowed. + */ + SemaphoreFactory(); + static SemaphoreFactory* factoryInstance; }; #endif /* FSFW_TASKS_SEMAPHOREFACTORY_H_ */ diff --git a/src/fsfw/tasks/SemaphoreIF.h b/src/fsfw/tasks/SemaphoreIF.h index dd327e23..3f544de8 100644 --- a/src/fsfw/tasks/SemaphoreIF.h +++ b/src/fsfw/tasks/SemaphoreIF.h @@ -1,8 +1,9 @@ #ifndef FRAMEWORK_TASKS_SEMAPHOREIF_H_ #define FRAMEWORK_TASKS_SEMAPHOREIF_H_ +#include + #include "../returnvalues/FwClassIds.h" #include "../returnvalues/HasReturnvaluesIF.h" -#include /** * @brief Generic interface for semaphores, which can be used to achieve @@ -19,50 +20,50 @@ * which is a special form of a semaphore and has an own interface. */ class SemaphoreIF { -public: - /** - * Different types of timeout for the mutex lock. - */ - enum TimeoutType { - POLLING, //!< If mutex is not available, return immediately - WAITING, //!< Wait a specified time for the mutex to become available - BLOCKING //!< Block indefinitely until the mutex becomes available. - }; + public: + /** + * Different types of timeout for the mutex lock. + */ + enum TimeoutType { + POLLING, //!< If mutex is not available, return immediately + WAITING, //!< Wait a specified time for the mutex to become available + BLOCKING //!< Block indefinitely until the mutex becomes available. + }; - virtual~ SemaphoreIF() {}; + virtual ~SemaphoreIF(){}; - static const uint8_t INTERFACE_ID = CLASS_ID::SEMAPHORE_IF; - //! Semaphore timeout - static constexpr ReturnValue_t SEMAPHORE_TIMEOUT = MAKE_RETURN_CODE(1); - //! The current semaphore can not be given, because it is not owned - static constexpr ReturnValue_t SEMAPHORE_NOT_OWNED = MAKE_RETURN_CODE(2); - static constexpr ReturnValue_t SEMAPHORE_INVALID = MAKE_RETURN_CODE(3); + static const uint8_t INTERFACE_ID = CLASS_ID::SEMAPHORE_IF; + //! Semaphore timeout + static constexpr ReturnValue_t SEMAPHORE_TIMEOUT = MAKE_RETURN_CODE(1); + //! The current semaphore can not be given, because it is not owned + static constexpr ReturnValue_t SEMAPHORE_NOT_OWNED = MAKE_RETURN_CODE(2); + static constexpr ReturnValue_t SEMAPHORE_INVALID = MAKE_RETURN_CODE(3); - /** - * Generic call to acquire a semaphore. - * If there are no more semaphores to be taken (for a counting semaphore, - * a semaphore may be taken more than once), the taks will block - * for a maximum of timeoutMs while trying to acquire the semaphore. - * This can be used to achieve task synchrnization. - * @param timeoutMs - * @return - c RETURN_OK for successfull acquisition - */ - virtual ReturnValue_t acquire(TimeoutType timeoutType = - TimeoutType::BLOCKING, uint32_t timeoutMs = 0) = 0; + /** + * Generic call to acquire a semaphore. + * If there are no more semaphores to be taken (for a counting semaphore, + * a semaphore may be taken more than once), the taks will block + * for a maximum of timeoutMs while trying to acquire the semaphore. + * This can be used to achieve task synchrnization. + * @param timeoutMs + * @return - c RETURN_OK for successfull acquisition + */ + virtual ReturnValue_t acquire(TimeoutType timeoutType = TimeoutType::BLOCKING, + uint32_t timeoutMs = 0) = 0; - /** - * Corrensponding call to release a semaphore. - * @return -@c RETURN_OK for successfull release - */ - virtual ReturnValue_t release() = 0; + /** + * Corrensponding call to release a semaphore. + * @return -@c RETURN_OK for successfull release + */ + virtual ReturnValue_t release() = 0; - /** - * If the semaphore is a counting semaphore then the semaphores current - * count value is returned. If the semaphore is a binary semaphore then 1 - * is returned if the semaphore is available, and 0 is returned if the - * semaphore is not available. - */ - virtual uint8_t getSemaphoreCounter() const = 0; + /** + * If the semaphore is a counting semaphore then the semaphores current + * count value is returned. If the semaphore is a binary semaphore then 1 + * is returned if the semaphore is available, and 0 is returned if the + * semaphore is not available. + */ + virtual uint8_t getSemaphoreCounter() const = 0; }; #endif /* FRAMEWORK_TASKS_SEMAPHOREIF_H_ */ diff --git a/src/fsfw/tasks/TaskFactory.h b/src/fsfw/tasks/TaskFactory.h index d4795202..fcd62678 100644 --- a/src/fsfw/tasks/TaskFactory.h +++ b/src/fsfw/tasks/TaskFactory.h @@ -1,98 +1,96 @@ #ifndef FSFW_TASKS_TASKFACTORY_H_ #define FSFW_TASKS_TASKFACTORY_H_ +#include + #include "FixedTimeslotTaskIF.h" #include "Typedef.h" -#include - /** * Singleton Class that produces Tasks. */ class TaskFactory { -public: - virtual ~TaskFactory(); - /** - * Returns the single instance of TaskFactory. - * The implementation of #instance is found in its subclasses. - * Thus, we choose link-time variability of the instance. - */ - static TaskFactory* instance(); + public: + virtual ~TaskFactory(); + /** + * Returns the single instance of TaskFactory. + * The implementation of #instance is found in its subclasses. + * Thus, we choose link-time variability of the instance. + */ + static TaskFactory* instance(); - /** - * Creates a new periodic task and returns the interface pointer. - * @param name_ Name of the task - * @param taskPriority_ - * Priority of the task. This value might have different ranges for the various OSALs. - * - Linux Value ranging from 0 to 99 with 99 being the highest value. - * - Host For Windows, the value can be retrieved by using the #tasks::makeWinPriority - * function. For Linux, same priority system as specified above. MacOS not tested - * yet - * - FreeRTOS Value depends on the FreeRTOS configuration, higher number means higher priority - * - RTEMS Values ranging from 0 to 99 with 99 being the highest value. - * - * @param stackSize_ Stack Size of the task - * This value might have different recommended ranges for the various OSALs. - * - Linux Lowest limit is the PeriodicTaskIF::MINIMUM_STACK_SIZE value - * - Host Value is ignored for now because the C++ threading abstraction layer is used. - * - FreeRTOS Stack size in bytes. It is recommended to specify at least 1kB of stack for - * FSFW tasks, but the lowest possible size is specified in the - * FreeRTOSConfig.h file. - * - RTEMS Lowest limit is specified the PeriodicTaskIF::MINIMUM_STACK_SIZE value. - * - * @param period_ Period of the task - * - * @param deadLineMissedFunction_ Function to be called if a deadline was missed - * @return PeriodicTaskIF* Pointer to the newly created Task - */ - PeriodicTaskIF* createPeriodicTask(TaskName name_, - TaskPriority taskPriority_, TaskStackSize stackSize_, - TaskPeriod periodInSeconds_, - TaskDeadlineMissedFunction deadLineMissedFunction_); + /** + * Creates a new periodic task and returns the interface pointer. + * @param name_ Name of the task + * @param taskPriority_ + * Priority of the task. This value might have different ranges for the various OSALs. + * - Linux Value ranging from 0 to 99 with 99 being the highest value. + * - Host For Windows, the value can be retrieved by using the #tasks::makeWinPriority + * function. For Linux, same priority system as specified above. MacOS not tested + * yet + * - FreeRTOS Value depends on the FreeRTOS configuration, higher number means higher priority + * - RTEMS Values ranging from 0 to 99 with 99 being the highest value. + * + * @param stackSize_ Stack Size of the task + * This value might have different recommended ranges for the various OSALs. + * - Linux Lowest limit is the PeriodicTaskIF::MINIMUM_STACK_SIZE value + * - Host Value is ignored for now because the C++ threading abstraction layer is used. + * - FreeRTOS Stack size in bytes. It is recommended to specify at least 1kB of stack for + * FSFW tasks, but the lowest possible size is specified in the + * FreeRTOSConfig.h file. + * - RTEMS Lowest limit is specified the PeriodicTaskIF::MINIMUM_STACK_SIZE value. + * + * @param period_ Period of the task + * + * @param deadLineMissedFunction_ Function to be called if a deadline was missed + * @return PeriodicTaskIF* Pointer to the newly created Task + */ + PeriodicTaskIF* createPeriodicTask(TaskName name_, TaskPriority taskPriority_, + TaskStackSize stackSize_, TaskPeriod periodInSeconds_, + TaskDeadlineMissedFunction deadLineMissedFunction_); - /** - * The meaning for the variables for fixed timeslot tasks is the same as for periodic tasks. - * See #createPeriodicTask documentation. - * @param name_ Name of the task - * @param taskPriority_ Priority of the task - * @param stackSize_ Stack Size of the task - * @param period_ Period of the task - * @param deadLineMissedFunction_ Function to be called if a deadline was missed - * @return FixedTimeslotTaskIF* Pointer to the newly created Task - */ - FixedTimeslotTaskIF* createFixedTimeslotTask(TaskName name_, - TaskPriority taskPriority_, TaskStackSize stackSize_, - TaskPeriod periodInSeconds_, - TaskDeadlineMissedFunction deadLineMissedFunction_); + /** + * The meaning for the variables for fixed timeslot tasks is the same as for periodic tasks. + * See #createPeriodicTask documentation. + * @param name_ Name of the task + * @param taskPriority_ Priority of the task + * @param stackSize_ Stack Size of the task + * @param period_ Period of the task + * @param deadLineMissedFunction_ Function to be called if a deadline was missed + * @return FixedTimeslotTaskIF* Pointer to the newly created Task + */ + FixedTimeslotTaskIF* createFixedTimeslotTask(TaskName name_, TaskPriority taskPriority_, + TaskStackSize stackSize_, + TaskPeriod periodInSeconds_, + TaskDeadlineMissedFunction deadLineMissedFunction_); - /** - * Function to be called to delete a task - * @param task The pointer to the task that shall be deleted, - * nullptr specifies current Task - * @return Success of deletion - */ - static ReturnValue_t deleteTask(PeriodicTaskIF* task = nullptr); + /** + * Function to be called to delete a task + * @param task The pointer to the task that shall be deleted, + * nullptr specifies current Task + * @return Success of deletion + */ + static ReturnValue_t deleteTask(PeriodicTaskIF* task = nullptr); - /** - * Function to be called to delay current task - * @param delay The delay in milliseconds - * @return Success of deletion - */ - static ReturnValue_t delayTask(uint32_t delayMs); + /** + * Function to be called to delay current task + * @param delay The delay in milliseconds + * @return Success of deletion + */ + static ReturnValue_t delayTask(uint32_t delayMs); - /** - * OS specific implementation to print deadline. In most cases, there is a OS specific - * way to retrieve the task name and print it out as well. - */ - static void printMissedDeadline(); - -private: - /** - * External instantiation is not allowed. - */ - TaskFactory(); - static TaskFactory* factoryInstance; + /** + * OS specific implementation to print deadline. In most cases, there is a OS specific + * way to retrieve the task name and print it out as well. + */ + static void printMissedDeadline(); + private: + /** + * External instantiation is not allowed. + */ + TaskFactory(); + static TaskFactory* factoryInstance; }; #endif /* FSFW_TASKS_TASKFACTORY_H_ */ diff --git a/src/fsfw/tasks/Typedef.h b/src/fsfw/tasks/Typedef.h index f2f9fe65..1bb75131 100644 --- a/src/fsfw/tasks/Typedef.h +++ b/src/fsfw/tasks/Typedef.h @@ -1,8 +1,8 @@ #ifndef FSFW_TASKS_TYPEDEF_H_ #define FSFW_TASKS_TYPEDEF_H_ -#include #include +#include typedef const char* TaskName; typedef uint32_t TaskPriority; diff --git a/src/fsfw/tcdistribution/CCSDSDistributor.cpp b/src/fsfw/tcdistribution/CCSDSDistributor.cpp index a040a5df..3f4bbee3 100644 --- a/src/fsfw/tcdistribution/CCSDSDistributor.cpp +++ b/src/fsfw/tcdistribution/CCSDSDistributor.cpp @@ -4,109 +4,103 @@ #include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/tmtcpacket/SpacePacketBase.h" -#define CCSDS_DISTRIBUTOR_DEBUGGING 0 +#define CCSDS_DISTRIBUTOR_DEBUGGING 0 -CCSDSDistributor::CCSDSDistributor(uint16_t setDefaultApid, - object_id_t setObjectId): - TcDistributor(setObjectId), defaultApid( setDefaultApid ) { -} +CCSDSDistributor::CCSDSDistributor(uint16_t setDefaultApid, object_id_t setObjectId) + : TcDistributor(setObjectId), defaultApid(setDefaultApid) {} CCSDSDistributor::~CCSDSDistributor() {} TcDistributor::TcMqMapIter CCSDSDistributor::selectDestination() { #if CCSDS_DISTRIBUTOR_DEBUGGING == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "CCSDSDistributor::selectDestination received: " << - this->currentMessage.getStorageId().poolIndex << ", " << - this->currentMessage.getStorageId().packetIndex << std::endl; + sif::debug << "CCSDSDistributor::selectDestination received: " + << this->currentMessage.getStorageId().poolIndex << ", " + << this->currentMessage.getStorageId().packetIndex << std::endl; #else - sif::printDebug("CCSDSDistributor::selectDestination received: %d, %d\n", - currentMessage.getStorageId().poolIndex, currentMessage.getStorageId().packetIndex); + sif::printDebug("CCSDSDistributor::selectDestination received: %d, %d\n", + currentMessage.getStorageId().poolIndex, + currentMessage.getStorageId().packetIndex); #endif #endif - const uint8_t* packet = nullptr; - size_t size = 0; - ReturnValue_t result = this->tcStore->getData(currentMessage.getStorageId(), - &packet, &size ); - if(result != HasReturnvaluesIF::RETURN_OK) { + const uint8_t* packet = nullptr; + size_t size = 0; + ReturnValue_t result = this->tcStore->getData(currentMessage.getStorageId(), &packet, &size); + if (result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "CCSDSDistributor::selectDestination: Getting data from" - " store failed!" << std::endl; + sif::error << "CCSDSDistributor::selectDestination: Getting data from" + " store failed!" + << std::endl; #else - sif::printError("CCSDSDistributor::selectDestination: Getting data from" - " store failed!\n"); + sif::printError( + "CCSDSDistributor::selectDestination: Getting data from" + " store failed!\n"); #endif #endif - } - SpacePacketBase currentPacket(packet); + } + SpacePacketBase currentPacket(packet); #if FSFW_CPP_OSTREAM_ENABLED == 1 && CCSDS_DISTRIBUTOR_DEBUGGING == 1 - sif::info << "CCSDSDistributor::selectDestination has packet with APID " << std::hex << - currentPacket.getAPID() << std::dec << std::endl; + sif::info << "CCSDSDistributor::selectDestination has packet with APID " << std::hex + << currentPacket.getAPID() << std::dec << std::endl; #endif - TcMqMapIter position = this->queueMap.find(currentPacket.getAPID()); - if ( position != this->queueMap.end() ) { - return position; - } else { - //The APID was not found. Forward packet to main SW-APID anyway to - // create acceptance failure report. - return this->queueMap.find( this->defaultApid ); - } + TcMqMapIter position = this->queueMap.find(currentPacket.getAPID()); + if (position != this->queueMap.end()) { + return position; + } else { + // The APID was not found. Forward packet to main SW-APID anyway to + // create acceptance failure report. + return this->queueMap.find(this->defaultApid); + } } -MessageQueueId_t CCSDSDistributor::getRequestQueue() { - return tcQueue->getId(); +MessageQueueId_t CCSDSDistributor::getRequestQueue() { return tcQueue->getId(); } + +ReturnValue_t CCSDSDistributor::registerApplication(AcceptsTelecommandsIF* application) { + ReturnValue_t returnValue = RETURN_OK; + auto insertPair = + this->queueMap.emplace(application->getIdentifier(), application->getRequestQueue()); + if (not insertPair.second) { + returnValue = RETURN_FAILED; + } + return returnValue; } -ReturnValue_t CCSDSDistributor::registerApplication( - AcceptsTelecommandsIF* application) { - ReturnValue_t returnValue = RETURN_OK; - auto insertPair = this->queueMap.emplace(application->getIdentifier(), - application->getRequestQueue()); - if(not insertPair.second) { - returnValue = RETURN_FAILED; - } - return returnValue; +ReturnValue_t CCSDSDistributor::registerApplication(uint16_t apid, MessageQueueId_t id) { + ReturnValue_t returnValue = RETURN_OK; + auto insertPair = this->queueMap.emplace(apid, id); + if (not insertPair.second) { + returnValue = RETURN_FAILED; + } + return returnValue; } -ReturnValue_t CCSDSDistributor::registerApplication(uint16_t apid, - MessageQueueId_t id) { - ReturnValue_t returnValue = RETURN_OK; - auto insertPair = this->queueMap.emplace(apid, id); - if(not insertPair.second) { - returnValue = RETURN_FAILED; - } - return returnValue; - -} - -uint16_t CCSDSDistributor::getIdentifier() { - return 0; -} +uint16_t CCSDSDistributor::getIdentifier() { return 0; } ReturnValue_t CCSDSDistributor::initialize() { - ReturnValue_t status = this->TcDistributor::initialize(); - this->tcStore = ObjectManager::instance()->get( objects::TC_STORE ); - if (this->tcStore == nullptr) { + ReturnValue_t status = this->TcDistributor::initialize(); + this->tcStore = ObjectManager::instance()->get(objects::TC_STORE); + if (this->tcStore == nullptr) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "CCSDSDistributor::initialize: Could not initialize" - " TC store!" << std::endl; + sif::error << "CCSDSDistributor::initialize: Could not initialize" + " TC store!" + << std::endl; #else - sif::printError("CCSDSDistributor::initialize: Could not initialize" - " TC store!\n"); + sif::printError( + "CCSDSDistributor::initialize: Could not initialize" + " TC store!\n"); #endif #endif - status = RETURN_FAILED; - } - return status; + status = RETURN_FAILED; + } + return status; } -ReturnValue_t CCSDSDistributor::callbackAfterSending( - ReturnValue_t queueStatus) { - if (queueStatus != RETURN_OK) { - tcStore->deleteData(currentMessage.getStorageId()); - } - return RETURN_OK; +ReturnValue_t CCSDSDistributor::callbackAfterSending(ReturnValue_t queueStatus) { + if (queueStatus != RETURN_OK) { + tcStore->deleteData(currentMessage.getStorageId()); + } + return RETURN_OK; } diff --git a/src/fsfw/tcdistribution/CCSDSDistributor.h b/src/fsfw/tcdistribution/CCSDSDistributor.h index f8995bc5..2d9b1fbd 100644 --- a/src/fsfw/tcdistribution/CCSDSDistributor.h +++ b/src/fsfw/tcdistribution/CCSDSDistributor.h @@ -15,58 +15,54 @@ * The Secondary Header (with Service/Subservice) is ignored. * @ingroup tc_distribution */ -class CCSDSDistributor: - public TcDistributor, - public CCSDSDistributorIF, - public AcceptsTelecommandsIF { -public: - /** - * @brief The constructor sets the default APID and calls the - * TcDistributor ctor with a certain object id. - * @details - * @c tcStore is set in the @c initialize method. - * @param setDefaultApid The default APID, where packets with unknown - * destination are sent to. - */ - CCSDSDistributor(uint16_t setDefaultApid, object_id_t setObjectId); - /** - * The destructor is empty. - */ - virtual ~CCSDSDistributor(); +class CCSDSDistributor : public TcDistributor, + public CCSDSDistributorIF, + public AcceptsTelecommandsIF { + public: + /** + * @brief The constructor sets the default APID and calls the + * TcDistributor ctor with a certain object id. + * @details + * @c tcStore is set in the @c initialize method. + * @param setDefaultApid The default APID, where packets with unknown + * destination are sent to. + */ + CCSDSDistributor(uint16_t setDefaultApid, object_id_t setObjectId); + /** + * The destructor is empty. + */ + virtual ~CCSDSDistributor(); - MessageQueueId_t getRequestQueue() override; - ReturnValue_t registerApplication( uint16_t apid, - MessageQueueId_t id) override; - ReturnValue_t registerApplication( - AcceptsTelecommandsIF* application) override; - uint16_t getIdentifier() override; - ReturnValue_t initialize() override; + MessageQueueId_t getRequestQueue() override; + ReturnValue_t registerApplication(uint16_t apid, MessageQueueId_t id) override; + ReturnValue_t registerApplication(AcceptsTelecommandsIF* application) override; + uint16_t getIdentifier() override; + ReturnValue_t initialize() override; -protected: - /** - * This implementation checks if an application with fitting APID has - * registered and forwards the packet to the according message queue. - * If the packet is not found, it returns the queue to @c defaultApid, - * where a Acceptance Failure message should be generated. - * @return Iterator to map entry of found APID or iterator to default APID. - */ - TcMqMapIter selectDestination() override; - /** - * The callback here handles the generation of acceptance - * success/failure messages. - */ - ReturnValue_t callbackAfterSending( ReturnValue_t queueStatus ) override; - - /** - * The default APID, where packets with unknown APID are sent to. - */ - uint16_t defaultApid; - /** - * A reference to the TC storage must be maintained, as this class handles - * pure Space Packets and there exists no SpacePacketStored class. - */ - StorageManagerIF* tcStore = nullptr; + protected: + /** + * This implementation checks if an application with fitting APID has + * registered and forwards the packet to the according message queue. + * If the packet is not found, it returns the queue to @c defaultApid, + * where a Acceptance Failure message should be generated. + * @return Iterator to map entry of found APID or iterator to default APID. + */ + TcMqMapIter selectDestination() override; + /** + * The callback here handles the generation of acceptance + * success/failure messages. + */ + ReturnValue_t callbackAfterSending(ReturnValue_t queueStatus) override; + /** + * The default APID, where packets with unknown APID are sent to. + */ + uint16_t defaultApid; + /** + * A reference to the TC storage must be maintained, as this class handles + * pure Space Packets and there exists no SpacePacketStored class. + */ + StorageManagerIF* tcStore = nullptr; }; #endif /* FRAMEWORK_TCDISTRIBUTION_CCSDSDISTRIBUTOR_H_ */ diff --git a/src/fsfw/tcdistribution/CCSDSDistributorIF.h b/src/fsfw/tcdistribution/CCSDSDistributorIF.h index 4e4c2a5b..d1c88118 100644 --- a/src/fsfw/tcdistribution/CCSDSDistributorIF.h +++ b/src/fsfw/tcdistribution/CCSDSDistributorIF.h @@ -1,8 +1,8 @@ #ifndef FSFW_TCDISTRIBUTION_CCSDSDISTRIBUTORIF_H_ #define FSFW_TCDISTRIBUTION_CCSDSDISTRIBUTORIF_H_ -#include "../tmtcservices/AcceptsTelecommandsIF.h" #include "../ipc/MessageQueueSenderIF.h" +#include "../tmtcservices/AcceptsTelecommandsIF.h" /** * This is the Interface to a CCSDS Distributor. * On a CCSDS Distributor, Applications (in terms of CCSDS) may register @@ -12,32 +12,29 @@ * @ingroup tc_distribution */ class CCSDSDistributorIF { -public: - /** - * With this call, a class implementing the CCSDSApplicationIF can register - * at the distributor. - * @param application A pointer to the Application to register. - * @return - @c RETURN_OK on success, - * - @c RETURN_FAILED on failure. - */ - virtual ReturnValue_t registerApplication( - AcceptsTelecommandsIF* application) = 0; - /** - * With this call, other Applications can register to the CCSDS distributor. - * This is done by passing an APID and a MessageQueueId to the method. - * @param apid The APID to register. - * @param id The MessageQueueId of the message queue to send the - * TC Packets to. - * @return - @c RETURN_OK on success, - * - @c RETURN_FAILED on failure. - */ - virtual ReturnValue_t registerApplication( uint16_t apid, - MessageQueueId_t id) = 0; - /** - * The empty virtual destructor. - */ - virtual ~CCSDSDistributorIF() {} + public: + /** + * With this call, a class implementing the CCSDSApplicationIF can register + * at the distributor. + * @param application A pointer to the Application to register. + * @return - @c RETURN_OK on success, + * - @c RETURN_FAILED on failure. + */ + virtual ReturnValue_t registerApplication(AcceptsTelecommandsIF* application) = 0; + /** + * With this call, other Applications can register to the CCSDS distributor. + * This is done by passing an APID and a MessageQueueId to the method. + * @param apid The APID to register. + * @param id The MessageQueueId of the message queue to send the + * TC Packets to. + * @return - @c RETURN_OK on success, + * - @c RETURN_FAILED on failure. + */ + virtual ReturnValue_t registerApplication(uint16_t apid, MessageQueueId_t id) = 0; + /** + * The empty virtual destructor. + */ + virtual ~CCSDSDistributorIF() {} }; - #endif /* FSFW_TCDISTRIBUTION_CCSDSDISTRIBUTORIF_H_ */ diff --git a/src/fsfw/tcdistribution/CFDPDistributor.cpp b/src/fsfw/tcdistribution/CFDPDistributor.cpp index f28a2998..d8be1543 100644 --- a/src/fsfw/tcdistribution/CFDPDistributor.cpp +++ b/src/fsfw/tcdistribution/CFDPDistributor.cpp @@ -1,147 +1,143 @@ -#include "fsfw/tcdistribution/CCSDSDistributorIF.h" #include "fsfw/tcdistribution/CFDPDistributor.h" +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/tcdistribution/CCSDSDistributorIF.h" #include "fsfw/tmtcpacket/cfdp/CFDPPacketStored.h" -#include "fsfw/objectmanager/ObjectManager.h" - #ifndef FSFW_CFDP_DISTRIBUTOR_DEBUGGING -#define FSFW_CFDP_DISTRIBUTOR_DEBUGGING 1 +#define FSFW_CFDP_DISTRIBUTOR_DEBUGGING 1 #endif CFDPDistributor::CFDPDistributor(uint16_t setApid, object_id_t setObjectId, - object_id_t setPacketSource): - TcDistributor(setObjectId), apid(setApid), checker(setApid), - tcStatus(RETURN_FAILED), packetSource(setPacketSource) { -} + object_id_t setPacketSource) + : TcDistributor(setObjectId), + apid(setApid), + checker(setApid), + tcStatus(RETURN_FAILED), + packetSource(setPacketSource) {} CFDPDistributor::~CFDPDistributor() {} CFDPDistributor::TcMqMapIter CFDPDistributor::selectDestination() { #if FSFW_CFDP_DISTRIBUTOR_DEBUGGING == 1 - store_address_t storeId = this->currentMessage.getStorageId(); + store_address_t storeId = this->currentMessage.getStorageId(); #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "CFDPDistributor::handlePacket received: " << storeId.poolIndex << ", " << - storeId.packetIndex << std::endl; + sif::debug << "CFDPDistributor::handlePacket received: " << storeId.poolIndex << ", " + << storeId.packetIndex << std::endl; #else - sif::printDebug("CFDPDistributor::handlePacket received: %d, %d\n", storeId.poolIndex, - storeId.packetIndex); + sif::printDebug("CFDPDistributor::handlePacket received: %d, %d\n", storeId.poolIndex, + storeId.packetIndex); #endif #endif - TcMqMapIter queueMapIt = this->queueMap.end(); - if(this->currentPacket == nullptr) { - return queueMapIt; - } - this->currentPacket->setStoreAddress(this->currentMessage.getStorageId()); - if (currentPacket->getWholeData() != nullptr) { - tcStatus = checker.checkPacket(currentPacket); - if(tcStatus != HasReturnvaluesIF::RETURN_OK) { + TcMqMapIter queueMapIt = this->queueMap.end(); + if (this->currentPacket == nullptr) { + return queueMapIt; + } + this->currentPacket->setStoreAddress(this->currentMessage.getStorageId()); + if (currentPacket->getWholeData() != nullptr) { + tcStatus = checker.checkPacket(currentPacket); + if (tcStatus != HasReturnvaluesIF::RETURN_OK) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "CFDPDistributor::handlePacket: Packet format invalid, code " << - static_cast(tcStatus) << std::endl; + sif::debug << "CFDPDistributor::handlePacket: Packet format invalid, code " + << static_cast(tcStatus) << std::endl; #else - sif::printDebug("CFDPDistributor::handlePacket: Packet format invalid, code %d\n", - static_cast(tcStatus)); + sif::printDebug("CFDPDistributor::handlePacket: Packet format invalid, code %d\n", + static_cast(tcStatus)); #endif #endif - } - queueMapIt = this->queueMap.find(0); - } - else { - tcStatus = PACKET_LOST; } + queueMapIt = this->queueMap.find(0); + } else { + tcStatus = PACKET_LOST; + } - if (queueMapIt == this->queueMap.end()) { - tcStatus = DESTINATION_NOT_FOUND; + if (queueMapIt == this->queueMap.end()) { + tcStatus = DESTINATION_NOT_FOUND; #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "CFDPDistributor::handlePacket: Destination not found" << std::endl; + sif::debug << "CFDPDistributor::handlePacket: Destination not found" << std::endl; #else - sif::printDebug("CFDPDistributor::handlePacket: Destination not found\n"); + sif::printDebug("CFDPDistributor::handlePacket: Destination not found\n"); #endif /* !FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif - } - - if (tcStatus != RETURN_OK) { - return this->queueMap.end(); - } - else { - return queueMapIt; - } + } + if (tcStatus != RETURN_OK) { + return this->queueMap.end(); + } else { + return queueMapIt; + } } - ReturnValue_t CFDPDistributor::registerHandler(AcceptsTelecommandsIF* handler) { - uint16_t handlerId = handler->getIdentifier(); //should be 0, because CFDPHandler does not set a set a service-ID + uint16_t handlerId = + handler->getIdentifier(); // should be 0, because CFDPHandler does not set a set a service-ID #if FSFW_CFDP_DISTRIBUTOR_DEBUGGING == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "CFDPDistributor::registerHandler: Handler ID: " << static_cast(handlerId) << std::endl; + sif::info << "CFDPDistributor::registerHandler: Handler ID: " << static_cast(handlerId) + << std::endl; #else - sif::printInfo("CFDPDistributor::registerHandler: Handler ID: %d\n", static_cast(handlerId)); + sif::printInfo("CFDPDistributor::registerHandler: Handler ID: %d\n", static_cast(handlerId)); #endif #endif - MessageQueueId_t queue = handler->getRequestQueue(); - auto returnPair = queueMap.emplace(handlerId, queue); - if (not returnPair.second) { + MessageQueueId_t queue = handler->getRequestQueue(); + auto returnPair = queueMap.emplace(handlerId, queue); + if (not returnPair.second) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "CFDPDistributor::registerHandler: Service ID already" - " exists in map" << std::endl; + sif::error << "CFDPDistributor::registerHandler: Service ID already" + " exists in map" + << std::endl; #else - sif::printError("CFDPDistributor::registerHandler: Service ID already exists in map\n"); + sif::printError("CFDPDistributor::registerHandler: Service ID already exists in map\n"); #endif #endif - return SERVICE_ID_ALREADY_EXISTS; - } - return HasReturnvaluesIF::RETURN_OK; + return SERVICE_ID_ALREADY_EXISTS; + } + return HasReturnvaluesIF::RETURN_OK; } -MessageQueueId_t CFDPDistributor::getRequestQueue() { - return tcQueue->getId(); -} +MessageQueueId_t CFDPDistributor::getRequestQueue() { return tcQueue->getId(); } -//ReturnValue_t CFDPDistributor::callbackAfterSending(ReturnValue_t queueStatus) { -// if (queueStatus != RETURN_OK) { -// tcStatus = queueStatus; -// } -// if (tcStatus != RETURN_OK) { -// this->verifyChannel.sendFailureReport(tc_verification::ACCEPTANCE_FAILURE, -// currentPacket, tcStatus); -// // A failed packet is deleted immediately after reporting, -// // otherwise it will block memory. -// currentPacket->deletePacket(); -// return RETURN_FAILED; -// } else { -// this->verifyChannel.sendSuccessReport(tc_verification::ACCEPTANCE_SUCCESS, -// currentPacket); -// return RETURN_OK; -// } -//} +// ReturnValue_t CFDPDistributor::callbackAfterSending(ReturnValue_t queueStatus) { +// if (queueStatus != RETURN_OK) { +// tcStatus = queueStatus; +// } +// if (tcStatus != RETURN_OK) { +// this->verifyChannel.sendFailureReport(tc_verification::ACCEPTANCE_FAILURE, +// currentPacket, tcStatus); +// // A failed packet is deleted immediately after reporting, +// // otherwise it will block memory. +// currentPacket->deletePacket(); +// return RETURN_FAILED; +// } else { +// this->verifyChannel.sendSuccessReport(tc_verification::ACCEPTANCE_SUCCESS, +// currentPacket); +// return RETURN_OK; +// } +// } -uint16_t CFDPDistributor::getIdentifier() { - return this->apid; -} +uint16_t CFDPDistributor::getIdentifier() { return this->apid; } ReturnValue_t CFDPDistributor::initialize() { - currentPacket = new CFDPPacketStored(); - if(currentPacket == nullptr) { - // Should not happen, memory allocation failed! - return ObjectManagerIF::CHILD_INIT_FAILED; - } + currentPacket = new CFDPPacketStored(); + if (currentPacket == nullptr) { + // Should not happen, memory allocation failed! + return ObjectManagerIF::CHILD_INIT_FAILED; + } - CCSDSDistributorIF* ccsdsDistributor = ObjectManager::instance()->get( - packetSource); - if (ccsdsDistributor == nullptr) { + CCSDSDistributorIF* ccsdsDistributor = + ObjectManager::instance()->get(packetSource); + if (ccsdsDistributor == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "CFDPDistributor::initialize: Packet source invalid" << std::endl; - sif::error << " Make sure it exists and implements CCSDSDistributorIF!" << std::endl; + sif::error << "CFDPDistributor::initialize: Packet source invalid" << std::endl; + sif::error << " Make sure it exists and implements CCSDSDistributorIF!" << std::endl; #else - sif::printError("CFDPDistributor::initialize: Packet source invalid\n"); - sif::printError("Make sure it exists and implements CCSDSDistributorIF\n"); + sif::printError("CFDPDistributor::initialize: Packet source invalid\n"); + sif::printError("Make sure it exists and implements CCSDSDistributorIF\n"); #endif - return RETURN_FAILED; - } - return ccsdsDistributor->registerApplication(this); + return RETURN_FAILED; + } + return ccsdsDistributor->registerApplication(this); } diff --git a/src/fsfw/tcdistribution/CFDPDistributor.h b/src/fsfw/tcdistribution/CFDPDistributor.h index 5c7513b3..2a901021 100644 --- a/src/fsfw/tcdistribution/CFDPDistributor.h +++ b/src/fsfw/tcdistribution/CFDPDistributor.h @@ -2,71 +2,70 @@ #define FSFW_TCDISTRIBUTION_CFDPDISTRIBUTOR_H_ #include -#include "CFDPDistributorIF.h" -#include "TcDistributor.h" -#include "../tmtcpacket/cfdp/CFDPPacketStored.h" + #include "../returnvalues/HasReturnvaluesIF.h" +#include "../tmtcpacket/cfdp/CFDPPacketStored.h" #include "../tmtcservices/AcceptsTelecommandsIF.h" #include "../tmtcservices/VerificationReporter.h" +#include "CFDPDistributorIF.h" +#include "TcDistributor.h" /** * This class accepts CFDP Telecommands and forwards them to Application * services. * @ingroup tc_distribution */ -class CFDPDistributor: - public TcDistributor, - public CFDPDistributorIF, - public AcceptsTelecommandsIF { -public: - /** - * The ctor passes @c set_apid to the checker class and calls the - * TcDistribution ctor with a certain object id. - * @param setApid The APID of this receiving Application. - * @param setObjectId Object ID of the distributor itself - * @param setPacketSource Object ID of the source of TC packets. - * Must implement CCSDSDistributorIF. - */ - CFDPDistributor(uint16_t setApid, object_id_t setObjectId, - object_id_t setPacketSource); - /** - * The destructor is empty. - */ - virtual ~CFDPDistributor(); - ReturnValue_t registerHandler(AcceptsTelecommandsIF* handler) override; - MessageQueueId_t getRequestQueue() override; - ReturnValue_t initialize() override; - uint16_t getIdentifier() override; +class CFDPDistributor : public TcDistributor, + public CFDPDistributorIF, + public AcceptsTelecommandsIF { + public: + /** + * The ctor passes @c set_apid to the checker class and calls the + * TcDistribution ctor with a certain object id. + * @param setApid The APID of this receiving Application. + * @param setObjectId Object ID of the distributor itself + * @param setPacketSource Object ID of the source of TC packets. + * Must implement CCSDSDistributorIF. + */ + CFDPDistributor(uint16_t setApid, object_id_t setObjectId, object_id_t setPacketSource); + /** + * The destructor is empty. + */ + virtual ~CFDPDistributor(); + ReturnValue_t registerHandler(AcceptsTelecommandsIF* handler) override; + MessageQueueId_t getRequestQueue() override; + ReturnValue_t initialize() override; + uint16_t getIdentifier() override; -protected: - uint16_t apid; - /** - * The currently handled packet is stored here. - */ - CFDPPacketStored* currentPacket = nullptr; - TcPacketCheckCFDP checker; - /** - * With this variable, the current check status is stored to generate - * acceptance messages later. - */ - ReturnValue_t tcStatus; + protected: + uint16_t apid; + /** + * The currently handled packet is stored here. + */ + CFDPPacketStored* currentPacket = nullptr; + TcPacketCheckCFDP checker; + /** + * With this variable, the current check status is stored to generate + * acceptance messages later. + */ + ReturnValue_t tcStatus; - const object_id_t packetSource; + const object_id_t packetSource; - /** - * This method reads the packet service, checks if such a service is - * registered and forwards the packet to the destination. - * It also initiates the formal packet check and sending of verification - * messages. - * @return Iterator to map entry of found service id - * or iterator to @c map.end(). - */ - TcMqMapIter selectDestination() override; - /** - * The callback here handles the generation of acceptance - * success/failure messages. - */ - //ReturnValue_t callbackAfterSending(ReturnValue_t queueStatus) override; + /** + * This method reads the packet service, checks if such a service is + * registered and forwards the packet to the destination. + * It also initiates the formal packet check and sending of verification + * messages. + * @return Iterator to map entry of found service id + * or iterator to @c map.end(). + */ + TcMqMapIter selectDestination() override; + /** + * The callback here handles the generation of acceptance + * success/failure messages. + */ + // ReturnValue_t callbackAfterSending(ReturnValue_t queueStatus) override; }; #endif /* FSFW_TCDISTRIBUTION_CFDPDISTRIBUTOR_H_ */ diff --git a/src/fsfw/tcdistribution/CFDPDistributorIF.h b/src/fsfw/tcdistribution/CFDPDistributorIF.h index f1c85772..3c1836f1 100644 --- a/src/fsfw/tcdistribution/CFDPDistributorIF.h +++ b/src/fsfw/tcdistribution/CFDPDistributorIF.h @@ -1,27 +1,26 @@ #ifndef FSFW_TCDISTRIBUTION_CFDPDISTRIBUTORIF_H_ #define FSFW_TCDISTRIBUTION_CFDPDISTRIBUTORIF_H_ -#include "../tmtcservices/AcceptsTelecommandsIF.h" #include "../ipc/MessageQueueSenderIF.h" +#include "../tmtcservices/AcceptsTelecommandsIF.h" /** * This interface allows CFDP Services to register themselves at a CFDP Distributor. * @ingroup tc_distribution */ class CFDPDistributorIF { -public: - /** - * The empty virtual destructor. - */ - virtual ~CFDPDistributorIF() { - } - /** - * With this method, Handlers can register themselves at the CFDP Distributor. - * @param handler A pointer to the registering Handler. - * @return - @c RETURN_OK on success, - * - @c RETURN_FAILED on failure. - */ - virtual ReturnValue_t registerHandler(AcceptsTelecommandsIF* handler) = 0; + public: + /** + * The empty virtual destructor. + */ + virtual ~CFDPDistributorIF() {} + /** + * With this method, Handlers can register themselves at the CFDP Distributor. + * @param handler A pointer to the registering Handler. + * @return - @c RETURN_OK on success, + * - @c RETURN_FAILED on failure. + */ + virtual ReturnValue_t registerHandler(AcceptsTelecommandsIF* handler) = 0; }; #endif /* FSFW_TCDISTRIBUTION_CFDPDISTRIBUTORIF_H_ */ diff --git a/src/fsfw/tcdistribution/PUSDistributor.cpp b/src/fsfw/tcdistribution/PUSDistributor.cpp index aafd1244..aadecd69 100644 --- a/src/fsfw/tcdistribution/PUSDistributor.cpp +++ b/src/fsfw/tcdistribution/PUSDistributor.cpp @@ -1,156 +1,149 @@ -#include "fsfw/tcdistribution/CCSDSDistributorIF.h" #include "fsfw/tcdistribution/PUSDistributor.h" #include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/tcdistribution/CCSDSDistributorIF.h" #include "fsfw/tmtcservices/PusVerificationReport.h" -#define PUS_DISTRIBUTOR_DEBUGGING 0 +#define PUS_DISTRIBUTOR_DEBUGGING 0 PUSDistributor::PUSDistributor(uint16_t setApid, object_id_t setObjectId, - object_id_t setPacketSource) : - TcDistributor(setObjectId), checker(setApid), verifyChannel(), - tcStatus(RETURN_FAILED), packetSource(setPacketSource) {} + object_id_t setPacketSource) + : TcDistributor(setObjectId), + checker(setApid), + verifyChannel(), + tcStatus(RETURN_FAILED), + packetSource(setPacketSource) {} PUSDistributor::~PUSDistributor() {} PUSDistributor::TcMqMapIter PUSDistributor::selectDestination() { #if FSFW_CPP_OSTREAM_ENABLED == 1 && PUS_DISTRIBUTOR_DEBUGGING == 1 store_address_t storeId = this->currentMessage.getStorageId()); - sif:: debug << "PUSDistributor::handlePacket received: " << storeId.poolIndex << ", " << - storeId.packetIndex << std::endl; + sif::debug << "PUSDistributor::handlePacket received: " << storeId.poolIndex << ", " + << storeId.packetIndex << std::endl; #endif TcMqMapIter queueMapIt = this->queueMap.end(); - if(this->currentPacket == nullptr) { - return queueMapIt; + if (this->currentPacket == nullptr) { + return queueMapIt; } this->currentPacket->setStoreAddress(this->currentMessage.getStorageId(), currentPacket); if (currentPacket->getWholeData() != nullptr) { - tcStatus = checker.checkPacket(currentPacket); - if(tcStatus != HasReturnvaluesIF::RETURN_OK) { + tcStatus = checker.checkPacket(currentPacket); + if (tcStatus != HasReturnvaluesIF::RETURN_OK) { #if FSFW_VERBOSE_LEVEL >= 1 - const char* keyword = "unnamed error"; - if(tcStatus == TcPacketCheckPUS::INCORRECT_CHECKSUM) { - keyword = "checksum"; - } - else if(tcStatus == TcPacketCheckPUS::INCORRECT_PRIMARY_HEADER) { - keyword = "incorrect primary header"; - } - else if(tcStatus == TcPacketCheckPUS::ILLEGAL_APID) { - keyword = "illegal APID"; - } - else if(tcStatus == TcPacketCheckPUS::INCORRECT_SECONDARY_HEADER) { - keyword = "incorrect secondary header"; - } - else if(tcStatus == TcPacketCheckPUS::INCOMPLETE_PACKET) { - keyword = "incomplete packet"; - } -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "PUSDistributor::handlePacket: Packet format invalid, " - << keyword << " error" << std::endl; -#else - sif::printWarning("PUSDistributor::handlePacket: Packet format invalid, " - "%s error\n", keyword); -#endif -#endif + const char* keyword = "unnamed error"; + if (tcStatus == TcPacketCheckPUS::INCORRECT_CHECKSUM) { + keyword = "checksum"; + } else if (tcStatus == TcPacketCheckPUS::INCORRECT_PRIMARY_HEADER) { + keyword = "incorrect primary header"; + } else if (tcStatus == TcPacketCheckPUS::ILLEGAL_APID) { + keyword = "illegal APID"; + } else if (tcStatus == TcPacketCheckPUS::INCORRECT_SECONDARY_HEADER) { + keyword = "incorrect secondary header"; + } else if (tcStatus == TcPacketCheckPUS::INCOMPLETE_PACKET) { + keyword = "incomplete packet"; } - uint32_t queue_id = currentPacket->getService(); - queueMapIt = this->queueMap.find(queue_id); - } - else { - tcStatus = PACKET_LOST; +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "PUSDistributor::handlePacket: Packet format invalid, " << keyword + << " error" << std::endl; +#else + sif::printWarning( + "PUSDistributor::handlePacket: Packet format invalid, " + "%s error\n", + keyword); +#endif +#endif + } + uint32_t queue_id = currentPacket->getService(); + queueMapIt = this->queueMap.find(queue_id); + } else { + tcStatus = PACKET_LOST; } if (queueMapIt == this->queueMap.end()) { - tcStatus = DESTINATION_NOT_FOUND; + tcStatus = DESTINATION_NOT_FOUND; #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "PUSDistributor::handlePacket: Destination not found" << std::endl; + sif::debug << "PUSDistributor::handlePacket: Destination not found" << std::endl; #else - sif::printDebug("PUSDistributor::handlePacket: Destination not found\n"); + sif::printDebug("PUSDistributor::handlePacket: Destination not found\n"); #endif /* !FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif } if (tcStatus != RETURN_OK) { - return this->queueMap.end(); + return this->queueMap.end(); + } else { + return queueMapIt; } - else { - return queueMapIt; - } - } - ReturnValue_t PUSDistributor::registerService(AcceptsTelecommandsIF* service) { - uint16_t serviceId = service->getIdentifier(); + uint16_t serviceId = service->getIdentifier(); #if PUS_DISTRIBUTOR_DEBUGGING == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "Service ID: " << static_cast(serviceId) << std::endl; + sif::info << "Service ID: " << static_cast(serviceId) << std::endl; #else - sif::printInfo("Service ID: %d\n", static_cast(serviceId)); + sif::printInfo("Service ID: %d\n", static_cast(serviceId)); #endif #endif - MessageQueueId_t queue = service->getRequestQueue(); - auto returnPair = queueMap.emplace(serviceId, queue); - if (not returnPair.second) { + MessageQueueId_t queue = service->getRequestQueue(); + auto returnPair = queueMap.emplace(serviceId, queue); + if (not returnPair.second) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "PUSDistributor::registerService: Service ID already" - " exists in map" << std::endl; + sif::error << "PUSDistributor::registerService: Service ID already" + " exists in map" + << std::endl; #else - sif::printError("PUSDistributor::registerService: Service ID already exists in map\n"); + sif::printError("PUSDistributor::registerService: Service ID already exists in map\n"); #endif #endif - return SERVICE_ID_ALREADY_EXISTS; - } - return HasReturnvaluesIF::RETURN_OK; + return SERVICE_ID_ALREADY_EXISTS; + } + return HasReturnvaluesIF::RETURN_OK; } -MessageQueueId_t PUSDistributor::getRequestQueue() { - return tcQueue->getId(); -} +MessageQueueId_t PUSDistributor::getRequestQueue() { return tcQueue->getId(); } ReturnValue_t PUSDistributor::callbackAfterSending(ReturnValue_t queueStatus) { - if (queueStatus != RETURN_OK) { - tcStatus = queueStatus; - } - if (tcStatus != RETURN_OK) { - this->verifyChannel.sendFailureReport(tc_verification::ACCEPTANCE_FAILURE, - currentPacket, tcStatus); - // A failed packet is deleted immediately after reporting, - // otherwise it will block memory. - currentPacket->deletePacket(); - return RETURN_FAILED; - } else { - this->verifyChannel.sendSuccessReport(tc_verification::ACCEPTANCE_SUCCESS, - currentPacket); - return RETURN_OK; - } + if (queueStatus != RETURN_OK) { + tcStatus = queueStatus; + } + if (tcStatus != RETURN_OK) { + this->verifyChannel.sendFailureReport(tc_verification::ACCEPTANCE_FAILURE, currentPacket, + tcStatus); + // A failed packet is deleted immediately after reporting, + // otherwise it will block memory. + currentPacket->deletePacket(); + return RETURN_FAILED; + } else { + this->verifyChannel.sendSuccessReport(tc_verification::ACCEPTANCE_SUCCESS, currentPacket); + return RETURN_OK; + } } -uint16_t PUSDistributor::getIdentifier() { - return checker.getApid(); -} +uint16_t PUSDistributor::getIdentifier() { return checker.getApid(); } ReturnValue_t PUSDistributor::initialize() { - currentPacket = new TcPacketStoredPus(); - if(currentPacket == nullptr) { - // Should not happen, memory allocation failed! - return ObjectManagerIF::CHILD_INIT_FAILED; - } + currentPacket = new TcPacketStoredPus(); + if (currentPacket == nullptr) { + // Should not happen, memory allocation failed! + return ObjectManagerIF::CHILD_INIT_FAILED; + } - CCSDSDistributorIF* ccsdsDistributor = - ObjectManager::instance()->get(packetSource); - if (ccsdsDistributor == nullptr) { + CCSDSDistributorIF* ccsdsDistributor = + ObjectManager::instance()->get(packetSource); + if (ccsdsDistributor == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "PUSDistributor::initialize: Packet source invalid" << std::endl; - sif::error << " Make sure it exists and implements CCSDSDistributorIF!" << std::endl; + sif::error << "PUSDistributor::initialize: Packet source invalid" << std::endl; + sif::error << " Make sure it exists and implements CCSDSDistributorIF!" << std::endl; #else - sif::printError("PUSDistributor::initialize: Packet source invalid\n"); - sif::printError("Make sure it exists and implements CCSDSDistributorIF\n"); + sif::printError("PUSDistributor::initialize: Packet source invalid\n"); + sif::printError("Make sure it exists and implements CCSDSDistributorIF\n"); #endif - return RETURN_FAILED; - } - return ccsdsDistributor->registerApplication(this); + return RETURN_FAILED; + } + return ccsdsDistributor->registerApplication(this); } diff --git a/src/fsfw/tcdistribution/PUSDistributor.h b/src/fsfw/tcdistribution/PUSDistributor.h index b010125c..c069c81b 100644 --- a/src/fsfw/tcdistribution/PUSDistributor.h +++ b/src/fsfw/tcdistribution/PUSDistributor.h @@ -4,9 +4,8 @@ #include "PUSDistributorIF.h" #include "TcDistributor.h" #include "TcPacketCheckPUS.h" - -#include "fsfw/tmtcpacket/pus/tc.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "fsfw/tmtcpacket/pus/tc.h" #include "fsfw/tmtcservices/AcceptsTelecommandsIF.h" #include "fsfw/tmtcservices/VerificationReporter.h" @@ -16,66 +15,63 @@ * sends acceptance success or failure messages. * @ingroup tc_distribution */ -class PUSDistributor: public TcDistributor, -public PUSDistributorIF, -public AcceptsTelecommandsIF { -public: - /** - * The ctor passes @c set_apid to the checker class and calls the - * TcDistribution ctor with a certain object id. - * @param setApid The APID of this receiving Application. - * @param setObjectId Object ID of the distributor itself - * @param setPacketSource Object ID of the source of TC packets. - * Must implement CCSDSDistributorIF. - */ - PUSDistributor(uint16_t setApid, object_id_t setObjectId, - object_id_t setPacketSource); - /** - * The destructor is empty. - */ - virtual ~PUSDistributor(); - ReturnValue_t registerService(AcceptsTelecommandsIF* service) override; - MessageQueueId_t getRequestQueue() override; - ReturnValue_t initialize() override; - uint16_t getIdentifier() override; +class PUSDistributor : public TcDistributor, public PUSDistributorIF, public AcceptsTelecommandsIF { + public: + /** + * The ctor passes @c set_apid to the checker class and calls the + * TcDistribution ctor with a certain object id. + * @param setApid The APID of this receiving Application. + * @param setObjectId Object ID of the distributor itself + * @param setPacketSource Object ID of the source of TC packets. + * Must implement CCSDSDistributorIF. + */ + PUSDistributor(uint16_t setApid, object_id_t setObjectId, object_id_t setPacketSource); + /** + * The destructor is empty. + */ + virtual ~PUSDistributor(); + ReturnValue_t registerService(AcceptsTelecommandsIF* service) override; + MessageQueueId_t getRequestQueue() override; + ReturnValue_t initialize() override; + uint16_t getIdentifier() override; -protected: - /** - * This attribute contains the class, that performs a formal packet check. - */ - TcPacketCheckPUS checker; - /** - * With this class, verification messages are sent to the - * TC Verification service. - */ - VerificationReporter verifyChannel; - /** - * The currently handled packet is stored here. - */ - TcPacketStoredPus* currentPacket = nullptr; + protected: + /** + * This attribute contains the class, that performs a formal packet check. + */ + TcPacketCheckPUS checker; + /** + * With this class, verification messages are sent to the + * TC Verification service. + */ + VerificationReporter verifyChannel; + /** + * The currently handled packet is stored here. + */ + TcPacketStoredPus* currentPacket = nullptr; - /** - * With this variable, the current check status is stored to generate - * acceptance messages later. - */ - ReturnValue_t tcStatus; + /** + * With this variable, the current check status is stored to generate + * acceptance messages later. + */ + ReturnValue_t tcStatus; - const object_id_t packetSource; + const object_id_t packetSource; - /** - * This method reads the packet service, checks if such a service is - * registered and forwards the packet to the destination. - * It also initiates the formal packet check and sending of verification - * messages. - * @return Iterator to map entry of found service id - * or iterator to @c map.end(). - */ - TcMqMapIter selectDestination() override; - /** - * The callback here handles the generation of acceptance - * success/failure messages. - */ - ReturnValue_t callbackAfterSending(ReturnValue_t queueStatus) override; + /** + * This method reads the packet service, checks if such a service is + * registered and forwards the packet to the destination. + * It also initiates the formal packet check and sending of verification + * messages. + * @return Iterator to map entry of found service id + * or iterator to @c map.end(). + */ + TcMqMapIter selectDestination() override; + /** + * The callback here handles the generation of acceptance + * success/failure messages. + */ + ReturnValue_t callbackAfterSending(ReturnValue_t queueStatus) override; }; #endif /* FSFW_TCDISTRIBUTION_PUSDISTRIBUTOR_H_ */ diff --git a/src/fsfw/tcdistribution/PUSDistributorIF.h b/src/fsfw/tcdistribution/PUSDistributorIF.h index e4a66758..da6db283 100644 --- a/src/fsfw/tcdistribution/PUSDistributorIF.h +++ b/src/fsfw/tcdistribution/PUSDistributorIF.h @@ -1,27 +1,26 @@ #ifndef FSFW_TCDISTRIBUTION_PUSDISTRIBUTORIF_H_ #define FSFW_TCDISTRIBUTION_PUSDISTRIBUTORIF_H_ -#include "../tmtcservices/AcceptsTelecommandsIF.h" #include "../ipc/MessageQueueSenderIF.h" +#include "../tmtcservices/AcceptsTelecommandsIF.h" /** * This interface allows PUS Services to register themselves at a PUS Distributor. * @ingroup tc_distribution */ class PUSDistributorIF { -public: - /** - * The empty virtual destructor. - */ - virtual ~PUSDistributorIF() { - } - /** - * With this method, Services can register themselves at the PUS Distributor. - * @param service A pointer to the registering Service. - * @return - @c RETURN_OK on success, - * - @c RETURN_FAILED on failure. - */ - virtual ReturnValue_t registerService( AcceptsTelecommandsIF* service ) = 0; + public: + /** + * The empty virtual destructor. + */ + virtual ~PUSDistributorIF() {} + /** + * With this method, Services can register themselves at the PUS Distributor. + * @param service A pointer to the registering Service. + * @return - @c RETURN_OK on success, + * - @c RETURN_FAILED on failure. + */ + virtual ReturnValue_t registerService(AcceptsTelecommandsIF* service) = 0; }; #endif /* FSFW_TCDISTRIBUTION_PUSDISTRIBUTORIF_H_ */ diff --git a/src/fsfw/tcdistribution/TcDistributor.cpp b/src/fsfw/tcdistribution/TcDistributor.cpp index 8384e6ee..a650546c 100644 --- a/src/fsfw/tcdistribution/TcDistributor.cpp +++ b/src/fsfw/tcdistribution/TcDistributor.cpp @@ -1,56 +1,46 @@ #include "fsfw/tcdistribution/TcDistributor.h" +#include "fsfw/ipc/QueueFactory.h" #include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/tmtcservices/TmTcMessage.h" -#include "fsfw/ipc/QueueFactory.h" -TcDistributor::TcDistributor(object_id_t objectId) : - SystemObject(objectId) { - tcQueue = QueueFactory::instance()-> - createMessageQueue(DISTRIBUTER_MAX_PACKETS); +TcDistributor::TcDistributor(object_id_t objectId) : SystemObject(objectId) { + tcQueue = QueueFactory::instance()->createMessageQueue(DISTRIBUTER_MAX_PACKETS); } -TcDistributor::~TcDistributor() { - QueueFactory::instance()->deleteMessageQueue(tcQueue); -} +TcDistributor::~TcDistributor() { QueueFactory::instance()->deleteMessageQueue(tcQueue); } ReturnValue_t TcDistributor::performOperation(uint8_t opCode) { - ReturnValue_t status = RETURN_OK; - for (status = tcQueue->receiveMessage(¤tMessage); status == RETURN_OK; - status = tcQueue->receiveMessage(¤tMessage)) { - status = handlePacket(); - } - if (status == MessageQueueIF::EMPTY) { - return RETURN_OK; - } else { - return status; - } + ReturnValue_t status = RETURN_OK; + for (status = tcQueue->receiveMessage(¤tMessage); status == RETURN_OK; + status = tcQueue->receiveMessage(¤tMessage)) { + status = handlePacket(); + } + if (status == MessageQueueIF::EMPTY) { + return RETURN_OK; + } else { + return status; + } } ReturnValue_t TcDistributor::handlePacket() { - - TcMqMapIter queueMapIt = this->selectDestination(); - ReturnValue_t returnValue = RETURN_FAILED; - if (queueMapIt != this->queueMap.end()) { - returnValue = this->tcQueue->sendMessage(queueMapIt->second, - &this->currentMessage); - } - return this->callbackAfterSending(returnValue); + TcMqMapIter queueMapIt = this->selectDestination(); + ReturnValue_t returnValue = RETURN_FAILED; + if (queueMapIt != this->queueMap.end()) { + returnValue = this->tcQueue->sendMessage(queueMapIt->second, &this->currentMessage); + } + return this->callbackAfterSending(returnValue); } void TcDistributor::print() { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "Distributor content is: " << std::endl - << "ID\t| Message Queue ID" << std::endl; - sif::debug << std::setfill('0') << std::setw(8) << std::hex; - for (const auto& queueMapIter: queueMap) { - sif::debug << queueMapIter.first << "\t| 0x" << queueMapIter.second - << std::endl; - } - sif::debug << std::setfill(' ') << std::dec; + sif::debug << "Distributor content is: " << std::endl << "ID\t| Message Queue ID" << std::endl; + sif::debug << std::setfill('0') << std::setw(8) << std::hex; + for (const auto& queueMapIter : queueMap) { + sif::debug << queueMapIter.first << "\t| 0x" << queueMapIter.second << std::endl; + } + sif::debug << std::setfill(' ') << std::dec; #endif } -ReturnValue_t TcDistributor::callbackAfterSending(ReturnValue_t queueStatus) { - return RETURN_OK; -} +ReturnValue_t TcDistributor::callbackAfterSending(ReturnValue_t queueStatus) { return RETURN_OK; } diff --git a/src/fsfw/tcdistribution/TcDistributor.h b/src/fsfw/tcdistribution/TcDistributor.h index 14b532bd..1b783ff4 100644 --- a/src/fsfw/tcdistribution/TcDistributor.h +++ b/src/fsfw/tcdistribution/TcDistributor.h @@ -1,14 +1,15 @@ #ifndef FSFW_TMTCSERVICES_TCDISTRIBUTOR_H_ #define FSFW_TMTCSERVICES_TCDISTRIBUTOR_H_ +#include + +#include "fsfw/ipc/MessageQueueIF.h" #include "fsfw/objectmanager/ObjectManagerIF.h" #include "fsfw/objectmanager/SystemObject.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" #include "fsfw/storagemanager/StorageManagerIF.h" #include "fsfw/tasks/ExecutableObjectIF.h" #include "fsfw/tmtcservices/TmTcMessage.h" -#include "fsfw/ipc/MessageQueueIF.h" -#include /** * @defgroup tc_distribution Telecommand Distribution @@ -16,7 +17,6 @@ * belong to this group. */ - /** * This is the base class to implement distributors for Space Packets. * Typically, the distribution is required to forward Telecommand packets @@ -27,96 +27,93 @@ * implementations. * @ingroup tc_distribution */ -class TcDistributor : public SystemObject, - public ExecutableObjectIF, - public HasReturnvaluesIF { -public: - using TcMessageQueueMap = std::map; - using TcMqMapIter = std::map::iterator; +class TcDistributor : public SystemObject, public ExecutableObjectIF, public HasReturnvaluesIF { + public: + using TcMessageQueueMap = std::map; + using TcMqMapIter = std::map::iterator; - static constexpr uint8_t INTERFACE_ID = CLASS_ID::PACKET_DISTRIBUTION; - static constexpr ReturnValue_t PACKET_LOST = MAKE_RETURN_CODE( 1 ); - static constexpr ReturnValue_t DESTINATION_NOT_FOUND = MAKE_RETURN_CODE( 2 ); - static constexpr ReturnValue_t SERVICE_ID_ALREADY_EXISTS = MAKE_RETURN_CODE(3); - /** - * Within the default constructor, the SystemObject id is set and the - * message queue is initialized. - * Filling the map is under control of the child classes. - * @param set_object_id This id is assigned to the distributor - * implementation. - */ - TcDistributor(object_id_t objectId); - /** - * The destructor is empty, the message queues are not in the vicinity of - * this class. - */ - virtual ~TcDistributor(); - /** - * The method is called cyclically and fetches new incoming packets from - * the message queue. - * In case a new packet is found, it calls the handlePacket method to deal - * with distribution. - * @return The error code of the message queue call. - */ - ReturnValue_t performOperation(uint8_t opCode); - /** - * A simple debug print, that prints all distribution information stored in - * queueMap. - */ - void print(); + static constexpr uint8_t INTERFACE_ID = CLASS_ID::PACKET_DISTRIBUTION; + static constexpr ReturnValue_t PACKET_LOST = MAKE_RETURN_CODE(1); + static constexpr ReturnValue_t DESTINATION_NOT_FOUND = MAKE_RETURN_CODE(2); + static constexpr ReturnValue_t SERVICE_ID_ALREADY_EXISTS = MAKE_RETURN_CODE(3); + /** + * Within the default constructor, the SystemObject id is set and the + * message queue is initialized. + * Filling the map is under control of the child classes. + * @param set_object_id This id is assigned to the distributor + * implementation. + */ + TcDistributor(object_id_t objectId); + /** + * The destructor is empty, the message queues are not in the vicinity of + * this class. + */ + virtual ~TcDistributor(); + /** + * The method is called cyclically and fetches new incoming packets from + * the message queue. + * In case a new packet is found, it calls the handlePacket method to deal + * with distribution. + * @return The error code of the message queue call. + */ + ReturnValue_t performOperation(uint8_t opCode); + /** + * A simple debug print, that prints all distribution information stored in + * queueMap. + */ + void print(); -protected: - /** - * This is the receiving queue for incoming Telecommands. - * The child classes must make its queue id public. - */ - MessageQueueIF* tcQueue = nullptr; - /** - * The last received incoming packet information is stored in this - * member. - * As different child classes unpack the incoming packet differently - * (i.e. as a CCSDS Space Packet or as a PUS Telecommand Packet), it - * is not tried to unpack the packet information within this class. - */ - TmTcMessage currentMessage; - /** - * The map that links certain packet information to a destination. - * The packet information may be the APID of the packet or the service - * identifier. Filling of the map is under control of the different child - * classes. - */ - TcMessageQueueMap queueMap; - /** - * This method shall unpack the routing information from the incoming - * packet and select the map entry which represents the packet's target. - * @return An iterator to the map element to forward to or queuMap.end(). - */ - virtual TcMqMapIter selectDestination() = 0; - /** - * The handlePacket method calls the child class's selectDestination method - * and forwards the packet to its destination, if found. - * @return The message queue return value or @c RETURN_FAILED, in case no - * destination was found. - */ - ReturnValue_t handlePacket(); - /** - * This method gives the child class a chance to perform some kind of - * operation after the parent tried to forward the message. - * A typically application would be sending success/failure messages. - * The default implementation just returns @c RETURN_OK. - * @param queueStatus The status of the message queue after an attempt - * to send the TC. - * @return - @c RETURN_OK on success - * - @c RETURN_FAILED on failure - */ - virtual ReturnValue_t callbackAfterSending( ReturnValue_t queueStatus ); + protected: + /** + * This is the receiving queue for incoming Telecommands. + * The child classes must make its queue id public. + */ + MessageQueueIF* tcQueue = nullptr; + /** + * The last received incoming packet information is stored in this + * member. + * As different child classes unpack the incoming packet differently + * (i.e. as a CCSDS Space Packet or as a PUS Telecommand Packet), it + * is not tried to unpack the packet information within this class. + */ + TmTcMessage currentMessage; + /** + * The map that links certain packet information to a destination. + * The packet information may be the APID of the packet or the service + * identifier. Filling of the map is under control of the different child + * classes. + */ + TcMessageQueueMap queueMap; + /** + * This method shall unpack the routing information from the incoming + * packet and select the map entry which represents the packet's target. + * @return An iterator to the map element to forward to or queuMap.end(). + */ + virtual TcMqMapIter selectDestination() = 0; + /** + * The handlePacket method calls the child class's selectDestination method + * and forwards the packet to its destination, if found. + * @return The message queue return value or @c RETURN_FAILED, in case no + * destination was found. + */ + ReturnValue_t handlePacket(); + /** + * This method gives the child class a chance to perform some kind of + * operation after the parent tried to forward the message. + * A typically application would be sending success/failure messages. + * The default implementation just returns @c RETURN_OK. + * @param queueStatus The status of the message queue after an attempt + * to send the TC. + * @return - @c RETURN_OK on success + * - @c RETURN_FAILED on failure + */ + virtual ReturnValue_t callbackAfterSending(ReturnValue_t queueStatus); -private: - /** - * This constant sets the maximum number of packets distributed per call. - */ - static constexpr uint8_t DISTRIBUTER_MAX_PACKETS = 128; + private: + /** + * This constant sets the maximum number of packets distributed per call. + */ + static constexpr uint8_t DISTRIBUTER_MAX_PACKETS = 128; }; - #endif /* FSFW_TMTCSERVICES_TCDISTRIBUTOR_H_ */ diff --git a/src/fsfw/tcdistribution/TcPacketCheckCFDP.cpp b/src/fsfw/tcdistribution/TcPacketCheckCFDP.cpp index 43e5511b..d1eb43bc 100644 --- a/src/fsfw/tcdistribution/TcPacketCheckCFDP.cpp +++ b/src/fsfw/tcdistribution/TcPacketCheckCFDP.cpp @@ -1,13 +1,9 @@ #include "fsfw/tcdistribution/TcPacketCheckCFDP.h" + #include "fsfw/tmtcpacket/cfdp/CFDPPacketStored.h" -TcPacketCheckCFDP::TcPacketCheckCFDP(uint16_t setApid): apid(setApid) { -} +TcPacketCheckCFDP::TcPacketCheckCFDP(uint16_t setApid) : apid(setApid) {} -ReturnValue_t TcPacketCheckCFDP::checkPacket(SpacePacketBase* currentPacket) { - return RETURN_OK; -} +ReturnValue_t TcPacketCheckCFDP::checkPacket(SpacePacketBase* currentPacket) { return RETURN_OK; } -uint16_t TcPacketCheckCFDP::getApid() const { - return apid; -} +uint16_t TcPacketCheckCFDP::getApid() const { return apid; } diff --git a/src/fsfw/tcdistribution/TcPacketCheckCFDP.h b/src/fsfw/tcdistribution/TcPacketCheckCFDP.h index 8205fe4b..3fe281d1 100644 --- a/src/fsfw/tcdistribution/TcPacketCheckCFDP.h +++ b/src/fsfw/tcdistribution/TcPacketCheckCFDP.h @@ -2,7 +2,6 @@ #define FSFW_TCDISTRIBUTION_TCPACKETCHECKCFDP_H_ #include "TcPacketCheckIF.h" - #include "fsfw/FSFW.h" class CFDPPacketStored; @@ -11,25 +10,24 @@ class CFDPPacketStored; * This class performs a formal packet check for incoming CFDP Packets. * @ingroup tc_distribution */ -class TcPacketCheckCFDP : - public TcPacketCheckIF, - public HasReturnvaluesIF { -protected: - /** - * The packet id each correct packet should have. - * It is composed of the APID and some static fields. - */ - uint16_t apid; -public: - /** - * The constructor only sets the APID attribute. - * @param set_apid The APID to set. - */ - TcPacketCheckCFDP(uint16_t setApid); +class TcPacketCheckCFDP : public TcPacketCheckIF, public HasReturnvaluesIF { + protected: + /** + * The packet id each correct packet should have. + * It is composed of the APID and some static fields. + */ + uint16_t apid; - ReturnValue_t checkPacket(SpacePacketBase* currentPacket) override; + public: + /** + * The constructor only sets the APID attribute. + * @param set_apid The APID to set. + */ + TcPacketCheckCFDP(uint16_t setApid); - uint16_t getApid() const; + ReturnValue_t checkPacket(SpacePacketBase* currentPacket) override; + + uint16_t getApid() const; }; #endif /* FSFW_TCDISTRIBUTION_TCPACKETCHECKCFDP_H_ */ diff --git a/src/fsfw/tcdistribution/TcPacketCheckIF.h b/src/fsfw/tcdistribution/TcPacketCheckIF.h index ac1dfef9..858c3093 100644 --- a/src/fsfw/tcdistribution/TcPacketCheckIF.h +++ b/src/fsfw/tcdistribution/TcPacketCheckIF.h @@ -10,22 +10,21 @@ class SpacePacketBase; * @ingroup tc_distribution */ class TcPacketCheckIF { -public: - /** - * The empty virtual destructor. - */ - virtual ~TcPacketCheckIF() { - } + public: + /** + * The empty virtual destructor. + */ + virtual ~TcPacketCheckIF() {} - /** - * This is the actual method to formally check a certain Packet. - * The packet's Application Data can not be checked here. - * @param current_packet The packet to check - * @return - @c RETURN_OK on success. - * - @c INCORRECT_CHECKSUM if checksum is invalid. - * - @c ILLEGAL_APID if APID does not match. - */ - virtual ReturnValue_t checkPacket(SpacePacketBase* currentPacket) = 0; + /** + * This is the actual method to formally check a certain Packet. + * The packet's Application Data can not be checked here. + * @param current_packet The packet to check + * @return - @c RETURN_OK on success. + * - @c INCORRECT_CHECKSUM if checksum is invalid. + * - @c ILLEGAL_APID if APID does not match. + */ + virtual ReturnValue_t checkPacket(SpacePacketBase* currentPacket) = 0; }; #endif /* FSFW_TCDISTRIBUTION_TCPACKETCHECKIF_H_ */ diff --git a/src/fsfw/tcdistribution/TcPacketCheckPUS.cpp b/src/fsfw/tcdistribution/TcPacketCheckPUS.cpp index d106a455..83844337 100644 --- a/src/fsfw/tcdistribution/TcPacketCheckPUS.cpp +++ b/src/fsfw/tcdistribution/TcPacketCheckPUS.cpp @@ -1,48 +1,44 @@ #include "fsfw/tcdistribution/TcPacketCheckPUS.h" #include "fsfw/globalfunctions/CRC.h" -#include "fsfw/tmtcpacket/pus/tc/TcPacketStoredPus.h" -#include "fsfw/tmtcpacket/pus/tc/TcPacketPusBase.h" -#include "fsfw/tmtcpacket/pus/tc/TcPacketStoredBase.h" #include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/storagemanager/StorageManagerIF.h" +#include "fsfw/tmtcpacket/pus/tc/TcPacketPusBase.h" +#include "fsfw/tmtcpacket/pus/tc/TcPacketStoredBase.h" +#include "fsfw/tmtcpacket/pus/tc/TcPacketStoredPus.h" #include "fsfw/tmtcservices/VerificationCodes.h" -TcPacketCheckPUS::TcPacketCheckPUS(uint16_t setApid): apid(setApid) { -} +TcPacketCheckPUS::TcPacketCheckPUS(uint16_t setApid) : apid(setApid) {} ReturnValue_t TcPacketCheckPUS::checkPacket(SpacePacketBase* currentPacket) { - TcPacketStoredBase* storedPacket = dynamic_cast(currentPacket); - TcPacketPusBase* tcPacketBase = dynamic_cast(currentPacket); - if(tcPacketBase == nullptr or storedPacket == nullptr) { - return RETURN_FAILED; - } - uint16_t calculated_crc = CRC::crc16ccitt(tcPacketBase->getWholeData(), - tcPacketBase->getFullSize()); - if (calculated_crc != 0) { - return INCORRECT_CHECKSUM; - } - bool condition = (not tcPacketBase->hasSecondaryHeader()) or - (tcPacketBase->getPacketVersionNumber() != CCSDS_VERSION_NUMBER) or - (not tcPacketBase->isTelecommand()); - if (condition) { - return INCORRECT_PRIMARY_HEADER; - } - if (tcPacketBase->getAPID() != this->apid) - return ILLEGAL_APID; + TcPacketStoredBase* storedPacket = dynamic_cast(currentPacket); + TcPacketPusBase* tcPacketBase = dynamic_cast(currentPacket); + if (tcPacketBase == nullptr or storedPacket == nullptr) { + return RETURN_FAILED; + } + uint16_t calculated_crc = + CRC::crc16ccitt(tcPacketBase->getWholeData(), tcPacketBase->getFullSize()); + if (calculated_crc != 0) { + return INCORRECT_CHECKSUM; + } + bool condition = (not tcPacketBase->hasSecondaryHeader()) or + (tcPacketBase->getPacketVersionNumber() != CCSDS_VERSION_NUMBER) or + (not tcPacketBase->isTelecommand()); + if (condition) { + return INCORRECT_PRIMARY_HEADER; + } + if (tcPacketBase->getAPID() != this->apid) return ILLEGAL_APID; - if (not storedPacket->isSizeCorrect()) { - return INCOMPLETE_PACKET; - } + if (not storedPacket->isSizeCorrect()) { + return INCOMPLETE_PACKET; + } - condition = (tcPacketBase->getSecondaryHeaderFlag() != CCSDS_SECONDARY_HEADER_FLAG) || - (tcPacketBase->getPusVersionNumber() != PUS_VERSION_NUMBER); - if (condition) { - return INCORRECT_SECONDARY_HEADER; - } - return RETURN_OK; + condition = (tcPacketBase->getSecondaryHeaderFlag() != CCSDS_SECONDARY_HEADER_FLAG) || + (tcPacketBase->getPusVersionNumber() != PUS_VERSION_NUMBER); + if (condition) { + return INCORRECT_SECONDARY_HEADER; + } + return RETURN_OK; } -uint16_t TcPacketCheckPUS::getApid() const { - return apid; -} +uint16_t TcPacketCheckPUS::getApid() const { return apid; } diff --git a/src/fsfw/tcdistribution/TcPacketCheckPUS.h b/src/fsfw/tcdistribution/TcPacketCheckPUS.h index ae4c7789..e3eca1a4 100644 --- a/src/fsfw/tcdistribution/TcPacketCheckPUS.h +++ b/src/fsfw/tcdistribution/TcPacketCheckPUS.h @@ -2,7 +2,6 @@ #define FSFW_TCDISTRIBUTION_TCPACKETCHECKPUS_H_ #include "TcPacketCheckIF.h" - #include "fsfw/FSFW.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" #include "fsfw/tmtcservices/PusVerificationReport.h" @@ -14,50 +13,49 @@ class TcPacketStoredBase; * Currently, it only checks if the APID and CRC are correct. * @ingroup tc_distribution */ -class TcPacketCheckPUS : - public TcPacketCheckIF, - public HasReturnvaluesIF { -protected: - /** - * Describes the version number a packet must have to pass. - */ - static constexpr uint8_t CCSDS_VERSION_NUMBER = 0; - /** - * Describes the secondary header a packet must have to pass. - */ - static constexpr uint8_t CCSDS_SECONDARY_HEADER_FLAG = 0; - /** - * Describes the TC Packet PUS Version Number a packet must have to pass. - */ +class TcPacketCheckPUS : public TcPacketCheckIF, public HasReturnvaluesIF { + protected: + /** + * Describes the version number a packet must have to pass. + */ + static constexpr uint8_t CCSDS_VERSION_NUMBER = 0; + /** + * Describes the secondary header a packet must have to pass. + */ + static constexpr uint8_t CCSDS_SECONDARY_HEADER_FLAG = 0; + /** + * Describes the TC Packet PUS Version Number a packet must have to pass. + */ #if FSFW_USE_PUS_C_TELECOMMANDS == 1 - static constexpr uint8_t PUS_VERSION_NUMBER = 2; + static constexpr uint8_t PUS_VERSION_NUMBER = 2; #else - static constexpr uint8_t PUS_VERSION_NUMBER = 1; + static constexpr uint8_t PUS_VERSION_NUMBER = 1; #endif - /** - * The packet id each correct packet should have. - * It is composed of the APID and some static fields. - */ - uint16_t apid; -public: - static const uint8_t INTERFACE_ID = CLASS_ID::TC_PACKET_CHECK; - static const ReturnValue_t ILLEGAL_APID = MAKE_RETURN_CODE( 0 ); - static const ReturnValue_t INCOMPLETE_PACKET = MAKE_RETURN_CODE( 1 ); - static const ReturnValue_t INCORRECT_CHECKSUM = MAKE_RETURN_CODE( 2 ); - static const ReturnValue_t ILLEGAL_PACKET_TYPE = MAKE_RETURN_CODE( 3 ); - static const ReturnValue_t ILLEGAL_PACKET_SUBTYPE = MAKE_RETURN_CODE( 4 ); - static const ReturnValue_t INCORRECT_PRIMARY_HEADER = MAKE_RETURN_CODE( 5 ); - static const ReturnValue_t INCORRECT_SECONDARY_HEADER = MAKE_RETURN_CODE( 6 ); - /** - * The constructor only sets the APID attribute. - * @param set_apid The APID to set. - */ - TcPacketCheckPUS(uint16_t setApid); + /** + * The packet id each correct packet should have. + * It is composed of the APID and some static fields. + */ + uint16_t apid; - ReturnValue_t checkPacket(SpacePacketBase* currentPacket) override; + public: + static const uint8_t INTERFACE_ID = CLASS_ID::TC_PACKET_CHECK; + static const ReturnValue_t ILLEGAL_APID = MAKE_RETURN_CODE(0); + static const ReturnValue_t INCOMPLETE_PACKET = MAKE_RETURN_CODE(1); + static const ReturnValue_t INCORRECT_CHECKSUM = MAKE_RETURN_CODE(2); + static const ReturnValue_t ILLEGAL_PACKET_TYPE = MAKE_RETURN_CODE(3); + static const ReturnValue_t ILLEGAL_PACKET_SUBTYPE = MAKE_RETURN_CODE(4); + static const ReturnValue_t INCORRECT_PRIMARY_HEADER = MAKE_RETURN_CODE(5); + static const ReturnValue_t INCORRECT_SECONDARY_HEADER = MAKE_RETURN_CODE(6); + /** + * The constructor only sets the APID attribute. + * @param set_apid The APID to set. + */ + TcPacketCheckPUS(uint16_t setApid); - uint16_t getApid() const; + ReturnValue_t checkPacket(SpacePacketBase* currentPacket) override; + + uint16_t getApid() const; }; #endif /* FSFW_TCDISTRIBUTION_TCPACKETCHECKPUS_H_ */ diff --git a/src/fsfw/thermal/AbstractTemperatureSensor.cpp b/src/fsfw/thermal/AbstractTemperatureSensor.cpp index 68e8d1c0..68cd3aca 100644 --- a/src/fsfw/thermal/AbstractTemperatureSensor.cpp +++ b/src/fsfw/thermal/AbstractTemperatureSensor.cpp @@ -1,70 +1,71 @@ #include "fsfw/thermal/AbstractTemperatureSensor.h" + #include "fsfw/ipc/QueueFactory.h" AbstractTemperatureSensor::AbstractTemperatureSensor(object_id_t setObjectid, - ThermalModuleIF *thermalModule) : - SystemObject(setObjectid), commandQueue(NULL), healthHelper(this, - setObjectid), parameterHelper(this) { - if (thermalModule != NULL) { - thermalModule->registerSensor(this); - } - commandQueue = QueueFactory::instance()->createMessageQueue(); + ThermalModuleIF *thermalModule) + : SystemObject(setObjectid), + commandQueue(NULL), + healthHelper(this, setObjectid), + parameterHelper(this) { + if (thermalModule != NULL) { + thermalModule->registerSensor(this); + } + commandQueue = QueueFactory::instance()->createMessageQueue(); } AbstractTemperatureSensor::~AbstractTemperatureSensor() { - QueueFactory::instance()->deleteMessageQueue(commandQueue); + QueueFactory::instance()->deleteMessageQueue(commandQueue); } MessageQueueId_t AbstractTemperatureSensor::getCommandQueue() const { - return commandQueue->getId(); + return commandQueue->getId(); } ReturnValue_t AbstractTemperatureSensor::initialize() { - ReturnValue_t result = SystemObject::initialize(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = healthHelper.initialize(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = parameterHelper.initialize(); - return result; + ReturnValue_t result = SystemObject::initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = healthHelper.initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = parameterHelper.initialize(); + return result; } ReturnValue_t AbstractTemperatureSensor::performOperation(uint8_t opCode) { - handleCommandQueue(); - doChildOperation(); - return HasReturnvaluesIF::RETURN_OK; + handleCommandQueue(); + doChildOperation(); + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t AbstractTemperatureSensor::performHealthOp() { - handleCommandQueue(); - return HasReturnvaluesIF::RETURN_OK; + handleCommandQueue(); + return HasReturnvaluesIF::RETURN_OK; } void AbstractTemperatureSensor::handleCommandQueue() { - CommandMessage command; - ReturnValue_t result = commandQueue->receiveMessage(&command); - if (result == HasReturnvaluesIF::RETURN_OK) { - result = healthHelper.handleHealthCommand(&command); - if (result == HasReturnvaluesIF::RETURN_OK) { - return; - } - result = parameterHelper.handleParameterMessage(&command); - if (result == HasReturnvaluesIF::RETURN_OK) { - return; - } - command.setToUnknownCommand(); - commandQueue->reply(&command); - } + CommandMessage command; + ReturnValue_t result = commandQueue->receiveMessage(&command); + if (result == HasReturnvaluesIF::RETURN_OK) { + result = healthHelper.handleHealthCommand(&command); + if (result == HasReturnvaluesIF::RETURN_OK) { + return; + } + result = parameterHelper.handleParameterMessage(&command); + if (result == HasReturnvaluesIF::RETURN_OK) { + return; + } + command.setToUnknownCommand(); + commandQueue->reply(&command); + } } ReturnValue_t AbstractTemperatureSensor::setHealth(HealthState health) { - healthHelper.setHealth(health); - return HasReturnvaluesIF::RETURN_OK; + healthHelper.setHealth(health); + return HasReturnvaluesIF::RETURN_OK; } -HasHealthIF::HealthState AbstractTemperatureSensor::getHealth() { - return healthHelper.getHealth(); -} +HasHealthIF::HealthState AbstractTemperatureSensor::getHealth() { return healthHelper.getHealth(); } diff --git a/src/fsfw/thermal/AbstractTemperatureSensor.h b/src/fsfw/thermal/AbstractTemperatureSensor.h index 719d84fe..0c6493fe 100644 --- a/src/fsfw/thermal/AbstractTemperatureSensor.h +++ b/src/fsfw/thermal/AbstractTemperatureSensor.h @@ -1,13 +1,13 @@ #ifndef ABSTRACTSENSOR_H_ #define ABSTRACTSENSOR_H_ +#include "ThermalModuleIF.h" #include "fsfw/health/HasHealthIF.h" #include "fsfw/health/HealthHelper.h" -#include "fsfw/objectmanager/SystemObject.h" -#include "fsfw/tasks/ExecutableObjectIF.h" -#include "fsfw/parameters/ParameterHelper.h" #include "fsfw/ipc/MessageQueueIF.h" -#include "ThermalModuleIF.h" +#include "fsfw/objectmanager/SystemObject.h" +#include "fsfw/parameters/ParameterHelper.h" +#include "fsfw/tasks/ExecutableObjectIF.h" #include "tcsDefinitions.h" /** @@ -20,45 +20,44 @@ * Please use the TemperatureSensor class to implement the actual sensors. * @ingroup thermal */ -class AbstractTemperatureSensor: public HasHealthIF, - public SystemObject, - public ExecutableObjectIF, - public ReceivesParameterMessagesIF { -public: +class AbstractTemperatureSensor : public HasHealthIF, + public SystemObject, + public ExecutableObjectIF, + public ReceivesParameterMessagesIF { + public: + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::T_SENSORS; + static const Event TEMP_SENSOR_HIGH = MAKE_EVENT(0, severity::LOW); + static const Event TEMP_SENSOR_LOW = MAKE_EVENT(1, severity::LOW); + static const Event TEMP_SENSOR_GRADIENT = MAKE_EVENT(2, severity::LOW); - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::T_SENSORS; - static const Event TEMP_SENSOR_HIGH = MAKE_EVENT(0, severity::LOW); - static const Event TEMP_SENSOR_LOW = MAKE_EVENT(1, severity::LOW); - static const Event TEMP_SENSOR_GRADIENT = MAKE_EVENT(2, severity::LOW); + static constexpr float ZERO_KELVIN_C = -273.15; + AbstractTemperatureSensor(object_id_t setObjectid, ThermalModuleIF* thermalModule); + virtual ~AbstractTemperatureSensor(); - static constexpr float ZERO_KELVIN_C = -273.15; - AbstractTemperatureSensor(object_id_t setObjectid, - ThermalModuleIF *thermalModule); - virtual ~AbstractTemperatureSensor(); + virtual MessageQueueId_t getCommandQueue() const; - virtual MessageQueueId_t getCommandQueue() const; + ReturnValue_t initialize(); - ReturnValue_t initialize(); + ReturnValue_t performHealthOp(); - ReturnValue_t performHealthOp(); + ReturnValue_t performOperation(uint8_t opCode); - ReturnValue_t performOperation(uint8_t opCode); + virtual float getTemperature() = 0; + virtual bool isValid() = 0; - virtual float getTemperature() = 0; - virtual bool isValid() = 0; + virtual void resetOldState() = 0; - virtual void resetOldState() = 0; + ReturnValue_t setHealth(HealthState health); + HasHealthIF::HealthState getHealth(); - ReturnValue_t setHealth(HealthState health); - HasHealthIF::HealthState getHealth(); -protected: - MessageQueueIF* commandQueue; - HealthHelper healthHelper; - ParameterHelper parameterHelper; + protected: + MessageQueueIF* commandQueue; + HealthHelper healthHelper; + ParameterHelper parameterHelper; - virtual void doChildOperation() = 0; + virtual void doChildOperation() = 0; - void handleCommandQueue(); + void handleCommandQueue(); }; #endif /* ABSTRACTSENSOR_H_ */ diff --git a/src/fsfw/thermal/AcceptsThermalMessagesIF.h b/src/fsfw/thermal/AcceptsThermalMessagesIF.h index 5fbd6bb3..52ded9da 100644 --- a/src/fsfw/thermal/AcceptsThermalMessagesIF.h +++ b/src/fsfw/thermal/AcceptsThermalMessagesIF.h @@ -9,14 +9,13 @@ #include "../ipc/MessageQueueSenderIF.h" class AcceptsThermalMessagesIF { -public: + public: + /** + * @brief This is the empty virtual destructor as required for C++ interfaces. + */ + virtual ~AcceptsThermalMessagesIF() {} - /** - * @brief This is the empty virtual destructor as required for C++ interfaces. - */ - virtual ~AcceptsThermalMessagesIF() { } - - virtual MessageQueueId_t getReceptionQueue() const = 0; + virtual MessageQueueId_t getReceptionQueue() const = 0; }; #endif /* FRAMEWORK_THERMAL_ACCEPTSTHERMALMESSAGESIF_H_ */ diff --git a/src/fsfw/thermal/Heater.cpp b/src/fsfw/thermal/Heater.cpp index e6acba13..4f0f8060 100644 --- a/src/fsfw/thermal/Heater.cpp +++ b/src/fsfw/thermal/Heater.cpp @@ -1,353 +1,334 @@ #include "fsfw/thermal/Heater.h" -#include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/devicehandlers/DeviceHandlerFailureIsolation.h" -#include "fsfw/power/Fuse.h" #include "fsfw/ipc/QueueFactory.h" +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/power/Fuse.h" -Heater::Heater(uint32_t objectId, uint8_t switch0, uint8_t switch1) : -HealthDevice(objectId, 0), internalState(STATE_OFF), switch0(switch0), switch1(switch1), - heaterOnCountdown(10800000)/*about two orbits*/, - parameterHelper(this) { - eventQueue = QueueFactory::instance()->createMessageQueue(); +Heater::Heater(uint32_t objectId, uint8_t switch0, uint8_t switch1) + : HealthDevice(objectId, 0), + internalState(STATE_OFF), + switch0(switch0), + switch1(switch1), + heaterOnCountdown(10800000) /*about two orbits*/, + parameterHelper(this) { + eventQueue = QueueFactory::instance()->createMessageQueue(); } -Heater::~Heater() { - QueueFactory::instance()->deleteMessageQueue(eventQueue); -} +Heater::~Heater() { QueueFactory::instance()->deleteMessageQueue(eventQueue); } ReturnValue_t Heater::set() { - passive = false; - //wait for clear before doing anything - if (internalState == STATE_WAIT) { - return HasReturnvaluesIF::RETURN_OK; - } - if (healthHelper.healthTable->isHealthy(getObjectId())) { - doAction(SET); - if ((internalState == STATE_OFF) || (internalState == STATE_PASSIVE)){ - return HasReturnvaluesIF::RETURN_FAILED; - } else { - return HasReturnvaluesIF::RETURN_OK; - } + passive = false; + // wait for clear before doing anything + if (internalState == STATE_WAIT) { + return HasReturnvaluesIF::RETURN_OK; + } + if (healthHelper.healthTable->isHealthy(getObjectId())) { + doAction(SET); + if ((internalState == STATE_OFF) || (internalState == STATE_PASSIVE)) { + return HasReturnvaluesIF::RETURN_FAILED; } else { - if (healthHelper.healthTable->isFaulty(getObjectId())) { - if (!reactedToBeingFaulty) { - reactedToBeingFaulty = true; - doAction(CLEAR); - } - } - return HasReturnvaluesIF::RETURN_FAILED; + return HasReturnvaluesIF::RETURN_OK; } + } else { + if (healthHelper.healthTable->isFaulty(getObjectId())) { + if (!reactedToBeingFaulty) { + reactedToBeingFaulty = true; + doAction(CLEAR); + } + } + return HasReturnvaluesIF::RETURN_FAILED; + } } void Heater::clear(bool passive) { - this->passive = passive; - //Force switching off - if (internalState == STATE_WAIT) { - internalState = STATE_ON; - } - if (healthHelper.healthTable->isHealthy(getObjectId())) { - doAction(CLEAR); - } else if (healthHelper.healthTable->isFaulty(getObjectId())) { - if (!reactedToBeingFaulty) { - reactedToBeingFaulty = true; - doAction(CLEAR); - } + this->passive = passive; + // Force switching off + if (internalState == STATE_WAIT) { + internalState = STATE_ON; + } + if (healthHelper.healthTable->isHealthy(getObjectId())) { + doAction(CLEAR); + } else if (healthHelper.healthTable->isFaulty(getObjectId())) { + if (!reactedToBeingFaulty) { + reactedToBeingFaulty = true; + doAction(CLEAR); } + } } void Heater::doAction(Action action) { - //only act if we are not in the right state or in a transition - if (action == SET) { - if ((internalState == STATE_OFF) || (internalState == STATE_PASSIVE) - || (internalState == STATE_EXTERNAL_CONTROL)) { - switchCountdown.setTimeout(powerSwitcher->getSwitchDelayMs()); - internalState = STATE_WAIT_FOR_SWITCHES_ON; - powerSwitcher->sendSwitchCommand(switch0, PowerSwitchIF::SWITCH_ON); - powerSwitcher->sendSwitchCommand(switch1, PowerSwitchIF::SWITCH_ON); - } - } else { //clear - if ((internalState == STATE_ON) || (internalState == STATE_FAULTY) - || (internalState == STATE_EXTERNAL_CONTROL)) { - internalState = STATE_WAIT_FOR_SWITCHES_OFF; - switchCountdown.setTimeout(powerSwitcher->getSwitchDelayMs()); - powerSwitcher->sendSwitchCommand(switch0, - PowerSwitchIF::SWITCH_OFF); - powerSwitcher->sendSwitchCommand(switch1, - PowerSwitchIF::SWITCH_OFF); - } + // only act if we are not in the right state or in a transition + if (action == SET) { + if ((internalState == STATE_OFF) || (internalState == STATE_PASSIVE) || + (internalState == STATE_EXTERNAL_CONTROL)) { + switchCountdown.setTimeout(powerSwitcher->getSwitchDelayMs()); + internalState = STATE_WAIT_FOR_SWITCHES_ON; + powerSwitcher->sendSwitchCommand(switch0, PowerSwitchIF::SWITCH_ON); + powerSwitcher->sendSwitchCommand(switch1, PowerSwitchIF::SWITCH_ON); } + } else { // clear + if ((internalState == STATE_ON) || (internalState == STATE_FAULTY) || + (internalState == STATE_EXTERNAL_CONTROL)) { + internalState = STATE_WAIT_FOR_SWITCHES_OFF; + switchCountdown.setTimeout(powerSwitcher->getSwitchDelayMs()); + powerSwitcher->sendSwitchCommand(switch0, PowerSwitchIF::SWITCH_OFF); + powerSwitcher->sendSwitchCommand(switch1, PowerSwitchIF::SWITCH_OFF); + } + } } -void Heater::setPowerSwitcher(PowerSwitchIF* powerSwitch) { - this->powerSwitcher = powerSwitch; -} +void Heater::setPowerSwitcher(PowerSwitchIF* powerSwitch) { this->powerSwitcher = powerSwitch; } ReturnValue_t Heater::performOperation(uint8_t opCode) { - handleQueue(); - handleEventQueue(); + handleQueue(); + handleEventQueue(); - if (!healthHelper.healthTable->isFaulty(getObjectId())) { - reactedToBeingFaulty = false; - } + if (!healthHelper.healthTable->isFaulty(getObjectId())) { + reactedToBeingFaulty = false; + } - switch (internalState) { + switch (internalState) { case STATE_ON: - if ((powerSwitcher->getSwitchState(switch0) == PowerSwitchIF::SWITCH_OFF) - || (powerSwitcher->getSwitchState(switch1) - == PowerSwitchIF::SWITCH_OFF)) { - //switch went off on its own - //trigger event. FDIR can confirm if it is caused by MniOps and decide on the action - //do not trigger FD events when under external control - if (healthHelper.getHealth() != EXTERNAL_CONTROL) { - triggerEvent(PowerSwitchIF::SWITCH_WENT_OFF); - } else { - internalState = STATE_EXTERNAL_CONTROL; - } + if ((powerSwitcher->getSwitchState(switch0) == PowerSwitchIF::SWITCH_OFF) || + (powerSwitcher->getSwitchState(switch1) == PowerSwitchIF::SWITCH_OFF)) { + // switch went off on its own + // trigger event. FDIR can confirm if it is caused by MniOps and decide on the action + // do not trigger FD events when under external control + if (healthHelper.getHealth() != EXTERNAL_CONTROL) { + triggerEvent(PowerSwitchIF::SWITCH_WENT_OFF); + } else { + internalState = STATE_EXTERNAL_CONTROL; } - break; + } + break; case STATE_OFF: - //check if heater is on, ie both switches are on - //if so, just command it to off, to resolve the situation or force a switch stayed on event - //But, only do anything if not already faulty (state off is the stable point for being faulty) - if ((!healthHelper.healthTable->isFaulty(getObjectId())) - && (powerSwitcher->getSwitchState(switch0) - == PowerSwitchIF::SWITCH_ON) - && (powerSwitcher->getSwitchState(switch1) - == PowerSwitchIF::SWITCH_ON)) { - //do not trigger FD events when under external control - if (healthHelper.getHealth() != EXTERNAL_CONTROL) { - internalState = STATE_WAIT_FOR_SWITCHES_OFF; - switchCountdown.setTimeout(powerSwitcher->getSwitchDelayMs()); - powerSwitcher->sendSwitchCommand(switch0, - PowerSwitchIF::SWITCH_OFF); - powerSwitcher->sendSwitchCommand(switch1, - PowerSwitchIF::SWITCH_OFF); - } else { - internalState = STATE_EXTERNAL_CONTROL; - } + // check if heater is on, ie both switches are on + // if so, just command it to off, to resolve the situation or force a switch stayed on event + // But, only do anything if not already faulty (state off is the stable point for being + // faulty) + if ((!healthHelper.healthTable->isFaulty(getObjectId())) && + (powerSwitcher->getSwitchState(switch0) == PowerSwitchIF::SWITCH_ON) && + (powerSwitcher->getSwitchState(switch1) == PowerSwitchIF::SWITCH_ON)) { + // do not trigger FD events when under external control + if (healthHelper.getHealth() != EXTERNAL_CONTROL) { + internalState = STATE_WAIT_FOR_SWITCHES_OFF; + switchCountdown.setTimeout(powerSwitcher->getSwitchDelayMs()); + powerSwitcher->sendSwitchCommand(switch0, PowerSwitchIF::SWITCH_OFF); + powerSwitcher->sendSwitchCommand(switch1, PowerSwitchIF::SWITCH_OFF); + } else { + internalState = STATE_EXTERNAL_CONTROL; } - break; + } + break; case STATE_PASSIVE: - break; + break; case STATE_WAIT_FOR_SWITCHES_ON: - if (switchCountdown.hasTimedOut()) { - if ((powerSwitcher->getSwitchState(switch0) - == PowerSwitchIF::SWITCH_OFF) - || (powerSwitcher->getSwitchState(switch1) - == PowerSwitchIF::SWITCH_OFF)) { - triggerEvent(HEATER_STAYED_OFF); - internalState = STATE_WAIT_FOR_FDIR; //wait before retrying or anything - } else { - triggerEvent(HEATER_ON); - internalState = STATE_ON; - } + if (switchCountdown.hasTimedOut()) { + if ((powerSwitcher->getSwitchState(switch0) == PowerSwitchIF::SWITCH_OFF) || + (powerSwitcher->getSwitchState(switch1) == PowerSwitchIF::SWITCH_OFF)) { + triggerEvent(HEATER_STAYED_OFF); + internalState = STATE_WAIT_FOR_FDIR; // wait before retrying or anything + } else { + triggerEvent(HEATER_ON); + internalState = STATE_ON; } - break; + } + break; case STATE_WAIT_FOR_SWITCHES_OFF: - if (switchCountdown.hasTimedOut()) { - //only check for both being on (ie heater still on) - if ((powerSwitcher->getSwitchState(switch0) - == PowerSwitchIF::SWITCH_ON) - && (powerSwitcher->getSwitchState(switch1) - == PowerSwitchIF::SWITCH_ON)) { - if (healthHelper.healthTable->isFaulty(getObjectId())) { - if (passive) { - internalState = STATE_PASSIVE; - } else { - internalState = STATE_OFF; //just accept it - } - triggerEvent(HEATER_ON); //but throw an event to make it more visible - break; - } - triggerEvent(HEATER_STAYED_ON); - internalState = STATE_WAIT_FOR_FDIR; //wait before retrying or anything + if (switchCountdown.hasTimedOut()) { + // only check for both being on (ie heater still on) + if ((powerSwitcher->getSwitchState(switch0) == PowerSwitchIF::SWITCH_ON) && + (powerSwitcher->getSwitchState(switch1) == PowerSwitchIF::SWITCH_ON)) { + if (healthHelper.healthTable->isFaulty(getObjectId())) { + if (passive) { + internalState = STATE_PASSIVE; } else { - triggerEvent(HEATER_OFF); - if (passive) { - internalState = STATE_PASSIVE; - } else { - internalState = STATE_OFF; - } + internalState = STATE_OFF; // just accept it } + triggerEvent(HEATER_ON); // but throw an event to make it more visible + break; + } + triggerEvent(HEATER_STAYED_ON); + internalState = STATE_WAIT_FOR_FDIR; // wait before retrying or anything + } else { + triggerEvent(HEATER_OFF); + if (passive) { + internalState = STATE_PASSIVE; + } else { + internalState = STATE_OFF; + } } - break; + } + break; default: - break; - } + break; + } - if ((powerSwitcher->getSwitchState(switch0) == PowerSwitchIF::SWITCH_ON) - && (powerSwitcher->getSwitchState(switch1) - == PowerSwitchIF::SWITCH_ON)) { - if (wasOn) { - if (heaterOnCountdown.hasTimedOut()) { - //SHOULDDO this means if a heater fails in single mode, the timeout will start again - //I am not sure if this is a bug, but atm I have no idea how to fix this and think - //it will be ok. whatcouldpossiblygowrongâ„¢ - if (!timedOut) { - triggerEvent(HEATER_TIMEOUT); - timedOut = true; - } - } - } else { - wasOn = true; - heaterOnCountdown.resetTimer(); - timedOut = false; + if ((powerSwitcher->getSwitchState(switch0) == PowerSwitchIF::SWITCH_ON) && + (powerSwitcher->getSwitchState(switch1) == PowerSwitchIF::SWITCH_ON)) { + if (wasOn) { + if (heaterOnCountdown.hasTimedOut()) { + // SHOULDDO this means if a heater fails in single mode, the timeout will start again + // I am not sure if this is a bug, but atm I have no idea how to fix this and think + // it will be ok. whatcouldpossiblygowrongâ„¢ + if (!timedOut) { + triggerEvent(HEATER_TIMEOUT); + timedOut = true; } + } } else { - wasOn = false; + wasOn = true; + heaterOnCountdown.resetTimer(); + timedOut = false; } + } else { + wasOn = false; + } - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } -void Heater::setSwitch(uint8_t number, ReturnValue_t state, - uint32_t* uptimeOfSwitching) { - if (powerSwitcher == NULL) { - return; - } - if (powerSwitcher->getSwitchState(number) == state) { +void Heater::setSwitch(uint8_t number, ReturnValue_t state, uint32_t* uptimeOfSwitching) { + if (powerSwitcher == NULL) { + return; + } + if (powerSwitcher->getSwitchState(number) == state) { + *uptimeOfSwitching = INVALID_UPTIME; + } else { + if ((*uptimeOfSwitching == INVALID_UPTIME)) { + powerSwitcher->sendSwitchCommand(number, state); + Clock::getUptime(uptimeOfSwitching); + } else { + uint32_t currentUptime; + Clock::getUptime(¤tUptime); + if (currentUptime - *uptimeOfSwitching > powerSwitcher->getSwitchDelayMs()) { *uptimeOfSwitching = INVALID_UPTIME; - } else { - if ((*uptimeOfSwitching == INVALID_UPTIME)) { - powerSwitcher->sendSwitchCommand(number, state); - Clock::getUptime(uptimeOfSwitching); - } else { - uint32_t currentUptime; - Clock::getUptime(¤tUptime); - if (currentUptime - *uptimeOfSwitching - > powerSwitcher->getSwitchDelayMs()) { - *uptimeOfSwitching = INVALID_UPTIME; - if (healthHelper.healthTable->isHealthy(getObjectId())) { - if (state == PowerSwitchIF::SWITCH_ON) { - triggerEvent(HEATER_STAYED_OFF); - } else { - triggerEvent(HEATER_STAYED_ON); - } - } - } + if (healthHelper.healthTable->isHealthy(getObjectId())) { + if (state == PowerSwitchIF::SWITCH_ON) { + triggerEvent(HEATER_STAYED_OFF); + } else { + triggerEvent(HEATER_STAYED_ON); + } } + } } + } } -MessageQueueId_t Heater::getCommandQueue() const { - return commandQueue->getId(); -} +MessageQueueId_t Heater::getCommandQueue() const { return commandQueue->getId(); } ReturnValue_t Heater::initialize() { - ReturnValue_t result = SystemObject::initialize(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + ReturnValue_t result = SystemObject::initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - EventManagerIF* manager = ObjectManager::instance()->get( - objects::EVENT_MANAGER); - if (manager == NULL) { - return HasReturnvaluesIF::RETURN_FAILED; - } - result = manager->registerListener(eventQueue->getId()); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + EventManagerIF* manager = ObjectManager::instance()->get(objects::EVENT_MANAGER); + if (manager == NULL) { + return HasReturnvaluesIF::RETURN_FAILED; + } + result = manager->registerListener(eventQueue->getId()); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - ConfirmsFailuresIF* pcdu = ObjectManager::instance()->get( - DeviceHandlerFailureIsolation::powerConfirmationId); - if (pcdu == NULL) { - return HasReturnvaluesIF::RETURN_FAILED; - } - pcduQueueId = pcdu->getEventReceptionQueue(); + ConfirmsFailuresIF* pcdu = ObjectManager::instance()->get( + DeviceHandlerFailureIsolation::powerConfirmationId); + if (pcdu == NULL) { + return HasReturnvaluesIF::RETURN_FAILED; + } + pcduQueueId = pcdu->getEventReceptionQueue(); - result = manager->subscribeToAllEventsFrom(eventQueue->getId(), - getObjectId()); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + result = manager->subscribeToAllEventsFrom(eventQueue->getId(), getObjectId()); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - result = parameterHelper.initialize(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + result = parameterHelper.initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - result = healthHelper.initialize(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + result = healthHelper.initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } void Heater::handleQueue() { - CommandMessage command; - ReturnValue_t result = commandQueue->receiveMessage(&command); + CommandMessage command; + ReturnValue_t result = commandQueue->receiveMessage(&command); + if (result == HasReturnvaluesIF::RETURN_OK) { + result = healthHelper.handleHealthCommand(&command); if (result == HasReturnvaluesIF::RETURN_OK) { - result = healthHelper.handleHealthCommand(&command); - if (result == HasReturnvaluesIF::RETURN_OK) { - return; - } - result = parameterHelper.handleParameterMessage(&command); - if (result == HasReturnvaluesIF::RETURN_OK) { - return; - } + return; } + result = parameterHelper.handleParameterMessage(&command); + if (result == HasReturnvaluesIF::RETURN_OK) { + return; + } + } } ReturnValue_t Heater::getParameter(uint8_t domainId, uint8_t uniqueId, - ParameterWrapper* parameterWrapper, const ParameterWrapper* newValues, - uint16_t startAtIndex) { - if (domainId != DOMAIN_ID_BASE) { - return INVALID_DOMAIN_ID; - } - switch (uniqueId) { + ParameterWrapper* parameterWrapper, + const ParameterWrapper* newValues, uint16_t startAtIndex) { + if (domainId != DOMAIN_ID_BASE) { + return INVALID_DOMAIN_ID; + } + switch (uniqueId) { case 0: - parameterWrapper->set(heaterOnCountdown.timeout); - break; + parameterWrapper->set(heaterOnCountdown.timeout); + break; default: - return INVALID_IDENTIFIER_ID; - } - return HasReturnvaluesIF::RETURN_OK; + return INVALID_IDENTIFIER_ID; + } + return HasReturnvaluesIF::RETURN_OK; } void Heater::handleEventQueue() { - EventMessage event; - for (ReturnValue_t result = eventQueue->receiveMessage(&event); - result == HasReturnvaluesIF::RETURN_OK; - result = eventQueue->receiveMessage(&event)) { - switch (event.getMessageId()) { - case EventMessage::EVENT_MESSAGE: - switch (event.getEvent()) { - case Fuse::FUSE_WENT_OFF: - case HEATER_STAYED_OFF: - // HEATER_STAYED_ON is a setting if faulty does not help, but we need to reach a stable state and can check - // for being faulty before throwing this event again. - case HEATER_STAYED_ON: - if (healthHelper.healthTable->isCommandable(getObjectId())) { - healthHelper.setHealth(HasHealthIF::FAULTY); - internalState = STATE_FAULTY; - } - break; - case PowerSwitchIF::SWITCH_WENT_OFF: - internalState = STATE_WAIT; - event.setMessageId(EventMessage::CONFIRMATION_REQUEST); - if (pcduQueueId != 0) { - eventQueue->sendMessage(pcduQueueId, &event); - } else { - healthHelper.setHealth(HasHealthIF::FAULTY); - internalState = STATE_FAULTY; - } - break; - default: - return; + EventMessage event; + for (ReturnValue_t result = eventQueue->receiveMessage(&event); + result == HasReturnvaluesIF::RETURN_OK; result = eventQueue->receiveMessage(&event)) { + switch (event.getMessageId()) { + case EventMessage::EVENT_MESSAGE: + switch (event.getEvent()) { + case Fuse::FUSE_WENT_OFF: + case HEATER_STAYED_OFF: + // HEATER_STAYED_ON is a setting if faulty does not help, but we need to reach a stable + // state and can check for being faulty before throwing this event again. + case HEATER_STAYED_ON: + if (healthHelper.healthTable->isCommandable(getObjectId())) { + healthHelper.setHealth(HasHealthIF::FAULTY); + internalState = STATE_FAULTY; } break; - case EventMessage::YOUR_FAULT: - healthHelper.setHealth(HasHealthIF::FAULTY); - internalState = STATE_FAULTY; - break; - case EventMessage::MY_FAULT: - //do nothing, we are already in STATE_WAIT and wait for a clear() - break; - default: - return; + case PowerSwitchIF::SWITCH_WENT_OFF: + internalState = STATE_WAIT; + event.setMessageId(EventMessage::CONFIRMATION_REQUEST); + if (pcduQueueId != 0) { + eventQueue->sendMessage(pcduQueueId, &event); + } else { + healthHelper.setHealth(HasHealthIF::FAULTY); + internalState = STATE_FAULTY; + } + break; + default: + return; } + break; + case EventMessage::YOUR_FAULT: + healthHelper.setHealth(HasHealthIF::FAULTY); + internalState = STATE_FAULTY; + break; + case EventMessage::MY_FAULT: + // do nothing, we are already in STATE_WAIT and wait for a clear() + break; + default: + return; } + } } diff --git a/src/fsfw/thermal/Heater.h b/src/fsfw/thermal/Heater.h index 2a40cac6..61d3776f 100644 --- a/src/fsfw/thermal/Heater.h +++ b/src/fsfw/thermal/Heater.h @@ -1,94 +1,89 @@ #ifndef FSFW_THERMAL_HEATER_H_ #define FSFW_THERMAL_HEATER_H_ +#include + #include "fsfw/devicehandlers/HealthDevice.h" #include "fsfw/parameters/ParameterHelper.h" #include "fsfw/power/PowerSwitchIF.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" #include "fsfw/timemanager/Countdown.h" -#include +class Heater : public HealthDevice, public ReceivesParameterMessagesIF { + friend class RedundantHeater; + public: + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::HEATER; + static const Event HEATER_ON = MAKE_EVENT(0, severity::INFO); + static const Event HEATER_OFF = MAKE_EVENT(1, severity::INFO); + static const Event HEATER_TIMEOUT = MAKE_EVENT(2, severity::LOW); + static const Event HEATER_STAYED_ON = MAKE_EVENT(3, severity::LOW); + static const Event HEATER_STAYED_OFF = MAKE_EVENT(4, severity::LOW); -class Heater: public HealthDevice, public ReceivesParameterMessagesIF { - friend class RedundantHeater; -public: + Heater(uint32_t objectId, uint8_t switch0, uint8_t switch1); + virtual ~Heater(); - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::HEATER; - static const Event HEATER_ON = MAKE_EVENT(0, severity::INFO); - static const Event HEATER_OFF = MAKE_EVENT(1, severity::INFO); - static const Event HEATER_TIMEOUT = MAKE_EVENT(2, severity::LOW); - static const Event HEATER_STAYED_ON = MAKE_EVENT(3, severity::LOW); - static const Event HEATER_STAYED_OFF = MAKE_EVENT(4, severity::LOW); + ReturnValue_t performOperation(uint8_t opCode); - Heater(uint32_t objectId, uint8_t switch0, uint8_t switch1); - virtual ~Heater(); + ReturnValue_t initialize(); - ReturnValue_t performOperation(uint8_t opCode); + ReturnValue_t set(); + void clear(bool passive); - ReturnValue_t initialize(); + void setPowerSwitcher(PowerSwitchIF *powerSwitch); - ReturnValue_t set(); - void clear(bool passive); + MessageQueueId_t getCommandQueue() const; - void setPowerSwitcher(PowerSwitchIF *powerSwitch); + ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, ParameterWrapper *parameterWrapper, + const ParameterWrapper *newValues, uint16_t startAtIndex); - MessageQueueId_t getCommandQueue() const; + protected: + static const uint32_t INVALID_UPTIME = 0; - ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, - ParameterWrapper *parameterWrapper, - const ParameterWrapper *newValues, uint16_t startAtIndex); + enum InternalState { + STATE_ON, + STATE_OFF, + STATE_PASSIVE, + STATE_WAIT_FOR_SWITCHES_ON, + STATE_WAIT_FOR_SWITCHES_OFF, + STATE_WAIT_FOR_FDIR, // Used to avoid doing anything until fdir decided what to do + STATE_FAULTY, + STATE_WAIT, // Used when waiting for system to recover from miniops + // Entered when under external control and a fdir reaction would be triggered. + // This is useful when leaving external control into an unknown state + STATE_EXTERNAL_CONTROL + // If no fdir reaction is triggered under external control the state is still ok and + // no need for any special treatment is needed + } internalState; -protected: - static const uint32_t INVALID_UPTIME = 0; + PowerSwitchIF *powerSwitcher = nullptr; + MessageQueueId_t pcduQueueId = MessageQueueIF::NO_QUEUE; - enum InternalState { - STATE_ON, - STATE_OFF, - STATE_PASSIVE, - STATE_WAIT_FOR_SWITCHES_ON, - STATE_WAIT_FOR_SWITCHES_OFF, - STATE_WAIT_FOR_FDIR, // Used to avoid doing anything until fdir decided what to do - STATE_FAULTY, - STATE_WAIT, // Used when waiting for system to recover from miniops - // Entered when under external control and a fdir reaction would be triggered. - // This is useful when leaving external control into an unknown state - STATE_EXTERNAL_CONTROL - // If no fdir reaction is triggered under external control the state is still ok and - // no need for any special treatment is needed - } internalState; + uint8_t switch0; + uint8_t switch1; - PowerSwitchIF *powerSwitcher = nullptr; - MessageQueueId_t pcduQueueId = MessageQueueIF::NO_QUEUE; + bool wasOn = false; - uint8_t switch0; - uint8_t switch1; + bool timedOut = false; - bool wasOn = false; + bool reactedToBeingFaulty = false; - bool timedOut = false; + bool passive = false; - bool reactedToBeingFaulty = false; + MessageQueueIF *eventQueue = nullptr; + Countdown heaterOnCountdown; + Countdown switchCountdown; + ParameterHelper parameterHelper; - bool passive = false; + enum Action { SET, CLEAR } lastAction = CLEAR; - MessageQueueIF* eventQueue = nullptr; - Countdown heaterOnCountdown; - Countdown switchCountdown; - ParameterHelper parameterHelper; + void doAction(Action action); - enum Action { - SET, CLEAR - } lastAction = CLEAR; + void setSwitch(uint8_t number, ReturnValue_t state, uint32_t *upTimeOfSwitching); - void doAction(Action action); + void handleQueue(); - void setSwitch(uint8_t number, ReturnValue_t state, - uint32_t *upTimeOfSwitching); - - void handleQueue(); - - void handleEventQueue(); + void handleEventQueue(); }; #endif /* FSFW_THERMAL_HEATER_H_ */ diff --git a/src/fsfw/thermal/RedundantHeater.cpp b/src/fsfw/thermal/RedundantHeater.cpp index e7b774cb..431d9900 100644 --- a/src/fsfw/thermal/RedundantHeater.cpp +++ b/src/fsfw/thermal/RedundantHeater.cpp @@ -1,40 +1,36 @@ #include "fsfw/thermal/RedundantHeater.h" -RedundantHeater::~RedundantHeater() { -} +RedundantHeater::~RedundantHeater() {} -RedundantHeater::RedundantHeater(Parameters parameters) : - heater0(parameters.objectIdHeater0, parameters.switch0Heater0, - parameters.switch1Heater0), heater1(parameters.objectIdHeater1, - parameters.switch0Heater1, parameters.switch1Heater1) { -} +RedundantHeater::RedundantHeater(Parameters parameters) + : heater0(parameters.objectIdHeater0, parameters.switch0Heater0, parameters.switch1Heater0), + heater1(parameters.objectIdHeater1, parameters.switch0Heater1, parameters.switch1Heater1) {} void RedundantHeater::performOperation(uint8_t opCode) { - heater0.performOperation(0); - heater1.performOperation(0); + heater0.performOperation(0); + heater1.performOperation(0); } void RedundantHeater::set(bool on, bool both, bool passive) { - if (on) { - ReturnValue_t result = heater0.set(); - if (result != HasReturnvaluesIF::RETURN_OK || both) { - heater1.set(); - } else { - heater1.clear(passive); - } - } else { - heater0.clear(passive); - heater1.clear(passive); - } - + if (on) { + ReturnValue_t result = heater0.set(); + if (result != HasReturnvaluesIF::RETURN_OK || both) { + heater1.set(); + } else { + heater1.clear(passive); + } + } else { + heater0.clear(passive); + heater1.clear(passive); + } } void RedundantHeater::triggerHeaterEvent(Event event) { - heater0.triggerEvent(event); - heater1.triggerEvent(event); + heater0.triggerEvent(event); + heater1.triggerEvent(event); } void RedundantHeater::setPowerSwitcher(PowerSwitchIF* powerSwitch) { - heater0.setPowerSwitcher(powerSwitch); - heater1.setPowerSwitcher(powerSwitch); + heater0.setPowerSwitcher(powerSwitch); + heater1.setPowerSwitcher(powerSwitch); } diff --git a/src/fsfw/thermal/RedundantHeater.h b/src/fsfw/thermal/RedundantHeater.h index 76537542..ada13401 100644 --- a/src/fsfw/thermal/RedundantHeater.h +++ b/src/fsfw/thermal/RedundantHeater.h @@ -4,47 +4,47 @@ #include "../thermal/Heater.h" class RedundantHeater { -public: + public: + struct Parameters { + Parameters(uint32_t objectIdHeater0, uint32_t objectIdHeater1, uint8_t switch0Heater0, + uint8_t switch1Heater0, uint8_t switch0Heater1, uint8_t switch1Heater1) + : objectIdHeater0(objectIdHeater0), + objectIdHeater1(objectIdHeater1), + switch0Heater0(switch0Heater0), + switch1Heater0(switch1Heater0), + switch0Heater1(switch0Heater1), + switch1Heater1(switch1Heater1) {} - struct Parameters { - Parameters(uint32_t objectIdHeater0, uint32_t objectIdHeater1, - uint8_t switch0Heater0, uint8_t switch1Heater0, - uint8_t switch0Heater1, uint8_t switch1Heater1) : - objectIdHeater0(objectIdHeater0), objectIdHeater1(objectIdHeater1), - switch0Heater0(switch0Heater0),switch1Heater0(switch1Heater0), - switch0Heater1(switch0Heater1), switch1Heater1(switch1Heater1) { - } + Parameters() + : objectIdHeater0(0), + objectIdHeater1(0), + switch0Heater0(0), + switch1Heater0(0), + switch0Heater1(0), + switch1Heater1(0) {} - Parameters() : - objectIdHeater0(0), objectIdHeater1(0), switch0Heater0(0), - switch1Heater0(0), switch0Heater1(0), switch1Heater1(0) { - } + uint32_t objectIdHeater0; + uint32_t objectIdHeater1; + uint8_t switch0Heater0; + uint8_t switch1Heater0; + uint8_t switch0Heater1; + uint8_t switch1Heater1; + }; - uint32_t objectIdHeater0; - uint32_t objectIdHeater1; - uint8_t switch0Heater0; - uint8_t switch1Heater0; - uint8_t switch0Heater1; - uint8_t switch1Heater1; - }; + RedundantHeater(Parameters parameters); + virtual ~RedundantHeater(); - RedundantHeater(Parameters parameters); - virtual ~RedundantHeater(); + void performOperation(uint8_t opCode); - void performOperation(uint8_t opCode); + void triggerHeaterEvent(Event event); - void triggerHeaterEvent(Event event); + void set(bool on, bool both, bool passive = false); - void set(bool on, bool both, bool passive = false); - - void setPowerSwitcher(PowerSwitchIF *powerSwitch); - -protected: - - Heater heater0; - Heater heater1; + void setPowerSwitcher(PowerSwitchIF *powerSwitch); + protected: + Heater heater0; + Heater heater1; }; #endif /* REDUNDANTHEATER_H_ */ - diff --git a/src/fsfw/thermal/TemperatureSensor.h b/src/fsfw/thermal/TemperatureSensor.h index c7b9d771..591fd7d9 100644 --- a/src/fsfw/thermal/TemperatureSensor.h +++ b/src/fsfw/thermal/TemperatureSensor.h @@ -1,13 +1,11 @@ #ifndef FSFW_THERMAL_TEMPERATURESENSOR_H_ #define FSFW_THERMAL_TEMPERATURESENSOR_H_ -#include "tcsDefinitions.h" -#include "AbstractTemperatureSensor.h" - #include "../datapoollocal/LocalPoolDataSetBase.h" #include "../datapoollocal/LocalPoolVariable.h" #include "../monitoring/LimitMonitor.h" - +#include "AbstractTemperatureSensor.h" +#include "tcsDefinitions.h" /** * @brief This building block handles non-linear value conversion and @@ -22,207 +20,199 @@ * @ingroup thermal */ -template -class TemperatureSensor: public AbstractTemperatureSensor { -public: - /** - * This structure contains parameters required for range checking - * and the conversion from the input value to the output temperature. - * a, b and c can be any parameters required to calculate the output - * temperature from the input value, depending on the formula used. - * - * The parameters a,b and c are used in the calculateOutputTemperature() call. - * - * The lower and upper limits can be specified in any type, for example float for C values - * or any other type for raw values. - */ - struct Parameters { - float a; - float b; - float c; - limitType lowerLimit; - limitType upperLimit; - float maxGradient; - }; +template +class TemperatureSensor : public AbstractTemperatureSensor { + public: + /** + * This structure contains parameters required for range checking + * and the conversion from the input value to the output temperature. + * a, b and c can be any parameters required to calculate the output + * temperature from the input value, depending on the formula used. + * + * The parameters a,b and c are used in the calculateOutputTemperature() call. + * + * The lower and upper limits can be specified in any type, for example float for C values + * or any other type for raw values. + */ + struct Parameters { + float a; + float b; + float c; + limitType lowerLimit; + limitType upperLimit; + float maxGradient; + }; - /** - * Forward declaration for explicit instantiation of used parameters. - */ - struct UsedParameters { - UsedParameters(Parameters parameters) : - a(parameters.a), b(parameters.b), c(parameters.c), - gradient(parameters.maxGradient) {} - float a; - float b; - float c; - float gradient; - }; + /** + * Forward declaration for explicit instantiation of used parameters. + */ + struct UsedParameters { + UsedParameters(Parameters parameters) + : a(parameters.a), b(parameters.b), c(parameters.c), gradient(parameters.maxGradient) {} + float a; + float b; + float c; + float gradient; + }; - /** - * Instantiate Temperature Sensor Object. - * @param setObjectid objectId of the sensor object - * @param inputTemperature Pointer to a raw input value which is converted to an floating - * point C output temperature - * @param outputGpid Global Pool ID of the output value - * @param vectorIndex Vector Index for the sensor monitor - * @param parameters Calculation parameters, temperature limits, gradient limit - * @param outputSet Output dataset for the output temperature to fetch it with read() - * @param thermalModule Respective thermal module, if it has one - */ - TemperatureSensor(object_id_t setObjectid,lp_var_t* inputTemperature, - gp_id_t outputGpid, uint8_t vectorIndex, Parameters parameters = {0, 0, 0, 0, 0, 0}, - LocalPoolDataSetBase *outputSet = nullptr, ThermalModuleIF *thermalModule = nullptr) : - AbstractTemperatureSensor(setObjectid, thermalModule), parameters(parameters), - inputTemperature(inputTemperature), - outputTemperature(outputGpid, outputSet, PoolVariableIF::VAR_WRITE), - sensorMonitor(setObjectid, DOMAIN_ID_SENSOR, outputGpid, - DEFAULT_CONFIRMATION_COUNT, parameters.lowerLimit, parameters.upperLimit, - TEMP_SENSOR_LOW, TEMP_SENSOR_HIGH), - oldTemperature(20), uptimeOfOldTemperature({ thermal::INVALID_TEMPERATURE, 0 }) { - } + /** + * Instantiate Temperature Sensor Object. + * @param setObjectid objectId of the sensor object + * @param inputTemperature Pointer to a raw input value which is converted to an floating + * point C output temperature + * @param outputGpid Global Pool ID of the output value + * @param vectorIndex Vector Index for the sensor monitor + * @param parameters Calculation parameters, temperature limits, gradient limit + * @param outputSet Output dataset for the output temperature to fetch it with read() + * @param thermalModule Respective thermal module, if it has one + */ + TemperatureSensor(object_id_t setObjectid, lp_var_t *inputTemperature, + gp_id_t outputGpid, uint8_t vectorIndex, + Parameters parameters = {0, 0, 0, 0, 0, 0}, + LocalPoolDataSetBase *outputSet = nullptr, + ThermalModuleIF *thermalModule = nullptr) + : AbstractTemperatureSensor(setObjectid, thermalModule), + parameters(parameters), + inputTemperature(inputTemperature), + outputTemperature(outputGpid, outputSet, PoolVariableIF::VAR_WRITE), + sensorMonitor(setObjectid, DOMAIN_ID_SENSOR, outputGpid, DEFAULT_CONFIRMATION_COUNT, + parameters.lowerLimit, parameters.upperLimit, TEMP_SENSOR_LOW, + TEMP_SENSOR_HIGH), + oldTemperature(20), + uptimeOfOldTemperature({thermal::INVALID_TEMPERATURE, 0}) {} + protected: + /** + * This formula is used to calculate the temperature from an input value + * with an arbitrary type. + * A default implementation is provided but can be replaced depending + * on the required calculation. + * @param inputTemperature + * @return + */ + virtual float calculateOutputTemperature(inputType inputValue) { + return parameters.a * inputValue * inputValue + parameters.b * inputValue + parameters.c; + } -protected: - /** - * This formula is used to calculate the temperature from an input value - * with an arbitrary type. - * A default implementation is provided but can be replaced depending - * on the required calculation. - * @param inputTemperature - * @return - */ - virtual float calculateOutputTemperature(inputType inputValue) { - return parameters.a * inputValue * inputValue - + parameters.b * inputValue + parameters.c; - } + private: + void setInvalid() { + outputTemperature = thermal::INVALID_TEMPERATURE; + outputTemperature.setValid(false); + uptimeOfOldTemperature.tv_sec = INVALID_UPTIME; + sensorMonitor.setToInvalid(); + } + protected: + static const int32_t INVALID_UPTIME = 0; -private: - void setInvalid() { - outputTemperature = thermal::INVALID_TEMPERATURE; - outputTemperature.setValid(false); - uptimeOfOldTemperature.tv_sec = INVALID_UPTIME; - sensorMonitor.setToInvalid(); - } -protected: - static const int32_t INVALID_UPTIME = 0; + UsedParameters parameters; - UsedParameters parameters; + lp_var_t *inputTemperature; + lp_var_t outputTemperature; - lp_var_t* inputTemperature; - lp_var_t outputTemperature; + LimitMonitor sensorMonitor; - LimitMonitor sensorMonitor; + float oldTemperature; + timeval uptimeOfOldTemperature; - float oldTemperature; - timeval uptimeOfOldTemperature; + void doChildOperation() { + ReturnValue_t result = inputTemperature->read(MutexIF::TimeoutType::WAITING, 20); + if (result != HasReturnvaluesIF::RETURN_OK) { + return; + } - void doChildOperation() { - ReturnValue_t result = inputTemperature->read(MutexIF::TimeoutType::WAITING, 20); - if(result != HasReturnvaluesIF::RETURN_OK) { - return; - } + if ((not inputTemperature->isValid()) or + (not healthHelper.healthTable->isHealthy(getObjectId()))) { + setInvalid(); + return; + } - if ((not inputTemperature->isValid()) or - (not healthHelper.healthTable->isHealthy(getObjectId()))) { - setInvalid(); - return; - } + outputTemperature = calculateOutputTemperature(inputTemperature->value); + outputTemperature.setValid(PoolVariableIF::VALID); - outputTemperature = calculateOutputTemperature(inputTemperature->value); - outputTemperature.setValid(PoolVariableIF::VALID); + timeval uptime; + Clock::getUptime(&uptime); - timeval uptime; - Clock::getUptime(&uptime); + if (uptimeOfOldTemperature.tv_sec != INVALID_UPTIME) { + // In theory, we could use an AbsValueMonitor to monitor the gradient. + // But this would require storing the maxGradient in DP and quite some overhead. + // The concept of delta limits is a bit strange anyway. + float deltaTime; + float deltaTemp; - if (uptimeOfOldTemperature.tv_sec != INVALID_UPTIME) { - // In theory, we could use an AbsValueMonitor to monitor the gradient. - // But this would require storing the maxGradient in DP and quite some overhead. - // The concept of delta limits is a bit strange anyway. - float deltaTime; - float deltaTemp; + deltaTime = (uptime.tv_sec + uptime.tv_usec / 1000000.) - + (uptimeOfOldTemperature.tv_sec + uptimeOfOldTemperature.tv_usec / 1000000.); + deltaTemp = oldTemperature - outputTemperature; + if (deltaTemp < 0) { + deltaTemp = -deltaTemp; + } + if (parameters.gradient < deltaTemp / deltaTime) { + triggerEvent(TEMP_SENSOR_GRADIENT); + // Don't set invalid, as we did not recognize it as invalid with full authority, + // let FDIR handle it + } + } - deltaTime = (uptime.tv_sec + uptime.tv_usec / 1000000.) - - (uptimeOfOldTemperature.tv_sec - + uptimeOfOldTemperature.tv_usec / 1000000.); - deltaTemp = oldTemperature - outputTemperature; - if (deltaTemp < 0) { - deltaTemp = -deltaTemp; - } - if (parameters.gradient < deltaTemp / deltaTime) { - triggerEvent(TEMP_SENSOR_GRADIENT); - // Don't set invalid, as we did not recognize it as invalid with full authority, - // let FDIR handle it - } - } + sensorMonitor.doCheck(outputTemperature.value); - sensorMonitor.doCheck(outputTemperature.value); + if (sensorMonitor.isOutOfLimits()) { + uptimeOfOldTemperature.tv_sec = INVALID_UPTIME; + outputTemperature.setValid(PoolVariableIF::INVALID); + outputTemperature = thermal::INVALID_TEMPERATURE; + } else { + oldTemperature = outputTemperature; + uptimeOfOldTemperature = uptime; + } + } - if (sensorMonitor.isOutOfLimits()) { - uptimeOfOldTemperature.tv_sec = INVALID_UPTIME; - outputTemperature.setValid(PoolVariableIF::INVALID); - outputTemperature = thermal::INVALID_TEMPERATURE; - } else { - oldTemperature = outputTemperature; - uptimeOfOldTemperature = uptime; - } - } + public: + float getTemperature() { return outputTemperature; } -public: - float getTemperature() { - return outputTemperature; - } + bool isValid() { return outputTemperature.isValid(); } - bool isValid() { - return outputTemperature.isValid(); - } + static const uint16_t ADDRESS_A = 0; + static const uint16_t ADDRESS_B = 1; + static const uint16_t ADDRESS_C = 2; + static const uint16_t ADDRESS_GRADIENT = 3; - static const uint16_t ADDRESS_A = 0; - static const uint16_t ADDRESS_B = 1; - static const uint16_t ADDRESS_C = 2; - static const uint16_t ADDRESS_GRADIENT = 3; + //! Changed due to issue with later temperature checking even tough the sensor monitor was + //! confirming already (Was 10 before with comment = Correlates to a 10s confirmation time. + //! Chosen rather large, should not be so bad for components and helps survive glitches.) + static const uint16_t DEFAULT_CONFIRMATION_COUNT = 1; - //! Changed due to issue with later temperature checking even tough the sensor monitor was - //! confirming already (Was 10 before with comment = Correlates to a 10s confirmation time. - //! Chosen rather large, should not be so bad for components and helps survive glitches.) - static const uint16_t DEFAULT_CONFIRMATION_COUNT = 1; + static const uint8_t DOMAIN_ID_SENSOR = 1; - static const uint8_t DOMAIN_ID_SENSOR = 1; - - virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, - ParameterWrapper *parameterWrapper, - const ParameterWrapper *newValues, uint16_t startAtIndex) { - ReturnValue_t result = sensorMonitor.getParameter(domainId, uniqueId, - parameterWrapper, newValues, startAtIndex); - if (result != INVALID_DOMAIN_ID) { - return result; - } - if (domainId != this->DOMAIN_ID_BASE) { - return INVALID_DOMAIN_ID; - } - switch (uniqueId) { - case ADDRESS_A: - parameterWrapper->set(parameters.a); - break; - case ADDRESS_B: - parameterWrapper->set(parameters.b); - break; - case ADDRESS_C: - parameterWrapper->set(parameters.c); - break; - case ADDRESS_GRADIENT: - parameterWrapper->set(parameters.gradient); - break; - default: - return INVALID_IDENTIFIER_ID; - } - return HasReturnvaluesIF::RETURN_OK; - } - - virtual void resetOldState() { - sensorMonitor.setToUnchecked(); - } + virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, + ParameterWrapper *parameterWrapper, + const ParameterWrapper *newValues, uint16_t startAtIndex) { + ReturnValue_t result = + sensorMonitor.getParameter(domainId, uniqueId, parameterWrapper, newValues, startAtIndex); + if (result != INVALID_DOMAIN_ID) { + return result; + } + if (domainId != this->DOMAIN_ID_BASE) { + return INVALID_DOMAIN_ID; + } + switch (uniqueId) { + case ADDRESS_A: + parameterWrapper->set(parameters.a); + break; + case ADDRESS_B: + parameterWrapper->set(parameters.b); + break; + case ADDRESS_C: + parameterWrapper->set(parameters.c); + break; + case ADDRESS_GRADIENT: + parameterWrapper->set(parameters.gradient); + break; + default: + return INVALID_IDENTIFIER_ID; + } + return HasReturnvaluesIF::RETURN_OK; + } + virtual void resetOldState() { sensorMonitor.setToUnchecked(); } }; #endif /* FSFW_THERMAL_TEMPERATURESENSOR_H_ */ diff --git a/src/fsfw/thermal/ThermalComponent.cpp b/src/fsfw/thermal/ThermalComponent.cpp index 8d4b7bbd..000f2e19 100644 --- a/src/fsfw/thermal/ThermalComponent.cpp +++ b/src/fsfw/thermal/ThermalComponent.cpp @@ -1,169 +1,159 @@ #include "fsfw/thermal/ThermalComponent.h" -ThermalComponent::ThermalComponent(object_id_t reportingObjectId, - uint8_t domainId, gp_id_t temperaturePoolId, - gp_id_t targetStatePoolId, gp_id_t currentStatePoolId, - gp_id_t requestPoolId, LocalPoolDataSetBase* dataSet, - AbstractTemperatureSensor* sensor, - AbstractTemperatureSensor* firstRedundantSensor, - AbstractTemperatureSensor* secondRedundantSensor, - ThermalModuleIF* thermalModule, Parameters parameters, - Priority priority) : - ThermalComponentCore(reportingObjectId, domainId, temperaturePoolId, - targetStatePoolId, currentStatePoolId, requestPoolId, dataSet, - { parameters.lowerOpLimit, parameters.upperOpLimit, - parameters.heaterOn, parameters.hysteresis, - parameters.heaterSwitchoff }, - ThermalComponentIF::STATE_REQUEST_NON_OPERATIONAL), - nopParameters({ parameters.lowerNopLimit, parameters.upperNopLimit }) { -} +ThermalComponent::ThermalComponent(object_id_t reportingObjectId, uint8_t domainId, + gp_id_t temperaturePoolId, gp_id_t targetStatePoolId, + gp_id_t currentStatePoolId, gp_id_t requestPoolId, + LocalPoolDataSetBase* dataSet, AbstractTemperatureSensor* sensor, + AbstractTemperatureSensor* firstRedundantSensor, + AbstractTemperatureSensor* secondRedundantSensor, + ThermalModuleIF* thermalModule, Parameters parameters, + Priority priority) + : ThermalComponentCore(reportingObjectId, domainId, temperaturePoolId, targetStatePoolId, + currentStatePoolId, requestPoolId, dataSet, + {parameters.lowerOpLimit, parameters.upperOpLimit, parameters.heaterOn, + parameters.hysteresis, parameters.heaterSwitchoff}, + ThermalComponentIF::STATE_REQUEST_NON_OPERATIONAL), + nopParameters({parameters.lowerNopLimit, parameters.upperNopLimit}) {} -ThermalComponent::~ThermalComponent() { -} +ThermalComponent::~ThermalComponent() {} ReturnValue_t ThermalComponent::setTargetState(int8_t newState) { - targetState.setReadWriteMode(pool_rwm_t::VAR_READ_WRITE); - targetState.read(); - if ((targetState == STATE_REQUEST_OPERATIONAL) - and (newState != STATE_REQUEST_IGNORE)) { - return HasReturnvaluesIF::RETURN_FAILED; - } - switch (newState) { - case STATE_REQUEST_NON_OPERATIONAL: - targetState = newState; - targetState.setValid(true); - targetState.commit(PoolVariableIF::VALID); - return HasReturnvaluesIF::RETURN_OK; - default: - return ThermalComponentCore::setTargetState(newState); - } - return HasReturnvaluesIF::RETURN_OK; + targetState.setReadWriteMode(pool_rwm_t::VAR_READ_WRITE); + targetState.read(); + if ((targetState == STATE_REQUEST_OPERATIONAL) and (newState != STATE_REQUEST_IGNORE)) { + return HasReturnvaluesIF::RETURN_FAILED; + } + switch (newState) { + case STATE_REQUEST_NON_OPERATIONAL: + targetState = newState; + targetState.setValid(true); + targetState.commit(PoolVariableIF::VALID); + return HasReturnvaluesIF::RETURN_OK; + default: + return ThermalComponentCore::setTargetState(newState); + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t ThermalComponent::setLimits(const uint8_t* data, size_t size) { - if (size != 4 * sizeof(parameters.lowerOpLimit)) { - return MonitoringIF::INVALID_SIZE; - } - size_t readSize = size; - SerializeAdapter::deSerialize(&nopParameters.lowerNopLimit, &data, - &readSize, SerializeIF::Endianness::BIG); - SerializeAdapter::deSerialize(¶meters.lowerOpLimit, &data, - &readSize, SerializeIF::Endianness::BIG); - SerializeAdapter::deSerialize(¶meters.upperOpLimit, &data, - &readSize, SerializeIF::Endianness::BIG); - SerializeAdapter::deSerialize(&nopParameters.upperNopLimit, &data, - &readSize, SerializeIF::Endianness::BIG); - return HasReturnvaluesIF::RETURN_OK; + if (size != 4 * sizeof(parameters.lowerOpLimit)) { + return MonitoringIF::INVALID_SIZE; + } + size_t readSize = size; + SerializeAdapter::deSerialize(&nopParameters.lowerNopLimit, &data, &readSize, + SerializeIF::Endianness::BIG); + SerializeAdapter::deSerialize(¶meters.lowerOpLimit, &data, &readSize, + SerializeIF::Endianness::BIG); + SerializeAdapter::deSerialize(¶meters.upperOpLimit, &data, &readSize, + SerializeIF::Endianness::BIG); + SerializeAdapter::deSerialize(&nopParameters.upperNopLimit, &data, &readSize, + SerializeIF::Endianness::BIG); + return HasReturnvaluesIF::RETURN_OK; } ThermalComponentIF::State ThermalComponent::getState(float temperature, - ThermalComponentCore::Parameters parameters, int8_t targetState) { - if (temperature < nopParameters.lowerNopLimit) { - return OUT_OF_RANGE_LOW; - } else { - State state = ThermalComponentCore::getState(temperature, parameters, - targetState); - if (state != NON_OPERATIONAL_HIGH - && state != NON_OPERATIONAL_HIGH_IGNORED) { - return state; - } - if (temperature > nopParameters.upperNopLimit) { - state = OUT_OF_RANGE_HIGH; - } - if (targetState == STATE_REQUEST_IGNORE) { - state = getIgnoredState(state); - } - return state; - } + ThermalComponentCore::Parameters parameters, + int8_t targetState) { + if (temperature < nopParameters.lowerNopLimit) { + return OUT_OF_RANGE_LOW; + } else { + State state = ThermalComponentCore::getState(temperature, parameters, targetState); + if (state != NON_OPERATIONAL_HIGH && state != NON_OPERATIONAL_HIGH_IGNORED) { + return state; + } + if (temperature > nopParameters.upperNopLimit) { + state = OUT_OF_RANGE_HIGH; + } + if (targetState == STATE_REQUEST_IGNORE) { + state = getIgnoredState(state); + } + return state; + } } void ThermalComponent::checkLimits(ThermalComponentIF::State state) { - if ((targetState == STATE_REQUEST_OPERATIONAL) or - (targetState == STATE_REQUEST_IGNORE)) { - ThermalComponentCore::checkLimits(state); - return; - } - // If component is not operational, it checks the NOP limits. - temperatureMonitor.translateState(state, temperature.value, - nopParameters.lowerNopLimit, nopParameters.upperNopLimit, false); + if ((targetState == STATE_REQUEST_OPERATIONAL) or (targetState == STATE_REQUEST_IGNORE)) { + ThermalComponentCore::checkLimits(state); + return; + } + // If component is not operational, it checks the NOP limits. + temperatureMonitor.translateState(state, temperature.value, nopParameters.lowerNopLimit, + nopParameters.upperNopLimit, false); } ThermalComponentIF::HeaterRequest ThermalComponent::getHeaterRequest( - int8_t targetState, float temperature, - ThermalComponentCore::Parameters parameters) { - if (targetState == STATE_REQUEST_IGNORE) { - isHeating = false; - return HEATER_DONT_CARE; - } + int8_t targetState, float temperature, ThermalComponentCore::Parameters parameters) { + if (targetState == STATE_REQUEST_IGNORE) { + isHeating = false; + return HEATER_DONT_CARE; + } - if (temperature - > nopParameters.upperNopLimit - parameters.heaterSwitchoff) { - isHeating = false; - return HEATER_REQUEST_EMERGENCY_OFF; - } + if (temperature > nopParameters.upperNopLimit - parameters.heaterSwitchoff) { + isHeating = false; + return HEATER_REQUEST_EMERGENCY_OFF; + } - float nopHeaterLimit = nopParameters.lowerNopLimit + parameters.heaterOn; - float opHeaterLimit = parameters.lowerOpLimit + parameters.heaterOn; + float nopHeaterLimit = nopParameters.lowerNopLimit + parameters.heaterOn; + float opHeaterLimit = parameters.lowerOpLimit + parameters.heaterOn; - if (isHeating) { - nopHeaterLimit += parameters.hysteresis; - opHeaterLimit += parameters.hysteresis; - } + if (isHeating) { + nopHeaterLimit += parameters.hysteresis; + opHeaterLimit += parameters.hysteresis; + } - if (temperature < nopHeaterLimit) { - isHeating = true; - return HEATER_REQUEST_EMERGENCY_ON; - } + if (temperature < nopHeaterLimit) { + isHeating = true; + return HEATER_REQUEST_EMERGENCY_ON; + } - if ((targetState == STATE_REQUEST_OPERATIONAL) - || (targetState == STATE_REQUEST_HEATING)) { - if (temperature < opHeaterLimit) { - isHeating = true; - return HEATER_REQUEST_ON; - } - if (temperature - > parameters.upperOpLimit - parameters.heaterSwitchoff) { - isHeating = false; - return HEATER_REQUEST_OFF; - } - } + if ((targetState == STATE_REQUEST_OPERATIONAL) || (targetState == STATE_REQUEST_HEATING)) { + if (temperature < opHeaterLimit) { + isHeating = true; + return HEATER_REQUEST_ON; + } + if (temperature > parameters.upperOpLimit - parameters.heaterSwitchoff) { + isHeating = false; + return HEATER_REQUEST_OFF; + } + } - isHeating = false; - return HEATER_DONT_CARE; + isHeating = false; + return HEATER_DONT_CARE; } ThermalComponentIF::State ThermalComponent::getIgnoredState(int8_t state) { - switch (state) { - case OUT_OF_RANGE_LOW: - return OUT_OF_RANGE_LOW_IGNORED; - case OUT_OF_RANGE_HIGH: - return OUT_OF_RANGE_HIGH_IGNORED; - case OUT_OF_RANGE_LOW_IGNORED: - return OUT_OF_RANGE_LOW_IGNORED; - case OUT_OF_RANGE_HIGH_IGNORED: - return OUT_OF_RANGE_HIGH_IGNORED; - default: - return ThermalComponentCore::getIgnoredState(state); - } + switch (state) { + case OUT_OF_RANGE_LOW: + return OUT_OF_RANGE_LOW_IGNORED; + case OUT_OF_RANGE_HIGH: + return OUT_OF_RANGE_HIGH_IGNORED; + case OUT_OF_RANGE_LOW_IGNORED: + return OUT_OF_RANGE_LOW_IGNORED; + case OUT_OF_RANGE_HIGH_IGNORED: + return OUT_OF_RANGE_HIGH_IGNORED; + default: + return ThermalComponentCore::getIgnoredState(state); + } } -ReturnValue_t ThermalComponent::getParameter(uint8_t domainId, - uint8_t uniqueId, ParameterWrapper* parameterWrapper, - const ParameterWrapper* newValues, uint16_t startAtIndex) { - ReturnValue_t result = ThermalComponentCore::getParameter(domainId, uniqueId, - parameterWrapper, newValues, startAtIndex); - if (result != INVALID_IDENTIFIER_ID) { - return result; - } - switch (uniqueId) { - case 12: - parameterWrapper->set(nopParameters.lowerNopLimit); - break; - case 13: - parameterWrapper->set(nopParameters.upperNopLimit); - break; - default: - return INVALID_IDENTIFIER_ID; - } - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t ThermalComponent::getParameter(uint8_t domainId, uint8_t uniqueId, + ParameterWrapper* parameterWrapper, + const ParameterWrapper* newValues, + uint16_t startAtIndex) { + ReturnValue_t result = ThermalComponentCore::getParameter(domainId, uniqueId, parameterWrapper, + newValues, startAtIndex); + if (result != INVALID_IDENTIFIER_ID) { + return result; + } + switch (uniqueId) { + case 12: + parameterWrapper->set(nopParameters.lowerNopLimit); + break; + case 13: + parameterWrapper->set(nopParameters.upperNopLimit); + break; + default: + return INVALID_IDENTIFIER_ID; + } + return HasReturnvaluesIF::RETURN_OK; } diff --git a/src/fsfw/thermal/ThermalComponent.h b/src/fsfw/thermal/ThermalComponent.h index 3b6dd9cd..3c53be64 100644 --- a/src/fsfw/thermal/ThermalComponent.h +++ b/src/fsfw/thermal/ThermalComponent.h @@ -8,73 +8,70 @@ * @details * Some more documentation. */ -class ThermalComponent: public ThermalComponentCore { -public: - struct Parameters { - float lowerNopLimit; - float lowerOpLimit; - float upperOpLimit; - float upperNopLimit; - float heaterOn; - float hysteresis; - float heaterSwitchoff; - }; +class ThermalComponent : public ThermalComponentCore { + public: + struct Parameters { + float lowerNopLimit; + float lowerOpLimit; + float upperOpLimit; + float upperNopLimit; + float heaterOn; + float hysteresis; + float heaterSwitchoff; + }; - /** - * Non-Operational Temperatures - */ - struct NopParameters { - float lowerNopLimit; - float upperNopLimit; - }; + /** + * Non-Operational Temperatures + */ + struct NopParameters { + float lowerNopLimit; + float upperNopLimit; + }; - /** - * How to use. - * @param reportingObjectId - * @param domainId - * @param temperaturePoolId - * @param targetStatePoolId - * @param currentStatePoolId - * @param requestPoolId - * @param dataSet - * @param sensor - * @param firstRedundantSensor - * @param secondRedundantSensor - * @param thermalModule - * @param parameters - * @param priority - */ - ThermalComponent(object_id_t reportingObjectId, uint8_t domainId, - gp_id_t temperaturePoolId, gp_id_t targetStatePoolId, - gp_id_t currentStatePoolId, gp_id_t requestPoolId, - LocalPoolDataSetBase *dataSet, AbstractTemperatureSensor *sensor, - AbstractTemperatureSensor *firstRedundantSensor, - AbstractTemperatureSensor *secondRedundantSensor, - ThermalModuleIF *thermalModule, Parameters parameters, - Priority priority); - virtual ~ThermalComponent(); + /** + * How to use. + * @param reportingObjectId + * @param domainId + * @param temperaturePoolId + * @param targetStatePoolId + * @param currentStatePoolId + * @param requestPoolId + * @param dataSet + * @param sensor + * @param firstRedundantSensor + * @param secondRedundantSensor + * @param thermalModule + * @param parameters + * @param priority + */ + ThermalComponent(object_id_t reportingObjectId, uint8_t domainId, gp_id_t temperaturePoolId, + gp_id_t targetStatePoolId, gp_id_t currentStatePoolId, gp_id_t requestPoolId, + LocalPoolDataSetBase *dataSet, AbstractTemperatureSensor *sensor, + AbstractTemperatureSensor *firstRedundantSensor, + AbstractTemperatureSensor *secondRedundantSensor, ThermalModuleIF *thermalModule, + Parameters parameters, Priority priority); + virtual ~ThermalComponent(); - ReturnValue_t setTargetState(int8_t newState); + ReturnValue_t setTargetState(int8_t newState); - virtual ReturnValue_t setLimits( const uint8_t* data, size_t size); + virtual ReturnValue_t setLimits(const uint8_t *data, size_t size); - virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, - ParameterWrapper *parameterWrapper, - const ParameterWrapper *newValues, uint16_t startAtIndex); + virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, + ParameterWrapper *parameterWrapper, + const ParameterWrapper *newValues, uint16_t startAtIndex); -protected: + protected: + NopParameters nopParameters; - NopParameters nopParameters; + State getState(float temperature, ThermalComponentCore::Parameters parameters, + int8_t targetState); - State getState(float temperature, ThermalComponentCore::Parameters parameters, - int8_t targetState); + virtual void checkLimits(State state); - virtual void checkLimits(State state); + virtual HeaterRequest getHeaterRequest(int8_t targetState, float temperature, + ThermalComponentCore::Parameters parameters); - virtual HeaterRequest getHeaterRequest(int8_t targetState, float temperature, - ThermalComponentCore::Parameters parameters); - - State getIgnoredState(int8_t state); + State getIgnoredState(int8_t state); }; #endif /* FSFW_THERMAL_THERMALCOMPONENT_H_ */ diff --git a/src/fsfw/thermal/ThermalComponentCore.cpp b/src/fsfw/thermal/ThermalComponentCore.cpp index 7718ac36..887c30f2 100644 --- a/src/fsfw/thermal/ThermalComponentCore.cpp +++ b/src/fsfw/thermal/ThermalComponentCore.cpp @@ -1,286 +1,271 @@ #include "fsfw/thermal/ThermalComponentCore.h" + #include "fsfw/thermal/tcsDefinitions.h" -ThermalComponentCore::ThermalComponentCore(object_id_t reportingObjectId, - uint8_t domainId, gp_id_t temperaturePoolId, - gp_id_t targetStatePoolId, gp_id_t currentStatePoolId, - gp_id_t requestPoolId, LocalPoolDataSetBase* dataSet, - Parameters parameters, StateRequest initialTargetState) : - temperature(temperaturePoolId, dataSet, PoolVariableIF::VAR_WRITE), - targetState(targetStatePoolId, dataSet, PoolVariableIF::VAR_READ), - currentState(currentStatePoolId, dataSet, PoolVariableIF::VAR_WRITE), - heaterRequest(requestPoolId, dataSet, PoolVariableIF::VAR_WRITE), - parameters(parameters), domainId(domainId), - temperatureMonitor(reportingObjectId, domainId + 1,temperaturePoolId, - COMPONENT_TEMP_CONFIRMATION) { - //Set thermal state once, then leave to operator. - targetState.setReadWriteMode(PoolVariableIF::VAR_WRITE); - ReturnValue_t result = targetState.read(); - if(result == HasReturnvaluesIF::RETURN_OK) { - targetState = initialTargetState; - targetState.setValid(true); - targetState.commit(); - } - targetState.setReadWriteMode(PoolVariableIF::VAR_READ); +ThermalComponentCore::ThermalComponentCore(object_id_t reportingObjectId, uint8_t domainId, + gp_id_t temperaturePoolId, gp_id_t targetStatePoolId, + gp_id_t currentStatePoolId, gp_id_t requestPoolId, + LocalPoolDataSetBase* dataSet, Parameters parameters, + StateRequest initialTargetState) + : temperature(temperaturePoolId, dataSet, PoolVariableIF::VAR_WRITE), + targetState(targetStatePoolId, dataSet, PoolVariableIF::VAR_READ), + currentState(currentStatePoolId, dataSet, PoolVariableIF::VAR_WRITE), + heaterRequest(requestPoolId, dataSet, PoolVariableIF::VAR_WRITE), + parameters(parameters), + domainId(domainId), + temperatureMonitor(reportingObjectId, domainId + 1, temperaturePoolId, + COMPONENT_TEMP_CONFIRMATION) { + // Set thermal state once, then leave to operator. + targetState.setReadWriteMode(PoolVariableIF::VAR_WRITE); + ReturnValue_t result = targetState.read(); + if (result == HasReturnvaluesIF::RETURN_OK) { + targetState = initialTargetState; + targetState.setValid(true); + targetState.commit(); + } + targetState.setReadWriteMode(PoolVariableIF::VAR_READ); } -void ThermalComponentCore::addSensor(AbstractTemperatureSensor* sensor) { - this->sensor = sensor; -} +void ThermalComponentCore::addSensor(AbstractTemperatureSensor* sensor) { this->sensor = sensor; } void ThermalComponentCore::addFirstRedundantSensor( - AbstractTemperatureSensor *firstRedundantSensor) { - this->firstRedundantSensor = firstRedundantSensor; + AbstractTemperatureSensor* firstRedundantSensor) { + this->firstRedundantSensor = firstRedundantSensor; } void ThermalComponentCore::addSecondRedundantSensor( - AbstractTemperatureSensor *secondRedundantSensor) { - this->secondRedundantSensor = secondRedundantSensor; + AbstractTemperatureSensor* secondRedundantSensor) { + this->secondRedundantSensor = secondRedundantSensor; } -void ThermalComponentCore::addThermalModule(ThermalModule *thermalModule, - Priority priority) { - this->thermalModule = thermalModule; - if(thermalModule != nullptr) { - thermalModule->registerComponent(this, priority); - } +void ThermalComponentCore::addThermalModule(ThermalModule* thermalModule, Priority priority) { + this->thermalModule = thermalModule; + if (thermalModule != nullptr) { + thermalModule->registerComponent(this, priority); + } } void ThermalComponentCore::setPriority(Priority priority) { - if(priority == SAFE) { - this->isSafeComponent = true; - } + if (priority == SAFE) { + this->isSafeComponent = true; + } } -ThermalComponentCore::~ThermalComponentCore() { -} +ThermalComponentCore::~ThermalComponentCore() {} -ThermalComponentIF::HeaterRequest ThermalComponentCore::performOperation( - uint8_t opCode) { - HeaterRequest request = HEATER_DONT_CARE; - //SHOULDDO: Better pass db_float_t* to getTemperature and set it invalid if invalid. - temperature = getTemperature(); - updateMinMaxTemp(); - if (temperature != thermal::INVALID_TEMPERATURE) { - temperature.setValid(PoolVariableIF::VALID); - State state = getState(temperature.value, getParameters(), - targetState.value); - currentState = state; - checkLimits(state); - request = getHeaterRequest(targetState.value, temperature.value, - getParameters()); - } else { - temperatureMonitor.setToInvalid(); - temperature.setValid(PoolVariableIF::INVALID); - currentState = UNKNOWN; - request = HEATER_DONT_CARE; - } - currentState.setValid(PoolVariableIF::VALID); - heaterRequest = request; - heaterRequest.setValid(PoolVariableIF::VALID); - return request; +ThermalComponentIF::HeaterRequest ThermalComponentCore::performOperation(uint8_t opCode) { + HeaterRequest request = HEATER_DONT_CARE; + // SHOULDDO: Better pass db_float_t* to getTemperature and set it invalid if invalid. + temperature = getTemperature(); + updateMinMaxTemp(); + if (temperature != thermal::INVALID_TEMPERATURE) { + temperature.setValid(PoolVariableIF::VALID); + State state = getState(temperature.value, getParameters(), targetState.value); + currentState = state; + checkLimits(state); + request = getHeaterRequest(targetState.value, temperature.value, getParameters()); + } else { + temperatureMonitor.setToInvalid(); + temperature.setValid(PoolVariableIF::INVALID); + currentState = UNKNOWN; + request = HEATER_DONT_CARE; + } + currentState.setValid(PoolVariableIF::VALID); + heaterRequest = request; + heaterRequest.setValid(PoolVariableIF::VALID); + return request; } void ThermalComponentCore::markStateIgnored() { - currentState = getIgnoredState(currentState.value); + currentState = getIgnoredState(currentState.value); } object_id_t ThermalComponentCore::getObjectId() { - return temperatureMonitor.getReporterId(); - return 0; + return temperatureMonitor.getReporterId(); + return 0; } -float ThermalComponentCore::getLowerOpLimit() { - return parameters.lowerOpLimit; -} - - +float ThermalComponentCore::getLowerOpLimit() { return parameters.lowerOpLimit; } ReturnValue_t ThermalComponentCore::setTargetState(int8_t newState) { - targetState.setReadWriteMode(pool_rwm_t::VAR_READ_WRITE); - targetState.read(); - if((targetState == STATE_REQUEST_OPERATIONAL) and - (newState != STATE_REQUEST_IGNORE)) { - return HasReturnvaluesIF::RETURN_FAILED; - } + targetState.setReadWriteMode(pool_rwm_t::VAR_READ_WRITE); + targetState.read(); + if ((targetState == STATE_REQUEST_OPERATIONAL) and (newState != STATE_REQUEST_IGNORE)) { + return HasReturnvaluesIF::RETURN_FAILED; + } - switch (newState) { - case STATE_REQUEST_HEATING: - case STATE_REQUEST_IGNORE: - case STATE_REQUEST_OPERATIONAL: - targetState = newState; - break; - case STATE_REQUEST_NON_OPERATIONAL: - default: - return INVALID_TARGET_STATE; - } - targetState.setValid(true); - targetState.commit(); - return HasReturnvaluesIF::RETURN_OK; + switch (newState) { + case STATE_REQUEST_HEATING: + case STATE_REQUEST_IGNORE: + case STATE_REQUEST_OPERATIONAL: + targetState = newState; + break; + case STATE_REQUEST_NON_OPERATIONAL: + default: + return INVALID_TARGET_STATE; + } + targetState.setValid(true); + targetState.commit(); + return HasReturnvaluesIF::RETURN_OK; } void ThermalComponentCore::setOutputInvalid() { - temperature = thermal::INVALID_TEMPERATURE; - temperature.setValid(PoolVariableIF::INVALID); - currentState.setValid(PoolVariableIF::INVALID); - heaterRequest = HEATER_DONT_CARE; - heaterRequest.setValid(PoolVariableIF::INVALID); - temperatureMonitor.setToUnchecked(); + temperature = thermal::INVALID_TEMPERATURE; + temperature.setValid(PoolVariableIF::INVALID); + currentState.setValid(PoolVariableIF::INVALID); + heaterRequest = HEATER_DONT_CARE; + heaterRequest.setValid(PoolVariableIF::INVALID); + temperatureMonitor.setToUnchecked(); } float ThermalComponentCore::getTemperature() { - if ((sensor != nullptr) && (sensor->isValid())) { - return sensor->getTemperature(); - } + if ((sensor != nullptr) && (sensor->isValid())) { + return sensor->getTemperature(); + } - if ((firstRedundantSensor != nullptr) && - (firstRedundantSensor->isValid())) { - return firstRedundantSensor->getTemperature(); - } + if ((firstRedundantSensor != nullptr) && (firstRedundantSensor->isValid())) { + return firstRedundantSensor->getTemperature(); + } - if ((secondRedundantSensor != nullptr) && - (secondRedundantSensor->isValid())) { - return secondRedundantSensor->getTemperature(); - } + if ((secondRedundantSensor != nullptr) && (secondRedundantSensor->isValid())) { + return secondRedundantSensor->getTemperature(); + } - if (thermalModule != nullptr) { - float temperature = thermalModule->getTemperature(); - if (temperature != thermal::INVALID_TEMPERATURE) { - return temperature; - } else { - return thermal::INVALID_TEMPERATURE; - } - } else { - return thermal::INVALID_TEMPERATURE; - } + if (thermalModule != nullptr) { + float temperature = thermalModule->getTemperature(); + if (temperature != thermal::INVALID_TEMPERATURE) { + return temperature; + } else { + return thermal::INVALID_TEMPERATURE; + } + } else { + return thermal::INVALID_TEMPERATURE; + } } -ThermalComponentIF::State ThermalComponentCore::getState(float temperature, - Parameters parameters, int8_t targetState) { - ThermalComponentIF::State state; +ThermalComponentIF::State ThermalComponentCore::getState(float temperature, Parameters parameters, + int8_t targetState) { + ThermalComponentIF::State state; - if (temperature < parameters.lowerOpLimit) { - state = NON_OPERATIONAL_LOW; - } else if (temperature < parameters.upperOpLimit) { - state = OPERATIONAL; - } else { - state = NON_OPERATIONAL_HIGH; - } - if (targetState == STATE_REQUEST_IGNORE) { - state = getIgnoredState(state); - } + if (temperature < parameters.lowerOpLimit) { + state = NON_OPERATIONAL_LOW; + } else if (temperature < parameters.upperOpLimit) { + state = OPERATIONAL; + } else { + state = NON_OPERATIONAL_HIGH; + } + if (targetState == STATE_REQUEST_IGNORE) { + state = getIgnoredState(state); + } - return state; + return state; } void ThermalComponentCore::checkLimits(ThermalComponentIF::State state) { - //Checks operational limits only. - temperatureMonitor.translateState(state, temperature.value, - getParameters().lowerOpLimit, getParameters().upperOpLimit); - + // Checks operational limits only. + temperatureMonitor.translateState(state, temperature.value, getParameters().lowerOpLimit, + getParameters().upperOpLimit); } -ThermalComponentIF::HeaterRequest ThermalComponentCore::getHeaterRequest( - int8_t targetState, float temperature, Parameters parameters) { - if (targetState == STATE_REQUEST_IGNORE) { - isHeating = false; - return HEATER_DONT_CARE; - } +ThermalComponentIF::HeaterRequest ThermalComponentCore::getHeaterRequest(int8_t targetState, + float temperature, + Parameters parameters) { + if (targetState == STATE_REQUEST_IGNORE) { + isHeating = false; + return HEATER_DONT_CARE; + } - if (temperature > parameters.upperOpLimit - parameters.heaterSwitchoff) { - isHeating = false; - return HEATER_REQUEST_EMERGENCY_OFF; - } + if (temperature > parameters.upperOpLimit - parameters.heaterSwitchoff) { + isHeating = false; + return HEATER_REQUEST_EMERGENCY_OFF; + } - float opHeaterLimit = parameters.lowerOpLimit + parameters.heaterOn; + float opHeaterLimit = parameters.lowerOpLimit + parameters.heaterOn; - if (isHeating) { - opHeaterLimit += parameters.hysteresis; - } + if (isHeating) { + opHeaterLimit += parameters.hysteresis; + } - if (temperature < opHeaterLimit) { - isHeating = true; - return HEATER_REQUEST_EMERGENCY_ON; - } - isHeating = false; - return HEATER_DONT_CARE; + if (temperature < opHeaterLimit) { + isHeating = true; + return HEATER_REQUEST_EMERGENCY_ON; + } + isHeating = false; + return HEATER_DONT_CARE; } ThermalComponentIF::State ThermalComponentCore::getIgnoredState(int8_t state) { - switch (state) { - case NON_OPERATIONAL_LOW: - return NON_OPERATIONAL_LOW_IGNORED; - case OPERATIONAL: - return OPERATIONAL_IGNORED; - case NON_OPERATIONAL_HIGH: - return NON_OPERATIONAL_HIGH_IGNORED; - case NON_OPERATIONAL_LOW_IGNORED: - return NON_OPERATIONAL_LOW_IGNORED; - case OPERATIONAL_IGNORED: - return OPERATIONAL_IGNORED; - case NON_OPERATIONAL_HIGH_IGNORED: - return NON_OPERATIONAL_HIGH_IGNORED; - default: - case UNKNOWN: - return UNKNOWN; - } + switch (state) { + case NON_OPERATIONAL_LOW: + return NON_OPERATIONAL_LOW_IGNORED; + case OPERATIONAL: + return OPERATIONAL_IGNORED; + case NON_OPERATIONAL_HIGH: + return NON_OPERATIONAL_HIGH_IGNORED; + case NON_OPERATIONAL_LOW_IGNORED: + return NON_OPERATIONAL_LOW_IGNORED; + case OPERATIONAL_IGNORED: + return OPERATIONAL_IGNORED; + case NON_OPERATIONAL_HIGH_IGNORED: + return NON_OPERATIONAL_HIGH_IGNORED; + default: + case UNKNOWN: + return UNKNOWN; + } } void ThermalComponentCore::updateMinMaxTemp() { - if (temperature == thermal::INVALID_TEMPERATURE) { - return; - } - if (temperature < minTemp) { - minTemp = static_cast(temperature); - } - if (temperature > maxTemp) { - maxTemp = static_cast(temperature); - } + if (temperature == thermal::INVALID_TEMPERATURE) { + return; + } + if (temperature < minTemp) { + minTemp = static_cast(temperature); + } + if (temperature > maxTemp) { + maxTemp = static_cast(temperature); + } } -uint8_t ThermalComponentCore::getDomainId() const { - return domainId; -} +uint8_t ThermalComponentCore::getDomainId() const { return domainId; } -ThermalComponentCore::Parameters ThermalComponentCore::getParameters() { - return parameters; -} +ThermalComponentCore::Parameters ThermalComponentCore::getParameters() { return parameters; } -ReturnValue_t ThermalComponentCore::getParameter(uint8_t domainId, - uint8_t uniqueId, ParameterWrapper* parameterWrapper, - const ParameterWrapper* newValues, uint16_t startAtIndex) { - ReturnValue_t result = temperatureMonitor.getParameter(domainId, - uniqueId, parameterWrapper, newValues, startAtIndex); - if (result != INVALID_DOMAIN_ID) { - return result; - } - if (domainId != this->domainId) { - return INVALID_DOMAIN_ID; - } - switch (uniqueId) { - case 0: - parameterWrapper->set(parameters.heaterOn); - break; - case 1: - parameterWrapper->set(parameters.hysteresis); - break; - case 2: - parameterWrapper->set(parameters.heaterSwitchoff); - break; - case 3: - parameterWrapper->set(minTemp); - break; - case 4: - parameterWrapper->set(maxTemp); - break; - case 10: - parameterWrapper->set(parameters.lowerOpLimit); - break; - case 11: - parameterWrapper->set(parameters.upperOpLimit); - break; - default: - return INVALID_IDENTIFIER_ID; - } - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t ThermalComponentCore::getParameter(uint8_t domainId, uint8_t uniqueId, + ParameterWrapper* parameterWrapper, + const ParameterWrapper* newValues, + uint16_t startAtIndex) { + ReturnValue_t result = temperatureMonitor.getParameter(domainId, uniqueId, parameterWrapper, + newValues, startAtIndex); + if (result != INVALID_DOMAIN_ID) { + return result; + } + if (domainId != this->domainId) { + return INVALID_DOMAIN_ID; + } + switch (uniqueId) { + case 0: + parameterWrapper->set(parameters.heaterOn); + break; + case 1: + parameterWrapper->set(parameters.hysteresis); + break; + case 2: + parameterWrapper->set(parameters.heaterSwitchoff); + break; + case 3: + parameterWrapper->set(minTemp); + break; + case 4: + parameterWrapper->set(maxTemp); + break; + case 10: + parameterWrapper->set(parameters.lowerOpLimit); + break; + case 11: + parameterWrapper->set(parameters.upperOpLimit); + break; + default: + return INVALID_IDENTIFIER_ID; + } + return HasReturnvaluesIF::RETURN_OK; } diff --git a/src/fsfw/thermal/ThermalComponentCore.h b/src/fsfw/thermal/ThermalComponentCore.h index 19430015..dcc6064b 100644 --- a/src/fsfw/thermal/ThermalComponentCore.h +++ b/src/fsfw/thermal/ThermalComponentCore.h @@ -1,117 +1,111 @@ #ifndef FSFW_THERMAL_THERMALCOMPONENTCORE_H_ #define FSFW_THERMAL_THERMALCOMPONENTCORE_H_ -#include "ThermalMonitorReporter.h" -#include "ThermalComponentIF.h" #include "AbstractTemperatureSensor.h" +#include "ThermalComponentIF.h" #include "ThermalModule.h" - +#include "ThermalMonitorReporter.h" #include "fsfw/datapoollocal/LocalPoolVariable.h" /** * @brief * @details */ -class ThermalComponentCore: public ThermalComponentIF { -public: - struct Parameters { - float lowerOpLimit; - float upperOpLimit; - float heaterOn; - float hysteresis; - float heaterSwitchoff; - }; +class ThermalComponentCore : public ThermalComponentIF { + public: + struct Parameters { + float lowerOpLimit; + float upperOpLimit; + float heaterOn; + float hysteresis; + float heaterSwitchoff; + }; - static const uint16_t COMPONENT_TEMP_CONFIRMATION = 5; + static const uint16_t COMPONENT_TEMP_CONFIRMATION = 5; - /** - * Some documentation - * @param reportingObjectId - * @param domainId - * @param temperaturePoolId - * @param targetStatePoolId - * @param currentStatePoolId - * @param requestPoolId - * @param dataSet - * @param parameters - * @param initialTargetState - */ - ThermalComponentCore(object_id_t reportingObjectId, uint8_t domainId, - gp_id_t temperaturePoolId, gp_id_t targetStatePoolId, - gp_id_t currentStatePoolId, gp_id_t requestPoolId, - LocalPoolDataSetBase* dataSet, Parameters parameters, - StateRequest initialTargetState = - ThermalComponentIF::STATE_REQUEST_OPERATIONAL); + /** + * Some documentation + * @param reportingObjectId + * @param domainId + * @param temperaturePoolId + * @param targetStatePoolId + * @param currentStatePoolId + * @param requestPoolId + * @param dataSet + * @param parameters + * @param initialTargetState + */ + ThermalComponentCore( + object_id_t reportingObjectId, uint8_t domainId, gp_id_t temperaturePoolId, + gp_id_t targetStatePoolId, gp_id_t currentStatePoolId, gp_id_t requestPoolId, + LocalPoolDataSetBase *dataSet, Parameters parameters, + StateRequest initialTargetState = ThermalComponentIF::STATE_REQUEST_OPERATIONAL); - void addSensor(AbstractTemperatureSensor* firstRedundantSensor); - void addFirstRedundantSensor( - AbstractTemperatureSensor* firstRedundantSensor); - void addSecondRedundantSensor( - AbstractTemperatureSensor* secondRedundantSensor); - void addThermalModule(ThermalModule* thermalModule, Priority priority); + void addSensor(AbstractTemperatureSensor *firstRedundantSensor); + void addFirstRedundantSensor(AbstractTemperatureSensor *firstRedundantSensor); + void addSecondRedundantSensor(AbstractTemperatureSensor *secondRedundantSensor); + void addThermalModule(ThermalModule *thermalModule, Priority priority); - void setPriority(Priority priority); + void setPriority(Priority priority); - virtual ~ThermalComponentCore(); + virtual ~ThermalComponentCore(); - virtual HeaterRequest performOperation(uint8_t opCode); + virtual HeaterRequest performOperation(uint8_t opCode); - void markStateIgnored(); + void markStateIgnored(); - object_id_t getObjectId(); + object_id_t getObjectId(); - uint8_t getDomainId() const; + uint8_t getDomainId() const; - virtual float getLowerOpLimit(); + virtual float getLowerOpLimit(); - ReturnValue_t setTargetState(int8_t newState); + ReturnValue_t setTargetState(int8_t newState); - virtual void setOutputInvalid(); + virtual void setOutputInvalid(); - virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, - ParameterWrapper *parameterWrapper, - const ParameterWrapper *newValues, uint16_t startAtIndex); + virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, + ParameterWrapper *parameterWrapper, + const ParameterWrapper *newValues, uint16_t startAtIndex); -protected: + protected: + AbstractTemperatureSensor *sensor = nullptr; + AbstractTemperatureSensor *firstRedundantSensor = nullptr; + AbstractTemperatureSensor *secondRedundantSensor = nullptr; + ThermalModuleIF *thermalModule = nullptr; - AbstractTemperatureSensor *sensor = nullptr; - AbstractTemperatureSensor *firstRedundantSensor = nullptr; - AbstractTemperatureSensor *secondRedundantSensor = nullptr; - ThermalModuleIF *thermalModule = nullptr; + lp_var_t temperature; + lp_var_t targetState; + lp_var_t currentState; + lp_var_t heaterRequest; - lp_var_t temperature; - lp_var_t targetState; - lp_var_t currentState; - lp_var_t heaterRequest; + bool isHeating = false; - bool isHeating = false; + bool isSafeComponent = false; - bool isSafeComponent = false; + float minTemp = 999; - float minTemp = 999; + float maxTemp = AbstractTemperatureSensor::ZERO_KELVIN_C; - float maxTemp = AbstractTemperatureSensor::ZERO_KELVIN_C; + Parameters parameters; - Parameters parameters; + const uint8_t domainId; - const uint8_t domainId; + ThermalMonitorReporter temperatureMonitor; - ThermalMonitorReporter temperatureMonitor; + virtual float getTemperature(); + virtual State getState(float temperature, Parameters parameters, int8_t targetState); - virtual float getTemperature(); - virtual State getState(float temperature, Parameters parameters, - int8_t targetState); + virtual void checkLimits(State state); - virtual void checkLimits(State state); + virtual HeaterRequest getHeaterRequest(int8_t targetState, float temperature, + Parameters parameters); - virtual HeaterRequest getHeaterRequest(int8_t targetState, - float temperature, Parameters parameters); + virtual State getIgnoredState(int8_t state); - virtual State getIgnoredState(int8_t state); + void updateMinMaxTemp(); - void updateMinMaxTemp(); - - virtual Parameters getParameters(); + virtual Parameters getParameters(); }; #endif /* FSFW_THERMAL_THERMALCOMPONENT_CORE_H_ */ diff --git a/src/fsfw/thermal/ThermalComponentIF.h b/src/fsfw/thermal/ThermalComponentIF.h index 89c2b2d0..0c50fbad 100644 --- a/src/fsfw/thermal/ThermalComponentIF.h +++ b/src/fsfw/thermal/ThermalComponentIF.h @@ -2,113 +2,109 @@ #define THERMALCOMPONENTIF_H_ #include "../events/Event.h" +#include "../objectmanager/SystemObjectIF.h" #include "../parameters/HasParametersIF.h" #include "../returnvalues/HasReturnvaluesIF.h" -#include "../objectmanager/SystemObjectIF.h" class ThermalComponentIF : public HasParametersIF { -public: + public: + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::TCS_1; + static const Event COMPONENT_TEMP_LOW = MAKE_EVENT(1, severity::LOW); + static const Event COMPONENT_TEMP_HIGH = MAKE_EVENT(2, severity::LOW); + static const Event COMPONENT_TEMP_OOL_LOW = MAKE_EVENT(3, severity::LOW); + static const Event COMPONENT_TEMP_OOL_HIGH = MAKE_EVENT(4, severity::LOW); + static const Event TEMP_NOT_IN_OP_RANGE = MAKE_EVENT( + 5, severity::LOW); //!< Is thrown when a device should start-up, but the temperature is out + //!< of OP range. P1: thermalState of the component, P2: 0 - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::TCS_1; - static const Event COMPONENT_TEMP_LOW = MAKE_EVENT(1, severity::LOW); - static const Event COMPONENT_TEMP_HIGH = MAKE_EVENT(2, severity::LOW); - static const Event COMPONENT_TEMP_OOL_LOW = MAKE_EVENT(3, severity::LOW); - static const Event COMPONENT_TEMP_OOL_HIGH = MAKE_EVENT(4, severity::LOW); - static const Event TEMP_NOT_IN_OP_RANGE = MAKE_EVENT(5, severity::LOW); //!< Is thrown when a device should start-up, but the temperature is out of OP range. P1: thermalState of the component, P2: 0 + static const uint8_t INTERFACE_ID = CLASS_ID::THERMAL_COMPONENT_IF; + static const ReturnValue_t INVALID_TARGET_STATE = MAKE_RETURN_CODE(1); + static const ReturnValue_t ABOVE_OPERATIONAL_LIMIT = MAKE_RETURN_CODE(0xF1); + static const ReturnValue_t BELOW_OPERATIONAL_LIMIT = MAKE_RETURN_CODE(0xF2); - static const uint8_t INTERFACE_ID = CLASS_ID::THERMAL_COMPONENT_IF; - static const ReturnValue_t INVALID_TARGET_STATE = MAKE_RETURN_CODE(1); - static const ReturnValue_t ABOVE_OPERATIONAL_LIMIT = MAKE_RETURN_CODE(0xF1); - static const ReturnValue_t BELOW_OPERATIONAL_LIMIT = MAKE_RETURN_CODE(0xF2); + enum State { + OUT_OF_RANGE_LOW = -2, + NON_OPERATIONAL_LOW = -1, + OPERATIONAL = 0, + NON_OPERATIONAL_HIGH = 1, + OUT_OF_RANGE_HIGH = 2, + OUT_OF_RANGE_LOW_IGNORED = OUT_OF_RANGE_LOW - 10, + NON_OPERATIONAL_LOW_IGNORED = NON_OPERATIONAL_LOW - 10, + OPERATIONAL_IGNORED = OPERATIONAL + 10, + NON_OPERATIONAL_HIGH_IGNORED = NON_OPERATIONAL_HIGH + 10, + OUT_OF_RANGE_HIGH_IGNORED = OUT_OF_RANGE_HIGH + 10, + UNKNOWN = 20 + }; - enum State { - OUT_OF_RANGE_LOW = -2, - NON_OPERATIONAL_LOW = -1, - OPERATIONAL = 0, - NON_OPERATIONAL_HIGH = 1, - OUT_OF_RANGE_HIGH = 2, - OUT_OF_RANGE_LOW_IGNORED = OUT_OF_RANGE_LOW - 10, - NON_OPERATIONAL_LOW_IGNORED = NON_OPERATIONAL_LOW - 10, - OPERATIONAL_IGNORED = OPERATIONAL + 10, - NON_OPERATIONAL_HIGH_IGNORED = NON_OPERATIONAL_HIGH + 10, - OUT_OF_RANGE_HIGH_IGNORED = OUT_OF_RANGE_HIGH + 10, - UNKNOWN = 20 - }; + enum StateRequest { + STATE_REQUEST_HEATING = 4, + STATE_REQUEST_IGNORE = 3, + STATE_REQUEST_OPERATIONAL = 1, + STATE_REQUEST_NON_OPERATIONAL = 0 + }; - enum StateRequest { - STATE_REQUEST_HEATING = 4, - STATE_REQUEST_IGNORE = 3, - STATE_REQUEST_OPERATIONAL = 1, - STATE_REQUEST_NON_OPERATIONAL = 0 - }; + /** + * The elements are ordered by priority, lowest have highest priority + */ + enum Priority { + SAFE = 0, //!< SAFE + IDLE, //!< IDLE + PAYLOAD, //!< PAYLOAD + NUMBER_OF_PRIORITIES //!< MAX_PRIORITY + }; - /** - * The elements are ordered by priority, lowest have highest priority - */ - enum Priority { - SAFE = 0, //!< SAFE - IDLE, //!< IDLE - PAYLOAD, //!< PAYLOAD - NUMBER_OF_PRIORITIES //!< MAX_PRIORITY - }; + /** + * The elements are ordered by priority, lowest have highest priority + */ + enum HeaterRequest { + HEATER_REQUEST_EMERGENCY_OFF = 0, //!< REQUEST_EMERGENCY_OFF + HEATER_REQUEST_EMERGENCY_ON, //!< REQUEST_EMERGENCY_ON + HEATER_REQUEST_OFF, //!< REQUEST_OFF + HEATER_REQUEST_ON, //!< REQUEST_ON + HEATER_DONT_CARE //!< DONT_CARE + }; - /** - * The elements are ordered by priority, lowest have highest priority - */ - enum HeaterRequest { - HEATER_REQUEST_EMERGENCY_OFF = 0, //!< REQUEST_EMERGENCY_OFF - HEATER_REQUEST_EMERGENCY_ON, //!< REQUEST_EMERGENCY_ON - HEATER_REQUEST_OFF, //!< REQUEST_OFF - HEATER_REQUEST_ON, //!< REQUEST_ON - HEATER_DONT_CARE //!< DONT_CARE - }; + virtual ~ThermalComponentIF() {} - virtual ~ThermalComponentIF() { + virtual HeaterRequest performOperation(uint8_t opCode) = 0; - } + virtual object_id_t getObjectId() = 0; - virtual HeaterRequest performOperation(uint8_t opCode) = 0; + virtual uint8_t getDomainId() const = 0; - virtual object_id_t getObjectId() = 0; + virtual void markStateIgnored() = 0; - virtual uint8_t getDomainId() const = 0; + virtual float getLowerOpLimit() = 0; - virtual void markStateIgnored() = 0; + virtual ReturnValue_t setTargetState(int8_t state) = 0; - virtual float getLowerOpLimit() = 0; + virtual void setOutputInvalid() = 0; - virtual ReturnValue_t setTargetState(int8_t state) = 0; + static bool isOperational(int8_t state) { + return ((state == OPERATIONAL) || (state == OPERATIONAL_IGNORED)); + } - virtual void setOutputInvalid() = 0; + static bool isOutOfRange(State state) { + return ((state == OUT_OF_RANGE_HIGH) || (state == OUT_OF_RANGE_HIGH_IGNORED) || + (state == OUT_OF_RANGE_LOW) || (state == OUT_OF_RANGE_LOW_IGNORED) || + (state == UNKNOWN)); + } - static bool isOperational(int8_t state) { - return ((state == OPERATIONAL) || (state == OPERATIONAL_IGNORED)); - } + static bool isNonOperational(State state) { return !isOutOfRange(state); } - static bool isOutOfRange(State state) { - return ((state == OUT_OF_RANGE_HIGH) - || (state == OUT_OF_RANGE_HIGH_IGNORED) - || (state == OUT_OF_RANGE_LOW) - || (state == OUT_OF_RANGE_LOW_IGNORED) || (state == UNKNOWN)); - } - - static bool isNonOperational(State state) { - return !isOutOfRange(state); - } - - static bool isIgnoredState(State state) { - switch (state) { - case OUT_OF_RANGE_LOW_IGNORED: - case OUT_OF_RANGE_HIGH_IGNORED: - case NON_OPERATIONAL_LOW_IGNORED: - case NON_OPERATIONAL_HIGH_IGNORED: - case OPERATIONAL_IGNORED: - case UNKNOWN: - return true; - default: - return false; - } - } + static bool isIgnoredState(State state) { + switch (state) { + case OUT_OF_RANGE_LOW_IGNORED: + case OUT_OF_RANGE_HIGH_IGNORED: + case NON_OPERATIONAL_LOW_IGNORED: + case NON_OPERATIONAL_HIGH_IGNORED: + case OPERATIONAL_IGNORED: + case UNKNOWN: + return true; + default: + return false; + } + } }; #endif /* THERMALCOMPONENTIF_H_ */ diff --git a/src/fsfw/thermal/ThermalModule.cpp b/src/fsfw/thermal/ThermalModule.cpp index d8108ab3..976bbe45 100644 --- a/src/fsfw/thermal/ThermalModule.cpp +++ b/src/fsfw/thermal/ThermalModule.cpp @@ -1,295 +1,269 @@ #include "fsfw/thermal/ThermalModule.h" -#include "fsfw/thermal/AbstractTemperatureSensor.h" #include "fsfw/monitoring/LimitViolationReporter.h" #include "fsfw/monitoring/MonitoringMessageContent.h" +#include "fsfw/thermal/AbstractTemperatureSensor.h" - -ThermalModule::ThermalModule(gp_id_t moduleTemperaturePoolId, - gp_id_t currentStatePoolId, gp_id_t targetStatePoolId, - LocalPoolDataSetBase *dataSet, Parameters parameters, - RedundantHeater::Parameters heaterParameters) : - oldStrategy(ACTIVE_SINGLE), parameters(parameters), - moduleTemperature(moduleTemperaturePoolId, dataSet, - PoolVariableIF::VAR_WRITE), - currentState(currentStatePoolId, dataSet, PoolVariableIF::VAR_WRITE), - targetState(targetStatePoolId, dataSet, PoolVariableIF::VAR_READ) { - heater = new RedundantHeater(heaterParameters); +ThermalModule::ThermalModule(gp_id_t moduleTemperaturePoolId, gp_id_t currentStatePoolId, + gp_id_t targetStatePoolId, LocalPoolDataSetBase* dataSet, + Parameters parameters, RedundantHeater::Parameters heaterParameters) + : oldStrategy(ACTIVE_SINGLE), + parameters(parameters), + moduleTemperature(moduleTemperaturePoolId, dataSet, PoolVariableIF::VAR_WRITE), + currentState(currentStatePoolId, dataSet, PoolVariableIF::VAR_WRITE), + targetState(targetStatePoolId, dataSet, PoolVariableIF::VAR_READ) { + heater = new RedundantHeater(heaterParameters); } -ThermalModule::ThermalModule(gp_id_t moduleTemperaturePoolId, - LocalPoolDataSetBase* dataSet) : - oldStrategy(ACTIVE_SINGLE), parameters( { 0, 0 }), - moduleTemperature(moduleTemperaturePoolId, dataSet, - PoolVariableIF::VAR_WRITE), - currentState(gp_id_t(), dataSet, - PoolVariableIF::VAR_WRITE), - targetState(gp_id_t(), dataSet, - PoolVariableIF::VAR_READ) { -} +ThermalModule::ThermalModule(gp_id_t moduleTemperaturePoolId, LocalPoolDataSetBase* dataSet) + : oldStrategy(ACTIVE_SINGLE), + parameters({0, 0}), + moduleTemperature(moduleTemperaturePoolId, dataSet, PoolVariableIF::VAR_WRITE), + currentState(gp_id_t(), dataSet, PoolVariableIF::VAR_WRITE), + targetState(gp_id_t(), dataSet, PoolVariableIF::VAR_READ) {} -ThermalModule::~ThermalModule() { - delete heater; -} +ThermalModule::~ThermalModule() { delete heater; } void ThermalModule::performOperation(uint8_t opCode) { - if (heater != nullptr) { - heater->performOperation(0); - } + if (heater != nullptr) { + heater->performOperation(0); + } } void ThermalModule::performMode(Strategy strategy) { - calculateTemperature(); + calculateTemperature(); - bool safeOnly = (strategy == ACTIVE_SURVIVAL); - ThermalComponentIF::HeaterRequest componentHeaterRequest = - letComponentsPerformAndDeciceIfWeNeedToHeat(safeOnly); + bool safeOnly = (strategy == ACTIVE_SURVIVAL); + ThermalComponentIF::HeaterRequest componentHeaterRequest = + letComponentsPerformAndDeciceIfWeNeedToHeat(safeOnly); - if (heater == nullptr) { - informComponentsAboutHeaterState(false, NONE); - return; - } + if (heater == nullptr) { + informComponentsAboutHeaterState(false, NONE); + return; + } - bool heating = calculateModuleHeaterRequestAndSetModuleStatus(strategy); + bool heating = calculateModuleHeaterRequestAndSetModuleStatus(strategy); - if (componentHeaterRequest != ThermalComponentIF::HEATER_DONT_CARE) { - //Components overwrite the module request. - heating = ((componentHeaterRequest - == ThermalComponentIF::HEATER_REQUEST_ON) - or (componentHeaterRequest - == ThermalComponentIF::HEATER_REQUEST_EMERGENCY_ON)); - } + if (componentHeaterRequest != ThermalComponentIF::HEATER_DONT_CARE) { + // Components overwrite the module request. + heating = ((componentHeaterRequest == ThermalComponentIF::HEATER_REQUEST_ON) or + (componentHeaterRequest == ThermalComponentIF::HEATER_REQUEST_EMERGENCY_ON)); + } - bool dual = (strategy == ACTIVE_DUAL); + bool dual = (strategy == ACTIVE_DUAL); - if (strategy == PASSIVE) { - informComponentsAboutHeaterState(false, NONE); - if (oldStrategy != PASSIVE) { - heater->set(false, false, true); - } - } else { - if (safeOnly) { - informComponentsAboutHeaterState(heating, SAFE); - } else { - informComponentsAboutHeaterState(heating, ALL); - } - heater->set(heating, dual); - } - oldStrategy = strategy; + if (strategy == PASSIVE) { + informComponentsAboutHeaterState(false, NONE); + if (oldStrategy != PASSIVE) { + heater->set(false, false, true); + } + } else { + if (safeOnly) { + informComponentsAboutHeaterState(heating, SAFE); + } else { + informComponentsAboutHeaterState(heating, ALL); + } + heater->set(heating, dual); + } + oldStrategy = strategy; } -float ThermalModule::getTemperature() { - return moduleTemperature.value; -} +float ThermalModule::getTemperature() { return moduleTemperature.value; } -void ThermalModule::registerSensor(AbstractTemperatureSensor * sensor) { - sensors.push_back(sensor); -} +void ThermalModule::registerSensor(AbstractTemperatureSensor* sensor) { sensors.push_back(sensor); } void ThermalModule::registerComponent(ThermalComponentIF* component, - ThermalComponentIF::Priority priority) { - components.push_back(ComponentData( { component, priority, - ThermalComponentIF::HEATER_DONT_CARE })); + ThermalComponentIF::Priority priority) { + components.push_back(ComponentData({component, priority, ThermalComponentIF::HEATER_DONT_CARE})); } void ThermalModule::calculateTemperature() { - uint32_t numberOfValidSensors = 0; - moduleTemperature = 0; - std::list::iterator iter = sensors.begin(); - for (; iter != sensors.end(); iter++) { - if ((*iter)->isValid()) { - moduleTemperature = moduleTemperature.value + - (*iter)->getTemperature(); - numberOfValidSensors++; - } - } - if (numberOfValidSensors != 0) { - moduleTemperature = moduleTemperature.value / numberOfValidSensors; - moduleTemperature.setValid(PoolVariableIF::VALID); - } else { - moduleTemperature.value = thermal::INVALID_TEMPERATURE; - moduleTemperature.setValid(PoolVariableIF::INVALID); - } + uint32_t numberOfValidSensors = 0; + moduleTemperature = 0; + std::list::iterator iter = sensors.begin(); + for (; iter != sensors.end(); iter++) { + if ((*iter)->isValid()) { + moduleTemperature = moduleTemperature.value + (*iter)->getTemperature(); + numberOfValidSensors++; + } + } + if (numberOfValidSensors != 0) { + moduleTemperature = moduleTemperature.value / numberOfValidSensors; + moduleTemperature.setValid(PoolVariableIF::VALID); + } else { + moduleTemperature.value = thermal::INVALID_TEMPERATURE; + moduleTemperature.setValid(PoolVariableIF::INVALID); + } } ThermalComponentIF* ThermalModule::findComponent(object_id_t objectId) { - std::list::iterator iter = components.begin(); - for (; iter != components.end(); iter++) { - if (iter->component->getObjectId() == objectId) { - return iter->component; - } - } - return NULL; + std::list::iterator iter = components.begin(); + for (; iter != components.end(); iter++) { + if (iter->component->getObjectId() == objectId) { + return iter->component; + } + } + return NULL; } -ThermalComponentIF::HeaterRequest -ThermalModule::letComponentsPerformAndDeciceIfWeNeedToHeat(bool safeOnly) { - ThermalComponentIF::HeaterRequest - heaterRequests[ThermalComponentIF::NUMBER_OF_PRIORITIES]; +ThermalComponentIF::HeaterRequest ThermalModule::letComponentsPerformAndDeciceIfWeNeedToHeat( + bool safeOnly) { + ThermalComponentIF::HeaterRequest heaterRequests[ThermalComponentIF::NUMBER_OF_PRIORITIES]; - survivalTargetTemp = -999; - targetTemp = -999; + survivalTargetTemp = -999; + targetTemp = -999; - for (uint8_t i = 0; i < ThermalComponentIF::NUMBER_OF_PRIORITIES; i++) { - heaterRequests[i] = ThermalComponentIF::HEATER_DONT_CARE; - } + for (uint8_t i = 0; i < ThermalComponentIF::NUMBER_OF_PRIORITIES; i++) { + heaterRequests[i] = ThermalComponentIF::HEATER_DONT_CARE; + } - std::list::iterator iter = components.begin(); - for (; iter != components.end(); iter++) { - updateTargetTemperatures(iter->component, - iter->priority == ThermalComponentIF::SAFE); - ThermalComponentIF::HeaterRequest request = - iter->component->performOperation(0); - iter->request = request; - if (request != ThermalComponentIF::HEATER_DONT_CARE) { - if (request < heaterRequests[iter->priority]) { - heaterRequests[iter->priority] = request; - } - } - } + std::list::iterator iter = components.begin(); + for (; iter != components.end(); iter++) { + updateTargetTemperatures(iter->component, iter->priority == ThermalComponentIF::SAFE); + ThermalComponentIF::HeaterRequest request = iter->component->performOperation(0); + iter->request = request; + if (request != ThermalComponentIF::HEATER_DONT_CARE) { + if (request < heaterRequests[iter->priority]) { + heaterRequests[iter->priority] = request; + } + } + } - if (!safeOnly) { - for (uint8_t i = ThermalComponentIF::NUMBER_OF_PRIORITIES - 1; i > 0; - i--) { - if (heaterRequests[i - 1] == ThermalComponentIF::HEATER_DONT_CARE) { - heaterRequests[i - 1] = heaterRequests[i]; - } - } - } - return heaterRequests[0]; + if (!safeOnly) { + for (uint8_t i = ThermalComponentIF::NUMBER_OF_PRIORITIES - 1; i > 0; i--) { + if (heaterRequests[i - 1] == ThermalComponentIF::HEATER_DONT_CARE) { + heaterRequests[i - 1] = heaterRequests[i]; + } + } + } + return heaterRequests[0]; } -void ThermalModule::informComponentsAboutHeaterState(bool heaterIsOn, - Informee whomToInform) { - std::list::iterator iter = components.begin(); - for (; iter != components.end(); iter++) { - switch (whomToInform) { - case ALL: - break; - case SAFE: - if (!(iter->priority == ThermalComponentIF::SAFE)) { - iter->component->markStateIgnored(); - continue; - } - break; - case NONE: - iter->component->markStateIgnored(); - continue; - } +void ThermalModule::informComponentsAboutHeaterState(bool heaterIsOn, Informee whomToInform) { + std::list::iterator iter = components.begin(); + for (; iter != components.end(); iter++) { + switch (whomToInform) { + case ALL: + break; + case SAFE: + if (!(iter->priority == ThermalComponentIF::SAFE)) { + iter->component->markStateIgnored(); + continue; + } + break; + case NONE: + iter->component->markStateIgnored(); + continue; + } - if (heaterIsOn) { - if ((iter->request - == ThermalComponentIF::HEATER_REQUEST_EMERGENCY_OFF) - || (iter->request == ThermalComponentIF::HEATER_REQUEST_OFF)) { - iter->component->markStateIgnored(); - } - } else { - if ((iter->request - == ThermalComponentIF::HEATER_REQUEST_EMERGENCY_ON) - || (iter->request == ThermalComponentIF::HEATER_REQUEST_ON)) { - iter->component->markStateIgnored(); - } - } - } + if (heaterIsOn) { + if ((iter->request == ThermalComponentIF::HEATER_REQUEST_EMERGENCY_OFF) || + (iter->request == ThermalComponentIF::HEATER_REQUEST_OFF)) { + iter->component->markStateIgnored(); + } + } else { + if ((iter->request == ThermalComponentIF::HEATER_REQUEST_EMERGENCY_ON) || + (iter->request == ThermalComponentIF::HEATER_REQUEST_ON)) { + iter->component->markStateIgnored(); + } + } + } } void ThermalModule::initialize(PowerSwitchIF* powerSwitch) { - if (heater != NULL) { - heater->setPowerSwitcher(powerSwitch); - } + if (heater != NULL) { + heater->setPowerSwitcher(powerSwitch); + } - std::list::iterator iter = components.begin(); - for (; iter != components.end(); iter++) { - float componentLowerOpLimit = iter->component->getLowerOpLimit(); - if (iter->priority == ThermalComponentIF::SAFE) { - if (componentLowerOpLimit > survivalTargetTemp) { - survivalTargetTemp = componentLowerOpLimit; - } - } else { - if (componentLowerOpLimit > targetTemp) { - targetTemp = componentLowerOpLimit; - } - } - } - if (survivalTargetTemp > targetTemp) { - targetTemp = survivalTargetTemp; - } + std::list::iterator iter = components.begin(); + for (; iter != components.end(); iter++) { + float componentLowerOpLimit = iter->component->getLowerOpLimit(); + if (iter->priority == ThermalComponentIF::SAFE) { + if (componentLowerOpLimit > survivalTargetTemp) { + survivalTargetTemp = componentLowerOpLimit; + } + } else { + if (componentLowerOpLimit > targetTemp) { + targetTemp = componentLowerOpLimit; + } + } + } + if (survivalTargetTemp > targetTemp) { + targetTemp = survivalTargetTemp; + } } -bool ThermalModule::calculateModuleHeaterRequestAndSetModuleStatus( - Strategy strategy) { - currentState.setValid(PoolVariableIF::VALID); - if (moduleTemperature == thermal::INVALID_TEMPERATURE) { - currentState = UNKNOWN; - return false; - } +bool ThermalModule::calculateModuleHeaterRequestAndSetModuleStatus(Strategy strategy) { + currentState.setValid(PoolVariableIF::VALID); + if (moduleTemperature == thermal::INVALID_TEMPERATURE) { + currentState = UNKNOWN; + return false; + } - float limit = targetTemp; - bool heaterRequest = false; - if (strategy == ACTIVE_SURVIVAL) { - limit = survivalTargetTemp; - } + float limit = targetTemp; + bool heaterRequest = false; + if (strategy == ACTIVE_SURVIVAL) { + limit = survivalTargetTemp; + } - if (moduleTemperature.value >= limit) { - currentState = OPERATIONAL; - } else { - currentState = NON_OPERATIONAL; - } + if (moduleTemperature.value >= limit) { + currentState = OPERATIONAL; + } else { + currentState = NON_OPERATIONAL; + } - limit += parameters.heaterOn; + limit += parameters.heaterOn; - if (heating) { - limit += parameters.hysteresis; - } + if (heating) { + limit += parameters.hysteresis; + } - if (targetState == STATE_REQUEST_HEATING) { - if (moduleTemperature < limit) { - heaterRequest = true; - } else { - heaterRequest = false; - } - } + if (targetState == STATE_REQUEST_HEATING) { + if (moduleTemperature < limit) { + heaterRequest = true; + } else { + heaterRequest = false; + } + } - heating = heaterRequest; + heating = heaterRequest; - return heaterRequest; + return heaterRequest; } void ThermalModule::setHeating(bool on) { - ReturnValue_t result = targetState.read(); - if(result == HasReturnvaluesIF::RETURN_OK) { - if(on) { - targetState.value = STATE_REQUEST_HEATING; - } - else { - targetState.value = STATE_REQUEST_PASSIVE; - } - } - targetState.setValid(true); + ReturnValue_t result = targetState.read(); + if (result == HasReturnvaluesIF::RETURN_OK) { + if (on) { + targetState.value = STATE_REQUEST_HEATING; + } else { + targetState.value = STATE_REQUEST_PASSIVE; + } + } + targetState.setValid(true); } -void ThermalModule::updateTargetTemperatures(ThermalComponentIF* component, - bool isSafe) { - if (isSafe) { - if (component->getLowerOpLimit() > survivalTargetTemp) { - survivalTargetTemp = component->getLowerOpLimit(); - } - } else { - if (component->getLowerOpLimit() > targetTemp) { - targetTemp = component->getLowerOpLimit(); - } - } +void ThermalModule::updateTargetTemperatures(ThermalComponentIF* component, bool isSafe) { + if (isSafe) { + if (component->getLowerOpLimit() > survivalTargetTemp) { + survivalTargetTemp = component->getLowerOpLimit(); + } + } else { + if (component->getLowerOpLimit() > targetTemp) { + targetTemp = component->getLowerOpLimit(); + } + } } void ThermalModule::setOutputInvalid() { - moduleTemperature = thermal::INVALID_TEMPERATURE; - moduleTemperature.setValid(PoolVariableIF::INVALID); - currentState.setValid(PoolVariableIF::INVALID); - std::list::iterator iter = components.begin(); - for (; iter != components.end(); iter++) { - iter->component->setOutputInvalid(); - } - if (heater != NULL) { - heater->set(false,true); - } + moduleTemperature = thermal::INVALID_TEMPERATURE; + moduleTemperature.setValid(PoolVariableIF::INVALID); + currentState.setValid(PoolVariableIF::INVALID); + std::list::iterator iter = components.begin(); + for (; iter != components.end(); iter++) { + iter->component->setOutputInvalid(); + } + if (heater != NULL) { + heater->set(false, true); + } } diff --git a/src/fsfw/thermal/ThermalModule.h b/src/fsfw/thermal/ThermalModule.h index 0abe51c7..3a33be7f 100644 --- a/src/fsfw/thermal/ThermalModule.h +++ b/src/fsfw/thermal/ThermalModule.h @@ -1,100 +1,94 @@ #ifndef FSFW_THERMAL_THERMALMODULE_H_ #define FSFW_THERMAL_THERMALMODULE_H_ -#include "ThermalModuleIF.h" -#include "tcsDefinitions.h" -#include "RedundantHeater.h" +#include #include "../datapoollocal/LocalPoolDataSetBase.h" #include "../datapoollocal/LocalPoolVariable.h" #include "../devicehandlers/HealthDevice.h" #include "../events/EventReportingProxyIF.h" - -#include - +#include "RedundantHeater.h" +#include "ThermalModuleIF.h" +#include "tcsDefinitions.h" class PowerSwitchIF; /** * @brief Allows creation of different thermal control domains within a system. */ -class ThermalModule: public ThermalModuleIF { - friend class ThermalController; -public: - struct Parameters { - float heaterOn; - float hysteresis; - }; +class ThermalModule : public ThermalModuleIF { + friend class ThermalController; - ThermalModule(gp_id_t moduleTemperaturePoolId, gp_id_t currentStatePoolId, - gp_id_t targetStatePoolId, LocalPoolDataSetBase *dataSet, - Parameters parameters, RedundantHeater::Parameters heaterParameters); + public: + struct Parameters { + float heaterOn; + float hysteresis; + }; - ThermalModule(gp_id_t moduleTemperaturePoolId, - LocalPoolDataSetBase *dataSet); + ThermalModule(gp_id_t moduleTemperaturePoolId, gp_id_t currentStatePoolId, + gp_id_t targetStatePoolId, LocalPoolDataSetBase *dataSet, Parameters parameters, + RedundantHeater::Parameters heaterParameters); - virtual ~ThermalModule(); + ThermalModule(gp_id_t moduleTemperaturePoolId, LocalPoolDataSetBase *dataSet); - void performOperation(uint8_t opCode); + virtual ~ThermalModule(); - void performMode(Strategy strategy); + void performOperation(uint8_t opCode); - float getTemperature(); + void performMode(Strategy strategy); - void registerSensor(AbstractTemperatureSensor *sensor); + float getTemperature(); - void registerComponent(ThermalComponentIF *component, - ThermalComponentIF::Priority priority); + void registerSensor(AbstractTemperatureSensor *sensor); - ThermalComponentIF *findComponent(object_id_t objectId); + void registerComponent(ThermalComponentIF *component, ThermalComponentIF::Priority priority); - void initialize(PowerSwitchIF* powerSwitch); + ThermalComponentIF *findComponent(object_id_t objectId); - void setHeating(bool on); + void initialize(PowerSwitchIF *powerSwitch); - virtual void setOutputInvalid(); + void setHeating(bool on); -protected: - enum Informee { - ALL, SAFE, NONE - }; + virtual void setOutputInvalid(); - struct ComponentData { - ThermalComponentIF *component; - ThermalComponentIF::Priority priority; - ThermalComponentIF::HeaterRequest request; - }; + protected: + enum Informee { ALL, SAFE, NONE }; - Strategy oldStrategy; + struct ComponentData { + ThermalComponentIF *component; + ThermalComponentIF::Priority priority; + ThermalComponentIF::HeaterRequest request; + }; - float survivalTargetTemp = 0.0; + Strategy oldStrategy; - float targetTemp = 0.0; + float survivalTargetTemp = 0.0; - bool heating = false; + float targetTemp = 0.0; - Parameters parameters; + bool heating = false; - lp_var_t moduleTemperature; + Parameters parameters; - RedundantHeater *heater = nullptr; + lp_var_t moduleTemperature; - lp_var_t currentState; - lp_var_t targetState; + RedundantHeater *heater = nullptr; - std::list sensors; - std::list components; + lp_var_t currentState; + lp_var_t targetState; - void calculateTemperature(); + std::list sensors; + std::list components; - ThermalComponentIF::HeaterRequest letComponentsPerformAndDeciceIfWeNeedToHeat(bool safeOnly); + void calculateTemperature(); - void informComponentsAboutHeaterState(bool heaterIsOn, - Informee whomToInform); + ThermalComponentIF::HeaterRequest letComponentsPerformAndDeciceIfWeNeedToHeat(bool safeOnly); - bool calculateModuleHeaterRequestAndSetModuleStatus(Strategy strategy); + void informComponentsAboutHeaterState(bool heaterIsOn, Informee whomToInform); - void updateTargetTemperatures(ThermalComponentIF *component, bool isSafe); + bool calculateModuleHeaterRequestAndSetModuleStatus(Strategy strategy); + + void updateTargetTemperatures(ThermalComponentIF *component, bool isSafe); }; #endif /* FSFW_THERMAL_THERMALMODULE_H_ */ diff --git a/src/fsfw/thermal/ThermalModuleIF.h b/src/fsfw/thermal/ThermalModuleIF.h index 89cf93d6..94431b8e 100644 --- a/src/fsfw/thermal/ThermalModuleIF.h +++ b/src/fsfw/thermal/ThermalModuleIF.h @@ -5,40 +5,37 @@ class AbstractTemperatureSensor; -class ThermalModuleIF{ -public: - enum Strategy { - PASSIVE = 0, ACTIVE_SURVIVAL = 1, ACTIVE_SINGLE = 2, ACTIVE_DUAL = 3, - }; +class ThermalModuleIF { + public: + enum Strategy { + PASSIVE = 0, + ACTIVE_SURVIVAL = 1, + ACTIVE_SINGLE = 2, + ACTIVE_DUAL = 3, + }; - enum StateRequest { - STATE_REQUEST_HEATING = 1, STATE_REQUEST_PASSIVE = 0 - }; + enum StateRequest { STATE_REQUEST_HEATING = 1, STATE_REQUEST_PASSIVE = 0 }; - enum State { - NON_OPERATIONAL = 0, OPERATIONAL = 1, UNKNOWN = 2 - }; + enum State { NON_OPERATIONAL = 0, OPERATIONAL = 1, UNKNOWN = 2 }; - virtual ~ThermalModuleIF() { + virtual ~ThermalModuleIF() {} - } + virtual void performOperation(uint8_t opCode) = 0; - virtual void performOperation(uint8_t opCode) = 0; + virtual void performMode(Strategy strategy) = 0; - virtual void performMode(Strategy strategy) = 0; + virtual float getTemperature() = 0; - virtual float getTemperature() = 0; + virtual void registerSensor(AbstractTemperatureSensor *sensor) = 0; - virtual void registerSensor(AbstractTemperatureSensor *sensor) = 0; + virtual void registerComponent(ThermalComponentIF *component, + ThermalComponentIF::Priority priority) = 0; - virtual void registerComponent(ThermalComponentIF *component, - ThermalComponentIF::Priority priority) = 0; + virtual ThermalComponentIF *findComponent(object_id_t objectId) = 0; - virtual ThermalComponentIF *findComponent(object_id_t objectId) = 0; + virtual void setHeating(bool on) = 0; - virtual void setHeating(bool on) = 0; - - virtual void setOutputInvalid() = 0; + virtual void setOutputInvalid() = 0; }; #endif /* THERMALMODULEIF_H_ */ diff --git a/src/fsfw/thermal/ThermalMonitorReporter.cpp b/src/fsfw/thermal/ThermalMonitorReporter.cpp index 31503203..dc64280e 100644 --- a/src/fsfw/thermal/ThermalMonitorReporter.cpp +++ b/src/fsfw/thermal/ThermalMonitorReporter.cpp @@ -1,75 +1,65 @@ #include "fsfw/thermal/ThermalMonitorReporter.h" -#include "fsfw/thermal/ThermalComponentIF.h" #include "fsfw/monitoring/MonitoringIF.h" +#include "fsfw/thermal/ThermalComponentIF.h" -ThermalMonitorReporter::~ThermalMonitorReporter() { -} +ThermalMonitorReporter::~ThermalMonitorReporter() {} -void ThermalMonitorReporter::sendTransitionEvent(float currentValue, - ReturnValue_t state) { - switch (state) { - case MonitoringIF::BELOW_LOW_LIMIT: - EventManagerIF::triggerEvent(reportingId, - ThermalComponentIF::COMPONENT_TEMP_OOL_LOW, state); - break; - case MonitoringIF::ABOVE_HIGH_LIMIT: - EventManagerIF::triggerEvent(reportingId, - ThermalComponentIF::COMPONENT_TEMP_OOL_HIGH, state); - break; - case ThermalComponentIF::BELOW_OPERATIONAL_LIMIT: - EventManagerIF::triggerEvent(reportingId, - ThermalComponentIF::COMPONENT_TEMP_LOW, state); - break; - case ThermalComponentIF::ABOVE_OPERATIONAL_LIMIT: - EventManagerIF::triggerEvent(reportingId, - ThermalComponentIF::COMPONENT_TEMP_HIGH, state); - break; - default: - break; - } +void ThermalMonitorReporter::sendTransitionEvent(float currentValue, ReturnValue_t state) { + switch (state) { + case MonitoringIF::BELOW_LOW_LIMIT: + EventManagerIF::triggerEvent(reportingId, ThermalComponentIF::COMPONENT_TEMP_OOL_LOW, state); + break; + case MonitoringIF::ABOVE_HIGH_LIMIT: + EventManagerIF::triggerEvent(reportingId, ThermalComponentIF::COMPONENT_TEMP_OOL_HIGH, state); + break; + case ThermalComponentIF::BELOW_OPERATIONAL_LIMIT: + EventManagerIF::triggerEvent(reportingId, ThermalComponentIF::COMPONENT_TEMP_LOW, state); + break; + case ThermalComponentIF::ABOVE_OPERATIONAL_LIMIT: + EventManagerIF::triggerEvent(reportingId, ThermalComponentIF::COMPONENT_TEMP_HIGH, state); + break; + default: + break; + } } bool ThermalMonitorReporter::isAboveHighLimit() { - if (oldState == ThermalComponentIF::ABOVE_OPERATIONAL_LIMIT) { - return true; - } else { - return false; - } + if (oldState == ThermalComponentIF::ABOVE_OPERATIONAL_LIMIT) { + return true; + } else { + return false; + } } -ReturnValue_t ThermalMonitorReporter::translateState( - ThermalComponentIF::State state, float sample, float lowerLimit, - float upperLimit, bool componentIsOperational) { - if (ThermalComponentIF::isIgnoredState(state)) { - setToUnchecked(); - return MonitoringIF::UNCHECKED; - } - switch (state) { - case ThermalComponentIF::OUT_OF_RANGE_LOW: - return monitorStateIs(MonitoringIF::BELOW_LOW_LIMIT, sample, - lowerLimit); - case ThermalComponentIF::NON_OPERATIONAL_LOW: - if (componentIsOperational) { - return monitorStateIs(ThermalComponentIF::BELOW_OPERATIONAL_LIMIT, - sample, lowerLimit); - } else { - return monitorStateIs(HasReturnvaluesIF::RETURN_OK, sample, 0.0); - } - case ThermalComponentIF::OPERATIONAL: - return monitorStateIs(HasReturnvaluesIF::RETURN_OK, sample, 0.0); - case ThermalComponentIF::NON_OPERATIONAL_HIGH: - if (componentIsOperational) { - return monitorStateIs(ThermalComponentIF::ABOVE_OPERATIONAL_LIMIT, - sample, upperLimit); - } else { - return monitorStateIs(HasReturnvaluesIF::RETURN_OK, sample, 0.0); - } - case ThermalComponentIF::OUT_OF_RANGE_HIGH: - return monitorStateIs(MonitoringIF::ABOVE_HIGH_LIMIT, sample, - upperLimit); - default: - //Never reached, all states covered. - return HasReturnvaluesIF::RETURN_FAILED; - } +ReturnValue_t ThermalMonitorReporter::translateState(ThermalComponentIF::State state, float sample, + float lowerLimit, float upperLimit, + bool componentIsOperational) { + if (ThermalComponentIF::isIgnoredState(state)) { + setToUnchecked(); + return MonitoringIF::UNCHECKED; + } + switch (state) { + case ThermalComponentIF::OUT_OF_RANGE_LOW: + return monitorStateIs(MonitoringIF::BELOW_LOW_LIMIT, sample, lowerLimit); + case ThermalComponentIF::NON_OPERATIONAL_LOW: + if (componentIsOperational) { + return monitorStateIs(ThermalComponentIF::BELOW_OPERATIONAL_LIMIT, sample, lowerLimit); + } else { + return monitorStateIs(HasReturnvaluesIF::RETURN_OK, sample, 0.0); + } + case ThermalComponentIF::OPERATIONAL: + return monitorStateIs(HasReturnvaluesIF::RETURN_OK, sample, 0.0); + case ThermalComponentIF::NON_OPERATIONAL_HIGH: + if (componentIsOperational) { + return monitorStateIs(ThermalComponentIF::ABOVE_OPERATIONAL_LIMIT, sample, upperLimit); + } else { + return monitorStateIs(HasReturnvaluesIF::RETURN_OK, sample, 0.0); + } + case ThermalComponentIF::OUT_OF_RANGE_HIGH: + return monitorStateIs(MonitoringIF::ABOVE_HIGH_LIMIT, sample, upperLimit); + default: + // Never reached, all states covered. + return HasReturnvaluesIF::RETURN_FAILED; + } } diff --git a/src/fsfw/thermal/ThermalMonitorReporter.h b/src/fsfw/thermal/ThermalMonitorReporter.h index 4fb68a99..521691fe 100644 --- a/src/fsfw/thermal/ThermalMonitorReporter.h +++ b/src/fsfw/thermal/ThermalMonitorReporter.h @@ -1,28 +1,24 @@ #ifndef FSFW_THERMAL_THERMALMONITORREPORTER_H_ #define FSFW_THERMAL_THERMALMONITORREPORTER_H_ -#include "ThermalComponentIF.h" #include "../monitoring/MonitorReporter.h" - +#include "ThermalComponentIF.h" /** * @brief Monitor Reporter implementation for thermal components. */ -class ThermalMonitorReporter: public MonitorReporter { -public: - template - ThermalMonitorReporter(Args ... args) : - MonitorReporter(std::forward(args)...) { - } - ~ThermalMonitorReporter(); - ReturnValue_t translateState(ThermalComponentIF::State state, float sample, - float lowerLimit, float upperLimit, - bool componentIsOperational = true); +class ThermalMonitorReporter : public MonitorReporter { + public: + template + ThermalMonitorReporter(Args... args) : MonitorReporter(std::forward(args)...) {} + ~ThermalMonitorReporter(); + ReturnValue_t translateState(ThermalComponentIF::State state, float sample, float lowerLimit, + float upperLimit, bool componentIsOperational = true); - bool isAboveHighLimit(); -protected: - virtual void sendTransitionEvent(float currentValue, ReturnValue_t state); + bool isAboveHighLimit(); + protected: + virtual void sendTransitionEvent(float currentValue, ReturnValue_t state); }; #endif /* FSFW_THERMAL_THERMALMONITORREPORTERREPORTER_H_ */ diff --git a/src/fsfw/timemanager/CCSDSTime.cpp b/src/fsfw/timemanager/CCSDSTime.cpp index 2475a5eb..4445fd24 100644 --- a/src/fsfw/timemanager/CCSDSTime.cpp +++ b/src/fsfw/timemanager/CCSDSTime.cpp @@ -1,615 +1,602 @@ -#include "fsfw/FSFW.h" #include "fsfw/timemanager/CCSDSTime.h" -#include #include #include +#include +#include "fsfw/FSFW.h" -CCSDSTime::CCSDSTime() { +CCSDSTime::CCSDSTime() {} + +CCSDSTime::~CCSDSTime() {} + +ReturnValue_t CCSDSTime::convertToCcsds(Ccs_seconds* to, const Clock::TimeOfDay_t* from) { + ReturnValue_t result = checkTimeOfDay(from); + if (result != RETURN_OK) { + return result; + } + + to->pField = (CCS << 4); + + to->yearMSB = (from->year >> 8); + to->yearLSB = from->year & 0xff; + to->month = from->month; + to->day = from->day; + to->hour = from->hour; + to->minute = from->minute; + to->second = from->second; + + return RETURN_OK; } -CCSDSTime::~CCSDSTime() { +ReturnValue_t CCSDSTime::convertToCcsds(Ccs_mseconds* to, const Clock::TimeOfDay_t* from) { + ReturnValue_t result = checkTimeOfDay(from); + if (result != RETURN_OK) { + return result; + } + + to->pField = (CCS << 4) + 2; + + to->yearMSB = (from->year >> 8); + to->yearLSB = from->year & 0xff; + to->month = from->month; + to->day = from->day; + to->hour = from->hour; + to->minute = from->minute; + to->second = from->second; + to->secondEminus2 = from->usecond / 10000; + to->secondEminus4 = (from->usecond % 10000) / 100; + + return RETURN_OK; } -ReturnValue_t CCSDSTime::convertToCcsds(Ccs_seconds* to, - const Clock::TimeOfDay_t* from) { - ReturnValue_t result = checkTimeOfDay(from); - if (result != RETURN_OK) { - return result; - } - - to->pField = (CCS << 4); - - to->yearMSB = (from->year >> 8); - to->yearLSB = from->year & 0xff; - to->month = from->month; - to->day = from->day; - to->hour = from->hour; - to->minute = from->minute; - to->second = from->second; - +ReturnValue_t CCSDSTime::convertFromCcsds(Clock::TimeOfDay_t* to, const uint8_t* from, + size_t length) { + ReturnValue_t result; + if (length > 0xFF) { + return LENGTH_MISMATCH; + } + result = convertFromASCII(to, from, length); // Try to parse it as ASCII + if (result == RETURN_OK) { return RETURN_OK; -} + } -ReturnValue_t CCSDSTime::convertToCcsds(Ccs_mseconds* to, - const Clock::TimeOfDay_t* from) { - ReturnValue_t result = checkTimeOfDay(from); - if (result != RETURN_OK) { - return result; - } - - to->pField = (CCS << 4) + 2; - - to->yearMSB = (from->year >> 8); - to->yearLSB = from->year & 0xff; - to->month = from->month; - to->day = from->day; - to->hour = from->hour; - to->minute = from->minute; - to->second = from->second; - to->secondEminus2 = from->usecond / 10000; - to->secondEminus4 = (from->usecond % 10000) / 100; - - return RETURN_OK; -} - -ReturnValue_t CCSDSTime::convertFromCcsds(Clock::TimeOfDay_t* to, - const uint8_t* from, size_t length) { - ReturnValue_t result; - if (length > 0xFF) { - return LENGTH_MISMATCH; - } - result = convertFromASCII(to, from, length); //Try to parse it as ASCII - if (result == RETURN_OK) { - return RETURN_OK; - } - - //Seems to be no ascii, try the other formats - uint8_t codeIdentification = (*from >> 4); - switch (codeIdentification) { - case CUC_LEVEL1: //CUC_LEVEL2 can not be converted to TimeOfDay (ToD is Level 1) <- Well, if we know the epoch, we can... <- see bug 1133 - return convertFromCUC(to, from, length); + // Seems to be no ascii, try the other formats + uint8_t codeIdentification = (*from >> 4); + switch (codeIdentification) { + case CUC_LEVEL1: // CUC_LEVEL2 can not be converted to TimeOfDay (ToD is Level 1) <- Well, if + // we know the epoch, we can... <- see bug 1133 + return convertFromCUC(to, from, length); case CDS: - return convertFromCDS(to, from, length); + return convertFromCDS(to, from, length); case CCS: { - size_t temp = 0; - return convertFromCCS(to, from, &temp, length); + size_t temp = 0; + return convertFromCCS(to, from, &temp, length); } default: - return UNSUPPORTED_TIME_FORMAT; - } + return UNSUPPORTED_TIME_FORMAT; + } } -ReturnValue_t CCSDSTime::convertFromCUC(Clock::TimeOfDay_t* to, - const uint8_t* from, uint8_t length) { - return UNSUPPORTED_TIME_FORMAT; +ReturnValue_t CCSDSTime::convertFromCUC(Clock::TimeOfDay_t* to, const uint8_t* from, + uint8_t length) { + return UNSUPPORTED_TIME_FORMAT; } -ReturnValue_t CCSDSTime::convertFromCDS(Clock::TimeOfDay_t* to, - const uint8_t* from, uint8_t length) { - timeval time; - ReturnValue_t result = convertFromCDS(&time, from, NULL, length); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return convertTimevalToTimeOfDay(to, &time); +ReturnValue_t CCSDSTime::convertFromCDS(Clock::TimeOfDay_t* to, const uint8_t* from, + uint8_t length) { + timeval time; + ReturnValue_t result = convertFromCDS(&time, from, NULL, length); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return convertTimevalToTimeOfDay(to, &time); } -ReturnValue_t CCSDSTime::convertFromCCS(Clock::TimeOfDay_t* to, - const uint8_t* from, size_t* foundLength, size_t maxLength) { - uint8_t subsecondsLength = *from & 0b111; - uint32_t totalLength = subsecondsLength + 8; - if (maxLength < totalLength) { - return LENGTH_MISMATCH; - } +ReturnValue_t CCSDSTime::convertFromCCS(Clock::TimeOfDay_t* to, const uint8_t* from, + size_t* foundLength, size_t maxLength) { + uint8_t subsecondsLength = *from & 0b111; + uint32_t totalLength = subsecondsLength + 8; + if (maxLength < totalLength) { + return LENGTH_MISMATCH; + } - *foundLength = totalLength; + *foundLength = totalLength; - ReturnValue_t result = checkCcs(from, maxLength); + ReturnValue_t result = checkCcs(from, maxLength); + if (result != RETURN_OK) { + return result; + } + + Ccs_mseconds* temp = (Ccs_mseconds*)from; + + to->year = (temp->yearMSB << 8) + temp->yearLSB; + to->hour = temp->hour; + to->minute = temp->minute; + to->second = temp->second; + + if (temp->pField & (1 << 3)) { // day of year variation + uint16_t tempDay = (temp->month << 8) + temp->day; + result = convertDaysOfYear(tempDay, to->year, &(temp->month), &(temp->day)); if (result != RETURN_OK) { - return result; + return result; } + } - Ccs_mseconds *temp = (Ccs_mseconds *) from; + to->month = temp->month; + to->day = temp->day; - to->year = (temp->yearMSB << 8) + temp->yearLSB; - to->hour = temp->hour; - to->minute = temp->minute; - to->second = temp->second; - - if (temp->pField & (1 << 3)) { //day of year variation - uint16_t tempDay = (temp->month << 8) + temp->day; - result = convertDaysOfYear(tempDay, to->year, - &(temp->month), &(temp->day)); - if (result != RETURN_OK) { - return result; - } + to->usecond = 0; + if (subsecondsLength > 0) { + *foundLength += 1; + if (temp->secondEminus2 >= 100) { + return INVALID_TIME_FORMAT; } + to->usecond = temp->secondEminus2 * 10000; + } - to->month = temp->month; - to->day = temp->day; - - to->usecond = 0; - if (subsecondsLength > 0) { - *foundLength += 1; - if (temp->secondEminus2 >= 100) { - return INVALID_TIME_FORMAT; - } - to->usecond = temp->secondEminus2 * 10000; + if (subsecondsLength > 1) { + *foundLength += 1; + if (temp->secondEminus4 >= 100) { + return INVALID_TIME_FORMAT; } + to->usecond += temp->secondEminus4 * 100; + } - if (subsecondsLength > 1) { - *foundLength += 1; - if (temp->secondEminus4 >= 100) { - return INVALID_TIME_FORMAT; - } - to->usecond += temp->secondEminus4 * 100; - } - - return RETURN_OK; - + return RETURN_OK; } -ReturnValue_t CCSDSTime::convertFromASCII(Clock::TimeOfDay_t* to, - const uint8_t* from, uint8_t length) { - if (length < 19) { - return RETURN_FAILED; - } - // Newlib nano can't parse uint8, see SCNu8 documentation and https://sourceware.org/newlib/README - // Suggestion: use uint16 all the time. This should work on all systems. +ReturnValue_t CCSDSTime::convertFromASCII(Clock::TimeOfDay_t* to, const uint8_t* from, + uint8_t length) { + if (length < 19) { + return RETURN_FAILED; + } + // Newlib nano can't parse uint8, see SCNu8 documentation and https://sourceware.org/newlib/README + // Suggestion: use uint16 all the time. This should work on all systems. #if FSFW_NO_C99_IO == 1 - uint16_t year; - uint16_t month; - uint16_t day; - uint16_t hour; - uint16_t minute; - float second; - int count = sscanf((char *) from, "%4" SCNu16 "-%2" SCNu16 "-%2" SCNu16 "T%" - "2" SCNu16 ":%2" SCNu16 ":%fZ", &year, &month, &day, &hour, - &minute, &second); - if (count == 6) { - to->year = year; - to->month = month; - to->day = day; - to->hour = hour; - to->minute = minute; - to->second = second; - to->usecond = (second - floor(second)) * 1000000; - return RETURN_OK; - } + uint16_t year; + uint16_t month; + uint16_t day; + uint16_t hour; + uint16_t minute; + float second; + int count = sscanf((char*)from, + "%4" SCNu16 "-%2" SCNu16 "-%2" SCNu16 + "T%" + "2" SCNu16 ":%2" SCNu16 ":%fZ", + &year, &month, &day, &hour, &minute, &second); + if (count == 6) { + to->year = year; + to->month = month; + to->day = day; + to->hour = hour; + to->minute = minute; + to->second = second; + to->usecond = (second - floor(second)) * 1000000; + return RETURN_OK; + } - // try Code B (yyyy-ddd) - count = sscanf((char *) from, "%4" SCNu16 "-%3" SCNu16 "T%2" SCNu16 ":%" - "2" SCNu16 ":%fZ", &year, &day, &hour, &minute, &second); - if (count == 5) { - uint8_t tempDay; - ReturnValue_t result = CCSDSTime::convertDaysOfYear(day, year, - reinterpret_cast(&month), - reinterpret_cast(&tempDay)); - if (result != RETURN_OK) { - return RETURN_FAILED; - } - to->year = year; - to->month = month; - to->day = tempDay; - to->hour = hour; - to->minute = minute; - to->second = second; - to->usecond = (second - floor(second)) * 1000000; - return RETURN_OK; + // try Code B (yyyy-ddd) + count = sscanf((char*)from, + "%4" SCNu16 "-%3" SCNu16 "T%2" SCNu16 + ":%" + "2" SCNu16 ":%fZ", + &year, &day, &hour, &minute, &second); + if (count == 5) { + uint8_t tempDay; + ReturnValue_t result = CCSDSTime::convertDaysOfYear( + day, year, reinterpret_cast(&month), reinterpret_cast(&tempDay)); + if (result != RETURN_OK) { + return RETURN_FAILED; } - // Warning: Compiler/Linker fails ambiguously if library does not implement - // C99 I/O + to->year = year; + to->month = month; + to->day = tempDay; + to->hour = hour; + to->minute = minute; + to->second = second; + to->usecond = (second - floor(second)) * 1000000; + return RETURN_OK; + } + // Warning: Compiler/Linker fails ambiguously if library does not implement + // C99 I/O #else - uint16_t year; - uint8_t month; - uint16_t day; - uint8_t hour; - uint8_t minute; - float second; - //try Code A (yyyy-mm-dd) - int count = sscanf((char *) from, "%4" SCNu16 "-%2" SCNu8 "-%2" SCNu16 - "T%2" SCNu8 ":%2" SCNu8 ":%fZ", &year, &month, &day, - &hour, &minute, &second); - if (count == 6) { - to->year = year; - to->month = month; - to->day = day; - to->hour = hour; - to->minute = minute; - to->second = second; - to->usecond = (second - floor(second)) * 1000000; - return RETURN_OK; - } + uint16_t year; + uint8_t month; + uint16_t day; + uint8_t hour; + uint8_t minute; + float second; + // try Code A (yyyy-mm-dd) + int count = + sscanf((char*)from, "%4" SCNu16 "-%2" SCNu8 "-%2" SCNu16 "T%2" SCNu8 ":%2" SCNu8 ":%fZ", + &year, &month, &day, &hour, &minute, &second); + if (count == 6) { + to->year = year; + to->month = month; + to->day = day; + to->hour = hour; + to->minute = minute; + to->second = second; + to->usecond = (second - floor(second)) * 1000000; + return RETURN_OK; + } - //try Code B (yyyy-ddd) - count = sscanf((char *) from, "%4" SCNu16 "-%3" SCNu16 "T%2" SCNu8 - ":%2" SCNu8 ":%fZ", &year, &day, &hour, &minute, &second); - if (count == 5) { - uint8_t tempDay; - ReturnValue_t result = CCSDSTime::convertDaysOfYear(day, year, &month, - &tempDay); - if (result != RETURN_OK) { - return RETURN_FAILED; - } - to->year = year; - to->month = month; - to->day = tempDay; - to->hour = hour; - to->minute = minute; - to->second = second; - to->usecond = (second - floor(second)) * 1000000; - return RETURN_OK; + // try Code B (yyyy-ddd) + count = sscanf((char*)from, "%4" SCNu16 "-%3" SCNu16 "T%2" SCNu8 ":%2" SCNu8 ":%fZ", &year, &day, + &hour, &minute, &second); + if (count == 5) { + uint8_t tempDay; + ReturnValue_t result = CCSDSTime::convertDaysOfYear(day, year, &month, &tempDay); + if (result != RETURN_OK) { + return RETURN_FAILED; } + to->year = year; + to->month = month; + to->day = tempDay; + to->hour = hour; + to->minute = minute; + to->second = second; + to->usecond = (second - floor(second)) * 1000000; + return RETURN_OK; + } #endif - return UNSUPPORTED_TIME_FORMAT; + return UNSUPPORTED_TIME_FORMAT; } ReturnValue_t CCSDSTime::checkCcs(const uint8_t* time, uint8_t length) { - Ccs_mseconds *time_struct = (Ccs_mseconds *) time; + Ccs_mseconds* time_struct = (Ccs_mseconds*)time; - uint8_t additionalBytes = time_struct->pField & 0b111; - if ((additionalBytes == 0b111) || (length < (additionalBytes + 8))) { - return INVALID_TIME_FORMAT; - } + uint8_t additionalBytes = time_struct->pField & 0b111; + if ((additionalBytes == 0b111) || (length < (additionalBytes + 8))) { + return INVALID_TIME_FORMAT; + } - if (time_struct->pField & (1 << 3)) { //day of year variation - uint16_t day = (time_struct->month << 8) + time_struct->day; - if (day > 366) { - return INVALID_TIME_FORMAT; - } - } else { - if (time_struct->month > 12) { - return INVALID_TIME_FORMAT; - } - if (time_struct->day > 31) { - return INVALID_TIME_FORMAT; - } + if (time_struct->pField & (1 << 3)) { // day of year variation + uint16_t day = (time_struct->month << 8) + time_struct->day; + if (day > 366) { + return INVALID_TIME_FORMAT; } - if (time_struct->hour > 23) { - return INVALID_TIME_FORMAT; + } else { + if (time_struct->month > 12) { + return INVALID_TIME_FORMAT; } - if (time_struct->minute > 59) { - return INVALID_TIME_FORMAT; - } - if (time_struct->second > 59) { - return INVALID_TIME_FORMAT; + if (time_struct->day > 31) { + return INVALID_TIME_FORMAT; } + } + if (time_struct->hour > 23) { + return INVALID_TIME_FORMAT; + } + if (time_struct->minute > 59) { + return INVALID_TIME_FORMAT; + } + if (time_struct->second > 59) { + return INVALID_TIME_FORMAT; + } - uint8_t *additionalByte = &time_struct->secondEminus2; + uint8_t* additionalByte = &time_struct->secondEminus2; - for (; additionalBytes != 0; additionalBytes--) { - if (*additionalByte++ > 99) { - return INVALID_TIME_FORMAT; - } + for (; additionalBytes != 0; additionalBytes--) { + if (*additionalByte++ > 99) { + return INVALID_TIME_FORMAT; } - return RETURN_OK; + } + return RETURN_OK; } -ReturnValue_t CCSDSTime::convertDaysOfYear(uint16_t dayofYear, uint16_t year, - uint8_t* month, uint8_t* day) { - if (isLeapYear(year)) { - if (dayofYear > 366) { - return INVALID_DAY_OF_YEAR; - } - } else { - if (dayofYear > 365) { - return INVALID_DAY_OF_YEAR; - } +ReturnValue_t CCSDSTime::convertDaysOfYear(uint16_t dayofYear, uint16_t year, uint8_t* month, + uint8_t* day) { + if (isLeapYear(year)) { + if (dayofYear > 366) { + return INVALID_DAY_OF_YEAR; } - *month = 1; + } else { + if (dayofYear > 365) { + return INVALID_DAY_OF_YEAR; + } + } + *month = 1; + if (dayofYear <= 31) { + *day = dayofYear; + return RETURN_OK; + } + *month += 1; + dayofYear -= 31; + if (isLeapYear(year)) { + if (dayofYear <= 29) { + *day = dayofYear; + return RETURN_OK; + } + *month += 1; + dayofYear -= 29; + } else { + if (dayofYear <= 28) { + *day = dayofYear; + return RETURN_OK; + } + *month += 1; + dayofYear -= 28; + } + while (*month <= 12) { if (dayofYear <= 31) { - *day = dayofYear; - return RETURN_OK; + *day = dayofYear; + return RETURN_OK; } *month += 1; dayofYear -= 31; - if (isLeapYear(year)) { - if (dayofYear <= 29) { - *day = dayofYear; - return RETURN_OK; - } - *month += 1; - dayofYear -= 29; - } else { - if (dayofYear <= 28) { - *day = dayofYear; - return RETURN_OK; - } - *month += 1; - dayofYear -= 28; - } - while (*month <= 12) { - if (dayofYear <= 31) { - *day = dayofYear; - return RETURN_OK; - } - *month += 1; - dayofYear -= 31; - if (*month == 8) { - continue; - } - - if (dayofYear <= 30) { - *day = dayofYear; - return RETURN_OK; - } - *month += 1; - dayofYear -= 30; + if (*month == 8) { + continue; } - return INVALID_DAY_OF_YEAR; + + if (dayofYear <= 30) { + *day = dayofYear; + return RETURN_OK; + } + *month += 1; + dayofYear -= 30; + } + return INVALID_DAY_OF_YEAR; } bool CCSDSTime::isLeapYear(uint32_t year) { - if ((year % 400) == 0) { - return true; - } - if ((year % 100) == 0) { - return false; - } - if ((year % 4) == 0) { - return true; - } + if ((year % 400) == 0) { + return true; + } + if ((year % 100) == 0) { return false; + } + if ((year % 4) == 0) { + return true; + } + return false; } ReturnValue_t CCSDSTime::convertToCcsds(CDS_short* to, const timeval* from) { - to->pField = (CDS << 4) + 0; - uint32_t days = ((from->tv_sec) / SECONDS_PER_DAY) - + DAYS_CCSDS_TO_UNIX_EPOCH; - if (days > (1 << 16)) { - //Date is beyond year 2137 - return TIME_DOES_NOT_FIT_FORMAT; - } - to->dayMSB = (days & 0xFF00) >> 8; - to->dayLSB = (days & 0xFF); - uint32_t msDay = ((from->tv_sec % SECONDS_PER_DAY) * 1000) - + (from->tv_usec / 1000); - to->msDay_hh = (msDay & 0xFF000000) >> 24; - to->msDay_h = (msDay & 0xFF0000) >> 16; - to->msDay_l = (msDay & 0xFF00) >> 8; - to->msDay_ll = (msDay & 0xFF); - return RETURN_OK; + to->pField = (CDS << 4) + 0; + uint32_t days = ((from->tv_sec) / SECONDS_PER_DAY) + DAYS_CCSDS_TO_UNIX_EPOCH; + if (days > (1 << 16)) { + // Date is beyond year 2137 + return TIME_DOES_NOT_FIT_FORMAT; + } + to->dayMSB = (days & 0xFF00) >> 8; + to->dayLSB = (days & 0xFF); + uint32_t msDay = ((from->tv_sec % SECONDS_PER_DAY) * 1000) + (from->tv_usec / 1000); + to->msDay_hh = (msDay & 0xFF000000) >> 24; + to->msDay_h = (msDay & 0xFF0000) >> 16; + to->msDay_l = (msDay & 0xFF00) >> 8; + to->msDay_ll = (msDay & 0xFF); + return RETURN_OK; } ReturnValue_t CCSDSTime::convertToCcsds(OBT_FLP* to, const timeval* from) { - to->pFiled = (AGENCY_DEFINED << 4) + 5; - to->seconds_hh = (from->tv_sec >> 24) & 0xff; - to->seconds_h = (from->tv_sec >> 16) & 0xff; - to->seconds_l = (from->tv_sec >> 8) & 0xff; - to->seconds_ll = (from->tv_sec >> 0) & 0xff; + to->pFiled = (AGENCY_DEFINED << 4) + 5; + to->seconds_hh = (from->tv_sec >> 24) & 0xff; + to->seconds_h = (from->tv_sec >> 16) & 0xff; + to->seconds_l = (from->tv_sec >> 8) & 0xff; + to->seconds_ll = (from->tv_sec >> 0) & 0xff; - //convert the µs to 2E-16 seconds - uint64_t temp = from->tv_usec; - temp = temp << 16; - temp = temp / 1E6; + // convert the µs to 2E-16 seconds + uint64_t temp = from->tv_usec; + temp = temp << 16; + temp = temp / 1E6; - to->subsecondsMSB = (temp >> 8) & 0xff; - to->subsecondsLSB = temp & 0xff; + to->subsecondsMSB = (temp >> 8) & 0xff; + to->subsecondsLSB = temp & 0xff; - return RETURN_OK; + return RETURN_OK; } -ReturnValue_t CCSDSTime::convertFromCcsds(timeval* to, const uint8_t* from, - size_t* foundLength, size_t maxLength) { - if(maxLength >= 19) { - Clock::TimeOfDay_t timeOfDay; - /* Try to parse it as ASCII */ - ReturnValue_t result = convertFromASCII(&timeOfDay, from, maxLength); - if (result == RETURN_OK) { - return Clock::convertTimeOfDayToTimeval(&timeOfDay, to); - } +ReturnValue_t CCSDSTime::convertFromCcsds(timeval* to, const uint8_t* from, size_t* foundLength, + size_t maxLength) { + if (maxLength >= 19) { + Clock::TimeOfDay_t timeOfDay; + /* Try to parse it as ASCII */ + ReturnValue_t result = convertFromASCII(&timeOfDay, from, maxLength); + if (result == RETURN_OK) { + return Clock::convertTimeOfDayToTimeval(&timeOfDay, to); } + } - uint8_t codeIdentification = (*from >> 4); - switch (codeIdentification) { + uint8_t codeIdentification = (*from >> 4); + switch (codeIdentification) { /* Unsupported, as Leap second correction would have to be applied */ case CUC_LEVEL1: - return UNSUPPORTED_TIME_FORMAT; + return UNSUPPORTED_TIME_FORMAT; case CDS: - return convertFromCDS(to, from, foundLength, maxLength); + return convertFromCDS(to, from, foundLength, maxLength); case CCS: - return convertFromCCS(to, from, foundLength, maxLength); + return convertFromCCS(to, from, foundLength, maxLength); default: - return UNSUPPORTED_TIME_FORMAT; - } - + return UNSUPPORTED_TIME_FORMAT; + } } -ReturnValue_t CCSDSTime::convertFromCUC(timeval* to, const uint8_t* from, - size_t* foundLength, size_t maxLength) { - if (maxLength < 1) { - return INVALID_TIME_FORMAT; +ReturnValue_t CCSDSTime::convertFromCUC(timeval* to, const uint8_t* from, size_t* foundLength, + size_t maxLength) { + if (maxLength < 1) { + return INVALID_TIME_FORMAT; + } + uint8_t pField = *from; + from++; + ReturnValue_t result = convertFromCUC(to, pField, from, foundLength, maxLength - 1); + if (result == HasReturnvaluesIF::RETURN_OK) { + if (foundLength != NULL) { + *foundLength += 1; } - uint8_t pField = *from; - from++; - ReturnValue_t result = convertFromCUC(to, pField, from, foundLength, - maxLength - 1); - if (result == HasReturnvaluesIF::RETURN_OK) { - if (foundLength != NULL) { - *foundLength += 1; - } - } - return result; + } + return result; } ReturnValue_t CCSDSTime::checkTimeOfDay(const Clock::TimeOfDay_t* time) { - if ((time->month > 12) || (time->month == 0)) { - return INVALID_TIME_FORMAT; - } + if ((time->month > 12) || (time->month == 0)) { + return INVALID_TIME_FORMAT; + } - if (time->day == 0) { - return INVALID_TIME_FORMAT; - } - switch (time->month) { + if (time->day == 0) { + return INVALID_TIME_FORMAT; + } + switch (time->month) { case 2: - if (isLeapYear(time->year)) { - if (time->day > 29) { - return INVALID_TIME_FORMAT; - } - } else { - if (time->day > 28) { - return INVALID_TIME_FORMAT; - } + if (isLeapYear(time->year)) { + if (time->day > 29) { + return INVALID_TIME_FORMAT; } - break; + } else { + if (time->day > 28) { + return INVALID_TIME_FORMAT; + } + } + break; case 4: case 6: case 9: case 11: - if (time->day > 30) { - return INVALID_TIME_FORMAT; - } - break; + if (time->day > 30) { + return INVALID_TIME_FORMAT; + } + break; default: - if (time->day > 31) { - return INVALID_TIME_FORMAT; - } - break; - } - - if (time->hour > 23) { + if (time->day > 31) { return INVALID_TIME_FORMAT; - } + } + break; + } - if (time->minute > 59) { - return INVALID_TIME_FORMAT; - } + if (time->hour > 23) { + return INVALID_TIME_FORMAT; + } - if (time->second > 59) { - return INVALID_TIME_FORMAT; - } + if (time->minute > 59) { + return INVALID_TIME_FORMAT; + } - if (time->usecond > 999999) { - return INVALID_TIME_FORMAT; - } + if (time->second > 59) { + return INVALID_TIME_FORMAT; + } - return RETURN_OK; + if (time->usecond > 999999) { + return INVALID_TIME_FORMAT; + } + return RETURN_OK; } -ReturnValue_t CCSDSTime::convertTimevalToTimeOfDay(Clock::TimeOfDay_t* to, - timeval* from) { - //This is rather tricky. Implement only if needed. Also, if so, move to OSAL. - return UNSUPPORTED_TIME_FORMAT; +ReturnValue_t CCSDSTime::convertTimevalToTimeOfDay(Clock::TimeOfDay_t* to, timeval* from) { + // This is rather tricky. Implement only if needed. Also, if so, move to OSAL. + return UNSUPPORTED_TIME_FORMAT; } -ReturnValue_t CCSDSTime::convertFromCDS(timeval* to, const uint8_t* from, - size_t* foundLength, size_t maxLength) { - uint8_t pField = *from; - from++; - //Check epoch - if (pField & 0b1000) { - return NOT_ENOUGH_INFORMATION_FOR_TARGET_FORMAT; +ReturnValue_t CCSDSTime::convertFromCDS(timeval* to, const uint8_t* from, size_t* foundLength, + size_t maxLength) { + uint8_t pField = *from; + from++; + // Check epoch + if (pField & 0b1000) { + return NOT_ENOUGH_INFORMATION_FOR_TARGET_FORMAT; + } + // Check length + uint8_t expectedLength = 7; // Including p-Field. + bool extendedDays = pField & 0b100; + if (extendedDays) { + expectedLength += 1; + } + if ((pField & 0b11) == 0b01) { + expectedLength += 2; + } else if ((pField & 0b11) == 0b10) { + expectedLength += 4; + } + if (foundLength != NULL) { + *foundLength = expectedLength; + } + if (expectedLength > maxLength) { + return LENGTH_MISMATCH; + } + // Check and count days + uint32_t days = 0; + if (extendedDays) { + days = (from[0] << 16) + (from[1] << 8) + from[2]; + from += 3; + } else { + days = (from[0] << 8) + from[1]; + from += 2; + } + // Move to POSIX epoch. + if (days <= DAYS_CCSDS_TO_UNIX_EPOCH) { + return INVALID_TIME_FORMAT; + } + days -= DAYS_CCSDS_TO_UNIX_EPOCH; + to->tv_sec = days * SECONDS_PER_DAY; + uint32_t msDay = (from[0] << 24) + (from[1] << 16) + (from[2] << 8) + from[3]; + from += 4; + to->tv_sec += (msDay / 1000); + to->tv_usec = (msDay % 1000) * 1000; + if ((pField & 0b11) == 0b01) { + uint16_t usecs = (from[0] << 16) + from[1]; + from += 2; + if (usecs > 999) { + return INVALID_TIME_FORMAT; } - //Check length - uint8_t expectedLength = 7; //Including p-Field. - bool extendedDays = pField & 0b100; - if (extendedDays) { - expectedLength += 1; - } - if ((pField & 0b11) == 0b01) { - expectedLength += 2; - } else if ((pField & 0b11) == 0b10) { - expectedLength += 4; - } - if (foundLength != NULL) { - *foundLength = expectedLength; - } - if (expectedLength > maxLength) { - return LENGTH_MISMATCH; - } - //Check and count days - uint32_t days = 0; - if (extendedDays) { - days = (from[0] << 16) + (from[1] << 8) + from[2]; - from += 3; - } else { - days = (from[0] << 8) + from[1]; - from += 2; - } - //Move to POSIX epoch. - if (days <= DAYS_CCSDS_TO_UNIX_EPOCH) { - return INVALID_TIME_FORMAT; - } - days -= DAYS_CCSDS_TO_UNIX_EPOCH; - to->tv_sec = days * SECONDS_PER_DAY; - uint32_t msDay = (from[0] << 24) + (from[1] << 16) + (from[2] << 8) - + from[3]; + to->tv_usec += usecs; + } else if ((pField & 0b11) == 0b10) { + uint32_t picosecs = (from[0] << 24) + (from[1] << 16) + (from[2] << 8) + from[3]; from += 4; - to->tv_sec += (msDay / 1000); - to->tv_usec = (msDay % 1000) * 1000; - if ((pField & 0b11) == 0b01) { - uint16_t usecs = (from[0] << 16) + from[1]; - from += 2; - if (usecs > 999) { - return INVALID_TIME_FORMAT; - } - to->tv_usec += usecs; - } else if ((pField & 0b11) == 0b10) { - uint32_t picosecs = (from[0] << 24) + (from[1] << 16) + (from[2] << 8) - + from[3]; - from += 4; - if (picosecs > 999999) { - return INVALID_TIME_FORMAT; - } - //Not very useful. - to->tv_usec += (picosecs / 1000); + if (picosecs > 999999) { + return INVALID_TIME_FORMAT; } - return RETURN_OK; + // Not very useful. + to->tv_usec += (picosecs / 1000); + } + return RETURN_OK; } -ReturnValue_t CCSDSTime::convertFromCUC(timeval* to, uint8_t pField, - const uint8_t* from, size_t* foundLength, size_t maxLength) { - uint32_t secs = 0; - uint32_t subSeconds = 0; - uint8_t nCoarse = ((pField & 0b1100) >> 2) + 1; - uint8_t nFine = (pField & 0b11); - size_t totalLength = nCoarse + nFine; - if (foundLength != NULL) { - *foundLength = totalLength; - } - if (totalLength > maxLength) { - return LENGTH_MISMATCH; - } - for (int count = 0; count < nCoarse; count++) { - secs += *from << ((nCoarse * 8 - 8) * (1 + count)); - from++; - } - for (int count = 0; count < nFine; count++) { - subSeconds += *from << ((nFine * 8 - 8) * (1 + count)); - from++; - } - //Move to POSIX epoch. - to->tv_sec = secs; - if (pField & 0b10000) { - //CCSDS-Epoch - to->tv_sec -= (DAYS_CCSDS_TO_UNIX_EPOCH * SECONDS_PER_DAY); - } - to->tv_usec = subsecondsToMicroseconds(subSeconds); - return RETURN_OK; +ReturnValue_t CCSDSTime::convertFromCUC(timeval* to, uint8_t pField, const uint8_t* from, + size_t* foundLength, size_t maxLength) { + uint32_t secs = 0; + uint32_t subSeconds = 0; + uint8_t nCoarse = ((pField & 0b1100) >> 2) + 1; + uint8_t nFine = (pField & 0b11); + size_t totalLength = nCoarse + nFine; + if (foundLength != NULL) { + *foundLength = totalLength; + } + if (totalLength > maxLength) { + return LENGTH_MISMATCH; + } + for (int count = 0; count < nCoarse; count++) { + secs += *from << ((nCoarse * 8 - 8) * (1 + count)); + from++; + } + for (int count = 0; count < nFine; count++) { + subSeconds += *from << ((nFine * 8 - 8) * (1 + count)); + from++; + } + // Move to POSIX epoch. + to->tv_sec = secs; + if (pField & 0b10000) { + // CCSDS-Epoch + to->tv_sec -= (DAYS_CCSDS_TO_UNIX_EPOCH * SECONDS_PER_DAY); + } + to->tv_usec = subsecondsToMicroseconds(subSeconds); + return RETURN_OK; } uint32_t CCSDSTime::subsecondsToMicroseconds(uint16_t subseconds) { - uint64_t temp = (uint64_t) subseconds * 1000000 - / (1 << (sizeof(subseconds) * 8)); - return temp; + uint64_t temp = (uint64_t)subseconds * 1000000 / (1 << (sizeof(subseconds) * 8)); + return temp; } -ReturnValue_t CCSDSTime::convertFromCCS(timeval* to, const uint8_t* from, - size_t* foundLength, size_t maxLength) { - Clock::TimeOfDay_t tempTime; - ReturnValue_t result = convertFromCCS(&tempTime, from, foundLength, - maxLength); - if (result != RETURN_OK) { - return result; - } - - return Clock::convertTimeOfDayToTimeval(&tempTime, to); +ReturnValue_t CCSDSTime::convertFromCCS(timeval* to, const uint8_t* from, size_t* foundLength, + size_t maxLength) { + Clock::TimeOfDay_t tempTime; + ReturnValue_t result = convertFromCCS(&tempTime, from, foundLength, maxLength); + if (result != RETURN_OK) { + return result; + } + return Clock::convertTimeOfDayToTimeval(&tempTime, to); } diff --git a/src/fsfw/timemanager/CCSDSTime.h b/src/fsfw/timemanager/CCSDSTime.h index de151852..4a0e1bfc 100644 --- a/src/fsfw/timemanager/CCSDSTime.h +++ b/src/fsfw/timemanager/CCSDSTime.h @@ -3,15 +3,16 @@ // COULDDO: have calls in Clock.h which return time quality and use timespec accordingly +#include +#include + +#include "../returnvalues/HasReturnvaluesIF.h" #include "Clock.h" #include "clockDefinitions.h" -#include "../returnvalues/HasReturnvaluesIF.h" -#include -#include -bool operator<(const timeval& lhs, const timeval& rhs); -bool operator<=(const timeval& lhs, const timeval& rhs); -bool operator==(const timeval& lhs, const timeval& rhs); +bool operator<(const timeval &lhs, const timeval &rhs); +bool operator<=(const timeval &lhs, const timeval &rhs); +bool operator==(const timeval &lhs, const timeval &rhs); /** * static helper class for CCSDS Time Code Formats * @@ -19,217 +20,208 @@ bool operator==(const timeval& lhs, const timeval& rhs); * * Still work in progress */ -class CCSDSTime: public HasReturnvaluesIF { -public: - /** - * The Time code identifications, bits 4-6 in the P-Field - */ - enum TimeCodeIdentification { - CCS = 0b101, - CUC_LEVEL1 = 0b001, - CUC_LEVEL2 = 0b010, - CDS = 0b100, - AGENCY_DEFINED = 0b110 - }; - static const uint8_t P_FIELD_CUC_6B_CCSDS = (CUC_LEVEL1 << 4) + (3 << 2) - + 2; - static const uint8_t P_FIELD_CUC_6B_AGENCY = (CUC_LEVEL2 << 4) + (3 << 2) - + 2; - static const uint8_t P_FIELD_CDS_SHORT = (CDS << 4); - /** - * Struct for CDS day-segmented format. - */ - struct CDS_short { - uint8_t pField; - uint8_t dayMSB; - uint8_t dayLSB; - uint8_t msDay_hh; - uint8_t msDay_h; - uint8_t msDay_l; - uint8_t msDay_ll; - }; - /** - * Struct for the CCS fromat in day of month variation with max resolution - */ - struct Ccs_seconds { - uint8_t pField; - uint8_t yearMSB; - uint8_t yearLSB; - uint8_t month; - uint8_t day; - uint8_t hour; - uint8_t minute; - uint8_t second; - }; +class CCSDSTime : public HasReturnvaluesIF { + public: + /** + * The Time code identifications, bits 4-6 in the P-Field + */ + enum TimeCodeIdentification { + CCS = 0b101, + CUC_LEVEL1 = 0b001, + CUC_LEVEL2 = 0b010, + CDS = 0b100, + AGENCY_DEFINED = 0b110 + }; + static const uint8_t P_FIELD_CUC_6B_CCSDS = (CUC_LEVEL1 << 4) + (3 << 2) + 2; + static const uint8_t P_FIELD_CUC_6B_AGENCY = (CUC_LEVEL2 << 4) + (3 << 2) + 2; + static const uint8_t P_FIELD_CDS_SHORT = (CDS << 4); + /** + * Struct for CDS day-segmented format. + */ + struct CDS_short { + uint8_t pField; + uint8_t dayMSB; + uint8_t dayLSB; + uint8_t msDay_hh; + uint8_t msDay_h; + uint8_t msDay_l; + uint8_t msDay_ll; + }; + /** + * Struct for the CCS fromat in day of month variation with max resolution + */ + struct Ccs_seconds { + uint8_t pField; + uint8_t yearMSB; + uint8_t yearLSB; + uint8_t month; + uint8_t day; + uint8_t hour; + uint8_t minute; + uint8_t second; + }; - /** - * Struct for the CCS fromat in day of month variation with 10E-4 seconds resolution - */ - struct Ccs_mseconds { - uint8_t pField; - uint8_t yearMSB; - uint8_t yearLSB; - uint8_t month; - uint8_t day; - uint8_t hour; - uint8_t minute; - uint8_t second; - uint8_t secondEminus2; - uint8_t secondEminus4; - }; + /** + * Struct for the CCS fromat in day of month variation with 10E-4 seconds resolution + */ + struct Ccs_mseconds { + uint8_t pField; + uint8_t yearMSB; + uint8_t yearLSB; + uint8_t month; + uint8_t day; + uint8_t hour; + uint8_t minute; + uint8_t second; + uint8_t secondEminus2; + uint8_t secondEminus4; + }; - struct OBT_FLP { - uint8_t pFiled; - uint8_t seconds_hh; - uint8_t seconds_h; - uint8_t seconds_l; - uint8_t seconds_ll; - uint8_t subsecondsMSB; - uint8_t subsecondsLSB; - }; + struct OBT_FLP { + uint8_t pFiled; + uint8_t seconds_hh; + uint8_t seconds_h; + uint8_t seconds_l; + uint8_t seconds_ll; + uint8_t subsecondsMSB; + uint8_t subsecondsLSB; + }; - struct TimevalLess { - bool operator()(const timeval& lhs, const timeval& rhs) const { - return (lhs < rhs); - } - }; + struct TimevalLess { + bool operator()(const timeval &lhs, const timeval &rhs) const { return (lhs < rhs); } + }; - static const uint8_t INTERFACE_ID = CLASS_ID::CCSDS_TIME_HELPER_CLASS; - static const ReturnValue_t UNSUPPORTED_TIME_FORMAT = MAKE_RETURN_CODE(0); - static const ReturnValue_t NOT_ENOUGH_INFORMATION_FOR_TARGET_FORMAT = - MAKE_RETURN_CODE(1); - static const ReturnValue_t LENGTH_MISMATCH = MAKE_RETURN_CODE(2); - static const ReturnValue_t INVALID_TIME_FORMAT = MAKE_RETURN_CODE(3); - static const ReturnValue_t INVALID_DAY_OF_YEAR = MAKE_RETURN_CODE(4); - static const ReturnValue_t TIME_DOES_NOT_FIT_FORMAT = MAKE_RETURN_CODE(5); + static const uint8_t INTERFACE_ID = CLASS_ID::CCSDS_TIME_HELPER_CLASS; + static const ReturnValue_t UNSUPPORTED_TIME_FORMAT = MAKE_RETURN_CODE(0); + static const ReturnValue_t NOT_ENOUGH_INFORMATION_FOR_TARGET_FORMAT = MAKE_RETURN_CODE(1); + static const ReturnValue_t LENGTH_MISMATCH = MAKE_RETURN_CODE(2); + static const ReturnValue_t INVALID_TIME_FORMAT = MAKE_RETURN_CODE(3); + static const ReturnValue_t INVALID_DAY_OF_YEAR = MAKE_RETURN_CODE(4); + static const ReturnValue_t TIME_DOES_NOT_FIT_FORMAT = MAKE_RETURN_CODE(5); - /** - * convert a TimeofDay struct to ccs with seconds resolution - * - * @param to pointer to a CCS struct - * @param from pointer to a TimeOfDay Struct - * @return - * - @c RETURN_OK if OK - * - @c INVALID_TIMECODE if not OK - */ - static ReturnValue_t convertToCcsds(Ccs_seconds *to, - Clock::TimeOfDay_t const *from); + /** + * convert a TimeofDay struct to ccs with seconds resolution + * + * @param to pointer to a CCS struct + * @param from pointer to a TimeOfDay Struct + * @return + * - @c RETURN_OK if OK + * - @c INVALID_TIMECODE if not OK + */ + static ReturnValue_t convertToCcsds(Ccs_seconds *to, Clock::TimeOfDay_t const *from); - /** - * Converts to CDS format from timeval. - * @param to pointer to the CDS struct to generate - * @param from pointer to a timeval struct which comprises a time of day since UNIX epoch. - * @return - * - @c RETURN_OK as it assumes a valid timeval. - */ - static ReturnValue_t convertToCcsds(CDS_short* to, timeval const *from); + /** + * Converts to CDS format from timeval. + * @param to pointer to the CDS struct to generate + * @param from pointer to a timeval struct which comprises a time of day since UNIX epoch. + * @return + * - @c RETURN_OK as it assumes a valid timeval. + */ + static ReturnValue_t convertToCcsds(CDS_short *to, timeval const *from); - static ReturnValue_t convertToCcsds(OBT_FLP* to, timeval const *from); + static ReturnValue_t convertToCcsds(OBT_FLP *to, timeval const *from); - /** - * convert a TimeofDay struct to ccs with 10E-3 seconds resolution - * - * The 10E-4 seconds in the CCS Struct are 0 as the TimeOfDay only has ms resolution - * - * @param to pointer to a CCS struct - * @param from pointer to a TimeOfDay Struct - * @return - * - @c RETURN_OK if OK - * - @c INVALID_TIMECODE if not OK - */ - static ReturnValue_t convertToCcsds(Ccs_mseconds *to, - Clock::TimeOfDay_t const *from); + /** + * convert a TimeofDay struct to ccs with 10E-3 seconds resolution + * + * The 10E-4 seconds in the CCS Struct are 0 as the TimeOfDay only has ms resolution + * + * @param to pointer to a CCS struct + * @param from pointer to a TimeOfDay Struct + * @return + * - @c RETURN_OK if OK + * - @c INVALID_TIMECODE if not OK + */ + static ReturnValue_t convertToCcsds(Ccs_mseconds *to, Clock::TimeOfDay_t const *from); - /** - * SHOULDDO: can this be modified to recognize padding? - * Tries to interpret a Level 1 CCSDS time code - * - * It assumes binary formats contain a valid P Field and recognizes the ASCII format - * by the lack of one. - * - * @param to an empty TimeOfDay struct - * @param from pointer to an CCSDS Time code - * @param length length of the Time code - * @return - * - @c RETURN_OK if successful - * - @c UNSUPPORTED_TIME_FORMAT if a (possibly valid) time code is not supported - * - @c LENGTH_MISMATCH if the length does not match the P Field - * - @c INVALID_TIME_FORMAT if the format or a value is invalid - */ - static ReturnValue_t convertFromCcsds(Clock::TimeOfDay_t *to, - uint8_t const *from, size_t length); + /** + * SHOULDDO: can this be modified to recognize padding? + * Tries to interpret a Level 1 CCSDS time code + * + * It assumes binary formats contain a valid P Field and recognizes the ASCII format + * by the lack of one. + * + * @param to an empty TimeOfDay struct + * @param from pointer to an CCSDS Time code + * @param length length of the Time code + * @return + * - @c RETURN_OK if successful + * - @c UNSUPPORTED_TIME_FORMAT if a (possibly valid) time code is not supported + * - @c LENGTH_MISMATCH if the length does not match the P Field + * - @c INVALID_TIME_FORMAT if the format or a value is invalid + */ + static ReturnValue_t convertFromCcsds(Clock::TimeOfDay_t *to, uint8_t const *from, size_t length); - /** - * not implemented yet - * - * @param to - * @param from - * @return - */ - static ReturnValue_t convertFromCcsds(timeval *to, uint8_t const *from, - size_t* foundLength, size_t maxLength); + /** + * not implemented yet + * + * @param to + * @param from + * @return + */ + static ReturnValue_t convertFromCcsds(timeval *to, uint8_t const *from, size_t *foundLength, + size_t maxLength); - static ReturnValue_t convertFromCUC(Clock::TimeOfDay_t *to, - uint8_t const *from, uint8_t length); + static ReturnValue_t convertFromCUC(Clock::TimeOfDay_t *to, uint8_t const *from, uint8_t length); - static ReturnValue_t convertFromCUC(timeval *to, uint8_t const *from, - size_t* foundLength, size_t maxLength); + static ReturnValue_t convertFromCUC(timeval *to, uint8_t const *from, size_t *foundLength, + size_t maxLength); - static ReturnValue_t convertFromCUC(timeval *to, uint8_t pField, - uint8_t const *from, size_t* foundLength, size_t maxLength); + static ReturnValue_t convertFromCUC(timeval *to, uint8_t pField, uint8_t const *from, + size_t *foundLength, size_t maxLength); - static ReturnValue_t convertFromCCS(timeval *to, uint8_t const *from, - size_t* foundLength, size_t maxLength); + static ReturnValue_t convertFromCCS(timeval *to, uint8_t const *from, size_t *foundLength, + size_t maxLength); - static ReturnValue_t convertFromCCS(timeval *to, uint8_t pField, - uint8_t const *from, size_t* foundLength, size_t maxLength); + static ReturnValue_t convertFromCCS(timeval *to, uint8_t pField, uint8_t const *from, + size_t *foundLength, size_t maxLength); - static ReturnValue_t convertFromCDS(Clock::TimeOfDay_t *to, - uint8_t const *from, uint8_t length); + static ReturnValue_t convertFromCDS(Clock::TimeOfDay_t *to, uint8_t const *from, uint8_t length); - static ReturnValue_t convertFromCDS(timeval *to, uint8_t const *from, - size_t* foundLength, size_t maxLength); + static ReturnValue_t convertFromCDS(timeval *to, uint8_t const *from, size_t *foundLength, + size_t maxLength); - static ReturnValue_t convertFromCCS(Clock::TimeOfDay_t *to, - uint8_t const *from, size_t* foundLength, size_t maxLength); + static ReturnValue_t convertFromCCS(Clock::TimeOfDay_t *to, uint8_t const *from, + size_t *foundLength, size_t maxLength); - static ReturnValue_t convertFromASCII(Clock::TimeOfDay_t *to, - uint8_t const *from, uint8_t length); + static ReturnValue_t convertFromASCII(Clock::TimeOfDay_t *to, uint8_t const *from, + uint8_t length); - static uint32_t subsecondsToMicroseconds(uint16_t subseconds); -private: - CCSDSTime(); - virtual ~CCSDSTime(); - /** - * checks a ccs time stream for validity - * - * Stream may be longer than the actual timecode - * - * @param time pointer to an Ccs stream - * @param length length of stream - * @return - */ - static ReturnValue_t checkCcs(const uint8_t* time, uint8_t length); + static uint32_t subsecondsToMicroseconds(uint16_t subseconds); - static ReturnValue_t checkTimeOfDay(const Clock::TimeOfDay_t *time); + private: + CCSDSTime(); + virtual ~CCSDSTime(); + /** + * checks a ccs time stream for validity + * + * Stream may be longer than the actual timecode + * + * @param time pointer to an Ccs stream + * @param length length of stream + * @return + */ + static ReturnValue_t checkCcs(const uint8_t *time, uint8_t length); - static const uint32_t SECONDS_PER_DAY = 24 * 60 * 60; - static const uint32_t SECONDS_PER_NON_LEAP_YEAR = SECONDS_PER_DAY * 365; - static const uint32_t DAYS_CCSDS_TO_UNIX_EPOCH = 4383; //!< Time difference between CCSDS and POSIX epoch. This is exact, because leap-seconds where not introduced before 1972. - static const uint32_t SECONDS_CCSDS_TO_UNIX_EPOCH = DAYS_CCSDS_TO_UNIX_EPOCH - * SECONDS_PER_DAY; - /** - * @param dayofYear - * @param year - * @param month - * @param day - */ - static ReturnValue_t convertDaysOfYear(uint16_t dayofYear, uint16_t year, - uint8_t *month, uint8_t *day); + static ReturnValue_t checkTimeOfDay(const Clock::TimeOfDay_t *time); - static bool isLeapYear(uint32_t year); - static ReturnValue_t convertTimevalToTimeOfDay(Clock::TimeOfDay_t* to, - timeval* from); + static const uint32_t SECONDS_PER_DAY = 24 * 60 * 60; + static const uint32_t SECONDS_PER_NON_LEAP_YEAR = SECONDS_PER_DAY * 365; + static const uint32_t DAYS_CCSDS_TO_UNIX_EPOCH = + 4383; //!< Time difference between CCSDS and POSIX epoch. This is exact, because leap-seconds + //!< where not introduced before 1972. + static const uint32_t SECONDS_CCSDS_TO_UNIX_EPOCH = DAYS_CCSDS_TO_UNIX_EPOCH * SECONDS_PER_DAY; + /** + * @param dayofYear + * @param year + * @param month + * @param day + */ + static ReturnValue_t convertDaysOfYear(uint16_t dayofYear, uint16_t year, uint8_t *month, + uint8_t *day); + + static bool isLeapYear(uint32_t year); + static ReturnValue_t convertTimevalToTimeOfDay(Clock::TimeOfDay_t *to, timeval *from); }; #endif /* FSFW_TIMEMANAGER_CCSDSTIME_H_ */ diff --git a/src/fsfw/timemanager/Clock.h b/src/fsfw/timemanager/Clock.h index b1d6bfaf..99e8a56a 100644 --- a/src/fsfw/timemanager/Clock.h +++ b/src/fsfw/timemanager/Clock.h @@ -1,13 +1,13 @@ #ifndef FSFW_TIMEMANAGER_CLOCK_H_ #define FSFW_TIMEMANAGER_CLOCK_H_ -#include "clockDefinitions.h" -#include "fsfw/returnvalues/HasReturnvaluesIF.h" -#include "fsfw/ipc/MutexFactory.h" -#include "fsfw/globalfunctions/timevalOperations.h" - #include +#include "clockDefinitions.h" +#include "fsfw/globalfunctions/timevalOperations.h" +#include "fsfw/ipc/MutexFactory.h" +#include "fsfw/returnvalues/HasReturnvaluesIF.h" + #ifdef WIN32 #include #else @@ -15,158 +15,157 @@ #endif class Clock { -public: - typedef struct { - uint32_t year; //!< Year, A.D. - uint32_t month; //!< Month, 1 .. 12. - uint32_t day; //!< Day, 1 .. 31. - uint32_t hour; //!< Hour, 0 .. 23. - uint32_t minute; //!< Minute, 0 .. 59. - uint32_t second; //!< Second, 0 .. 59. - uint32_t usecond; //!< Microseconds, 0 .. 999999 - } TimeOfDay_t; + public: + typedef struct { + uint32_t year; //!< Year, A.D. + uint32_t month; //!< Month, 1 .. 12. + uint32_t day; //!< Day, 1 .. 31. + uint32_t hour; //!< Hour, 0 .. 23. + uint32_t minute; //!< Minute, 0 .. 59. + uint32_t second; //!< Second, 0 .. 59. + uint32_t usecond; //!< Microseconds, 0 .. 999999 + } TimeOfDay_t; - /** - * This method returns the number of clock ticks per second. - * In RTEMS, this is typically 1000. - * @return The number of ticks. - * - * @deprecated, we should not worry about ticks, but only time - */ - static uint32_t getTicksPerSecond(void); - /** - * This system call sets the system time. - * To set the time, it uses a TimeOfDay_t struct. - * @param time The struct with the time settings to set. - * @return -@c RETURN_OK on success. Otherwise, the OS failure code - * is returned. - */ - static ReturnValue_t setClock(const TimeOfDay_t *time); - /** - * This system call sets the system time. - * To set the time, it uses a timeval struct. - * @param time The struct with the time settings to set. - * @return -@c RETURN_OK on success. Otherwise, the OS failure code is returned. - */ - static ReturnValue_t setClock(const timeval *time); - /** - * This system call returns the current system clock in timeval format. - * The timval format has the fields @c tv_sec with seconds and @c tv_usec with - * microseconds since an OS-defined epoch. - * @param time A pointer to a timeval struct where the current time is stored. - * @return @c RETURN_OK on success. Otherwise, the OS failure code is returned. - */ - static ReturnValue_t getClock_timeval(timeval *time); + /** + * This method returns the number of clock ticks per second. + * In RTEMS, this is typically 1000. + * @return The number of ticks. + * + * @deprecated, we should not worry about ticks, but only time + */ + static uint32_t getTicksPerSecond(void); + /** + * This system call sets the system time. + * To set the time, it uses a TimeOfDay_t struct. + * @param time The struct with the time settings to set. + * @return -@c RETURN_OK on success. Otherwise, the OS failure code + * is returned. + */ + static ReturnValue_t setClock(const TimeOfDay_t *time); + /** + * This system call sets the system time. + * To set the time, it uses a timeval struct. + * @param time The struct with the time settings to set. + * @return -@c RETURN_OK on success. Otherwise, the OS failure code is returned. + */ + static ReturnValue_t setClock(const timeval *time); + /** + * This system call returns the current system clock in timeval format. + * The timval format has the fields @c tv_sec with seconds and @c tv_usec with + * microseconds since an OS-defined epoch. + * @param time A pointer to a timeval struct where the current time is stored. + * @return @c RETURN_OK on success. Otherwise, the OS failure code is returned. + */ + static ReturnValue_t getClock_timeval(timeval *time); - /** - * Get the time since boot in a timeval struct - * - * @param[out] time A pointer to a timeval struct where the uptime is stored. - * @return @c RETURN_OK on success. Otherwise, the OS failure code is returned. - * - * @deprecated, I do not think this should be able to fail, use timeval getUptime() - */ - static ReturnValue_t getUptime(timeval *uptime); + /** + * Get the time since boot in a timeval struct + * + * @param[out] time A pointer to a timeval struct where the uptime is stored. + * @return @c RETURN_OK on success. Otherwise, the OS failure code is returned. + * + * @deprecated, I do not think this should be able to fail, use timeval getUptime() + */ + static ReturnValue_t getUptime(timeval *uptime); - static timeval getUptime(); + static timeval getUptime(); - /** - * Get the time since boot in milliseconds - * - * This value can overflow! Still, it can be used to calculate time intervalls - * between two calls up to 49 days by always using uint32_t in the calculation - * - * @param ms uptime in ms - * @return RETURN_OK on success. Otherwise, the OS failure code is returned. - */ - static ReturnValue_t getUptime(uint32_t *uptimeMs); + /** + * Get the time since boot in milliseconds + * + * This value can overflow! Still, it can be used to calculate time intervalls + * between two calls up to 49 days by always using uint32_t in the calculation + * + * @param ms uptime in ms + * @return RETURN_OK on success. Otherwise, the OS failure code is returned. + */ + static ReturnValue_t getUptime(uint32_t *uptimeMs); - /** - * Returns the time in microseconds since an OS-defined epoch. - * The time is returned in a 64 bit unsigned integer. - * @param time A pointer to a 64 bit unisigned integer where the data is stored. - * @return - * - @c RETURN_OK on success. - * - Otherwise, the OS failure code is returned. - */ - static ReturnValue_t getClock_usecs(uint64_t *time); - /** - * Returns the time in a TimeOfDay_t struct. - * @param time A pointer to a TimeOfDay_t struct. - * @return - * - @c RETURN_OK on success. - * - Otherwise, the OS failure code is returned. - */ - static ReturnValue_t getDateAndTime(TimeOfDay_t *time); + /** + * Returns the time in microseconds since an OS-defined epoch. + * The time is returned in a 64 bit unsigned integer. + * @param time A pointer to a 64 bit unisigned integer where the data is stored. + * @return + * - @c RETURN_OK on success. + * - Otherwise, the OS failure code is returned. + */ + static ReturnValue_t getClock_usecs(uint64_t *time); + /** + * Returns the time in a TimeOfDay_t struct. + * @param time A pointer to a TimeOfDay_t struct. + * @return + * - @c RETURN_OK on success. + * - Otherwise, the OS failure code is returned. + */ + static ReturnValue_t getDateAndTime(TimeOfDay_t *time); - /** - * Converts a time of day struct to POSIX seconds. - * @param time The time of day as input - * @param timeval The corresponding seconds since the epoch. - * @return - * - @c RETURN_OK on success. - * - Otherwise, the OS failure code is returned. - */ - static ReturnValue_t convertTimeOfDayToTimeval(const TimeOfDay_t *from, - timeval *to); + /** + * Converts a time of day struct to POSIX seconds. + * @param time The time of day as input + * @param timeval The corresponding seconds since the epoch. + * @return + * - @c RETURN_OK on success. + * - Otherwise, the OS failure code is returned. + */ + static ReturnValue_t convertTimeOfDayToTimeval(const TimeOfDay_t *from, timeval *to); - /** - * Converts a time represented as seconds and subseconds since unix - * epoch to days since J2000 - * - * @param time seconds since unix epoch - * @param[out] JD2000 days since J2000 - * @return @c RETURN_OK - */ - static ReturnValue_t convertTimevalToJD2000(timeval time, double *JD2000); + /** + * Converts a time represented as seconds and subseconds since unix + * epoch to days since J2000 + * + * @param time seconds since unix epoch + * @param[out] JD2000 days since J2000 + * @return @c RETURN_OK + */ + static ReturnValue_t convertTimevalToJD2000(timeval time, double *JD2000); - /** - * Calculates and adds the offset between UTC and TT - * - * Depends on the leap seconds to be set correctly. - * Therefore, it does not work for historic - * dates as only the current leap seconds are known. - * - * @param utc timeval, corresponding to UTC time - * @param[out] tt timeval, corresponding to Terrestial Time - * @return - * - @c RETURN_OK on success - * - @c RETURN_FAILED if leapSeconds are not set - */ - static ReturnValue_t convertUTCToTT(timeval utc, timeval *tt); + /** + * Calculates and adds the offset between UTC and TT + * + * Depends on the leap seconds to be set correctly. + * Therefore, it does not work for historic + * dates as only the current leap seconds are known. + * + * @param utc timeval, corresponding to UTC time + * @param[out] tt timeval, corresponding to Terrestial Time + * @return + * - @c RETURN_OK on success + * - @c RETURN_FAILED if leapSeconds are not set + */ + static ReturnValue_t convertUTCToTT(timeval utc, timeval *tt); - /** - * Set the Leap Seconds since 1972 - * - * @param leapSeconds_ - * @return - * - @c RETURN_OK on success. - */ - static ReturnValue_t setLeapSeconds(const uint16_t leapSeconds_); + /** + * Set the Leap Seconds since 1972 + * + * @param leapSeconds_ + * @return + * - @c RETURN_OK on success. + */ + static ReturnValue_t setLeapSeconds(const uint16_t leapSeconds_); - /** - * Get the Leap Seconds since 1972 - * - * Setter must be called before - * - * @param[out] leapSeconds_ - * @return - * - @c RETURN_OK on success. - * - @c RETURN_FAILED on error - */ - static ReturnValue_t getLeapSeconds(uint16_t *leapSeconds_); + /** + * Get the Leap Seconds since 1972 + * + * Setter must be called before + * + * @param[out] leapSeconds_ + * @return + * - @c RETURN_OK on success. + * - @c RETURN_FAILED on error + */ + static ReturnValue_t getLeapSeconds(uint16_t *leapSeconds_); -private: - /** - * Function to check and create the Mutex for the clock - * @return - * - @c RETURN_OK on success. - * - Otherwise @c RETURN_FAILED if not able to create one - */ - static ReturnValue_t checkOrCreateClockMutex(); + private: + /** + * Function to check and create the Mutex for the clock + * @return + * - @c RETURN_OK on success. + * - Otherwise @c RETURN_FAILED if not able to create one + */ + static ReturnValue_t checkOrCreateClockMutex(); - static MutexIF *timeMutex; - static uint16_t leapSeconds; + static MutexIF *timeMutex; + static uint16_t leapSeconds; }; #endif /* FSFW_TIMEMANAGER_CLOCK_H_ */ diff --git a/src/fsfw/timemanager/ClockCommon.cpp b/src/fsfw/timemanager/ClockCommon.cpp index 82c65b96..e5749b19 100644 --- a/src/fsfw/timemanager/ClockCommon.cpp +++ b/src/fsfw/timemanager/ClockCommon.cpp @@ -1,57 +1,57 @@ -#include "fsfw/timemanager/Clock.h" #include "fsfw/ipc/MutexGuard.h" +#include "fsfw/timemanager/Clock.h" ReturnValue_t Clock::convertUTCToTT(timeval utc, timeval *tt) { - uint16_t leapSeconds; - ReturnValue_t result = getLeapSeconds(&leapSeconds); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - timeval leapSeconds_timeval = { 0, 0 }; - leapSeconds_timeval.tv_sec = leapSeconds; + uint16_t leapSeconds; + ReturnValue_t result = getLeapSeconds(&leapSeconds); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + timeval leapSeconds_timeval = {0, 0}; + leapSeconds_timeval.tv_sec = leapSeconds; - //initial offset between UTC and TAI - timeval UTCtoTAI1972 = { 10, 0 }; + // initial offset between UTC and TAI + timeval UTCtoTAI1972 = {10, 0}; - timeval TAItoTT = { 32, 184000 }; + timeval TAItoTT = {32, 184000}; - *tt = utc + leapSeconds_timeval + UTCtoTAI1972 + TAItoTT; + *tt = utc + leapSeconds_timeval + UTCtoTAI1972 + TAItoTT; - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t Clock::setLeapSeconds(const uint16_t leapSeconds_) { - if (checkOrCreateClockMutex() != HasReturnvaluesIF::RETURN_OK) { - return HasReturnvaluesIF::RETURN_FAILED; - } - MutexGuard helper(timeMutex); + if (checkOrCreateClockMutex() != HasReturnvaluesIF::RETURN_OK) { + return HasReturnvaluesIF::RETURN_FAILED; + } + MutexGuard helper(timeMutex); - leapSeconds = leapSeconds_; + leapSeconds = leapSeconds_; - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t Clock::getLeapSeconds(uint16_t *leapSeconds_) { - if (timeMutex == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - MutexGuard helper(timeMutex); + if (timeMutex == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + MutexGuard helper(timeMutex); - *leapSeconds_ = leapSeconds; + *leapSeconds_ = leapSeconds; - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t Clock::checkOrCreateClockMutex() { - if (timeMutex == nullptr) { - MutexFactory *mutexFactory = MutexFactory::instance(); - if (mutexFactory == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - timeMutex = mutexFactory->createMutex(); - if (timeMutex == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - } - return HasReturnvaluesIF::RETURN_OK; + if (timeMutex == nullptr) { + MutexFactory *mutexFactory = MutexFactory::instance(); + if (mutexFactory == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + timeMutex = mutexFactory->createMutex(); + if (timeMutex == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + } + return HasReturnvaluesIF::RETURN_OK; } diff --git a/src/fsfw/timemanager/Countdown.cpp b/src/fsfw/timemanager/Countdown.cpp index 23d57477..8ff46f8d 100644 --- a/src/fsfw/timemanager/Countdown.cpp +++ b/src/fsfw/timemanager/Countdown.cpp @@ -1,51 +1,43 @@ #include "fsfw/timemanager/Countdown.h" -Countdown::Countdown(uint32_t initialTimeout): timeout(initialTimeout) { -} +Countdown::Countdown(uint32_t initialTimeout) : timeout(initialTimeout) {} -Countdown::~Countdown() { -} +Countdown::~Countdown() {} ReturnValue_t Countdown::setTimeout(uint32_t milliseconds) { - ReturnValue_t returnValue = Clock::getUptime( &startTime ); - timeout = milliseconds; - return returnValue; + ReturnValue_t returnValue = Clock::getUptime(&startTime); + timeout = milliseconds; + return returnValue; } bool Countdown::hasTimedOut() const { - if ( uint32_t( this->getCurrentTime() - startTime) >= timeout) { - return true; - } else { - return false; - } + if (uint32_t(this->getCurrentTime() - startTime) >= timeout) { + return true; + } else { + return false; + } } -bool Countdown::isBusy() const { - return !hasTimedOut(); -} +bool Countdown::isBusy() const { return !hasTimedOut(); } -ReturnValue_t Countdown::resetTimer() { - return setTimeout(timeout); -} +ReturnValue_t Countdown::resetTimer() { return setTimeout(timeout); } -void Countdown::timeOut() { - startTime = this->getCurrentTime() - timeout; -} +void Countdown::timeOut() { startTime = this->getCurrentTime() - timeout; } uint32_t Countdown::getRemainingMillis() const { - // We fetch the time before the if-statement - // to be sure that the return is in - // range 0 <= number <= timeout - uint32_t currentTime = this->getCurrentTime(); - if (this->hasTimedOut()){ - return 0; - }else{ - return (startTime + timeout) - currentTime; - } + // We fetch the time before the if-statement + // to be sure that the return is in + // range 0 <= number <= timeout + uint32_t currentTime = this->getCurrentTime(); + if (this->hasTimedOut()) { + return 0; + } else { + return (startTime + timeout) - currentTime; + } } uint32_t Countdown::getCurrentTime() const { - uint32_t currentTime; - Clock::getUptime( ¤tTime ); - return currentTime; + uint32_t currentTime; + Clock::getUptime(¤tTime); + return currentTime; } diff --git a/src/fsfw/timemanager/Countdown.h b/src/fsfw/timemanager/Countdown.h index c0afdf75..44be2b1a 100644 --- a/src/fsfw/timemanager/Countdown.h +++ b/src/fsfw/timemanager/Countdown.h @@ -17,64 +17,65 @@ * */ class Countdown { -public: - /** - * Constructor which sets the countdown duration in milliseconds - * - * It does not start the countdown! - * Call resetTimer or setTimeout before usage! - * Otherwise a call to hasTimedOut might return True. - * - * @param initialTimeout Countdown duration in milliseconds - */ - Countdown(uint32_t initialTimeout = 0); - ~Countdown(); - /** - * Call to set a new countdown duration. - * - * Resets the countdown! - * - * @param milliseconds new countdown duration in milliseconds - * @return Returnvalue from Clock::getUptime - */ - ReturnValue_t setTimeout(uint32_t milliseconds); - /** - * Returns true if the countdown duration has passed. - * - * @return True if the countdown has passed - * False if it is still running - */ - bool hasTimedOut() const; - /** - * Complementary to hasTimedOut. - * - * @return True if the countdown is till running - * False if it is still running - */ - bool isBusy() const; - /** - * Uses last set timeout value and restarts timer. - */ - ReturnValue_t resetTimer(); - /** - * Returns the remaining milliseconds (0 if timeout) - */ - uint32_t getRemainingMillis() const; - /** - * Makes hasTimedOut() return true - */ - void timeOut(); - /** - * Internal countdown duration in milliseconds - */ - uint32_t timeout; -private: - /** - * Last time the timer was started (uptime) - */ - uint32_t startTime = 0; + public: + /** + * Constructor which sets the countdown duration in milliseconds + * + * It does not start the countdown! + * Call resetTimer or setTimeout before usage! + * Otherwise a call to hasTimedOut might return True. + * + * @param initialTimeout Countdown duration in milliseconds + */ + Countdown(uint32_t initialTimeout = 0); + ~Countdown(); + /** + * Call to set a new countdown duration. + * + * Resets the countdown! + * + * @param milliseconds new countdown duration in milliseconds + * @return Returnvalue from Clock::getUptime + */ + ReturnValue_t setTimeout(uint32_t milliseconds); + /** + * Returns true if the countdown duration has passed. + * + * @return True if the countdown has passed + * False if it is still running + */ + bool hasTimedOut() const; + /** + * Complementary to hasTimedOut. + * + * @return True if the countdown is till running + * False if it is still running + */ + bool isBusy() const; + /** + * Uses last set timeout value and restarts timer. + */ + ReturnValue_t resetTimer(); + /** + * Returns the remaining milliseconds (0 if timeout) + */ + uint32_t getRemainingMillis() const; + /** + * Makes hasTimedOut() return true + */ + void timeOut(); + /** + * Internal countdown duration in milliseconds + */ + uint32_t timeout; - uint32_t getCurrentTime() const; + private: + /** + * Last time the timer was started (uptime) + */ + uint32_t startTime = 0; + + uint32_t getCurrentTime() const; }; #endif /* FSFW_TIMEMANAGER_COUNTDOWN_H_ */ diff --git a/src/fsfw/timemanager/ReceivesTimeInfoIF.h b/src/fsfw/timemanager/ReceivesTimeInfoIF.h index c1247a42..5fb915ae 100644 --- a/src/fsfw/timemanager/ReceivesTimeInfoIF.h +++ b/src/fsfw/timemanager/ReceivesTimeInfoIF.h @@ -8,19 +8,16 @@ * with the help of a dedicated message queue. */ class ReceivesTimeInfoIF { -public: - /** - * Returns the id of the queue which receives the timing information. - * @return Queue id of the timing queue. - */ - virtual MessageQueueId_t getTimeReceptionQueue() const = 0; - /** - * Empty virtual destructor. - */ - virtual ~ReceivesTimeInfoIF() { - } - + public: + /** + * Returns the id of the queue which receives the timing information. + * @return Queue id of the timing queue. + */ + virtual MessageQueueId_t getTimeReceptionQueue() const = 0; + /** + * Empty virtual destructor. + */ + virtual ~ReceivesTimeInfoIF() {} }; - #endif /* FSFW_TIMEMANAGER_RECEIVESTIMEINFOIF_H_ */ diff --git a/src/fsfw/timemanager/Stopwatch.cpp b/src/fsfw/timemanager/Stopwatch.cpp index a8f87029..05d5c0e8 100644 --- a/src/fsfw/timemanager/Stopwatch.cpp +++ b/src/fsfw/timemanager/Stopwatch.cpp @@ -1,74 +1,68 @@ #include "fsfw/timemanager/Stopwatch.h" + #include "fsfw/serviceinterface/ServiceInterface.h" #if FSFW_CPP_OSTREAM_ENABLED == 1 #include #endif -Stopwatch::Stopwatch(bool displayOnDestruction, - StopwatchDisplayMode displayMode): displayOnDestruction( - displayOnDestruction), displayMode(displayMode) { - // Measures start time on initialization. - Clock::getUptime(&startTime); +Stopwatch::Stopwatch(bool displayOnDestruction, StopwatchDisplayMode displayMode) + : displayOnDestruction(displayOnDestruction), displayMode(displayMode) { + // Measures start time on initialization. + Clock::getUptime(&startTime); } -void Stopwatch::start() { - Clock::getUptime(&startTime); -} +void Stopwatch::start() { Clock::getUptime(&startTime); } dur_millis_t Stopwatch::stop(bool display) { - stopInternal(); - if(display) { - this->display(); - } - return elapsedTime.tv_sec * 1000 + elapsedTime.tv_usec / 1000; + stopInternal(); + if (display) { + this->display(); + } + return elapsedTime.tv_sec * 1000 + elapsedTime.tv_usec / 1000; } double Stopwatch::stopSeconds() { - stopInternal(); - return timevalOperations::toDouble(elapsedTime); + stopInternal(); + return timevalOperations::toDouble(elapsedTime); } void Stopwatch::display() { - if(displayMode == StopwatchDisplayMode::MILLIS) { - dur_millis_t timeMillis = static_cast( - elapsedTime.tv_sec * 1000 + elapsedTime.tv_usec / 1000); + if (displayMode == StopwatchDisplayMode::MILLIS) { + dur_millis_t timeMillis = + static_cast(elapsedTime.tv_sec * 1000 + elapsedTime.tv_usec / 1000); #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "Stopwatch: Operation took " << timeMillis << " milliseconds" << std::endl; + sif::info << "Stopwatch: Operation took " << timeMillis << " milliseconds" << std::endl; #else - sif::printInfo("Stopwatch: Operation took %lu milliseconds\n\r", - static_cast(timeMillis)); + sif::printInfo("Stopwatch: Operation took %lu milliseconds\n\r", + static_cast(timeMillis)); #endif - } - else if(displayMode == StopwatchDisplayMode::SECONDS) { + } else if (displayMode == StopwatchDisplayMode::SECONDS) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info <<"Stopwatch: Operation took " << std::setprecision(3) - << std::fixed << timevalOperations::toDouble(elapsedTime) - << " seconds" << std::endl; + sif::info << "Stopwatch: Operation took " << std::setprecision(3) << std::fixed + << timevalOperations::toDouble(elapsedTime) << " seconds" << std::endl; #else - sif::printInfo("Stopwatch: Operation took %.3f seconds\n\r", - static_cast(timevalOperations::toDouble(elapsedTime))); + sif::printInfo("Stopwatch: Operation took %.3f seconds\n\r", + static_cast(timevalOperations::toDouble(elapsedTime))); #endif - } + } } Stopwatch::~Stopwatch() { - if(displayOnDestruction) { - stopInternal(); - display(); - } + if (displayOnDestruction) { + stopInternal(); + display(); + } } void Stopwatch::setDisplayMode(StopwatchDisplayMode displayMode) { - this->displayMode = displayMode; + this->displayMode = displayMode; } -StopwatchDisplayMode Stopwatch::getDisplayMode() const { - return displayMode; -} +StopwatchDisplayMode Stopwatch::getDisplayMode() const { return displayMode; } void Stopwatch::stopInternal() { - timeval endTime; - Clock::getUptime(&endTime); - elapsedTime = endTime - startTime; + timeval endTime; + Clock::getUptime(&endTime); + elapsedTime = endTime - startTime; } diff --git a/src/fsfw/timemanager/Stopwatch.h b/src/fsfw/timemanager/Stopwatch.h index ea72c66e..a4922133 100644 --- a/src/fsfw/timemanager/Stopwatch.h +++ b/src/fsfw/timemanager/Stopwatch.h @@ -3,10 +3,7 @@ #include "Clock.h" -enum class StopwatchDisplayMode { - MILLIS, - SECONDS -}; +enum class StopwatchDisplayMode { MILLIS, SECONDS }; /** * @brief Simple Stopwatch implementation to measure elapsed time @@ -18,53 +15,53 @@ enum class StopwatchDisplayMode { * @author R. Mueller */ class Stopwatch { -public: - /** - * Default constructor. Call "Stopwatch stopwatch" without brackets if - * no parameters are required! - * @param displayOnDestruction If set to true, displays measured time on - * object destruction - * @param displayMode Display format is either MS rounded or MS as double - * format - * @param outputPrecision If using double format, specify precision here. - */ - Stopwatch(bool displayOnDestruction = true, StopwatchDisplayMode displayMode - = StopwatchDisplayMode::MILLIS); - virtual~ Stopwatch(); + public: + /** + * Default constructor. Call "Stopwatch stopwatch" without brackets if + * no parameters are required! + * @param displayOnDestruction If set to true, displays measured time on + * object destruction + * @param displayMode Display format is either MS rounded or MS as double + * format + * @param outputPrecision If using double format, specify precision here. + */ + Stopwatch(bool displayOnDestruction = true, + StopwatchDisplayMode displayMode = StopwatchDisplayMode::MILLIS); + virtual ~Stopwatch(); - /** - * Caches the start time - */ - void start(); + /** + * Caches the start time + */ + void start(); - /** - * Calculates the elapsed time since start and returns it - * @return elapsed time in milliseconds (rounded) - */ - dur_millis_t stop(bool display = false); - /** - * Calculates the elapsed time since start and returns it - * @return elapsed time in seconds (double precision) - */ - double stopSeconds(); + /** + * Calculates the elapsed time since start and returns it + * @return elapsed time in milliseconds (rounded) + */ + dur_millis_t stop(bool display = false); + /** + * Calculates the elapsed time since start and returns it + * @return elapsed time in seconds (double precision) + */ + double stopSeconds(); - /** - * Displays the elapsed times on the osstream, depending on internal display - * mode. - */ - void display(); + /** + * Displays the elapsed times on the osstream, depending on internal display + * mode. + */ + void display(); - StopwatchDisplayMode getDisplayMode() const; - void setDisplayMode(StopwatchDisplayMode displayMode); - bool displayOnDestruction = true; -private: - timeval startTime {0, 0}; - timeval elapsedTime {0, 0}; + StopwatchDisplayMode getDisplayMode() const; + void setDisplayMode(StopwatchDisplayMode displayMode); + bool displayOnDestruction = true; - StopwatchDisplayMode displayMode = StopwatchDisplayMode::MILLIS; + private: + timeval startTime{0, 0}; + timeval elapsedTime{0, 0}; - void stopInternal(); + StopwatchDisplayMode displayMode = StopwatchDisplayMode::MILLIS; + + void stopInternal(); }; - #endif /* FSFW_TIMEMANAGER_STOPWATCH_H_ */ diff --git a/src/fsfw/timemanager/TimeMessage.cpp b/src/fsfw/timemanager/TimeMessage.cpp index 320f3000..d3cc4f01 100644 --- a/src/fsfw/timemanager/TimeMessage.cpp +++ b/src/fsfw/timemanager/TimeMessage.cpp @@ -1,30 +1,25 @@ #include "fsfw/timemanager/TimeMessage.h" -TimeMessage::TimeMessage() { - this->messageSize += sizeof(timeval) + sizeof(uint32_t); -} +TimeMessage::TimeMessage() { this->messageSize += sizeof(timeval) + sizeof(uint32_t); } TimeMessage::TimeMessage(timeval setTime, uint32_t CounterValue) { - memcpy (this->getData(), &setTime, sizeof(timeval)); - this->messageSize += sizeof(timeval) + sizeof(uint32_t); - memcpy (this->getData() + sizeof(timeval), &CounterValue, sizeof(uint32_t)); + memcpy(this->getData(), &setTime, sizeof(timeval)); + this->messageSize += sizeof(timeval) + sizeof(uint32_t); + memcpy(this->getData() + sizeof(timeval), &CounterValue, sizeof(uint32_t)); } -TimeMessage::~TimeMessage() { -} +TimeMessage::~TimeMessage() {} timeval TimeMessage::getTime() { - timeval temp; - memcpy( &temp, this->getData(), sizeof(timeval)); - return temp; + timeval temp; + memcpy(&temp, this->getData(), sizeof(timeval)); + return temp; } uint32_t TimeMessage::getCounterValue() { - uint32_t temp; - memcpy ( &temp, this->getData() + sizeof(timeval), sizeof(uint32_t)); - return temp; + uint32_t temp; + memcpy(&temp, this->getData() + sizeof(timeval), sizeof(uint32_t)); + return temp; } -size_t TimeMessage::getMinimumMessageSize() const { - return this->MAX_SIZE; -} +size_t TimeMessage::getMinimumMessageSize() const { return this->MAX_SIZE; } diff --git a/src/fsfw/timemanager/TimeMessage.h b/src/fsfw/timemanager/TimeMessage.h index 00778fb7..ae4a9caf 100644 --- a/src/fsfw/timemanager/TimeMessage.h +++ b/src/fsfw/timemanager/TimeMessage.h @@ -1,49 +1,50 @@ #ifndef FSFW_TIMEMANAGER_TIMEMESSAGE_H_ #define FSFW_TIMEMANAGER_TIMEMESSAGE_H_ -#include "Clock.h" -#include "../ipc/MessageQueueMessage.h" #include +#include "../ipc/MessageQueueMessage.h" +#include "Clock.h" + class TimeMessage : public MessageQueueMessage { -protected: - /** - * @brief This call always returns the same fixed size of the message. - * @return Returns HEADER_SIZE + \c sizeof(timeval) + sizeof(uint32_t). - */ - size_t getMinimumMessageSize() const override; -public: + protected: + /** + * @brief This call always returns the same fixed size of the message. + * @return Returns HEADER_SIZE + \c sizeof(timeval) + sizeof(uint32_t). + */ + size_t getMinimumMessageSize() const override; - /** - * @ brief the size of a TimeMessage - */ - static const uint32_t MAX_SIZE = HEADER_SIZE + sizeof(timeval) + sizeof(uint32_t); + public: + /** + * @ brief the size of a TimeMessage + */ + static const uint32_t MAX_SIZE = HEADER_SIZE + sizeof(timeval) + sizeof(uint32_t); - /** - * @brief In the default constructor, only the message_size is set. - */ - TimeMessage(); - /** - * @brief With this constructor, the passed time information is directly put - * into the message. - * @param setTime The time information to put into the message. - * @param counterValue The counterValue to put into the message (GPS PPS). - */ - TimeMessage( timeval setTime, uint32_t counterValue = 0 ); - /** - * @brief The class's destructor is empty. - */ - ~TimeMessage(); - /** - * @brief This getter returns the time information in timeval format. - * @return Returns the time stored in this packet. - */ - timeval getTime(); - /** - * @brief This getter returns the CounterValue in uint32_t format. - * @return Returns the CounterValue stored in this packet. - */ - uint32_t getCounterValue(); + /** + * @brief In the default constructor, only the message_size is set. + */ + TimeMessage(); + /** + * @brief With this constructor, the passed time information is directly put + * into the message. + * @param setTime The time information to put into the message. + * @param counterValue The counterValue to put into the message (GPS PPS). + */ + TimeMessage(timeval setTime, uint32_t counterValue = 0); + /** + * @brief The class's destructor is empty. + */ + ~TimeMessage(); + /** + * @brief This getter returns the time information in timeval format. + * @return Returns the time stored in this packet. + */ + timeval getTime(); + /** + * @brief This getter returns the CounterValue in uint32_t format. + * @return Returns the CounterValue stored in this packet. + */ + uint32_t getCounterValue(); }; #endif /* FSFW_TIMEMANAGER_TIMEMESSAGE_H_ */ diff --git a/src/fsfw/timemanager/TimeStamper.cpp b/src/fsfw/timemanager/TimeStamper.cpp index 4926c2d5..9b4ad3d3 100644 --- a/src/fsfw/timemanager/TimeStamper.cpp +++ b/src/fsfw/timemanager/TimeStamper.cpp @@ -1,24 +1,23 @@ #include "fsfw/timemanager/TimeStamper.h" -#include "fsfw/timemanager/Clock.h" #include -TimeStamper::TimeStamper(object_id_t objectId): SystemObject(objectId) {} +#include "fsfw/timemanager/Clock.h" +TimeStamper::TimeStamper(object_id_t objectId) : SystemObject(objectId) {} -ReturnValue_t TimeStamper::addTimeStamp(uint8_t* buffer, - const uint8_t maxSize) { - if(maxSize < TimeStamperIF::MISSION_TIMESTAMP_SIZE){ - return HasReturnvaluesIF::RETURN_FAILED; - } +ReturnValue_t TimeStamper::addTimeStamp(uint8_t* buffer, const uint8_t maxSize) { + if (maxSize < TimeStamperIF::MISSION_TIMESTAMP_SIZE) { + return HasReturnvaluesIF::RETURN_FAILED; + } - timeval now; - Clock::getClock_timeval(&now); - CCSDSTime::CDS_short cds; - ReturnValue_t result = CCSDSTime::convertToCcsds(&cds,&now); - if(result != HasReturnvaluesIF::RETURN_OK){ - return result; - } - std::memcpy(buffer,&cds,sizeof(cds)); - return result; + timeval now; + Clock::getClock_timeval(&now); + CCSDSTime::CDS_short cds; + ReturnValue_t result = CCSDSTime::convertToCcsds(&cds, &now); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + std::memcpy(buffer, &cds, sizeof(cds)); + return result; } diff --git a/src/fsfw/timemanager/TimeStamper.h b/src/fsfw/timemanager/TimeStamper.h index 6895c14b..aa311ec4 100644 --- a/src/fsfw/timemanager/TimeStamper.h +++ b/src/fsfw/timemanager/TimeStamper.h @@ -1,9 +1,9 @@ #ifndef FSFW_TIMEMANAGER_TIMESTAMPER_H_ #define FSFW_TIMEMANAGER_TIMESTAMPER_H_ -#include "TimeStamperIF.h" -#include "CCSDSTime.h" #include "../objectmanager/SystemObject.h" +#include "CCSDSTime.h" +#include "TimeStamperIF.h" /** * @brief Time stamper which can be used to add any timestamp to a @@ -14,23 +14,23 @@ * overriding the #addTimeStamp function. * @ingroup utility */ -class TimeStamper: public TimeStamperIF, public SystemObject { -public: - /** - * @brief Default constructor which also registers the time stamper as a - * system object so it can be found with the #objectManager. - * @param objectId - */ - TimeStamper(object_id_t objectId); +class TimeStamper : public TimeStamperIF, public SystemObject { + public: + /** + * @brief Default constructor which also registers the time stamper as a + * system object so it can be found with the #objectManager. + * @param objectId + */ + TimeStamper(object_id_t objectId); - /** - * Adds a CCSDS CDC short 8 byte timestamp to the given buffer. - * This function can be overriden to use a custom timestamp. - * @param buffer - * @param maxSize - * @return - */ - virtual ReturnValue_t addTimeStamp(uint8_t* buffer, const uint8_t maxSize); + /** + * Adds a CCSDS CDC short 8 byte timestamp to the given buffer. + * This function can be overriden to use a custom timestamp. + * @param buffer + * @param maxSize + * @return + */ + virtual ReturnValue_t addTimeStamp(uint8_t* buffer, const uint8_t maxSize); }; #endif /* FSFW_TIMEMANAGER_TIMESTAMPER_H_ */ diff --git a/src/fsfw/timemanager/TimeStamperIF.h b/src/fsfw/timemanager/TimeStamperIF.h index 34990500..5c3880ea 100644 --- a/src/fsfw/timemanager/TimeStamperIF.h +++ b/src/fsfw/timemanager/TimeStamperIF.h @@ -2,8 +2,8 @@ #define FSFW_TIMEMANAGER_TIMESTAMPERIF_H_ #include + #include "../returnvalues/HasReturnvaluesIF.h" -#include /** * A class implementing this IF provides facilities to add a time stamp to the @@ -12,19 +12,16 @@ * addTimeStamp may be called in parallel from a different context. */ class TimeStamperIF { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::TIME_STAMPER_IF; - static const ReturnValue_t BAD_TIMESTAMP = MAKE_RETURN_CODE(1); + public: + static const uint8_t INTERFACE_ID = CLASS_ID::TIME_STAMPER_IF; + static const ReturnValue_t BAD_TIMESTAMP = MAKE_RETURN_CODE(1); - //! This is a mission-specific constant and determines the total - //! size reserved for timestamps. - static const uint8_t MISSION_TIMESTAMP_SIZE = fsfwconfig::FSFW_MISSION_TIMESTAMP_SIZE; + //! This is a mission-specific constant and determines the total + //! size reserved for timestamps. + static const uint8_t MISSION_TIMESTAMP_SIZE = fsfwconfig::FSFW_MISSION_TIMESTAMP_SIZE; - virtual ReturnValue_t addTimeStamp(uint8_t* buffer, - const uint8_t maxSize) = 0; - virtual ~TimeStamperIF() {} + virtual ReturnValue_t addTimeStamp(uint8_t* buffer, const uint8_t maxSize) = 0; + virtual ~TimeStamperIF() {} }; - - #endif /* FSFW_TIMEMANAGER_TIMESTAMPERIF_H_ */ diff --git a/src/fsfw/tmstorage/TmStoreBackendIF.h b/src/fsfw/tmstorage/TmStoreBackendIF.h index 4183334b..d9f1a17b 100644 --- a/src/fsfw/tmstorage/TmStoreBackendIF.h +++ b/src/fsfw/tmstorage/TmStoreBackendIF.h @@ -1,12 +1,12 @@ #ifndef FSFW_TMTCSERVICES_TMSTOREBACKENDIF_H_ #define FSFW_TMTCSERVICES_TMSTOREBACKENDIF_H_ -#include "tmStorageConf.h" -#include "fsfw/returnvalues/HasReturnvaluesIF.h" #include "fsfw/objectmanager/SystemObjectIF.h" #include "fsfw/parameters/HasParametersIF.h" +#include "fsfw/returnvalues/HasReturnvaluesIF.h" #include "fsfw/storagemanager/StorageManagerIF.h" #include "fsfw/timemanager/Clock.h" +#include "tmStorageConf.h" class TmPacketInformation; class TmPacketMinimal; @@ -14,84 +14,108 @@ class SpacePacketBase; class ApidSsc; class TmStoreBackendIF : public HasParametersIF { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::TM_STORE_BACKEND_IF; - static const ReturnValue_t BUSY = MAKE_RETURN_CODE(1); - static const ReturnValue_t FULL = MAKE_RETURN_CODE(2); - static const ReturnValue_t EMPTY = MAKE_RETURN_CODE(3); - static const ReturnValue_t NULL_REQUESTED = MAKE_RETURN_CODE(4); - static const ReturnValue_t TOO_LARGE = MAKE_RETURN_CODE(5); - static const ReturnValue_t NOT_READY = MAKE_RETURN_CODE(6); - static const ReturnValue_t DUMP_ERROR = MAKE_RETURN_CODE(7); - static const ReturnValue_t CRC_ERROR = MAKE_RETURN_CODE(8); - static const ReturnValue_t TIMEOUT = MAKE_RETURN_CODE(9); - static const ReturnValue_t IDLE_PACKET_FOUND = MAKE_RETURN_CODE(10); - static const ReturnValue_t TELECOMMAND_FOUND = MAKE_RETURN_CODE(11); - static const ReturnValue_t NO_PUS_A_TM = MAKE_RETURN_CODE(12); - static const ReturnValue_t TOO_SMALL = MAKE_RETURN_CODE(13); - static const ReturnValue_t BLOCK_NOT_FOUND = MAKE_RETURN_CODE(14); - static const ReturnValue_t INVALID_REQUEST = MAKE_RETURN_CODE(15); + public: + static const uint8_t INTERFACE_ID = CLASS_ID::TM_STORE_BACKEND_IF; + static const ReturnValue_t BUSY = MAKE_RETURN_CODE(1); + static const ReturnValue_t FULL = MAKE_RETURN_CODE(2); + static const ReturnValue_t EMPTY = MAKE_RETURN_CODE(3); + static const ReturnValue_t NULL_REQUESTED = MAKE_RETURN_CODE(4); + static const ReturnValue_t TOO_LARGE = MAKE_RETURN_CODE(5); + static const ReturnValue_t NOT_READY = MAKE_RETURN_CODE(6); + static const ReturnValue_t DUMP_ERROR = MAKE_RETURN_CODE(7); + static const ReturnValue_t CRC_ERROR = MAKE_RETURN_CODE(8); + static const ReturnValue_t TIMEOUT = MAKE_RETURN_CODE(9); + static const ReturnValue_t IDLE_PACKET_FOUND = MAKE_RETURN_CODE(10); + static const ReturnValue_t TELECOMMAND_FOUND = MAKE_RETURN_CODE(11); + static const ReturnValue_t NO_PUS_A_TM = MAKE_RETURN_CODE(12); + static const ReturnValue_t TOO_SMALL = MAKE_RETURN_CODE(13); + static const ReturnValue_t BLOCK_NOT_FOUND = MAKE_RETURN_CODE(14); + static const ReturnValue_t INVALID_REQUEST = MAKE_RETURN_CODE(15); - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::MEMORY; - static const Event STORE_SEND_WRITE_FAILED = MAKE_EVENT(0, severity::LOW); //!< Initiating sending data to store failed. Low, par1: returnCode, par2: integer (debug info) - static const Event STORE_WRITE_FAILED = MAKE_EVENT(1, severity::LOW); //!< Data was sent, but writing failed. Low, par1: returnCode, par2: 0 - static const Event STORE_SEND_READ_FAILED = MAKE_EVENT(2, severity::LOW); //!< Initiating reading data from store failed. Low, par1: returnCode, par2: 0 - static const Event STORE_READ_FAILED = MAKE_EVENT(3, severity::LOW); //!< Data was requested, but access failed. Low, par1: returnCode, par2: 0 - static const Event UNEXPECTED_MSG = MAKE_EVENT(4, severity::LOW); //!< An unexpected TM packet or data message occurred. Low, par1: 0, par2: integer (debug info) - static const Event STORING_FAILED = MAKE_EVENT(5, severity::LOW); //!< Storing data failed. May simply be a full store. Low, par1: returnCode, par2: integer (sequence count of failed packet). - static const Event TM_DUMP_FAILED = MAKE_EVENT(6, severity::LOW); //!< Dumping retrieved data failed. Low, par1: returnCode, par2: integer (sequence count of failed packet). - static const Event STORE_INIT_FAILED = MAKE_EVENT(7, severity::LOW); //!< Corrupted init data or read error. Low, par1: returnCode, par2: integer (debug info) - static const Event STORE_INIT_EMPTY = MAKE_EVENT(8, severity::INFO); //!< Store was not initialized. Starts empty. Info, parameters both zero. - static const Event STORE_CONTENT_CORRUPTED = MAKE_EVENT(9, severity::LOW); //!< Data was read out, but it is inconsistent. Low par1: Memory address of corruption, par2: integer (debug info) - static const Event STORE_INITIALIZE = MAKE_EVENT(10, severity::INFO); //!< Info event indicating the store will be initialized, either at boot or after IOB switch. Info. pars: 0 - static const Event INIT_DONE = MAKE_EVENT(11, severity::INFO); //!< Info event indicating the store was successfully initialized, either at boot or after IOB switch. Info. pars: 0 - static const Event DUMP_FINISHED = MAKE_EVENT(12, severity::INFO); //!< Info event indicating that dumping finished successfully. par1: Number of dumped packets. par2: APID/SSC (16bits each) - static const Event DELETION_FINISHED = MAKE_EVENT(13, severity::INFO); //!< Info event indicating that deletion finished successfully. par1: Number of deleted packets. par2: APID/SSC (16bits each) - static const Event DELETION_FAILED = MAKE_EVENT(14, severity::LOW); //!< Info event indicating that something went wrong during deletion. pars: 0 - static const Event AUTO_CATALOGS_SENDING_FAILED = MAKE_EVENT(15, severity::INFO);//!< Info that the a auto catalog report failed + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::MEMORY; + static const Event STORE_SEND_WRITE_FAILED = + MAKE_EVENT(0, severity::LOW); //!< Initiating sending data to store failed. Low, par1: + //!< returnCode, par2: integer (debug info) + static const Event STORE_WRITE_FAILED = MAKE_EVENT( + 1, severity::LOW); //!< Data was sent, but writing failed. Low, par1: returnCode, par2: 0 + static const Event STORE_SEND_READ_FAILED = + MAKE_EVENT(2, severity::LOW); //!< Initiating reading data from store failed. Low, par1: + //!< returnCode, par2: 0 + static const Event STORE_READ_FAILED = MAKE_EVENT( + 3, severity::LOW); //!< Data was requested, but access failed. Low, par1: returnCode, par2: 0 + static const Event UNEXPECTED_MSG = + MAKE_EVENT(4, severity::LOW); //!< An unexpected TM packet or data message occurred. Low, + //!< par1: 0, par2: integer (debug info) + static const Event STORING_FAILED = MAKE_EVENT( + 5, severity::LOW); //!< Storing data failed. May simply be a full store. Low, par1: + //!< returnCode, par2: integer (sequence count of failed packet). + static const Event TM_DUMP_FAILED = + MAKE_EVENT(6, severity::LOW); //!< Dumping retrieved data failed. Low, par1: returnCode, + //!< par2: integer (sequence count of failed packet). + static const Event STORE_INIT_FAILED = + MAKE_EVENT(7, severity::LOW); //!< Corrupted init data or read error. Low, par1: returnCode, + //!< par2: integer (debug info) + static const Event STORE_INIT_EMPTY = MAKE_EVENT( + 8, severity::INFO); //!< Store was not initialized. Starts empty. Info, parameters both zero. + static const Event STORE_CONTENT_CORRUPTED = + MAKE_EVENT(9, severity::LOW); //!< Data was read out, but it is inconsistent. Low par1: + //!< Memory address of corruption, par2: integer (debug info) + static const Event STORE_INITIALIZE = + MAKE_EVENT(10, severity::INFO); //!< Info event indicating the store will be initialized, + //!< either at boot or after IOB switch. Info. pars: 0 + static const Event INIT_DONE = MAKE_EVENT( + 11, severity::INFO); //!< Info event indicating the store was successfully initialized, + //!< either at boot or after IOB switch. Info. pars: 0 + static const Event DUMP_FINISHED = MAKE_EVENT( + 12, severity::INFO); //!< Info event indicating that dumping finished successfully. par1: + //!< Number of dumped packets. par2: APID/SSC (16bits each) + static const Event DELETION_FINISHED = MAKE_EVENT( + 13, severity::INFO); //!< Info event indicating that deletion finished successfully. par1: + //!< Number of deleted packets. par2: APID/SSC (16bits each) + static const Event DELETION_FAILED = MAKE_EVENT( + 14, + severity::LOW); //!< Info event indicating that something went wrong during deletion. pars: 0 + static const Event AUTO_CATALOGS_SENDING_FAILED = + MAKE_EVENT(15, severity::INFO); //!< Info that the a auto catalog report failed - virtual ~TmStoreBackendIF() {} + virtual ~TmStoreBackendIF() {} - /** - * SHOULDDO: Specification on what has to be implemented here - * @param opCode - * @return - */ - virtual ReturnValue_t performOperation(uint8_t opCode) = 0; - virtual ReturnValue_t initialize() = 0; + /** + * SHOULDDO: Specification on what has to be implemented here + * @param opCode + * @return + */ + virtual ReturnValue_t performOperation(uint8_t opCode) = 0; + virtual ReturnValue_t initialize() = 0; - /** - * Implement the storage of TM packets to mass memory - * @param tmPacket - * @return - */ - virtual ReturnValue_t storePacket(TmPacketMinimal* tmPacket) = 0; - virtual ReturnValue_t setFetchLimitTime(const timeval* loverLimit, const timeval* upperLimit) = 0; - virtual ReturnValue_t setFetchLimitBlocks(uint32_t startAddress, uint32_t endAddress) = 0; - virtual ReturnValue_t fetchPackets(bool fromBegin = false) = 0; - virtual ReturnValue_t initializeStore(object_id_t dumpTarget) = 0; - virtual ReturnValue_t dumpIndex(store_address_t* storeId) = 0; - - /** - * SHOULDDO: Adapt for file management system? - * @param startAddress - * @param endAddress - * @return - */ - virtual ReturnValue_t deleteBlocks(uint32_t startAddress, uint32_t endAddress) = 0; - virtual ReturnValue_t deleteTime(const timeval* timeUntil, - uint32_t* deletedPackets) = 0; - virtual void resetStore(bool clearStore, bool resetWrite, bool resetRead) = 0; - virtual bool isReady() = 0; - virtual uint32_t availableData() = 0; - virtual float getPercentageFilled() const = 0; - virtual uint32_t getStoredPacketsCount() const = 0; - virtual TmPacketInformation* getOldestPacket() = 0; - virtual TmPacketInformation* getYoungestPacket() = 0; - virtual float getDataRate() = 0; + /** + * Implement the storage of TM packets to mass memory + * @param tmPacket + * @return + */ + virtual ReturnValue_t storePacket(TmPacketMinimal* tmPacket) = 0; + virtual ReturnValue_t setFetchLimitTime(const timeval* loverLimit, const timeval* upperLimit) = 0; + virtual ReturnValue_t setFetchLimitBlocks(uint32_t startAddress, uint32_t endAddress) = 0; + virtual ReturnValue_t fetchPackets(bool fromBegin = false) = 0; + virtual ReturnValue_t initializeStore(object_id_t dumpTarget) = 0; + virtual ReturnValue_t dumpIndex(store_address_t* storeId) = 0; + /** + * SHOULDDO: Adapt for file management system? + * @param startAddress + * @param endAddress + * @return + */ + virtual ReturnValue_t deleteBlocks(uint32_t startAddress, uint32_t endAddress) = 0; + virtual ReturnValue_t deleteTime(const timeval* timeUntil, uint32_t* deletedPackets) = 0; + virtual void resetStore(bool clearStore, bool resetWrite, bool resetRead) = 0; + virtual bool isReady() = 0; + virtual uint32_t availableData() = 0; + virtual float getPercentageFilled() const = 0; + virtual uint32_t getStoredPacketsCount() const = 0; + virtual TmPacketInformation* getOldestPacket() = 0; + virtual TmPacketInformation* getYoungestPacket() = 0; + virtual float getDataRate() = 0; }; - - #endif /* FSFW_TMTCSERVICES_TMSTOREBACKENDIF_H_ */ diff --git a/src/fsfw/tmstorage/TmStoreFrontendIF.h b/src/fsfw/tmstorage/TmStoreFrontendIF.h index 11b2a686..3ab93ba1 100644 --- a/src/fsfw/tmstorage/TmStoreFrontendIF.h +++ b/src/fsfw/tmstorage/TmStoreFrontendIF.h @@ -1,65 +1,63 @@ #ifndef FSFW_TMTCSERVICES_TMSTOREFRONTENDIF_H_ #define FSFW_TMTCSERVICES_TMSTOREFRONTENDIF_H_ -#include "tmStorageConf.h" #include "TmStorePackets.h" -#include "fsfw/returnvalues/HasReturnvaluesIF.h" #include "fsfw/ipc/MessageQueueSenderIF.h" +#include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "tmStorageConf.h" class TmPacketMinimal; class SpacePacketBase; class TmStoreBackendIF; class TmStoreFrontendIF { -public: - virtual TmStoreBackendIF* getBackend() const = 0; + public: + virtual TmStoreBackendIF* getBackend() const = 0; - /** - * What do I need to implement here? - * This is propably used by PUS Service 15 so we should propably check for messages.. - * Provide base implementation? - * @param opCode - * @return - */ - virtual ReturnValue_t performOperation(uint8_t opCode) = 0; - /** - * Callback from the back-end to indicate a certain packet was received. - * front-end takes care of discarding/downloading the packet. - * @param packet Pointer to the newly received Space Packet. - * @param address Start address of the packet found - * @param isLastPacket Indicates if no more packets can be fetched. - * @return If more packets shall be fetched, RETURN_OK must be returned. - * Any other code stops fetching packets. - */ - virtual ReturnValue_t packetRetrieved(TmPacketMinimal* packet, uint32_t address) = 0; - virtual void noMorePacketsInStore() = 0; - virtual void handleRetrievalFailed(ReturnValue_t errorCode, uint32_t parameter1 = 0, uint32_t parameter2 = 0) = 0; - /** - * To get the queue where commands shall be sent. - * @return Id of command queue. - */ - virtual MessageQueueId_t getCommandQueue() const = 0; - virtual ReturnValue_t fetchPackets(ApidSsc start, ApidSsc end) = 0; - virtual ReturnValue_t deletePackets(ApidSsc upTo) = 0; - virtual ReturnValue_t checkPacket(SpacePacketBase* tmPacket) = 0; - virtual bool isEnabled() const = 0; - virtual void setEnabled(bool enabled) = 0; - virtual void resetDownlinkedPacketCount() = 0; - virtual ReturnValue_t setDumpTarget(object_id_t dumpTarget) = 0; - static const uint8_t INTERFACE_ID = CLASS_ID::TM_STORE_FRONTEND_IF; - static const ReturnValue_t BUSY = MAKE_RETURN_CODE(1); - static const ReturnValue_t LAST_PACKET_FOUND = MAKE_RETURN_CODE(2); - static const ReturnValue_t STOP_FETCH = MAKE_RETURN_CODE(3); - static const ReturnValue_t TIMEOUT = MAKE_RETURN_CODE(4); - static const ReturnValue_t TM_CHANNEL_FULL = MAKE_RETURN_CODE(5); - static const ReturnValue_t NOT_STORED = MAKE_RETURN_CODE(6); - static const ReturnValue_t ALL_DELETED = MAKE_RETURN_CODE(7); - static const ReturnValue_t INVALID_DATA = MAKE_RETURN_CODE(8); - static const ReturnValue_t NOT_READY = MAKE_RETURN_CODE(9); - virtual ~TmStoreFrontendIF() { - } + /** + * What do I need to implement here? + * This is propably used by PUS Service 15 so we should propably check for messages.. + * Provide base implementation? + * @param opCode + * @return + */ + virtual ReturnValue_t performOperation(uint8_t opCode) = 0; + /** + * Callback from the back-end to indicate a certain packet was received. + * front-end takes care of discarding/downloading the packet. + * @param packet Pointer to the newly received Space Packet. + * @param address Start address of the packet found + * @param isLastPacket Indicates if no more packets can be fetched. + * @return If more packets shall be fetched, RETURN_OK must be returned. + * Any other code stops fetching packets. + */ + virtual ReturnValue_t packetRetrieved(TmPacketMinimal* packet, uint32_t address) = 0; + virtual void noMorePacketsInStore() = 0; + virtual void handleRetrievalFailed(ReturnValue_t errorCode, uint32_t parameter1 = 0, + uint32_t parameter2 = 0) = 0; + /** + * To get the queue where commands shall be sent. + * @return Id of command queue. + */ + virtual MessageQueueId_t getCommandQueue() const = 0; + virtual ReturnValue_t fetchPackets(ApidSsc start, ApidSsc end) = 0; + virtual ReturnValue_t deletePackets(ApidSsc upTo) = 0; + virtual ReturnValue_t checkPacket(SpacePacketBase* tmPacket) = 0; + virtual bool isEnabled() const = 0; + virtual void setEnabled(bool enabled) = 0; + virtual void resetDownlinkedPacketCount() = 0; + virtual ReturnValue_t setDumpTarget(object_id_t dumpTarget) = 0; + static const uint8_t INTERFACE_ID = CLASS_ID::TM_STORE_FRONTEND_IF; + static const ReturnValue_t BUSY = MAKE_RETURN_CODE(1); + static const ReturnValue_t LAST_PACKET_FOUND = MAKE_RETURN_CODE(2); + static const ReturnValue_t STOP_FETCH = MAKE_RETURN_CODE(3); + static const ReturnValue_t TIMEOUT = MAKE_RETURN_CODE(4); + static const ReturnValue_t TM_CHANNEL_FULL = MAKE_RETURN_CODE(5); + static const ReturnValue_t NOT_STORED = MAKE_RETURN_CODE(6); + static const ReturnValue_t ALL_DELETED = MAKE_RETURN_CODE(7); + static const ReturnValue_t INVALID_DATA = MAKE_RETURN_CODE(8); + static const ReturnValue_t NOT_READY = MAKE_RETURN_CODE(9); + virtual ~TmStoreFrontendIF() {} }; - - #endif /* FSFW_TMTCSERVICES_TMSTOREFRONTENDIF_H_ */ diff --git a/src/fsfw/tmstorage/TmStoreMessage.cpp b/src/fsfw/tmstorage/TmStoreMessage.cpp index fa5fb541..a6bab6c5 100644 --- a/src/fsfw/tmstorage/TmStoreMessage.cpp +++ b/src/fsfw/tmstorage/TmStoreMessage.cpp @@ -1,165 +1,147 @@ #include "TmStoreMessage.h" + #include "fsfw/objectmanager/ObjectManager.h" -TmStoreMessage::~TmStoreMessage() { - +TmStoreMessage::~TmStoreMessage() {} + +TmStoreMessage::TmStoreMessage() {} + +ReturnValue_t TmStoreMessage::setEnableStoringMessage(CommandMessage* cmd, bool setEnabled) { + cmd->setCommand(ENABLE_STORING); + cmd->setParameter(setEnabled); + return HasReturnvaluesIF::RETURN_OK; } -TmStoreMessage::TmStoreMessage() { +ReturnValue_t TmStoreMessage::setDeleteContentMessage(CommandMessage* cmd, ApidSsc upTo) { + cmd->setCommand(DELETE_STORE_CONTENT); + cmd->setParameter((upTo.apid << 16) + upTo.ssc); + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t TmStoreMessage::setEnableStoringMessage(CommandMessage* cmd, - bool setEnabled) { - cmd->setCommand(ENABLE_STORING); - cmd->setParameter(setEnabled); - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t TmStoreMessage::setDeleteContentMessage(CommandMessage* cmd, - ApidSsc upTo) { - cmd->setCommand(DELETE_STORE_CONTENT); - cmd->setParameter((upTo.apid<<16) + upTo.ssc); - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t TmStoreMessage::setDownlinkContentMessage(CommandMessage* cmd, - ApidSsc fromPacket, - ApidSsc toPacket) { - cmd->setCommand(DOWNLINK_STORE_CONTENT); - cmd->setParameter((fromPacket.apid<<16) + fromPacket.ssc); - cmd->setParameter2((toPacket.apid<<16) + toPacket.ssc); - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t TmStoreMessage::setDownlinkContentMessage(CommandMessage* cmd, ApidSsc fromPacket, + ApidSsc toPacket) { + cmd->setCommand(DOWNLINK_STORE_CONTENT); + cmd->setParameter((fromPacket.apid << 16) + fromPacket.ssc); + cmd->setParameter2((toPacket.apid << 16) + toPacket.ssc); + return HasReturnvaluesIF::RETURN_OK; } ApidSsc TmStoreMessage::getPacketId1(CommandMessage* cmd) { - ApidSsc temp; - temp.apid = (cmd->getParameter() >> 16) & 0xFFFF; - temp.ssc = cmd->getParameter() & 0xFFFF; - return temp; + ApidSsc temp; + temp.apid = (cmd->getParameter() >> 16) & 0xFFFF; + temp.ssc = cmd->getParameter() & 0xFFFF; + return temp; } ApidSsc TmStoreMessage::getPacketId2(CommandMessage* cmd) { - ApidSsc temp; - temp.apid = (cmd->getParameter2() >> 16) & 0xFFFF; - temp.ssc = cmd->getParameter2() & 0xFFFF; - return temp; + ApidSsc temp; + temp.apid = (cmd->getParameter2() >> 16) & 0xFFFF; + temp.ssc = cmd->getParameter2() & 0xFFFF; + return temp; } -bool TmStoreMessage::getEnableStoring(CommandMessage* cmd) { - return (bool)cmd->getParameter(); -} +bool TmStoreMessage::getEnableStoring(CommandMessage* cmd) { return (bool)cmd->getParameter(); } -void TmStoreMessage::setChangeSelectionDefinitionMessage( - CommandMessage* cmd, bool addDefinition, store_address_t store_id) { - cmd->setCommand(CHANGE_SELECTION_DEFINITION); - cmd->setParameter(addDefinition); - cmd->setParameter2(store_id.raw); +void TmStoreMessage::setChangeSelectionDefinitionMessage(CommandMessage* cmd, bool addDefinition, + store_address_t store_id) { + cmd->setCommand(CHANGE_SELECTION_DEFINITION); + cmd->setParameter(addDefinition); + cmd->setParameter2(store_id.raw); } void TmStoreMessage::clear(CommandMessage* cmd) { - switch(cmd->getCommand()) { - case SELECTION_DEFINITION_REPORT: - case STORE_CATALOGUE_REPORT: - case CHANGE_SELECTION_DEFINITION: - case INDEX_REPORT: - case DELETE_STORE_CONTENT_TIME: - case DOWNLINK_STORE_CONTENT_TIME: { - StorageManagerIF *ipcStore = ObjectManager::instance()->get( - objects::IPC_STORE); - if (ipcStore != NULL) { - ipcStore->deleteData(getStoreId(cmd)); - } - } - /* NO BREAK falls through*/ - case DELETE_STORE_CONTENT_BLOCKS: - case DOWNLINK_STORE_CONTENT_BLOCKS: - case REPORT_INDEX_REQUEST: - cmd->setCommand(CommandMessage::UNKNOWN_COMMAND); - cmd->setParameter(0); - cmd->setParameter2(0); - break; - default: - break; - } + switch (cmd->getCommand()) { + case SELECTION_DEFINITION_REPORT: + case STORE_CATALOGUE_REPORT: + case CHANGE_SELECTION_DEFINITION: + case INDEX_REPORT: + case DELETE_STORE_CONTENT_TIME: + case DOWNLINK_STORE_CONTENT_TIME: { + StorageManagerIF* ipcStore = + ObjectManager::instance()->get(objects::IPC_STORE); + if (ipcStore != NULL) { + ipcStore->deleteData(getStoreId(cmd)); + } + } + /* NO BREAK falls through*/ + case DELETE_STORE_CONTENT_BLOCKS: + case DOWNLINK_STORE_CONTENT_BLOCKS: + case REPORT_INDEX_REQUEST: + cmd->setCommand(CommandMessage::UNKNOWN_COMMAND); + cmd->setParameter(0); + cmd->setParameter2(0); + break; + default: + break; + } } store_address_t TmStoreMessage::getStoreId(const CommandMessage* cmd) { - store_address_t temp; - temp.raw = cmd->getParameter2(); - return temp; + store_address_t temp; + temp.raw = cmd->getParameter2(); + return temp; } -bool TmStoreMessage::getAddToSelection(CommandMessage* cmd) { - return (bool)cmd->getParameter(); +bool TmStoreMessage::getAddToSelection(CommandMessage* cmd) { return (bool)cmd->getParameter(); } + +ReturnValue_t TmStoreMessage::setReportSelectionDefinitionMessage(CommandMessage* cmd) { + cmd->setCommand(REPORT_SELECTION_DEFINITION); + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t TmStoreMessage::setReportSelectionDefinitionMessage( - CommandMessage* cmd) { - cmd->setCommand(REPORT_SELECTION_DEFINITION); - return HasReturnvaluesIF::RETURN_OK; +void TmStoreMessage::setSelectionDefinitionReportMessage(CommandMessage* cmd, + store_address_t storeId) { + cmd->setCommand(SELECTION_DEFINITION_REPORT); + cmd->setParameter2(storeId.raw); } -void TmStoreMessage::setSelectionDefinitionReportMessage( - CommandMessage* cmd, store_address_t storeId) { - cmd->setCommand(SELECTION_DEFINITION_REPORT); - cmd->setParameter2(storeId.raw); -} - -ReturnValue_t TmStoreMessage::setReportStoreCatalogueMessage( - CommandMessage* cmd) { - cmd->setCommand(REPORT_STORE_CATALOGUE); - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t TmStoreMessage::setReportStoreCatalogueMessage(CommandMessage* cmd) { + cmd->setCommand(REPORT_STORE_CATALOGUE); + return HasReturnvaluesIF::RETURN_OK; } void TmStoreMessage::setStoreCatalogueReportMessage(CommandMessage* cmd, object_id_t objectId, - store_address_t storeId) { - cmd->setCommand(STORE_CATALOGUE_REPORT); - cmd->setParameter(objectId); - cmd->setParameter2(storeId.raw); + store_address_t storeId) { + cmd->setCommand(STORE_CATALOGUE_REPORT); + cmd->setParameter(objectId); + cmd->setParameter2(storeId.raw); } -object_id_t TmStoreMessage::getObjectId(CommandMessage* cmd) { - return cmd->getParameter(); +object_id_t TmStoreMessage::getObjectId(CommandMessage* cmd) { return cmd->getParameter(); } + +void TmStoreMessage::setDownlinkContentTimeMessage(CommandMessage* cmd, store_address_t storeId) { + cmd->setCommand(DOWNLINK_STORE_CONTENT_TIME); + cmd->setParameter2(storeId.raw); } -void TmStoreMessage::setDownlinkContentTimeMessage(CommandMessage* cmd, - store_address_t storeId) { - cmd->setCommand(DOWNLINK_STORE_CONTENT_TIME); - cmd->setParameter2(storeId.raw); +uint32_t TmStoreMessage::getAddressLow(CommandMessage* cmd) { return cmd->getParameter(); } +uint32_t TmStoreMessage::getAddressHigh(CommandMessage* cmd) { return cmd->getParameter2(); } + +void TmStoreMessage::setDeleteContentTimeMessage(CommandMessage* cmd, store_address_t storeId) { + cmd->setCommand(DELETE_STORE_CONTENT_TIME); + cmd->setParameter2(storeId.raw); } -uint32_t TmStoreMessage::getAddressLow(CommandMessage* cmd){ - return cmd->getParameter(); +ReturnValue_t TmStoreMessage::setDeleteBlocksMessage(CommandMessage* cmd, uint32_t addressLow, + uint32_t addressHigh) { + cmd->setCommand(DELETE_STORE_CONTENT_BLOCKS); + cmd->setParameter(addressLow); + cmd->setParameter2(addressHigh); + return HasReturnvaluesIF::RETURN_OK; } -uint32_t TmStoreMessage::getAddressHigh(CommandMessage* cmd){ - return cmd->getParameter2(); +ReturnValue_t TmStoreMessage::setDownlinkBlocksMessage(CommandMessage* cmd, uint32_t addressLow, + uint32_t addressHigh) { + cmd->setCommand(DOWNLINK_STORE_CONTENT_BLOCKS); + cmd->setParameter(addressLow); + cmd->setParameter2(addressHigh); + return HasReturnvaluesIF::RETURN_OK; +} +ReturnValue_t TmStoreMessage::setIndexRequestMessage(CommandMessage* cmd) { + cmd->setCommand(REPORT_INDEX_REQUEST); + return HasReturnvaluesIF::RETURN_OK; } -void TmStoreMessage::setDeleteContentTimeMessage(CommandMessage* cmd, - store_address_t storeId) { - cmd->setCommand(DELETE_STORE_CONTENT_TIME); - cmd->setParameter2(storeId.raw); -} - -ReturnValue_t TmStoreMessage::setDeleteBlocksMessage(CommandMessage* cmd, uint32_t addressLow, uint32_t addressHigh){ - cmd->setCommand(DELETE_STORE_CONTENT_BLOCKS); - cmd->setParameter(addressLow); - cmd->setParameter2(addressHigh); - return HasReturnvaluesIF::RETURN_OK; -} -ReturnValue_t TmStoreMessage::setDownlinkBlocksMessage(CommandMessage* cmd, uint32_t addressLow, uint32_t addressHigh){ - cmd->setCommand(DOWNLINK_STORE_CONTENT_BLOCKS); - cmd->setParameter(addressLow); - cmd->setParameter2(addressHigh); - return HasReturnvaluesIF::RETURN_OK; -} -ReturnValue_t TmStoreMessage::setIndexRequestMessage(CommandMessage* cmd){ - cmd->setCommand(REPORT_INDEX_REQUEST); - return HasReturnvaluesIF::RETURN_OK; -} - - -void TmStoreMessage::setIndexReportMessage(CommandMessage* cmd, store_address_t storeId){ - cmd->setCommand(INDEX_REPORT); - cmd->setParameter2(storeId.raw); +void TmStoreMessage::setIndexReportMessage(CommandMessage* cmd, store_address_t storeId) { + cmd->setCommand(INDEX_REPORT); + cmd->setParameter2(storeId.raw); } diff --git a/src/fsfw/tmstorage/TmStoreMessage.h b/src/fsfw/tmstorage/TmStoreMessage.h index 51f86b3a..90669335 100644 --- a/src/fsfw/tmstorage/TmStoreMessage.h +++ b/src/fsfw/tmstorage/TmStoreMessage.h @@ -1,67 +1,62 @@ #ifndef FSFW_TMSTORAGE_TMSTOREMESSAGE_H_ #define FSFW_TMSTORAGE_TMSTOREMESSAGE_H_ -#include "tmStorageConf.h" #include "TmStorePackets.h" #include "fsfw/ipc/CommandMessage.h" -#include "fsfw/storagemanager/StorageManagerIF.h" #include "fsfw/objectmanager/SystemObjectIF.h" +#include "fsfw/storagemanager/StorageManagerIF.h" +#include "tmStorageConf.h" -class TmStoreMessage { -public: - static ReturnValue_t setEnableStoringMessage(CommandMessage* cmd, - bool setEnabled); - static ReturnValue_t setDeleteContentMessage(CommandMessage* cmd, - ApidSsc upTo); - static ReturnValue_t setDownlinkContentMessage(CommandMessage* cmd, - ApidSsc fromPacket, ApidSsc toPacket); - static void setChangeSelectionDefinitionMessage(CommandMessage* cmd, - bool addDefinition, store_address_t store_id); - static ReturnValue_t setReportSelectionDefinitionMessage( - CommandMessage* cmd); - static void setSelectionDefinitionReportMessage(CommandMessage* cmd, - store_address_t storeId); - static ReturnValue_t setReportStoreCatalogueMessage(CommandMessage* cmd); - static void setStoreCatalogueReportMessage(CommandMessage* cmd, object_id_t objectId, - store_address_t storeId); - static void setDownlinkContentTimeMessage(CommandMessage* cmd, - store_address_t storeId); - static void setIndexReportMessage(CommandMessage* cmd, store_address_t storeId); - static ReturnValue_t setDeleteBlocksMessage(CommandMessage* cmd, - uint32_t addressLow, uint32_t addressHigh); - static ReturnValue_t setDownlinkBlocksMessage(CommandMessage* cmd, - uint32_t addressLow, uint32_t addressHigh); - static ReturnValue_t setIndexRequestMessage(CommandMessage* cmd); - static void setDeleteContentTimeMessage(CommandMessage* cmd, - store_address_t storeId); - static void clear(CommandMessage* cmd); - static object_id_t getObjectId(CommandMessage* cmd); - static ApidSsc getPacketId1(CommandMessage* cmd); - static ApidSsc getPacketId2(CommandMessage* cmd); - static bool getEnableStoring(CommandMessage* cmd); - static bool getAddToSelection(CommandMessage* cmd); - static uint32_t getAddressLow(CommandMessage* cmd); - static uint32_t getAddressHigh(CommandMessage* cmd); +class TmStoreMessage { + public: + static ReturnValue_t setEnableStoringMessage(CommandMessage* cmd, bool setEnabled); + static ReturnValue_t setDeleteContentMessage(CommandMessage* cmd, ApidSsc upTo); + static ReturnValue_t setDownlinkContentMessage(CommandMessage* cmd, ApidSsc fromPacket, + ApidSsc toPacket); + static void setChangeSelectionDefinitionMessage(CommandMessage* cmd, bool addDefinition, + store_address_t store_id); + static ReturnValue_t setReportSelectionDefinitionMessage(CommandMessage* cmd); + static void setSelectionDefinitionReportMessage(CommandMessage* cmd, store_address_t storeId); + static ReturnValue_t setReportStoreCatalogueMessage(CommandMessage* cmd); + static void setStoreCatalogueReportMessage(CommandMessage* cmd, object_id_t objectId, + store_address_t storeId); + static void setDownlinkContentTimeMessage(CommandMessage* cmd, store_address_t storeId); + static void setIndexReportMessage(CommandMessage* cmd, store_address_t storeId); + static ReturnValue_t setDeleteBlocksMessage(CommandMessage* cmd, uint32_t addressLow, + uint32_t addressHigh); + static ReturnValue_t setDownlinkBlocksMessage(CommandMessage* cmd, uint32_t addressLow, + uint32_t addressHigh); + static ReturnValue_t setIndexRequestMessage(CommandMessage* cmd); + static void setDeleteContentTimeMessage(CommandMessage* cmd, store_address_t storeId); + static void clear(CommandMessage* cmd); + static object_id_t getObjectId(CommandMessage* cmd); + static ApidSsc getPacketId1(CommandMessage* cmd); + static ApidSsc getPacketId2(CommandMessage* cmd); + static bool getEnableStoring(CommandMessage* cmd); + static bool getAddToSelection(CommandMessage* cmd); + static uint32_t getAddressLow(CommandMessage* cmd); + static uint32_t getAddressHigh(CommandMessage* cmd); - static store_address_t getStoreId(const CommandMessage* cmd); - virtual ~TmStoreMessage(); - static const uint8_t MESSAGE_ID = messagetypes::TM_STORE; - static const Command_t ENABLE_STORING = MAKE_COMMAND_ID(1); - static const Command_t DELETE_STORE_CONTENT = MAKE_COMMAND_ID(2); - static const Command_t DOWNLINK_STORE_CONTENT = MAKE_COMMAND_ID(3); - static const Command_t CHANGE_SELECTION_DEFINITION = MAKE_COMMAND_ID(4); - static const Command_t REPORT_SELECTION_DEFINITION = MAKE_COMMAND_ID(5); - static const Command_t SELECTION_DEFINITION_REPORT = MAKE_COMMAND_ID(6); - static const Command_t REPORT_STORE_CATALOGUE = MAKE_COMMAND_ID(7); - static const Command_t STORE_CATALOGUE_REPORT = MAKE_COMMAND_ID(8); - static const Command_t DOWNLINK_STORE_CONTENT_TIME = MAKE_COMMAND_ID(9); - static const Command_t DELETE_STORE_CONTENT_TIME = MAKE_COMMAND_ID(10); - static const Command_t DELETE_STORE_CONTENT_BLOCKS = MAKE_COMMAND_ID(11); - static const Command_t DOWNLINK_STORE_CONTENT_BLOCKS = MAKE_COMMAND_ID(12); - static const Command_t REPORT_INDEX_REQUEST = MAKE_COMMAND_ID(13); - static const Command_t INDEX_REPORT = MAKE_COMMAND_ID(14); -private: - TmStoreMessage(); + static store_address_t getStoreId(const CommandMessage* cmd); + virtual ~TmStoreMessage(); + static const uint8_t MESSAGE_ID = messagetypes::TM_STORE; + static const Command_t ENABLE_STORING = MAKE_COMMAND_ID(1); + static const Command_t DELETE_STORE_CONTENT = MAKE_COMMAND_ID(2); + static const Command_t DOWNLINK_STORE_CONTENT = MAKE_COMMAND_ID(3); + static const Command_t CHANGE_SELECTION_DEFINITION = MAKE_COMMAND_ID(4); + static const Command_t REPORT_SELECTION_DEFINITION = MAKE_COMMAND_ID(5); + static const Command_t SELECTION_DEFINITION_REPORT = MAKE_COMMAND_ID(6); + static const Command_t REPORT_STORE_CATALOGUE = MAKE_COMMAND_ID(7); + static const Command_t STORE_CATALOGUE_REPORT = MAKE_COMMAND_ID(8); + static const Command_t DOWNLINK_STORE_CONTENT_TIME = MAKE_COMMAND_ID(9); + static const Command_t DELETE_STORE_CONTENT_TIME = MAKE_COMMAND_ID(10); + static const Command_t DELETE_STORE_CONTENT_BLOCKS = MAKE_COMMAND_ID(11); + static const Command_t DOWNLINK_STORE_CONTENT_BLOCKS = MAKE_COMMAND_ID(12); + static const Command_t REPORT_INDEX_REQUEST = MAKE_COMMAND_ID(13); + static const Command_t INDEX_REPORT = MAKE_COMMAND_ID(14); + + private: + TmStoreMessage(); }; #endif /* FSFW_TMSTORAGE_TMSTOREMESSAGE_H_ */ diff --git a/src/fsfw/tmstorage/TmStorePackets.h b/src/fsfw/tmstorage/TmStorePackets.h index 738f7ac2..d54b7b52 100644 --- a/src/fsfw/tmstorage/TmStorePackets.h +++ b/src/fsfw/tmstorage/TmStorePackets.h @@ -1,304 +1,268 @@ #ifndef FSFW_TMSTORAGE_TMSTOREPACKETS_H_ #define FSFW_TMSTORAGE_TMSTOREPACKETS_H_ -#include "tmStorageConf.h" -#include "fsfw/serialize/SerialFixedArrayListAdapter.h" -#include "fsfw/serialize/SerializeElement.h" -#include "fsfw/serialize/SerialLinkedListAdapter.h" -#include "fsfw/serialize/SerialBufferAdapter.h" -#include "fsfw/tmtcpacket/pus/tm/TmPacketMinimal.h" -#include "fsfw/timemanager/TimeStamperIF.h" -#include "fsfw/timemanager/CCSDSTime.h" #include "fsfw/globalfunctions/timevalOperations.h" +#include "fsfw/serialize/SerialBufferAdapter.h" +#include "fsfw/serialize/SerialFixedArrayListAdapter.h" +#include "fsfw/serialize/SerialLinkedListAdapter.h" +#include "fsfw/serialize/SerializeElement.h" +#include "fsfw/timemanager/CCSDSTime.h" +#include "fsfw/timemanager/TimeStamperIF.h" +#include "fsfw/tmtcpacket/pus/tm/TmPacketMinimal.h" +#include "tmStorageConf.h" -class ServiceSubservice: public SerialLinkedListAdapter { -public: - SerializeElement service; - SerialFixedArrayListAdapter subservices; - LinkedElement linkedSubservices; - ServiceSubservice() : - SerialLinkedListAdapter(&service), linkedSubservices( - &subservices) { - service.setNext(&linkedSubservices); - } +class ServiceSubservice : public SerialLinkedListAdapter { + public: + SerializeElement service; + SerialFixedArrayListAdapter subservices; + LinkedElement linkedSubservices; + ServiceSubservice() + : SerialLinkedListAdapter(&service), linkedSubservices(&subservices) { + service.setNext(&linkedSubservices); + } }; -class ApidSsc: public SerializeIF { -public: - ApidSsc() : - apid(SpacePacketBase::LIMIT_APID), ssc(0) { - } - ApidSsc(uint16_t apid, uint16_t ssc) : - apid(apid), ssc(ssc) { - } - uint16_t apid; - uint16_t ssc; - ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const { - ReturnValue_t result = SerializeAdapter::serialize(&apid, - buffer, size, maxSize, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return SerializeAdapter::serialize(&ssc, buffer, size, - maxSize, streamEndianness); +class ApidSsc : public SerializeIF { + public: + ApidSsc() : apid(SpacePacketBase::LIMIT_APID), ssc(0) {} + ApidSsc(uint16_t apid, uint16_t ssc) : apid(apid), ssc(ssc) {} + uint16_t apid; + uint16_t ssc; + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const { + ReturnValue_t result = + SerializeAdapter::serialize(&apid, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return SerializeAdapter::serialize(&ssc, buffer, size, maxSize, streamEndianness); + } - } + size_t getSerializedSize() const { return sizeof(apid) + sizeof(ssc); } - size_t getSerializedSize() const { - return sizeof(apid) + sizeof(ssc); - } - - ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) { - ReturnValue_t result = SerializeAdapter::deSerialize(&apid, - buffer, size, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return SerializeAdapter::deSerialize(&ssc, buffer, size, - streamEndianness); - } + ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, Endianness streamEndianness) { + ReturnValue_t result = SerializeAdapter::deSerialize(&apid, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return SerializeAdapter::deSerialize(&ssc, buffer, size, streamEndianness); + } }; -class ChangeSelectionDefinition: public SerialLinkedListAdapter { -public: - SerializeElement apid; - SerialFixedArrayListAdapter serviceList; - LinkedElement linkedServiceList; - ChangeSelectionDefinition() : - SerialLinkedListAdapter(&apid), linkedServiceList( - &serviceList) { - apid.setNext(&linkedServiceList); - } +class ChangeSelectionDefinition : public SerialLinkedListAdapter { + public: + SerializeElement apid; + SerialFixedArrayListAdapter serviceList; + LinkedElement linkedServiceList; + ChangeSelectionDefinition() + : SerialLinkedListAdapter(&apid), linkedServiceList(&serviceList) { + apid.setNext(&linkedServiceList); + } }; -class TmPacketInformation: public SerializeIF { -public: - TmPacketInformation(TmPacketMinimal* packet){ - setContent(packet); - } - TmPacketInformation() :apid( - SpacePacketBase::LIMIT_APID), sourceSequenceCount(0), serviceType( - 0), serviceSubtype(0), subCounter(0) { - } - void reset() { - apid = SpacePacketBase::LIMIT_APID; - sourceSequenceCount = 0; - serviceType = 0; - serviceSubtype = 0; - subCounter = 0; - memset(rawTimestamp, 0, sizeof(rawTimestamp)); - } - void setContent(TmPacketMinimal* packet) { - apid = packet->getAPID(); - sourceSequenceCount = packet->getPacketSequenceCount(); - serviceType = packet->getService(); - serviceSubtype = packet->getSubService(); - subCounter = packet->getPacketSubcounter(); - memset(rawTimestamp, 0, sizeof(rawTimestamp)); - const uint8_t* pField = NULL; - uint32_t size = 0; - ReturnValue_t result = packet->getPacketTimeRaw(&pField, &size); - if (result != HasReturnvaluesIF::RETURN_OK) { - return; - } - if (*pField == CCSDSTime::P_FIELD_CDS_SHORT - && size <= TimeStamperIF::MISSION_TIMESTAMP_SIZE) { - //Shortcut to avoid converting CDS back and forth. - memcpy(rawTimestamp, pField, size); - return; - } - timeval time = { 0, 0 }; - result = packet->getPacketTime(&time); - if (result != HasReturnvaluesIF::RETURN_OK) { - return; - } +class TmPacketInformation : public SerializeIF { + public: + TmPacketInformation(TmPacketMinimal* packet) { setContent(packet); } + TmPacketInformation() + : apid(SpacePacketBase::LIMIT_APID), + sourceSequenceCount(0), + serviceType(0), + serviceSubtype(0), + subCounter(0) {} + void reset() { + apid = SpacePacketBase::LIMIT_APID; + sourceSequenceCount = 0; + serviceType = 0; + serviceSubtype = 0; + subCounter = 0; + memset(rawTimestamp, 0, sizeof(rawTimestamp)); + } + void setContent(TmPacketMinimal* packet) { + apid = packet->getAPID(); + sourceSequenceCount = packet->getPacketSequenceCount(); + serviceType = packet->getService(); + serviceSubtype = packet->getSubService(); + subCounter = packet->getPacketSubcounter(); + memset(rawTimestamp, 0, sizeof(rawTimestamp)); + const uint8_t* pField = NULL; + uint32_t size = 0; + ReturnValue_t result = packet->getPacketTimeRaw(&pField, &size); + if (result != HasReturnvaluesIF::RETURN_OK) { + return; + } + if (*pField == CCSDSTime::P_FIELD_CDS_SHORT && size <= TimeStamperIF::MISSION_TIMESTAMP_SIZE) { + // Shortcut to avoid converting CDS back and forth. + memcpy(rawTimestamp, pField, size); + return; + } + timeval time = {0, 0}; + result = packet->getPacketTime(&time); + if (result != HasReturnvaluesIF::RETURN_OK) { + return; + } - CCSDSTime::CDS_short cdsFormat; - result = CCSDSTime::convertToCcsds(&cdsFormat, &time); - if (result != HasReturnvaluesIF::RETURN_OK) { - return; - } - memcpy(rawTimestamp, &cdsFormat, sizeof(cdsFormat)); - } - void setContent(TmPacketInformation* content) { - apid = content->apid; - sourceSequenceCount = content->sourceSequenceCount; - serviceType = content->serviceType; - serviceSubtype = content->serviceSubtype; - subCounter = content->subCounter; - memcpy(rawTimestamp, content->rawTimestamp, sizeof(rawTimestamp)); - } - bool isValid() const { - return (apid < SpacePacketBase::LIMIT_APID) ? true : false; - } - static void reset(TmPacketInformation* packet){ - packet->reset(); - } + CCSDSTime::CDS_short cdsFormat; + result = CCSDSTime::convertToCcsds(&cdsFormat, &time); + if (result != HasReturnvaluesIF::RETURN_OK) { + return; + } + memcpy(rawTimestamp, &cdsFormat, sizeof(cdsFormat)); + } + void setContent(TmPacketInformation* content) { + apid = content->apid; + sourceSequenceCount = content->sourceSequenceCount; + serviceType = content->serviceType; + serviceSubtype = content->serviceSubtype; + subCounter = content->subCounter; + memcpy(rawTimestamp, content->rawTimestamp, sizeof(rawTimestamp)); + } + bool isValid() const { return (apid < SpacePacketBase::LIMIT_APID) ? true : false; } + static void reset(TmPacketInformation* packet) { packet->reset(); } - static bool isOlderThan(const TmPacketInformation* packet, const timeval* cmpTime){ - if(packet->isValid()){ - timeval packetTime = {0,0}; - size_t foundlen = 0; - CCSDSTime::convertFromCcsds(&packetTime,&packet->rawTimestamp[0], - &foundlen,sizeof(rawTimestamp)); - if(packetTime <= *cmpTime){ - return true; - } - } - return false; - } + static bool isOlderThan(const TmPacketInformation* packet, const timeval* cmpTime) { + if (packet->isValid()) { + timeval packetTime = {0, 0}; + size_t foundlen = 0; + CCSDSTime::convertFromCcsds(&packetTime, &packet->rawTimestamp[0], &foundlen, + sizeof(rawTimestamp)); + if (packetTime <= *cmpTime) { + return true; + } + } + return false; + } - static bool isNewerThan(const TmPacketInformation* packet, const timeval* cmpTime){ - if(packet->isValid()){ - timeval packetTime = {0,0}; - size_t foundlen = 0; - CCSDSTime::convertFromCcsds(&packetTime,&packet->rawTimestamp[0], - &foundlen,sizeof(rawTimestamp)); - if(packetTime >= *cmpTime){ - return true; - } - } - return false; - } + static bool isNewerThan(const TmPacketInformation* packet, const timeval* cmpTime) { + if (packet->isValid()) { + timeval packetTime = {0, 0}; + size_t foundlen = 0; + CCSDSTime::convertFromCcsds(&packetTime, &packet->rawTimestamp[0], &foundlen, + sizeof(rawTimestamp)); + if (packetTime >= *cmpTime) { + return true; + } + } + return false; + } - static bool isSmallerSSC(const TmPacketInformation* packet,const ApidSsc* compareSSC){ - if(packet->isValid()){ - if(packet->apid == compareSSC->apid){ - if(packet->sourceSequenceCount <= compareSSC->ssc){ - return true; - } - } - } - return false; - } + static bool isSmallerSSC(const TmPacketInformation* packet, const ApidSsc* compareSSC) { + if (packet->isValid()) { + if (packet->apid == compareSSC->apid) { + if (packet->sourceSequenceCount <= compareSSC->ssc) { + return true; + } + } + } + return false; + } - static bool isLargerSSC(const TmPacketInformation* packet,const ApidSsc* compareSSC){ - if(packet->isValid()){ - if(packet->apid == compareSSC->apid){ - if(packet->sourceSequenceCount >= compareSSC->ssc){ - return true; - } - } - } - return false; - } + static bool isLargerSSC(const TmPacketInformation* packet, const ApidSsc* compareSSC) { + if (packet->isValid()) { + if (packet->apid == compareSSC->apid) { + if (packet->sourceSequenceCount >= compareSSC->ssc) { + return true; + } + } + } + return false; + } - uint16_t getApid() const{ - return apid; - } + uint16_t getApid() const { return apid; } - uint16_t getSsc() const{ - return sourceSequenceCount; - } + uint16_t getSsc() const { return sourceSequenceCount; } - uint8_t getServiceType() const{ - return serviceType; - } + uint8_t getServiceType() const { return serviceType; } - uint8_t getServiceSubtype() const{ - return serviceSubtype; - } + uint8_t getServiceSubtype() const { return serviceSubtype; } - uint8_t getSubCounter() const{ - return subCounter; - } + uint8_t getSubCounter() const { return subCounter; } - timeval getTime() const { - timeval packetTime = {0,0}; - size_t foundlen = 0; - CCSDSTime::convertFromCcsds(&packetTime, &this->rawTimestamp[0], - &foundlen, sizeof(rawTimestamp)); - return packetTime; - } + timeval getTime() const { + timeval packetTime = {0, 0}; + size_t foundlen = 0; + CCSDSTime::convertFromCcsds(&packetTime, &this->rawTimestamp[0], &foundlen, + sizeof(rawTimestamp)); + return packetTime; + } - bool operator==(const TmPacketInformation& other) { - //TODO Does not compare Raw Timestamp - return ((apid == other.getApid()) - && (sourceSequenceCount == other.getSsc()) - && (serviceType == other.getServiceType()) && (serviceSubtype = - other.getServiceSubtype())); - } + bool operator==(const TmPacketInformation& other) { + // TODO Does not compare Raw Timestamp + return ((apid == other.getApid()) && (sourceSequenceCount == other.getSsc()) && + (serviceType == other.getServiceType()) && + (serviceSubtype = other.getServiceSubtype())); + } + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const { + ReturnValue_t result = + SerializeAdapter::serialize(&apid, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = + SerializeAdapter::serialize(&sourceSequenceCount, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::serialize(&serviceType, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::serialize(&serviceSubtype, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::serialize(&subCounter, buffer, size, maxSize, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + SerialBufferAdapter adapter(rawTimestamp, sizeof(rawTimestamp)); + return adapter.serialize(buffer, size, maxSize, streamEndianness); + } - ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const { - ReturnValue_t result = SerializeAdapter::serialize(&apid,buffer,size,maxSize,streamEndianness); - if(result!=HasReturnvaluesIF::RETURN_OK){ - return result; - } - result = SerializeAdapter::serialize(&sourceSequenceCount,buffer,size,maxSize,streamEndianness); - if(result!=HasReturnvaluesIF::RETURN_OK){ - return result; - } - result = SerializeAdapter::serialize(&serviceType,buffer,size,maxSize,streamEndianness); - if(result!=HasReturnvaluesIF::RETURN_OK){ - return result; - } - result = SerializeAdapter::serialize(&serviceSubtype,buffer,size,maxSize,streamEndianness); - if(result!=HasReturnvaluesIF::RETURN_OK){ - return result; - } - result = SerializeAdapter::serialize(&subCounter,buffer,size,maxSize,streamEndianness); - if(result!=HasReturnvaluesIF::RETURN_OK){ - return result; - } - SerialBufferAdapter adapter(rawTimestamp,sizeof(rawTimestamp)); - return adapter.serialize(buffer,size,maxSize,streamEndianness); - } + size_t getSerializedSize() const { + uint32_t size = 0; + size += SerializeAdapter::getSerializedSize(&apid); + size += SerializeAdapter::getSerializedSize(&sourceSequenceCount); + size += SerializeAdapter::getSerializedSize(&serviceType); + size += SerializeAdapter::getSerializedSize(&serviceSubtype); + size += SerializeAdapter::getSerializedSize(&subCounter); + SerialBufferAdapter adapter(rawTimestamp, sizeof(rawTimestamp)); + size += adapter.getSerializedSize(); + return size; + }; - size_t getSerializedSize() const { - uint32_t size = 0; - size += SerializeAdapter::getSerializedSize(&apid); - size += SerializeAdapter::getSerializedSize(&sourceSequenceCount); - size += SerializeAdapter::getSerializedSize(&serviceType); - size += SerializeAdapter::getSerializedSize(&serviceSubtype); - size += SerializeAdapter::getSerializedSize(&subCounter); - SerialBufferAdapter adapter(rawTimestamp,sizeof(rawTimestamp)); - size += adapter.getSerializedSize(); - return size; - - }; - - ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) { - ReturnValue_t result = SerializeAdapter::deSerialize(&apid, buffer, - size, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::deSerialize(&sourceSequenceCount, buffer, - size, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::deSerialize(&serviceType, buffer, size, - streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::deSerialize(&serviceSubtype, buffer, - size, streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = SerializeAdapter::deSerialize(&subCounter, buffer, size, - streamEndianness); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - SerialBufferAdapter adapter(rawTimestamp,sizeof(rawTimestamp)); - return adapter.deSerialize(buffer,size,streamEndianness); - } - -private: - uint16_t apid; - uint16_t sourceSequenceCount; - uint8_t serviceType; - uint8_t serviceSubtype; - uint8_t subCounter; - uint8_t rawTimestamp[TimeStamperIF::MISSION_TIMESTAMP_SIZE]; + ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, Endianness streamEndianness) { + ReturnValue_t result = SerializeAdapter::deSerialize(&apid, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::deSerialize(&sourceSequenceCount, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::deSerialize(&serviceType, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::deSerialize(&serviceSubtype, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::deSerialize(&subCounter, buffer, size, streamEndianness); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + SerialBufferAdapter adapter(rawTimestamp, sizeof(rawTimestamp)); + return adapter.deSerialize(buffer, size, streamEndianness); + } + private: + uint16_t apid; + uint16_t sourceSequenceCount; + uint8_t serviceType; + uint8_t serviceSubtype; + uint8_t subCounter; + uint8_t rawTimestamp[TimeStamperIF::MISSION_TIMESTAMP_SIZE]; }; #endif /* FSFW_TMSTORAGE_TMSTOREPACKETS_H_ */ diff --git a/src/fsfw/tmtcpacket/RedirectableDataPointerIF.h b/src/fsfw/tmtcpacket/RedirectableDataPointerIF.h index 63a760ec..364feb4e 100644 --- a/src/fsfw/tmtcpacket/RedirectableDataPointerIF.h +++ b/src/fsfw/tmtcpacket/RedirectableDataPointerIF.h @@ -1,34 +1,33 @@ #ifndef TMTCPACKET_PUS_TC_SETTABLEDATAPOINTERIF_H_ #define TMTCPACKET_PUS_TC_SETTABLEDATAPOINTERIF_H_ -#include "fsfw/returnvalues/HasReturnvaluesIF.h" #include +#include "fsfw/returnvalues/HasReturnvaluesIF.h" + /** * @brief This interface can be used for classes which store a reference to data. It allows * the implementing class to redirect the data it refers too. */ class RedirectableDataPointerIF { -public: - virtual ~RedirectableDataPointerIF() {}; + public: + virtual ~RedirectableDataPointerIF(){}; - /** - * Redirect the data pointer, but allow an implementation to change the data. - * The default implementation also sets a read-only pointer where applicable. - * @param dataPtr - * @param maxSize Maximum allowed size in buffer which holds the data. Can be used for size - * checks if a struct is cast directly onto the data pointer to ensure that the buffer is - * large enough - * @param args Any additional user arguments required to set the data pointer - * @return - * - RETURN_OK if the pointer was set successfully - * - RETURN_FAILED on general error of if the maximum size is too small - */ - virtual ReturnValue_t setData(uint8_t* dataPtr, size_t maxSize, void* args = nullptr) = 0; + /** + * Redirect the data pointer, but allow an implementation to change the data. + * The default implementation also sets a read-only pointer where applicable. + * @param dataPtr + * @param maxSize Maximum allowed size in buffer which holds the data. Can be used for size + * checks if a struct is cast directly onto the data pointer to ensure that the buffer is + * large enough + * @param args Any additional user arguments required to set the data pointer + * @return + * - RETURN_OK if the pointer was set successfully + * - RETURN_FAILED on general error of if the maximum size is too small + */ + virtual ReturnValue_t setData(uint8_t* dataPtr, size_t maxSize, void* args = nullptr) = 0; -private: + private: }; - - #endif /* FSFW_SRC_FSFW_TMTCPACKET_PUS_TC_SETTABLEDATAPOINTERIF_H_ */ diff --git a/src/fsfw/tmtcpacket/SpacePacket.cpp b/src/fsfw/tmtcpacket/SpacePacket.cpp index 5284eb5c..c8ebbd97 100644 --- a/src/fsfw/tmtcpacket/SpacePacket.cpp +++ b/src/fsfw/tmtcpacket/SpacePacket.cpp @@ -1,27 +1,28 @@ -#include "fsfw/tmtcpacket/ccsds_header.h" #include "fsfw/tmtcpacket/SpacePacket.h" + #include +#include "fsfw/tmtcpacket/ccsds_header.h" + SpacePacket::SpacePacket(uint16_t packetDataLength, bool isTelecommand, uint16_t apid, - uint16_t sequenceCount): - SpacePacketBase( (uint8_t*)&this->localData ) { - initSpacePacketHeader(isTelecommand, false, apid, sequenceCount); - this->setPacketSequenceCount(sequenceCount); - if ( packetDataLength <= sizeof(this->localData.fields.buffer) ) { - this->setPacketDataLength(packetDataLength); - } else { - this->setPacketDataLength( sizeof(this->localData.fields.buffer) ); - } + uint16_t sequenceCount) + : SpacePacketBase((uint8_t*)&this->localData) { + initSpacePacketHeader(isTelecommand, false, apid, sequenceCount); + this->setPacketSequenceCount(sequenceCount); + if (packetDataLength <= sizeof(this->localData.fields.buffer)) { + this->setPacketDataLength(packetDataLength); + } else { + this->setPacketDataLength(sizeof(this->localData.fields.buffer)); + } } -SpacePacket::~SpacePacket( void ) { -} +SpacePacket::~SpacePacket(void) {} -bool SpacePacket::addWholeData( const uint8_t* p_Data, uint32_t packet_size ) { - if ( packet_size <= sizeof(this->data) ) { - memcpy( &this->localData.byteStream, p_Data, packet_size ); - return true; - } else { - return false; - } +bool SpacePacket::addWholeData(const uint8_t* p_Data, uint32_t packet_size) { + if (packet_size <= sizeof(this->data)) { + memcpy(&this->localData.byteStream, p_Data, packet_size); + return true; + } else { + return false; + } } diff --git a/src/fsfw/tmtcpacket/SpacePacket.h b/src/fsfw/tmtcpacket/SpacePacket.h index d9e51f35..10140db1 100644 --- a/src/fsfw/tmtcpacket/SpacePacket.h +++ b/src/fsfw/tmtcpacket/SpacePacket.h @@ -13,80 +13,77 @@ * so the parent's methods are reachable. * @ingroup tmtcpackets */ -class SpacePacket: public SpacePacketBase { -public: - static const uint16_t PACKET_MAX_SIZE = 1024; - /** - * The constructor initializes the packet and sets all header information - * according to the passed parameters. - * @param packetDataLength Sets the packet data length field and therefore specifies - * the size of the packet. - * @param isTelecommand Sets the packet type field to either TC (true) or TM (false). - * @param apid Sets the packet's APID field. The default value describes an idle packet. - * @param sequenceCount ets the packet's Source Sequence Count field. - */ - SpacePacket(uint16_t packetDataLength, bool isTelecommand = false, - uint16_t apid = APID_IDLE_PACKET, uint16_t sequenceCount = 0); - /** - * The class's default destructor. - */ - virtual ~SpacePacket(); - /** - * With this call, the complete data content (including the CCSDS Primary - * Header) is overwritten with the byte stream given. - * @param p_data Pointer to data to overwrite the content with - * @param packet_size Size of the data - * @return @li \c true if packet_size is smaller than \c MAX_PACKET_SIZE. - * @li \c false else. - */ - bool addWholeData(const uint8_t* p_data, uint32_t packet_size); +class SpacePacket : public SpacePacketBase { + public: + static const uint16_t PACKET_MAX_SIZE = 1024; + /** + * The constructor initializes the packet and sets all header information + * according to the passed parameters. + * @param packetDataLength Sets the packet data length field and therefore specifies + * the size of the packet. + * @param isTelecommand Sets the packet type field to either TC (true) or TM (false). + * @param apid Sets the packet's APID field. The default value describes an idle packet. + * @param sequenceCount ets the packet's Source Sequence Count field. + */ + SpacePacket(uint16_t packetDataLength, bool isTelecommand = false, + uint16_t apid = APID_IDLE_PACKET, uint16_t sequenceCount = 0); + /** + * The class's default destructor. + */ + virtual ~SpacePacket(); + /** + * With this call, the complete data content (including the CCSDS Primary + * Header) is overwritten with the byte stream given. + * @param p_data Pointer to data to overwrite the content with + * @param packet_size Size of the data + * @return @li \c true if packet_size is smaller than \c MAX_PACKET_SIZE. + * @li \c false else. + */ + bool addWholeData(const uint8_t* p_data, uint32_t packet_size); -protected: - /** - * This structure defines the data structure of a Space Packet as local data. - * There's a buffer which corresponds to the Space Packet Data Field with a - * maximum size of \c PACKET_MAX_SIZE. - */ - struct PacketStructured { - CCSDSPrimaryHeader header; - uint8_t buffer[PACKET_MAX_SIZE]; - }; - /** - * This union simplifies accessing the full data content of the Space Packet. - * This is achieved by putting the \c PacketStructured struct in a union with - * a plain buffer. - */ - union SpacePacketData { - PacketStructured fields; - uint8_t byteStream[PACKET_MAX_SIZE + sizeof(CCSDSPrimaryHeader)]; - }; - /** - * This is the data representation of the class. - * It is a struct of CCSDS Primary Header and a data field, which again is - * packed in an union, so the data can be accessed as a byte stream without - * a cast. - */ - SpacePacketData localData; + protected: + /** + * This structure defines the data structure of a Space Packet as local data. + * There's a buffer which corresponds to the Space Packet Data Field with a + * maximum size of \c PACKET_MAX_SIZE. + */ + struct PacketStructured { + CCSDSPrimaryHeader header; + uint8_t buffer[PACKET_MAX_SIZE]; + }; + /** + * This union simplifies accessing the full data content of the Space Packet. + * This is achieved by putting the \c PacketStructured struct in a union with + * a plain buffer. + */ + union SpacePacketData { + PacketStructured fields; + uint8_t byteStream[PACKET_MAX_SIZE + sizeof(CCSDSPrimaryHeader)]; + }; + /** + * This is the data representation of the class. + * It is a struct of CCSDS Primary Header and a data field, which again is + * packed in an union, so the data can be accessed as a byte stream without + * a cast. + */ + SpacePacketData localData; }; namespace spacepacket { constexpr uint16_t getSpacePacketIdFromApid(bool isTc, uint16_t apid, - bool secondaryHeaderFlag = true) { - return ((isTc << 4) | (secondaryHeaderFlag << 3) | - ((apid >> 8) & 0x07)) << 8 | (apid & 0x00ff); + bool secondaryHeaderFlag = true) { + return ((isTc << 4) | (secondaryHeaderFlag << 3) | ((apid >> 8) & 0x07)) << 8 | (apid & 0x00ff); } -constexpr uint16_t getTcSpacePacketIdFromApid(uint16_t apid, - bool secondaryHeaderFlag = true) { - return getSpacePacketIdFromApid(true, apid, secondaryHeaderFlag); +constexpr uint16_t getTcSpacePacketIdFromApid(uint16_t apid, bool secondaryHeaderFlag = true) { + return getSpacePacketIdFromApid(true, apid, secondaryHeaderFlag); } -constexpr uint16_t getTmSpacePacketIdFromApid(uint16_t apid, - bool secondaryHeaderFlag = true) { - return getSpacePacketIdFromApid(false, apid, secondaryHeaderFlag); +constexpr uint16_t getTmSpacePacketIdFromApid(uint16_t apid, bool secondaryHeaderFlag = true) { + return getSpacePacketIdFromApid(false, apid, secondaryHeaderFlag); } -} +} // namespace spacepacket #endif /* SPACEPACKET_H_ */ diff --git a/src/fsfw/tmtcpacket/SpacePacketBase.cpp b/src/fsfw/tmtcpacket/SpacePacketBase.cpp index 58f4feea..756d7e50 100644 --- a/src/fsfw/tmtcpacket/SpacePacketBase.cpp +++ b/src/fsfw/tmtcpacket/SpacePacketBase.cpp @@ -1,127 +1,118 @@ #include "fsfw/tmtcpacket/SpacePacketBase.h" -#include "fsfw/serviceinterface/ServiceInterface.h" #include +#include "fsfw/serviceinterface/ServiceInterface.h" + SpacePacketBase::SpacePacketBase(const uint8_t* setAddress) { - this->data = reinterpret_cast(const_cast(setAddress)); + this->data = reinterpret_cast(const_cast(setAddress)); } -SpacePacketBase::~SpacePacketBase() { -}; +SpacePacketBase::~SpacePacketBase(){}; -//CCSDS Methods: -uint8_t SpacePacketBase::getPacketVersionNumber( void ) { - return (this->data->header.packet_id_h & 0b11100000) >> 5; +// CCSDS Methods: +uint8_t SpacePacketBase::getPacketVersionNumber(void) { + return (this->data->header.packet_id_h & 0b11100000) >> 5; } -ReturnValue_t SpacePacketBase::initSpacePacketHeader(bool isTelecommand, - bool hasSecondaryHeader, uint16_t apid, uint16_t sequenceCount) { - if(data == nullptr) { +ReturnValue_t SpacePacketBase::initSpacePacketHeader(bool isTelecommand, bool hasSecondaryHeader, + uint16_t apid, uint16_t sequenceCount) { + if (data == nullptr) { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "SpacePacketBase::initSpacePacketHeader: Data pointer is invalid" - << std::endl; + sif::warning << "SpacePacketBase::initSpacePacketHeader: Data pointer is invalid" << std::endl; #else - sif::printWarning("SpacePacketBase::initSpacePacketHeader: Data pointer is invalid!\n"); + sif::printWarning("SpacePacketBase::initSpacePacketHeader: Data pointer is invalid!\n"); #endif #endif - return HasReturnvaluesIF::RETURN_FAILED; - } - //reset header to zero: - memset(data, 0, sizeof(this->data->header) ); - //Set TC/TM bit. - data->header.packet_id_h = ((isTelecommand? 1 : 0)) << 4; - //Set secondaryHeader bit - data->header.packet_id_h |= ((hasSecondaryHeader? 1 : 0)) << 3; - this->setAPID( apid ); - //Always initialize as standalone packets. - data->header.sequence_control_h = 0b11000000; - setPacketSequenceCount(sequenceCount); - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_FAILED; + } + // reset header to zero: + memset(data, 0, sizeof(this->data->header)); + // Set TC/TM bit. + data->header.packet_id_h = ((isTelecommand ? 1 : 0)) << 4; + // Set secondaryHeader bit + data->header.packet_id_h |= ((hasSecondaryHeader ? 1 : 0)) << 3; + this->setAPID(apid); + // Always initialize as standalone packets. + data->header.sequence_control_h = 0b11000000; + setPacketSequenceCount(sequenceCount); + return HasReturnvaluesIF::RETURN_OK; } -bool SpacePacketBase::isTelecommand( void ) { - return (this->data->header.packet_id_h & 0b00010000) >> 4; +bool SpacePacketBase::isTelecommand(void) { + return (this->data->header.packet_id_h & 0b00010000) >> 4; } -bool SpacePacketBase::hasSecondaryHeader( void ) { - return (this->data->header.packet_id_h & 0b00001000) >> 3; +bool SpacePacketBase::hasSecondaryHeader(void) { + return (this->data->header.packet_id_h & 0b00001000) >> 3; } uint16_t SpacePacketBase::getPacketId() { - return ( (this->data->header.packet_id_h) << 8 ) + - this->data->header.packet_id_l; + return ((this->data->header.packet_id_h) << 8) + this->data->header.packet_id_l; } -uint16_t SpacePacketBase::getAPID( void ) const { - return ( (this->data->header.packet_id_h & 0b00000111) << 8 ) + - this->data->header.packet_id_l; +uint16_t SpacePacketBase::getAPID(void) const { + return ((this->data->header.packet_id_h & 0b00000111) << 8) + this->data->header.packet_id_l; } -void SpacePacketBase::setAPID( uint16_t new_apid ) { - // Use first three bits of new APID, but keep rest of packet id as it was (see specification). - this->data->header.packet_id_h = (this->data->header.packet_id_h & 0b11111000) | - ( ( new_apid & 0x0700 ) >> 8 ); - this->data->header.packet_id_l = ( new_apid & 0x00FF ); +void SpacePacketBase::setAPID(uint16_t new_apid) { + // Use first three bits of new APID, but keep rest of packet id as it was (see specification). + this->data->header.packet_id_h = + (this->data->header.packet_id_h & 0b11111000) | ((new_apid & 0x0700) >> 8); + this->data->header.packet_id_l = (new_apid & 0x00FF); } -void SpacePacketBase::setSequenceFlags( uint8_t sequenceflags ) { - this->data->header.sequence_control_h &= 0x3F; - this->data->header.sequence_control_h |= sequenceflags << 6; +void SpacePacketBase::setSequenceFlags(uint8_t sequenceflags) { + this->data->header.sequence_control_h &= 0x3F; + this->data->header.sequence_control_h |= sequenceflags << 6; } -uint16_t SpacePacketBase::getPacketSequenceControl( void ) { - return ( (this->data->header.sequence_control_h) << 8 ) - + this->data->header.sequence_control_l; +uint16_t SpacePacketBase::getPacketSequenceControl(void) { + return ((this->data->header.sequence_control_h) << 8) + this->data->header.sequence_control_l; } -uint8_t SpacePacketBase::getSequenceFlags( void ) { - return (this->data->header.sequence_control_h & 0b11000000) >> 6 ; +uint8_t SpacePacketBase::getSequenceFlags(void) { + return (this->data->header.sequence_control_h & 0b11000000) >> 6; } -uint16_t SpacePacketBase::getPacketSequenceCount( void ) const { - return ( (this->data->header.sequence_control_h & 0b00111111) << 8 ) - + this->data->header.sequence_control_l; +uint16_t SpacePacketBase::getPacketSequenceCount(void) const { + return ((this->data->header.sequence_control_h & 0b00111111) << 8) + + this->data->header.sequence_control_l; } -void SpacePacketBase::setPacketSequenceCount( uint16_t new_count) { - this->data->header.sequence_control_h = ( this->data->header.sequence_control_h & 0b11000000 ) | - ( ( (new_count%LIMIT_SEQUENCE_COUNT) & 0x3F00 ) >> 8 ); - this->data->header.sequence_control_l = ( (new_count%LIMIT_SEQUENCE_COUNT) & 0x00FF ); +void SpacePacketBase::setPacketSequenceCount(uint16_t new_count) { + this->data->header.sequence_control_h = (this->data->header.sequence_control_h & 0b11000000) | + (((new_count % LIMIT_SEQUENCE_COUNT) & 0x3F00) >> 8); + this->data->header.sequence_control_l = ((new_count % LIMIT_SEQUENCE_COUNT) & 0x00FF); } uint16_t SpacePacketBase::getPacketDataLength() const { - return ( (this->data->header.packet_length_h) << 8 ) - + this->data->header.packet_length_l; + return ((this->data->header.packet_length_h) << 8) + this->data->header.packet_length_l; } -void SpacePacketBase::setPacketDataLength( uint16_t new_length) { - this->data->header.packet_length_h = ( ( new_length & 0xFF00 ) >> 8 ); - this->data->header.packet_length_l = ( new_length & 0x00FF ); +void SpacePacketBase::setPacketDataLength(uint16_t new_length) { + this->data->header.packet_length_h = ((new_length & 0xFF00) >> 8); + this->data->header.packet_length_l = (new_length & 0x00FF); } size_t SpacePacketBase::getFullSize() { - // +1 is done because size in packet data length field is: size of data field -1 - return this->getPacketDataLength() + sizeof(this->data->header) + 1; + // +1 is done because size in packet data length field is: size of data field -1 + return this->getPacketDataLength() + sizeof(this->data->header) + 1; } -uint8_t* SpacePacketBase::getWholeData() { - return (uint8_t*)this->data; -} +uint8_t* SpacePacketBase::getWholeData() { return (uint8_t*)this->data; } uint32_t SpacePacketBase::getApidAndSequenceCount() const { - return (getAPID() << 16) + getPacketSequenceCount(); + return (getAPID() << 16) + getPacketSequenceCount(); } -uint8_t* SpacePacketBase::getPacketData() { - return &(data->packet_data); -} +uint8_t* SpacePacketBase::getPacketData() { return &(data->packet_data); } -ReturnValue_t SpacePacketBase::setData(uint8_t *pData, size_t maxSize, void *args) { - if(maxSize < 6) { - return HasReturnvaluesIF::RETURN_FAILED; - } - this->data = reinterpret_cast(const_cast(pData)); - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t SpacePacketBase::setData(uint8_t* pData, size_t maxSize, void* args) { + if (maxSize < 6) { + return HasReturnvaluesIF::RETURN_FAILED; + } + this->data = reinterpret_cast(const_cast(pData)); + return HasReturnvaluesIF::RETURN_OK; } diff --git a/src/fsfw/tmtcpacket/SpacePacketBase.h b/src/fsfw/tmtcpacket/SpacePacketBase.h index dfc808e3..d9ee2b83 100644 --- a/src/fsfw/tmtcpacket/SpacePacketBase.h +++ b/src/fsfw/tmtcpacket/SpacePacketBase.h @@ -2,11 +2,12 @@ #define FSFW_TMTCPACKET_SPACEPACKETBASE_H_ #include -#include "ccsds_header.h" -#include "fsfw/returnvalues/HasReturnvaluesIF.h" #include +#include "ccsds_header.h" +#include "fsfw/returnvalues/HasReturnvaluesIF.h" + /** * @defgroup tmtcpackets Space Packets * This is the group, where all classes associated with Telecommand and @@ -23,8 +24,8 @@ * @ingroup tmtcpackets */ struct SpacePacketPointer { - CCSDSPrimaryHeader header; - uint8_t packet_data; + CCSDSPrimaryHeader header; + uint8_t packet_data; }; /** @@ -38,155 +39,154 @@ struct SpacePacketPointer { * the most significant bit (from left). * @ingroup tmtcpackets */ -class SpacePacketBase: virtual public RedirectableDataPointerIF { -protected: - /** - * A pointer to a structure which defines the data structure of - * the packet header. - * To be hardware-safe, all elements are of byte size. - */ - SpacePacketPointer* data; -public: - static const uint16_t LIMIT_APID = 2048; //2^1 - static const uint16_t LIMIT_SEQUENCE_COUNT = 16384; // 2^14 - static const uint16_t APID_IDLE_PACKET = 0x7FF; - static const uint8_t TELECOMMAND_PACKET = 1; - static const uint8_t TELEMETRY_PACKET = 0; - /** - * This definition defines the CRC size in byte. - */ - static const uint8_t CRC_SIZE = 2; - /** - * This is the minimum size of a SpacePacket. - */ - static const uint16_t MINIMUM_SIZE = sizeof(CCSDSPrimaryHeader) + CRC_SIZE; - /** - * This is the default constructor. - * It sets its internal data pointer to the address passed. - * @param set_address The position where the packet data lies. - */ - SpacePacketBase( const uint8_t* set_address ); - /** - * No data is allocated, so the destructor is empty. - */ - virtual ~SpacePacketBase(); +class SpacePacketBase : virtual public RedirectableDataPointerIF { + protected: + /** + * A pointer to a structure which defines the data structure of + * the packet header. + * To be hardware-safe, all elements are of byte size. + */ + SpacePacketPointer* data; - //CCSDS Methods: - /** - * Getter for the packet version number field. - * @return Returns the highest three bit of the packet in one byte. - */ - uint8_t getPacketVersionNumber( void ); - /** - * This method checks the type field in the header. - * This bit specifies, if the command is interpreted as Telecommand of - * as Telemetry. For a Telecommand, the bit is set. - * @return Returns true if the bit is set and false if not. - */ - bool isTelecommand( void ); + public: + static const uint16_t LIMIT_APID = 2048; // 2^1 + static const uint16_t LIMIT_SEQUENCE_COUNT = 16384; // 2^14 + static const uint16_t APID_IDLE_PACKET = 0x7FF; + static const uint8_t TELECOMMAND_PACKET = 1; + static const uint8_t TELEMETRY_PACKET = 0; + /** + * This definition defines the CRC size in byte. + */ + static const uint8_t CRC_SIZE = 2; + /** + * This is the minimum size of a SpacePacket. + */ + static const uint16_t MINIMUM_SIZE = sizeof(CCSDSPrimaryHeader) + CRC_SIZE; + /** + * This is the default constructor. + * It sets its internal data pointer to the address passed. + * @param set_address The position where the packet data lies. + */ + SpacePacketBase(const uint8_t* set_address); + /** + * No data is allocated, so the destructor is empty. + */ + virtual ~SpacePacketBase(); - ReturnValue_t initSpacePacketHeader(bool isTelecommand, bool hasSecondaryHeader, - uint16_t apid, uint16_t sequenceCount = 0); - /** - * The CCSDS header provides a secondary header flag (the fifth-highest bit), - * which is checked with this method. - * @return Returns true if the bit is set and false if not. - */ - bool hasSecondaryHeader( void ); - /** - * Returns the complete first two bytes of the packet, which together form - * the CCSDS packet id. - * @return The CCSDS packet id. - */ - uint16_t getPacketId( void ); - /** - * Returns the APID of a packet, which are the lowest 11 bit of the packet - * id. - * @return The CCSDS APID. - */ - uint16_t getAPID( void ) const; - /** - * Sets the APID of a packet, which are the lowest 11 bit of the packet - * id. - * @param The APID to set. The highest five bits of the parameter are - * ignored. - */ - void setAPID( uint16_t setAPID ); + // CCSDS Methods: + /** + * Getter for the packet version number field. + * @return Returns the highest three bit of the packet in one byte. + */ + uint8_t getPacketVersionNumber(void); + /** + * This method checks the type field in the header. + * This bit specifies, if the command is interpreted as Telecommand of + * as Telemetry. For a Telecommand, the bit is set. + * @return Returns true if the bit is set and false if not. + */ + bool isTelecommand(void); - /** - * Sets the sequence flags of a packet, which are bit 17 and 18 in the space packet header. - * @param The sequence flags to set - */ - void setSequenceFlags( uint8_t sequenceflags ); + ReturnValue_t initSpacePacketHeader(bool isTelecommand, bool hasSecondaryHeader, uint16_t apid, + uint16_t sequenceCount = 0); + /** + * The CCSDS header provides a secondary header flag (the fifth-highest bit), + * which is checked with this method. + * @return Returns true if the bit is set and false if not. + */ + bool hasSecondaryHeader(void); + /** + * Returns the complete first two bytes of the packet, which together form + * the CCSDS packet id. + * @return The CCSDS packet id. + */ + uint16_t getPacketId(void); + /** + * Returns the APID of a packet, which are the lowest 11 bit of the packet + * id. + * @return The CCSDS APID. + */ + uint16_t getAPID(void) const; + /** + * Sets the APID of a packet, which are the lowest 11 bit of the packet + * id. + * @param The APID to set. The highest five bits of the parameter are + * ignored. + */ + void setAPID(uint16_t setAPID); - /** - * Returns the CCSDS packet sequence control field, which are the third and - * the fourth byte of the CCSDS primary header. - * @return The CCSDS packet sequence control field. - */ - uint16_t getPacketSequenceControl( void ); - /** - * Returns the SequenceFlags, which are the highest two bit of the packet - * sequence control field. - * @return The CCSDS sequence flags. - */ - uint8_t getSequenceFlags( void ); - /** - * Returns the packet sequence count, which are the lowest 14 bit of the - * packet sequence control field. - * @return The CCSDS sequence count. - */ - uint16_t getPacketSequenceCount( void ) const; - /** - * Sets the packet sequence count, which are the lowest 14 bit of the - * packet sequence control field. - * setCount is modulo-divided by \c LIMIT_SEQUENCE_COUNT to avoid overflows. - * @param setCount The value to set the count to. - */ - void setPacketSequenceCount( uint16_t setCount ); - /** - * Returns the packet data length, which is the fifth and sixth byte of the - * CCSDS Primary Header. The packet data length is the size of every kind - * of data \b after the CCSDS Primary Header \b -1. - * @return - * The CCSDS packet data length. uint16_t is sufficient, - * because this is limit in CCSDS standard - */ - uint16_t getPacketDataLength(void) const; - /** - * Sets the packet data length, which is the fifth and sixth byte of the - * CCSDS Primary Header. - * @param setLength The value of the length to set. It must fit the true - * CCSDS packet data length . The packet data length is - * the size of every kind of data \b after the CCSDS - * Primary Header \b -1. - */ - void setPacketDataLength( uint16_t setLength ); + /** + * Sets the sequence flags of a packet, which are bit 17 and 18 in the space packet header. + * @param The sequence flags to set + */ + void setSequenceFlags(uint8_t sequenceflags); - //Helper methods: - /** - * This method returns a raw uint8_t pointer to the packet. - * @return A \c uint8_t pointer to the first byte of the CCSDS primary header. - */ - virtual uint8_t* getWholeData( void ); + /** + * Returns the CCSDS packet sequence control field, which are the third and + * the fourth byte of the CCSDS primary header. + * @return The CCSDS packet sequence control field. + */ + uint16_t getPacketSequenceControl(void); + /** + * Returns the SequenceFlags, which are the highest two bit of the packet + * sequence control field. + * @return The CCSDS sequence flags. + */ + uint8_t getSequenceFlags(void); + /** + * Returns the packet sequence count, which are the lowest 14 bit of the + * packet sequence control field. + * @return The CCSDS sequence count. + */ + uint16_t getPacketSequenceCount(void) const; + /** + * Sets the packet sequence count, which are the lowest 14 bit of the + * packet sequence control field. + * setCount is modulo-divided by \c LIMIT_SEQUENCE_COUNT to avoid overflows. + * @param setCount The value to set the count to. + */ + void setPacketSequenceCount(uint16_t setCount); + /** + * Returns the packet data length, which is the fifth and sixth byte of the + * CCSDS Primary Header. The packet data length is the size of every kind + * of data \b after the CCSDS Primary Header \b -1. + * @return + * The CCSDS packet data length. uint16_t is sufficient, + * because this is limit in CCSDS standard + */ + uint16_t getPacketDataLength(void) const; + /** + * Sets the packet data length, which is the fifth and sixth byte of the + * CCSDS Primary Header. + * @param setLength The value of the length to set. It must fit the true + * CCSDS packet data length . The packet data length is + * the size of every kind of data \b after the CCSDS + * Primary Header \b -1. + */ + void setPacketDataLength(uint16_t setLength); - uint8_t* getPacketData(); + // Helper methods: + /** + * This method returns a raw uint8_t pointer to the packet. + * @return A \c uint8_t pointer to the first byte of the CCSDS primary header. + */ + virtual uint8_t* getWholeData(void); - /** - * With this method, the packet data pointer can be redirected to another - * location. - * @param p_Data A pointer to another raw Space Packet. - */ - virtual ReturnValue_t setData(uint8_t* p_Data , size_t maxSize, - void* args = nullptr) override; - /** - * This method returns the full raw packet size. - * @return The full size of the packet in bytes. - */ - size_t getFullSize(); + uint8_t* getPacketData(); - uint32_t getApidAndSequenceCount() const; + /** + * With this method, the packet data pointer can be redirected to another + * location. + * @param p_Data A pointer to another raw Space Packet. + */ + virtual ReturnValue_t setData(uint8_t* p_Data, size_t maxSize, void* args = nullptr) override; + /** + * This method returns the full raw packet size. + * @return The full size of the packet in bytes. + */ + size_t getFullSize(); + uint32_t getApidAndSequenceCount() const; }; #endif /* FSFW_TMTCPACKET_SPACEPACKETBASE_H_ */ diff --git a/src/fsfw/tmtcpacket/ccsds_header.h b/src/fsfw/tmtcpacket/ccsds_header.h index 40d6829f..232790c0 100644 --- a/src/fsfw/tmtcpacket/ccsds_header.h +++ b/src/fsfw/tmtcpacket/ccsds_header.h @@ -4,12 +4,12 @@ #include struct CCSDSPrimaryHeader { - uint8_t packet_id_h; - uint8_t packet_id_l; - uint8_t sequence_control_h; - uint8_t sequence_control_l; - uint8_t packet_length_h; - uint8_t packet_length_l; + uint8_t packet_id_h; + uint8_t packet_id_l; + uint8_t sequence_control_h; + uint8_t sequence_control_l; + uint8_t packet_length_h; + uint8_t packet_length_l; }; #endif /* CCSDS_HEADER_H_ */ diff --git a/src/fsfw/tmtcpacket/cfdp/CFDPPacket.cpp b/src/fsfw/tmtcpacket/cfdp/CFDPPacket.cpp index 6172201e..5df50cd7 100644 --- a/src/fsfw/tmtcpacket/cfdp/CFDPPacket.cpp +++ b/src/fsfw/tmtcpacket/cfdp/CFDPPacket.cpp @@ -1,20 +1,20 @@ #include "fsfw/tmtcpacket/cfdp/CFDPPacket.h" +#include + #include "fsfw/globalfunctions/CRC.h" #include "fsfw/globalfunctions/arrayprinter.h" #include "fsfw/serviceinterface/ServiceInterface.h" -#include - -CFDPPacket::CFDPPacket(const uint8_t* setData): SpacePacketBase(setData) {} +CFDPPacket::CFDPPacket(const uint8_t* setData) : SpacePacketBase(setData) {} CFDPPacket::~CFDPPacket() {} void CFDPPacket::print() { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "CFDPPacket::print:" << std::endl; + sif::info << "CFDPPacket::print:" << std::endl; #else - sif::printInfo("CFDPPacket::print:\n"); + sif::printInfo("CFDPPacket::print:\n"); #endif - arrayprinter::print(getWholeData(), getFullSize()); + arrayprinter::print(getWholeData(), getFullSize()); } diff --git a/src/fsfw/tmtcpacket/cfdp/CFDPPacket.h b/src/fsfw/tmtcpacket/cfdp/CFDPPacket.h index f288a8ae..30ba98ae 100644 --- a/src/fsfw/tmtcpacket/cfdp/CFDPPacket.h +++ b/src/fsfw/tmtcpacket/cfdp/CFDPPacket.h @@ -4,24 +4,24 @@ #include "fsfw/tmtcpacket/SpacePacketBase.h" class CFDPPacket : public SpacePacketBase { -public: - /** - * This is the default constructor. - * It sets its internal data pointer to the address passed and also - * forwards the data pointer to the parent SpacePacketBase class. - * @param setData The position where the packet data lies. - */ - CFDPPacket( const uint8_t* setData ); - /** - * This is the empty default destructor. - */ - virtual ~CFDPPacket(); + public: + /** + * This is the default constructor. + * It sets its internal data pointer to the address passed and also + * forwards the data pointer to the parent SpacePacketBase class. + * @param setData The position where the packet data lies. + */ + CFDPPacket(const uint8_t* setData); + /** + * This is the empty default destructor. + */ + virtual ~CFDPPacket(); - /** - * This is a debugging helper method that prints the whole packet content - * to the screen. - */ - void print(); + /** + * This is a debugging helper method that prints the whole packet content + * to the screen. + */ + void print(); }; #endif /* FSFW_INC_FSFW_TMTCPACKET_CFDP_CFDPPACKET_H_ */ diff --git a/src/fsfw/tmtcpacket/cfdp/CFDPPacketStored.cpp b/src/fsfw/tmtcpacket/cfdp/CFDPPacketStored.cpp index 568d8981..9a410b40 100644 --- a/src/fsfw/tmtcpacket/cfdp/CFDPPacketStored.cpp +++ b/src/fsfw/tmtcpacket/cfdp/CFDPPacketStored.cpp @@ -1,97 +1,92 @@ #include "fsfw/tmtcpacket/cfdp/CFDPPacketStored.h" + #include "fsfw/objectmanager/ObjectManager.h" StorageManagerIF* CFDPPacketStored::store = nullptr; -CFDPPacketStored::CFDPPacketStored(): CFDPPacket(nullptr) { +CFDPPacketStored::CFDPPacketStored() : CFDPPacket(nullptr) {} + +CFDPPacketStored::CFDPPacketStored(store_address_t setAddress) : CFDPPacket(nullptr) { + this->setStoreAddress(setAddress); } -CFDPPacketStored::CFDPPacketStored(store_address_t setAddress): CFDPPacket(nullptr) { - this->setStoreAddress(setAddress); -} - -CFDPPacketStored::CFDPPacketStored(const uint8_t* data, size_t size): CFDPPacket(data) { - if (this->getFullSize() != size) { - return; - } - if (this->checkAndSetStore()) { - ReturnValue_t status = store->addData(&storeAddress, data, size); - if (status != HasReturnvaluesIF::RETURN_OK) { - this->setData(nullptr, -1); - } - const uint8_t* storePtr = nullptr; - // Repoint base data pointer to the data in the store. - store->getData(storeAddress, &storePtr, &size); - this->setData(const_cast(storePtr), size); +CFDPPacketStored::CFDPPacketStored(const uint8_t* data, size_t size) : CFDPPacket(data) { + if (this->getFullSize() != size) { + return; + } + if (this->checkAndSetStore()) { + ReturnValue_t status = store->addData(&storeAddress, data, size); + if (status != HasReturnvaluesIF::RETURN_OK) { + this->setData(nullptr, -1); } + const uint8_t* storePtr = nullptr; + // Repoint base data pointer to the data in the store. + store->getData(storeAddress, &storePtr, &size); + this->setData(const_cast(storePtr), size); + } } ReturnValue_t CFDPPacketStored::deletePacket() { - ReturnValue_t result = this->store->deleteData(this->storeAddress); - this->storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; + ReturnValue_t result = this->store->deleteData(this->storeAddress); + this->storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; + // To circumvent size checks + this->setData(nullptr, -1); + return result; +} + +// CFDPPacket* CFDPPacketStored::getPacketBase() { +// return this; +// } +void CFDPPacketStored::setStoreAddress(store_address_t setAddress) { + this->storeAddress = setAddress; + const uint8_t* tempData = nullptr; + size_t tempSize; + ReturnValue_t status = StorageManagerIF::RETURN_FAILED; + if (this->checkAndSetStore()) { + status = this->store->getData(this->storeAddress, &tempData, &tempSize); + } + if (status == StorageManagerIF::RETURN_OK) { + this->setData(const_cast(tempData), tempSize); + } else { // To circumvent size checks this->setData(nullptr, -1); - return result; + this->storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; + } } -//CFDPPacket* CFDPPacketStored::getPacketBase() { -// return this; -//} -void CFDPPacketStored::setStoreAddress(store_address_t setAddress) { - this->storeAddress = setAddress; - const uint8_t* tempData = nullptr; - size_t tempSize; - ReturnValue_t status = StorageManagerIF::RETURN_FAILED; - if (this->checkAndSetStore()) { - status = this->store->getData(this->storeAddress, &tempData, &tempSize); - } - if (status == StorageManagerIF::RETURN_OK) { - this->setData(const_cast(tempData), tempSize); - } else { - // To circumvent size checks - this->setData(nullptr, -1); - this->storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; - } +store_address_t CFDPPacketStored::getStoreAddress() { return this->storeAddress; } + +CFDPPacketStored::~CFDPPacketStored() {} + +ReturnValue_t CFDPPacketStored::getData(const uint8_t** dataPtr, size_t* dataSize) { + return HasReturnvaluesIF::RETURN_OK; } -store_address_t CFDPPacketStored::getStoreAddress() { - return this->storeAddress; -} - -CFDPPacketStored::~CFDPPacketStored() { -} - -ReturnValue_t CFDPPacketStored::getData(const uint8_t **dataPtr, size_t *dataSize) { - return HasReturnvaluesIF::RETURN_OK; -} - -//ReturnValue_t CFDPPacketStored::setData(const uint8_t *data) { -// return HasReturnvaluesIF::RETURN_OK; -//} +// ReturnValue_t CFDPPacketStored::setData(const uint8_t *data) { +// return HasReturnvaluesIF::RETURN_OK; +// } bool CFDPPacketStored::checkAndSetStore() { + if (this->store == nullptr) { + this->store = ObjectManager::instance()->get(objects::TC_STORE); if (this->store == nullptr) { - this->store = ObjectManager::instance()->get(objects::TC_STORE); - if (this->store == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "CFDPPacketStored::CFDPPacketStored: TC Store not found!" - << std::endl; + sif::error << "CFDPPacketStored::CFDPPacketStored: TC Store not found!" << std::endl; #endif - return false; - } + return false; } - return true; + } + return true; } bool CFDPPacketStored::isSizeCorrect() { - const uint8_t* temp_data = nullptr; - size_t temp_size; - ReturnValue_t status = this->store->getData(this->storeAddress, &temp_data, - &temp_size); - if (status == StorageManagerIF::RETURN_OK) { - if (this->getFullSize() == temp_size) { - return true; - } + const uint8_t* temp_data = nullptr; + size_t temp_size; + ReturnValue_t status = this->store->getData(this->storeAddress, &temp_data, &temp_size); + if (status == StorageManagerIF::RETURN_OK) { + if (this->getFullSize() == temp_size) { + return true; } - return false; + } + return false; } diff --git a/src/fsfw/tmtcpacket/cfdp/CFDPPacketStored.h b/src/fsfw/tmtcpacket/cfdp/CFDPPacketStored.h index 2c03439b..f9c73bdd 100644 --- a/src/fsfw/tmtcpacket/cfdp/CFDPPacketStored.h +++ b/src/fsfw/tmtcpacket/cfdp/CFDPPacketStored.h @@ -4,64 +4,60 @@ #include "../pus/tc/TcPacketStoredBase.h" #include "CFDPPacket.h" -class CFDPPacketStored: - public CFDPPacket, - public TcPacketStoredBase { -public: - /** - * Create stored packet with existing data. - * @param data - * @param size - */ - CFDPPacketStored(const uint8_t* data, size_t size); - /** - * Create stored packet from existing packet in store - * @param setAddress - */ - CFDPPacketStored(store_address_t setAddress); - CFDPPacketStored(); +class CFDPPacketStored : public CFDPPacket, public TcPacketStoredBase { + public: + /** + * Create stored packet with existing data. + * @param data + * @param size + */ + CFDPPacketStored(const uint8_t* data, size_t size); + /** + * Create stored packet from existing packet in store + * @param setAddress + */ + CFDPPacketStored(store_address_t setAddress); + CFDPPacketStored(); - virtual ~CFDPPacketStored(); + virtual ~CFDPPacketStored(); - /** - * Getter function for the raw data. - * @param dataPtr [out] Pointer to the data pointer to set - * @param dataSize [out] Address of size to set. - * @return -@c RETURN_OK if data was retrieved successfully. - */ - ReturnValue_t getData(const uint8_t ** dataPtr, size_t* dataSize); + /** + * Getter function for the raw data. + * @param dataPtr [out] Pointer to the data pointer to set + * @param dataSize [out] Address of size to set. + * @return -@c RETURN_OK if data was retrieved successfully. + */ + ReturnValue_t getData(const uint8_t** dataPtr, size_t* dataSize); - void setStoreAddress(store_address_t setAddress); + void setStoreAddress(store_address_t setAddress); - store_address_t getStoreAddress(); + store_address_t getStoreAddress(); - ReturnValue_t deletePacket(); + ReturnValue_t deletePacket(); -private: + private: + bool isSizeCorrect(); - bool isSizeCorrect(); -protected: - /** - * This is a pointer to the store all instances of the class use. - * If the store is not yet set (i.e. @c store is NULL), every constructor - * call tries to set it and throws an error message in case of failures. - * The default store is objects::TC_STORE. - */ - static StorageManagerIF* store; - /** - * The address where the packet data of the object instance is stored. - */ - store_address_t storeAddress; - /** - * A helper method to check if a store is assigned to the class. - * If not, the method tries to retrieve the store from the global - * ObjectManager. - * @return @li @c true if the store is linked or could be created. - * @li @c false otherwise. - */ - bool checkAndSetStore(); + protected: + /** + * This is a pointer to the store all instances of the class use. + * If the store is not yet set (i.e. @c store is NULL), every constructor + * call tries to set it and throws an error message in case of failures. + * The default store is objects::TC_STORE. + */ + static StorageManagerIF* store; + /** + * The address where the packet data of the object instance is stored. + */ + store_address_t storeAddress; + /** + * A helper method to check if a store is assigned to the class. + * If not, the method tries to retrieve the store from the global + * ObjectManager. + * @return @li @c true if the store is linked or could be created. + * @li @c false otherwise. + */ + bool checkAndSetStore(); }; - - #endif /* FSFW_INC_FSFW_TMTCPACKET_CFDP_CFDPPACKETSTORED_H_ */ diff --git a/src/fsfw/tmtcpacket/packetmatcher/ApidMatcher.h b/src/fsfw/tmtcpacket/packetmatcher/ApidMatcher.h index 33db7151..cf4c88f2 100644 --- a/src/fsfw/tmtcpacket/packetmatcher/ApidMatcher.h +++ b/src/fsfw/tmtcpacket/packetmatcher/ApidMatcher.h @@ -5,36 +5,28 @@ #include "../../serialize/SerializeAdapter.h" #include "../../tmtcpacket/pus/tm/TmPacketMinimal.h" -class ApidMatcher: public SerializeableMatcherIF { -private: - uint16_t apid; -public: - ApidMatcher(uint16_t setApid) : - apid(setApid) { - } - ApidMatcher(TmPacketMinimal* test) : - apid(test->getAPID()) { - } - bool match(TmPacketMinimal* packet) { - if (packet->getAPID() == apid) { - return true; - } else { - return false; - } - } - ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const { - return SerializeAdapter::serialize(&apid, buffer, size, maxSize, streamEndianness); - } - size_t getSerializedSize() const { - return SerializeAdapter::getSerializedSize(&apid); - } - ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) { - return SerializeAdapter::deSerialize(&apid, buffer, size, streamEndianness); +class ApidMatcher : public SerializeableMatcherIF { + private: + uint16_t apid; + + public: + ApidMatcher(uint16_t setApid) : apid(setApid) {} + ApidMatcher(TmPacketMinimal* test) : apid(test->getAPID()) {} + bool match(TmPacketMinimal* packet) { + if (packet->getAPID() == apid) { + return true; + } else { + return false; } + } + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const { + return SerializeAdapter::serialize(&apid, buffer, size, maxSize, streamEndianness); + } + size_t getSerializedSize() const { return SerializeAdapter::getSerializedSize(&apid); } + ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, Endianness streamEndianness) { + return SerializeAdapter::deSerialize(&apid, buffer, size, streamEndianness); + } }; - - #endif /* FRAMEWORK_TMTCPACKET_PACKETMATCHER_APIDMATCHER_H_ */ diff --git a/src/fsfw/tmtcpacket/packetmatcher/PacketMatchTree.cpp b/src/fsfw/tmtcpacket/packetmatcher/PacketMatchTree.cpp index 7f8aae9a..6b900030 100644 --- a/src/fsfw/tmtcpacket/packetmatcher/PacketMatchTree.cpp +++ b/src/fsfw/tmtcpacket/packetmatcher/PacketMatchTree.cpp @@ -1,198 +1,190 @@ -#include "fsfw/tmtcpacket/packetmatcher/ApidMatcher.h" #include "fsfw/tmtcpacket/packetmatcher/PacketMatchTree.h" + +#include "fsfw/tmtcpacket/packetmatcher/ApidMatcher.h" #include "fsfw/tmtcpacket/packetmatcher/ServiceMatcher.h" #include "fsfw/tmtcpacket/packetmatcher/SubserviceMatcher.h" // This should be configurable.. const LocalPool::LocalPoolConfig PacketMatchTree::poolConfig = { - {10, sizeof(ServiceMatcher)}, - {20, sizeof(SubServiceMatcher)}, - {2, sizeof(ApidMatcher)}, - {40, sizeof(PacketMatchTree::Node)} -}; + {10, sizeof(ServiceMatcher)}, + {20, sizeof(SubServiceMatcher)}, + {2, sizeof(ApidMatcher)}, + {40, sizeof(PacketMatchTree::Node)}}; -PacketMatchTree::PacketMatchTree(Node* root): MatchTree(root, 2), - factoryBackend(0, poolConfig, false, true), - factory(&factoryBackend) { -} +PacketMatchTree::PacketMatchTree(Node* root) + : MatchTree(root, 2), + factoryBackend(0, poolConfig, false, true), + factory(&factoryBackend) {} -PacketMatchTree::PacketMatchTree(iterator root): MatchTree(root.element, 2), - factoryBackend(0, poolConfig, false, true), - factory(&factoryBackend) { -} +PacketMatchTree::PacketMatchTree(iterator root) + : MatchTree(root.element, 2), + factoryBackend(0, poolConfig, false, true), + factory(&factoryBackend) {} -PacketMatchTree::PacketMatchTree(): MatchTree((Node*) NULL, 2), - factoryBackend(0, poolConfig, false, true), - factory(&factoryBackend) { -} +PacketMatchTree::PacketMatchTree() + : MatchTree((Node*)NULL, 2), + factoryBackend(0, poolConfig, false, true), + factory(&factoryBackend) {} -PacketMatchTree::~PacketMatchTree() { -} +PacketMatchTree::~PacketMatchTree() {} -ReturnValue_t PacketMatchTree::addMatch(uint16_t apid, uint8_t type, - uint8_t subtype) { - //We assume adding APID is always requested. - TmPacketMinimal::TmPacketMinimalPointer data; - data.data_field.service_type = type; - data.data_field.service_subtype = subtype; - TmPacketMinimal testPacket((uint8_t*) &data); - testPacket.setAPID(apid); - iterator lastTest; - iterator rollback; - ReturnValue_t result = findOrInsertMatch( - this->begin(), &testPacket, &lastTest); - if (result == NEW_NODE_CREATED) { - rollback = lastTest; - } else if (result != RETURN_OK) { - return result; - } - if (type == 0) { - //Check if lastTest has no children, otherwise, delete them, - //as a more general check is requested. - if (lastTest.left() != this->end()) { - removeElementAndAllChildren(lastTest.left()); - } - return RETURN_OK; - } - //Type insertion required. - result = findOrInsertMatch( - lastTest.left(), &testPacket, &lastTest); - if (result == NEW_NODE_CREATED) { - if (rollback == this->end()) { - rollback = lastTest; - } - } else if (result != RETURN_OK) { - if (rollback != this->end()) { - removeElementAndAllChildren(rollback); - } - return result; - } - if (subtype == 0) { - if (lastTest.left() != this->end()) { - //See above - removeElementAndAllChildren(lastTest.left()); - } - return RETURN_OK; - } - //Subtype insertion required. - result = findOrInsertMatch( - lastTest.left(), &testPacket, &lastTest); - if (result == NEW_NODE_CREATED) { - return RETURN_OK; - } else if (result != RETURN_OK) { - if (rollback != this->end()) { - removeElementAndAllChildren(rollback); - } - return result; +ReturnValue_t PacketMatchTree::addMatch(uint16_t apid, uint8_t type, uint8_t subtype) { + // We assume adding APID is always requested. + TmPacketMinimal::TmPacketMinimalPointer data; + data.data_field.service_type = type; + data.data_field.service_subtype = subtype; + TmPacketMinimal testPacket((uint8_t*)&data); + testPacket.setAPID(apid); + iterator lastTest; + iterator rollback; + ReturnValue_t result = + findOrInsertMatch(this->begin(), &testPacket, &lastTest); + if (result == NEW_NODE_CREATED) { + rollback = lastTest; + } else if (result != RETURN_OK) { + return result; + } + if (type == 0) { + // Check if lastTest has no children, otherwise, delete them, + // as a more general check is requested. + if (lastTest.left() != this->end()) { + removeElementAndAllChildren(lastTest.left()); } return RETURN_OK; + } + // Type insertion required. + result = + findOrInsertMatch(lastTest.left(), &testPacket, &lastTest); + if (result == NEW_NODE_CREATED) { + if (rollback == this->end()) { + rollback = lastTest; + } + } else if (result != RETURN_OK) { + if (rollback != this->end()) { + removeElementAndAllChildren(rollback); + } + return result; + } + if (subtype == 0) { + if (lastTest.left() != this->end()) { + // See above + removeElementAndAllChildren(lastTest.left()); + } + return RETURN_OK; + } + // Subtype insertion required. + result = findOrInsertMatch(lastTest.left(), &testPacket, + &lastTest); + if (result == NEW_NODE_CREATED) { + return RETURN_OK; + } else if (result != RETURN_OK) { + if (rollback != this->end()) { + removeElementAndAllChildren(rollback); + } + return result; + } + return RETURN_OK; } -template +template ReturnValue_t PacketMatchTree::findOrInsertMatch(iterator startAt, VALUE_T test, - iterator* lastTest) { - bool attachToBranch = AND; - iterator iter = startAt; - while (iter != this->end()) { - bool isMatch = iter->match(test); - attachToBranch = OR; - *lastTest = iter; - if (isMatch) { - return RETURN_OK; - } else { - //Go down OR branch. - iter = iter.right(); - } - } - //Only reached if nothing was found. - SerializeableMatcherIF* newContent = factory.generate( - test); - if (newContent == NULL) { - return FULL; - } - Node* newNode = factory.generate(newContent); - if (newNode == NULL) { - //Need to make sure partially generated content is deleted, otherwise, that's a leak. - factory.destroy(static_cast(newContent)); - return FULL; - } - *lastTest = insert(attachToBranch, *lastTest, newNode); - if (*lastTest == end()) { - //This actaully never fails, so creating a dedicated returncode seems an overshoot. - return RETURN_FAILED; - } - return NEW_NODE_CREATED; -} - -ReturnValue_t PacketMatchTree::removeMatch(uint16_t apid, uint8_t type, - uint8_t subtype) { - TmPacketMinimal::TmPacketMinimalPointer data; - data.data_field.service_type = type; - data.data_field.service_subtype = subtype; - TmPacketMinimal testPacket((uint8_t*) &data); - testPacket.setAPID(apid); - iterator foundElement = findMatch(begin(), &testPacket); - if (foundElement == this->end()) { - return NO_MATCH; - } - if (type == 0) { - if (foundElement.left() == end()) { - return removeElementAndReconnectChildren(foundElement); - } else { - return TOO_GENERAL_REQUEST; - } - } - //Go down AND branch. Will abort if empty. - foundElement = findMatch(foundElement.left(), &testPacket); - if (foundElement == this->end()) { - return NO_MATCH; - } - if (subtype == 0) { - if (foundElement.left() == end()) { - return removeElementAndReconnectChildren(foundElement); - } else { - return TOO_GENERAL_REQUEST; - } - } - //Again, go down AND branch. - foundElement = findMatch(foundElement.left(), &testPacket); - if (foundElement == end()) { - return NO_MATCH; - } - return removeElementAndReconnectChildren(foundElement); -} - -PacketMatchTree::iterator PacketMatchTree::findMatch(iterator startAt, - TmPacketMinimal* test) { - iterator iter = startAt; - while (iter != end()) { - bool isMatch = iter->match(test); - if (isMatch) { - break; - } else { - iter = iter.right(); //next OR element - } - } - return iter; -} - -ReturnValue_t PacketMatchTree::initialize() { - return factoryBackend.initialize(); -} - - -ReturnValue_t PacketMatchTree::changeMatch(bool addToMatch, uint16_t apid, - uint8_t type, uint8_t subtype) { - if (addToMatch) { - return addMatch(apid, type, subtype); + iterator* lastTest) { + bool attachToBranch = AND; + iterator iter = startAt; + while (iter != this->end()) { + bool isMatch = iter->match(test); + attachToBranch = OR; + *lastTest = iter; + if (isMatch) { + return RETURN_OK; } else { - return removeMatch(apid, type, subtype); + // Go down OR branch. + iter = iter.right(); } + } + // Only reached if nothing was found. + SerializeableMatcherIF* newContent = factory.generate(test); + if (newContent == NULL) { + return FULL; + } + Node* newNode = factory.generate(newContent); + if (newNode == NULL) { + // Need to make sure partially generated content is deleted, otherwise, that's a leak. + factory.destroy(static_cast(newContent)); + return FULL; + } + *lastTest = insert(attachToBranch, *lastTest, newNode); + if (*lastTest == end()) { + // This actaully never fails, so creating a dedicated returncode seems an overshoot. + return RETURN_FAILED; + } + return NEW_NODE_CREATED; +} + +ReturnValue_t PacketMatchTree::removeMatch(uint16_t apid, uint8_t type, uint8_t subtype) { + TmPacketMinimal::TmPacketMinimalPointer data; + data.data_field.service_type = type; + data.data_field.service_subtype = subtype; + TmPacketMinimal testPacket((uint8_t*)&data); + testPacket.setAPID(apid); + iterator foundElement = findMatch(begin(), &testPacket); + if (foundElement == this->end()) { + return NO_MATCH; + } + if (type == 0) { + if (foundElement.left() == end()) { + return removeElementAndReconnectChildren(foundElement); + } else { + return TOO_GENERAL_REQUEST; + } + } + // Go down AND branch. Will abort if empty. + foundElement = findMatch(foundElement.left(), &testPacket); + if (foundElement == this->end()) { + return NO_MATCH; + } + if (subtype == 0) { + if (foundElement.left() == end()) { + return removeElementAndReconnectChildren(foundElement); + } else { + return TOO_GENERAL_REQUEST; + } + } + // Again, go down AND branch. + foundElement = findMatch(foundElement.left(), &testPacket); + if (foundElement == end()) { + return NO_MATCH; + } + return removeElementAndReconnectChildren(foundElement); +} + +PacketMatchTree::iterator PacketMatchTree::findMatch(iterator startAt, TmPacketMinimal* test) { + iterator iter = startAt; + while (iter != end()) { + bool isMatch = iter->match(test); + if (isMatch) { + break; + } else { + iter = iter.right(); // next OR element + } + } + return iter; +} + +ReturnValue_t PacketMatchTree::initialize() { return factoryBackend.initialize(); } + +ReturnValue_t PacketMatchTree::changeMatch(bool addToMatch, uint16_t apid, uint8_t type, + uint8_t subtype) { + if (addToMatch) { + return addMatch(apid, type, subtype); + } else { + return removeMatch(apid, type, subtype); + } } ReturnValue_t PacketMatchTree::cleanUpElement(iterator position) { - factory.destroy(position.element->value); - //Go on anyway, there's nothing we can do. - //SHOULDDO: Throw event, or write debug message? - return factory.destroy(position.element); + factory.destroy(position.element->value); + // Go on anyway, there's nothing we can do. + // SHOULDDO: Throw event, or write debug message? + return factory.destroy(position.element); } diff --git a/src/fsfw/tmtcpacket/packetmatcher/PacketMatchTree.h b/src/fsfw/tmtcpacket/packetmatcher/PacketMatchTree.h index e2439c74..0cbd4494 100644 --- a/src/fsfw/tmtcpacket/packetmatcher/PacketMatchTree.h +++ b/src/fsfw/tmtcpacket/packetmatcher/PacketMatchTree.h @@ -6,32 +6,30 @@ #include "fsfw/storagemanager/LocalPool.h" #include "fsfw/tmtcpacket/pus/tm/TmPacketMinimal.h" -class PacketMatchTree: public MatchTree, public HasReturnvaluesIF { -public: - PacketMatchTree(Node* root); - PacketMatchTree(iterator root); - PacketMatchTree(); - virtual ~PacketMatchTree(); - ReturnValue_t changeMatch(bool addToMatch, uint16_t apid, uint8_t type = 0, - uint8_t subtype = 0); - ReturnValue_t addMatch(uint16_t apid, uint8_t type = 0, - uint8_t subtype = 0); - ReturnValue_t removeMatch(uint16_t apid, uint8_t type = 0, - uint8_t subtype = 0); - ReturnValue_t initialize(); -protected: - ReturnValue_t cleanUpElement(iterator position); -private: - static const uint8_t N_POOLS = 4; - LocalPool factoryBackend; - PlacementFactory factory; - static const LocalPool::LocalPoolConfig poolConfig; - static const uint16_t POOL_SIZES[N_POOLS]; - static const uint16_t N_ELEMENTS[N_POOLS]; - template - ReturnValue_t findOrInsertMatch(iterator startAt, VALUE_T test, iterator* lastTest); - iterator findMatch(iterator startAt, TmPacketMinimal* test); +class PacketMatchTree : public MatchTree, public HasReturnvaluesIF { + public: + PacketMatchTree(Node* root); + PacketMatchTree(iterator root); + PacketMatchTree(); + virtual ~PacketMatchTree(); + ReturnValue_t changeMatch(bool addToMatch, uint16_t apid, uint8_t type = 0, uint8_t subtype = 0); + ReturnValue_t addMatch(uint16_t apid, uint8_t type = 0, uint8_t subtype = 0); + ReturnValue_t removeMatch(uint16_t apid, uint8_t type = 0, uint8_t subtype = 0); + ReturnValue_t initialize(); + + protected: + ReturnValue_t cleanUpElement(iterator position); + + private: + static const uint8_t N_POOLS = 4; + LocalPool factoryBackend; + PlacementFactory factory; + static const LocalPool::LocalPoolConfig poolConfig; + static const uint16_t POOL_SIZES[N_POOLS]; + static const uint16_t N_ELEMENTS[N_POOLS]; + template + ReturnValue_t findOrInsertMatch(iterator startAt, VALUE_T test, iterator* lastTest); + iterator findMatch(iterator startAt, TmPacketMinimal* test); }; #endif /* FRAMEWORK_TMTCPACKET_PACKETMATCHER_PACKETMATCHTREE_H_ */ - diff --git a/src/fsfw/tmtcpacket/packetmatcher/ServiceMatcher.h b/src/fsfw/tmtcpacket/packetmatcher/ServiceMatcher.h index 67d09d2b..752c0354 100644 --- a/src/fsfw/tmtcpacket/packetmatcher/ServiceMatcher.h +++ b/src/fsfw/tmtcpacket/packetmatcher/ServiceMatcher.h @@ -5,35 +5,28 @@ #include "../../serialize/SerializeAdapter.h" #include "../pus/tm/TmPacketMinimal.h" -class ServiceMatcher: public SerializeableMatcherIF { -private: - uint8_t service; -public: - ServiceMatcher(uint8_t setService) : - service(setService) { - } - ServiceMatcher(TmPacketMinimal* test) : - service(test->getService()) { - } - bool match(TmPacketMinimal* packet) { - if (packet->getService() == service) { - return true; - } else { - return false; - } - } - ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const { - return SerializeAdapter::serialize(&service, buffer, size, maxSize, streamEndianness); - } - size_t getSerializedSize() const { - return SerializeAdapter::getSerializedSize(&service); - } - ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) { - return SerializeAdapter::deSerialize(&service, buffer, size, streamEndianness); +class ServiceMatcher : public SerializeableMatcherIF { + private: + uint8_t service; + + public: + ServiceMatcher(uint8_t setService) : service(setService) {} + ServiceMatcher(TmPacketMinimal* test) : service(test->getService()) {} + bool match(TmPacketMinimal* packet) { + if (packet->getService() == service) { + return true; + } else { + return false; } + } + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const { + return SerializeAdapter::serialize(&service, buffer, size, maxSize, streamEndianness); + } + size_t getSerializedSize() const { return SerializeAdapter::getSerializedSize(&service); } + ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, Endianness streamEndianness) { + return SerializeAdapter::deSerialize(&service, buffer, size, streamEndianness); + } }; - #endif /* FRAMEWORK_TMTCPACKET_PACKETMATCHER_SERVICEMATCHER_H_ */ diff --git a/src/fsfw/tmtcpacket/packetmatcher/SubserviceMatcher.h b/src/fsfw/tmtcpacket/packetmatcher/SubserviceMatcher.h index e570b452..934e8cb8 100644 --- a/src/fsfw/tmtcpacket/packetmatcher/SubserviceMatcher.h +++ b/src/fsfw/tmtcpacket/packetmatcher/SubserviceMatcher.h @@ -5,36 +5,28 @@ #include "../../serialize/SerializeAdapter.h" #include "../pus/tm/TmPacketMinimal.h" -class SubServiceMatcher: public SerializeableMatcherIF { -public: - SubServiceMatcher(uint8_t subService) : - subService(subService) { +class SubServiceMatcher : public SerializeableMatcherIF { + public: + SubServiceMatcher(uint8_t subService) : subService(subService) {} + SubServiceMatcher(TmPacketMinimal* test) : subService(test->getSubService()) {} + bool match(TmPacketMinimal* packet) { + if (packet->getSubService() == subService) { + return true; + } else { + return false; } - SubServiceMatcher(TmPacketMinimal* test) : - subService(test->getSubService()) { - } - bool match(TmPacketMinimal* packet) { - if (packet->getSubService() == subService) { - return true; - } else { - return false; - } - } - ReturnValue_t serialize(uint8_t** buffer, size_t* size, - size_t maxSize, Endianness streamEndianness) const { - return SerializeAdapter::serialize(&subService, buffer, size, maxSize, streamEndianness); - } - size_t getSerializedSize() const { - return SerializeAdapter::getSerializedSize(&subService); - } - ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, - Endianness streamEndianness) { - return SerializeAdapter::deSerialize(&subService, buffer, size, streamEndianness); - } -private: - uint8_t subService; + } + ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const { + return SerializeAdapter::serialize(&subService, buffer, size, maxSize, streamEndianness); + } + size_t getSerializedSize() const { return SerializeAdapter::getSerializedSize(&subService); } + ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, Endianness streamEndianness) { + return SerializeAdapter::deSerialize(&subService, buffer, size, streamEndianness); + } + + private: + uint8_t subService; }; - - #endif /* FRAMEWORK_TMTCPACKET_PACKETMATCHER_SUBSERVICEMATCHER_H_ */ diff --git a/src/fsfw/tmtcpacket/pus/PacketTimestampInterpreterIF.h b/src/fsfw/tmtcpacket/pus/PacketTimestampInterpreterIF.h index b839223a..340f7825 100644 --- a/src/fsfw/tmtcpacket/pus/PacketTimestampInterpreterIF.h +++ b/src/fsfw/tmtcpacket/pus/PacketTimestampInterpreterIF.h @@ -6,14 +6,11 @@ class TmPacketMinimal; class PacketTimestampInterpreterIF { -public: - virtual ~PacketTimestampInterpreterIF() {} - virtual ReturnValue_t getPacketTime(TmPacketMinimal* packet, - timeval* timestamp) const = 0; - virtual ReturnValue_t getPacketTimeRaw(TmPacketMinimal* packet, const uint8_t** timePtr, - uint32_t* size) const = 0; + public: + virtual ~PacketTimestampInterpreterIF() {} + virtual ReturnValue_t getPacketTime(TmPacketMinimal* packet, timeval* timestamp) const = 0; + virtual ReturnValue_t getPacketTimeRaw(TmPacketMinimal* packet, const uint8_t** timePtr, + uint32_t* size) const = 0; }; - - #endif /* FSFW_TMTCPACKET_PUS_PACKETTIMESTAMPINTERPRETERIF_H_ */ diff --git a/src/fsfw/tmtcpacket/pus/definitions.h b/src/fsfw/tmtcpacket/pus/definitions.h index d92ab312..d4b649d0 100644 --- a/src/fsfw/tmtcpacket/pus/definitions.h +++ b/src/fsfw/tmtcpacket/pus/definitions.h @@ -6,11 +6,8 @@ namespace pus { //! Version numbers according to ECSS-E-ST-70-41C p.439 -enum PusVersion: uint8_t { - PUS_A_VERSION = 1, - PUS_C_VERSION = 2 -}; +enum PusVersion : uint8_t { PUS_A_VERSION = 1, PUS_C_VERSION = 2 }; -} +} // namespace pus #endif /* FSFW_SRC_FSFW_TMTCPACKET_PUS_TM_DEFINITIONS_H_ */ diff --git a/src/fsfw/tmtcpacket/pus/tc.h b/src/fsfw/tmtcpacket/pus/tc.h index 156e49fe..f5a467aa 100644 --- a/src/fsfw/tmtcpacket/pus/tc.h +++ b/src/fsfw/tmtcpacket/pus/tc.h @@ -1,7 +1,7 @@ #ifndef FSFW_TMTCPACKET_PUS_TC_H_ #define FSFW_TMTCPACKET_PUS_TC_H_ -#include "tc/TcPacketStoredPus.h" #include "tc/TcPacketPus.h" +#include "tc/TcPacketStoredPus.h" #endif /* FSFW_TMTCPACKET_PUS_TC_H_ */ diff --git a/src/fsfw/tmtcpacket/pus/tc/TcPacketPus.cpp b/src/fsfw/tmtcpacket/pus/tc/TcPacketPus.cpp index dc1eb4bf..f5ebe38c 100644 --- a/src/fsfw/tmtcpacket/pus/tc/TcPacketPus.cpp +++ b/src/fsfw/tmtcpacket/pus/tc/TcPacketPus.cpp @@ -1,105 +1,99 @@ #include "TcPacketPus.h" -#include "fsfw/globalfunctions/CRC.h" #include -TcPacketPus::TcPacketPus(const uint8_t *setData): TcPacketPusBase(setData) { - tcData = reinterpret_cast(const_cast(setData)); +#include "fsfw/globalfunctions/CRC.h" + +TcPacketPus::TcPacketPus(const uint8_t *setData) : TcPacketPusBase(setData) { + tcData = reinterpret_cast(const_cast(setData)); } -void TcPacketPus::initializeTcPacket(uint16_t apid, uint16_t sequenceCount, - uint8_t ack, uint8_t service, uint8_t subservice, pus::PusVersion pusVersion, - uint16_t sourceId) { - initSpacePacketHeader(true, true, apid, sequenceCount); - std::memset(&tcData->dataField, 0, sizeof(tcData->dataField)); - setPacketDataLength(sizeof(PUSTcDataFieldHeader) + CRC_SIZE - 1); - // Data Field Header. For PUS A, the first bit (CCSDS Secondary Header Flag) is zero - tcData->dataField.versionTypeAck = pusVersion << 4 | (ack & 0x0F); - tcData->dataField.serviceType = service; - tcData->dataField.serviceSubtype = subservice; +void TcPacketPus::initializeTcPacket(uint16_t apid, uint16_t sequenceCount, uint8_t ack, + uint8_t service, uint8_t subservice, + pus::PusVersion pusVersion, uint16_t sourceId) { + initSpacePacketHeader(true, true, apid, sequenceCount); + std::memset(&tcData->dataField, 0, sizeof(tcData->dataField)); + setPacketDataLength(sizeof(PUSTcDataFieldHeader) + CRC_SIZE - 1); + // Data Field Header. For PUS A, the first bit (CCSDS Secondary Header Flag) is zero + tcData->dataField.versionTypeAck = pusVersion << 4 | (ack & 0x0F); + tcData->dataField.serviceType = service; + tcData->dataField.serviceSubtype = subservice; #if FSFW_USE_PUS_C_TELECOMMANDS == 1 - tcData->dataField.sourceIdH = (sourceId >> 8) | 0xff; - tcData->dataField.sourceIdL = sourceId & 0xff; + tcData->dataField.sourceIdH = (sourceId >> 8) | 0xff; + tcData->dataField.sourceIdL = sourceId & 0xff; #else - tcData->dataField.sourceId = sourceId; + tcData->dataField.sourceId = sourceId; #endif } -uint8_t TcPacketPus::getService() const { - return tcData->dataField.serviceType; -} +uint8_t TcPacketPus::getService() const { return tcData->dataField.serviceType; } -uint8_t TcPacketPus::getSubService() const { - return tcData->dataField.serviceSubtype; -} +uint8_t TcPacketPus::getSubService() const { return tcData->dataField.serviceSubtype; } uint8_t TcPacketPus::getAcknowledgeFlags() const { - return tcData->dataField.versionTypeAck & 0b00001111; + return tcData->dataField.versionTypeAck & 0b00001111; } -const uint8_t* TcPacketPus::getApplicationData() const { - return &tcData->appData; -} +const uint8_t *TcPacketPus::getApplicationData() const { return &tcData->appData; } uint16_t TcPacketPus::getApplicationDataSize() const { - return getPacketDataLength() - sizeof(tcData->dataField) - CRC_SIZE + 1; + return getPacketDataLength() - sizeof(tcData->dataField) - CRC_SIZE + 1; } uint16_t TcPacketPus::getErrorControl() const { - uint16_t size = getApplicationDataSize() + CRC_SIZE; - uint8_t* p_to_buffer = &tcData->appData; - return (p_to_buffer[size - 2] << 8) + p_to_buffer[size - 1]; + uint16_t size = getApplicationDataSize() + CRC_SIZE; + uint8_t *p_to_buffer = &tcData->appData; + return (p_to_buffer[size - 2] << 8) + p_to_buffer[size - 1]; } void TcPacketPus::setErrorControl() { - uint32_t full_size = getFullSize(); - uint16_t crc = CRC::crc16ccitt(getWholeData(), full_size - CRC_SIZE); - uint32_t size = getApplicationDataSize(); - (&tcData->appData)[size] = (crc & 0XFF00) >> 8; // CRCH - (&tcData->appData)[size + 1] = (crc) & 0X00FF; // CRCL + uint32_t full_size = getFullSize(); + uint16_t crc = CRC::crc16ccitt(getWholeData(), full_size - CRC_SIZE); + uint32_t size = getApplicationDataSize(); + (&tcData->appData)[size] = (crc & 0XFF00) >> 8; // CRCH + (&tcData->appData)[size + 1] = (crc)&0X00FF; // CRCL } uint8_t TcPacketPus::getSecondaryHeaderFlag() const { #if FSFW_USE_PUS_C_TELECOMMANDS == 1 - // Does not exist for PUS C - return 0; + // Does not exist for PUS C + return 0; #else - return (tcData->dataField.versionTypeAck & 0b10000000) >> 7; + return (tcData->dataField.versionTypeAck & 0b10000000) >> 7; #endif } uint8_t TcPacketPus::getPusVersionNumber() const { #if FSFW_USE_PUS_C_TELECOMMANDS == 1 - return (tcData->dataField.versionTypeAck & 0b11110000) >> 4; + return (tcData->dataField.versionTypeAck & 0b11110000) >> 4; #else - return (tcData->dataField.versionTypeAck & 0b01110000) >> 4; + return (tcData->dataField.versionTypeAck & 0b01110000) >> 4; #endif } uint16_t TcPacketPus::getSourceId() const { #if FSFW_USE_PUS_C_TELECOMMANDS == 1 - return (tcData->dataField.sourceIdH << 8) | tcData->dataField.sourceIdL; + return (tcData->dataField.sourceIdH << 8) | tcData->dataField.sourceIdL; #else - return tcData->dataField.sourceId; + return tcData->dataField.sourceId; #endif } size_t TcPacketPus::calculateFullPacketLength(size_t appDataLen) const { - return sizeof(CCSDSPrimaryHeader) + sizeof(PUSTcDataFieldHeader) + - appDataLen + TcPacketPusBase::CRC_SIZE; + return sizeof(CCSDSPrimaryHeader) + sizeof(PUSTcDataFieldHeader) + appDataLen + + TcPacketPusBase::CRC_SIZE; } ReturnValue_t TcPacketPus::setData(uint8_t *dataPtr, size_t maxSize, void *args) { - ReturnValue_t result = SpacePacketBase::setData(dataPtr, maxSize); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if(maxSize < sizeof(TcPacketPointer)) { - return HasReturnvaluesIF::RETURN_FAILED; - } - // This function is const-correct, but it was decided to keep the pointer non-const - // for convenience. Therefore, cast away constness here and then cast to packet type. - tcData = reinterpret_cast(const_cast(dataPtr)); - return HasReturnvaluesIF::RETURN_OK; + ReturnValue_t result = SpacePacketBase::setData(dataPtr, maxSize); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (maxSize < sizeof(TcPacketPointer)) { + return HasReturnvaluesIF::RETURN_FAILED; + } + // This function is const-correct, but it was decided to keep the pointer non-const + // for convenience. Therefore, cast away constness here and then cast to packet type. + tcData = reinterpret_cast(const_cast(dataPtr)); + return HasReturnvaluesIF::RETURN_OK; } - diff --git a/src/fsfw/tmtcpacket/pus/tc/TcPacketPus.h b/src/fsfw/tmtcpacket/pus/tc/TcPacketPus.h index 1b0facaf..47173dad 100644 --- a/src/fsfw/tmtcpacket/pus/tc/TcPacketPus.h +++ b/src/fsfw/tmtcpacket/pus/tc/TcPacketPus.h @@ -1,13 +1,13 @@ #ifndef FSFW_TMTCPACKET_PUS_TCPACKETPUSA_H_ #define FSFW_TMTCPACKET_PUS_TCPACKETPUSA_H_ -#include "fsfw/FSFW.h" -#include "../definitions.h" -#include "fsfw/tmtcpacket/ccsds_header.h" -#include "TcPacketPusBase.h" - #include +#include "../definitions.h" +#include "TcPacketPusBase.h" +#include "fsfw/FSFW.h" +#include "fsfw/tmtcpacket/ccsds_header.h" + /** * This struct defines a byte-wise structured PUS TC A Data Field Header. * Any optional fields in the header must be added or removed here. @@ -15,14 +15,14 @@ * @ingroup tmtcpackets */ struct PUSTcDataFieldHeader { - uint8_t versionTypeAck; - uint8_t serviceType; - uint8_t serviceSubtype; + uint8_t versionTypeAck; + uint8_t serviceType; + uint8_t serviceSubtype; #if FSFW_USE_PUS_C_TELECOMMANDS == 1 - uint8_t sourceIdH; - uint8_t sourceIdL; + uint8_t sourceIdH; + uint8_t sourceIdL; #else - uint8_t sourceId; + uint8_t sourceId; #endif }; @@ -32,62 +32,57 @@ struct PUSTcDataFieldHeader { * @ingroup tmtcpackets */ struct TcPacketPointer { - CCSDSPrimaryHeader primary; - PUSTcDataFieldHeader dataField; - uint8_t appData; + CCSDSPrimaryHeader primary; + PUSTcDataFieldHeader dataField; + uint8_t appData; }; +class TcPacketPus : public TcPacketPusBase { + public: + static const uint16_t TC_PACKET_MIN_SIZE = + (sizeof(CCSDSPrimaryHeader) + sizeof(PUSTcDataFieldHeader) + 2); -class TcPacketPus: public TcPacketPusBase { -public: - static const uint16_t TC_PACKET_MIN_SIZE = (sizeof(CCSDSPrimaryHeader) + - sizeof(PUSTcDataFieldHeader) + 2); + /** + * Initialize a PUS A telecommand packet which already exists. You can also + * create an empty (invalid) object by passing nullptr as the data pointer + * @param setData + */ + TcPacketPus(const uint8_t* setData); - /** - * Initialize a PUS A telecommand packet which already exists. You can also - * create an empty (invalid) object by passing nullptr as the data pointer - * @param setData - */ - TcPacketPus(const uint8_t* setData); + // Base class overrides + uint8_t getSecondaryHeaderFlag() const override; + uint8_t getPusVersionNumber() const override; + uint8_t getAcknowledgeFlags() const override; + uint8_t getService() const override; + uint8_t getSubService() const override; + uint16_t getSourceId() const override; + const uint8_t* getApplicationData() const override; + uint16_t getApplicationDataSize() const override; + uint16_t getErrorControl() const override; + void setErrorControl() override; + size_t calculateFullPacketLength(size_t appDataLen) const override; - // Base class overrides - uint8_t getSecondaryHeaderFlag() const override; - uint8_t getPusVersionNumber() const override; - uint8_t getAcknowledgeFlags() const override; - uint8_t getService() const override; - uint8_t getSubService() const override; - uint16_t getSourceId() const override; - const uint8_t* getApplicationData() const override; - uint16_t getApplicationDataSize() const override; - uint16_t getErrorControl() const override; - void setErrorControl() override; - size_t calculateFullPacketLength(size_t appDataLen) const override; + protected: + ReturnValue_t setData(uint8_t* dataPtr, size_t maxSize, void* args = nullptr) override; -protected: + /** + * Initializes the Tc Packet header. + * @param apid APID used. + * @param sequenceCount Sequence Count in the primary header. + * @param ack Which acknowledeges are expected from the receiver. + * @param service PUS Service + * @param subservice PUS Subservice + */ + void initializeTcPacket(uint16_t apid, uint16_t sequenceCount, uint8_t ack, uint8_t service, + uint8_t subservice, pus::PusVersion pusVersion, uint16_t sourceId = 0); - ReturnValue_t setData(uint8_t* dataPtr, size_t maxSize, - void* args = nullptr) override; - - /** - * Initializes the Tc Packet header. - * @param apid APID used. - * @param sequenceCount Sequence Count in the primary header. - * @param ack Which acknowledeges are expected from the receiver. - * @param service PUS Service - * @param subservice PUS Subservice - */ - void initializeTcPacket(uint16_t apid, uint16_t sequenceCount, uint8_t ack, - uint8_t service, uint8_t subservice, pus::PusVersion pusVersion, - uint16_t sourceId = 0); - - /** - * A pointer to a structure which defines the data structure of - * the packet's data. - * - * To be hardware-safe, all elements are of byte size. - */ - TcPacketPointer* tcData = nullptr; + /** + * A pointer to a structure which defines the data structure of + * the packet's data. + * + * To be hardware-safe, all elements are of byte size. + */ + TcPacketPointer* tcData = nullptr; }; - #endif /* FSFW_TMTCPACKET_PUS_TCPACKETPUSA_H_ */ diff --git a/src/fsfw/tmtcpacket/pus/tc/TcPacketPusBase.cpp b/src/fsfw/tmtcpacket/pus/tc/TcPacketPusBase.cpp index 1a8850b1..812bae43 100644 --- a/src/fsfw/tmtcpacket/pus/tc/TcPacketPusBase.cpp +++ b/src/fsfw/tmtcpacket/pus/tc/TcPacketPusBase.cpp @@ -1,20 +1,20 @@ #include "TcPacketPusBase.h" +#include + #include "fsfw/globalfunctions/CRC.h" #include "fsfw/globalfunctions/arrayprinter.h" #include "fsfw/serviceinterface/ServiceInterface.h" -#include - -TcPacketPusBase::TcPacketPusBase(const uint8_t* setData): SpacePacketBase(setData) {} +TcPacketPusBase::TcPacketPusBase(const uint8_t* setData) : SpacePacketBase(setData) {} TcPacketPusBase::~TcPacketPusBase() {} void TcPacketPusBase::print() { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TcPacketBase::print:" << std::endl; + sif::info << "TcPacketBase::print:" << std::endl; #else - sif::printInfo("TcPacketBase::print:\n"); + sif::printInfo("TcPacketBase::print:\n"); #endif - arrayprinter::print(getWholeData(), getFullSize()); + arrayprinter::print(getWholeData(), getFullSize()); } diff --git a/src/fsfw/tmtcpacket/pus/tc/TcPacketPusBase.h b/src/fsfw/tmtcpacket/pus/tc/TcPacketPusBase.h index b65ca0fb..9f1d07ed 100644 --- a/src/fsfw/tmtcpacket/pus/tc/TcPacketPusBase.h +++ b/src/fsfw/tmtcpacket/pus/tc/TcPacketPusBase.h @@ -2,9 +2,11 @@ #define TMTCPACKET_PUS_TCPACKETBASE_H_ #include -#include "fsfw/tmtcpacket/SpacePacketBase.h" + #include +#include "fsfw/tmtcpacket/SpacePacketBase.h" + /** * This class is the basic data handler for any ECSS PUS Telecommand packet. * @@ -16,139 +18,134 @@ * check can be performed by making use of the getWholeData method. * @ingroup tmtcpackets */ -class TcPacketPusBase : public SpacePacketBase, - virtual public RedirectableDataPointerIF { - friend class TcPacketStoredBase; -public: +class TcPacketPusBase : public SpacePacketBase, virtual public RedirectableDataPointerIF { + friend class TcPacketStoredBase; - enum AckField { - //! No acknowledgements are expected. - ACK_NONE = 0b0000, - //! Acknowledgements on acceptance are expected. - ACK_ACCEPTANCE = 0b0001, - //! Acknowledgements on start are expected. - ACK_START = 0b0010, - //! Acknowledgements on step are expected. - ACK_STEP = 0b0100, - //! Acknowledfgement on completion are expected. - ACK_COMPLETION = 0b1000 - }; + public: + enum AckField { + //! No acknowledgements are expected. + ACK_NONE = 0b0000, + //! Acknowledgements on acceptance are expected. + ACK_ACCEPTANCE = 0b0001, + //! Acknowledgements on start are expected. + ACK_START = 0b0010, + //! Acknowledgements on step are expected. + ACK_STEP = 0b0100, + //! Acknowledfgement on completion are expected. + ACK_COMPLETION = 0b1000 + }; - static constexpr uint8_t ACK_ALL = ACK_ACCEPTANCE | ACK_START | ACK_STEP | - ACK_COMPLETION; + static constexpr uint8_t ACK_ALL = ACK_ACCEPTANCE | ACK_START | ACK_STEP | ACK_COMPLETION; - /** - * This is the default constructor. - * It sets its internal data pointer to the address passed and also - * forwards the data pointer to the parent SpacePacketBase class. - * @param setData The position where the packet data lies. - */ - TcPacketPusBase( const uint8_t* setData ); - /** - * This is the empty default destructor. - */ - virtual ~TcPacketPusBase(); + /** + * This is the default constructor. + * It sets its internal data pointer to the address passed and also + * forwards the data pointer to the parent SpacePacketBase class. + * @param setData The position where the packet data lies. + */ + TcPacketPusBase(const uint8_t* setData); + /** + * This is the empty default destructor. + */ + virtual ~TcPacketPusBase(); - /** - * This command returns the CCSDS Secondary Header Flag. - * It shall always be zero for PUS Packets. This is the - * highest bit of the first byte of the Data Field Header. - * @return the CCSDS Secondary Header Flag - */ - virtual uint8_t getSecondaryHeaderFlag() const = 0; - /** - * This command returns the TC Packet PUS Version Number. - * The version number of ECSS PUS 2003 is 1. - * It consists of the second to fourth highest bits of the - * first byte. - * @return - */ - virtual uint8_t getPusVersionNumber() const = 0; - /** - * This is a getter for the packet's Ack field, which are the lowest four - * bits of the first byte of the Data Field Header. - * - * It is packed in a uint8_t variable. - * @return The packet's PUS Ack field. - */ - virtual uint8_t getAcknowledgeFlags() const = 0; - /** - * This is a getter for the packet's PUS Service ID, which is the second - * byte of the Data Field Header. - * @return The packet's PUS Service ID. - */ - virtual uint8_t getService() const = 0; - /** - * This is a getter for the packet's PUS Service Subtype, which is the - * third byte of the Data Field Header. - * @return The packet's PUS Service Subtype. - */ - virtual uint8_t getSubService() const = 0; - /** - * The source ID can be used to have an additional identifier, e.g. for different ground - * station. - * @return - */ - virtual uint16_t getSourceId() const = 0; + /** + * This command returns the CCSDS Secondary Header Flag. + * It shall always be zero for PUS Packets. This is the + * highest bit of the first byte of the Data Field Header. + * @return the CCSDS Secondary Header Flag + */ + virtual uint8_t getSecondaryHeaderFlag() const = 0; + /** + * This command returns the TC Packet PUS Version Number. + * The version number of ECSS PUS 2003 is 1. + * It consists of the second to fourth highest bits of the + * first byte. + * @return + */ + virtual uint8_t getPusVersionNumber() const = 0; + /** + * This is a getter for the packet's Ack field, which are the lowest four + * bits of the first byte of the Data Field Header. + * + * It is packed in a uint8_t variable. + * @return The packet's PUS Ack field. + */ + virtual uint8_t getAcknowledgeFlags() const = 0; + /** + * This is a getter for the packet's PUS Service ID, which is the second + * byte of the Data Field Header. + * @return The packet's PUS Service ID. + */ + virtual uint8_t getService() const = 0; + /** + * This is a getter for the packet's PUS Service Subtype, which is the + * third byte of the Data Field Header. + * @return The packet's PUS Service Subtype. + */ + virtual uint8_t getSubService() const = 0; + /** + * The source ID can be used to have an additional identifier, e.g. for different ground + * station. + * @return + */ + virtual uint16_t getSourceId() const = 0; - /** - * This is a getter for a pointer to the packet's Application data. - * - * These are the bytes that follow after the Data Field Header. They form - * the packet's application data. - * @return A pointer to the PUS Application Data. - */ - virtual const uint8_t* getApplicationData() const = 0; - /** - * This method calculates the size of the PUS Application data field. - * - * It takes the information stored in the CCSDS Packet Data Length field - * and subtracts the Data Field Header size and the CRC size. - * @return The size of the PUS Application Data (without Error Control - * field) - */ - virtual uint16_t getApplicationDataSize() const = 0; - /** - * This getter returns the Error Control Field of the packet. - * - * The field is placed after any possible Application Data. If no - * Application Data is present there's still an Error Control field. It is - * supposed to be a 16bit-CRC. - * @return The PUS Error Control - */ - virtual uint16_t getErrorControl() const = 0; - /** - * With this method, the Error Control Field is updated to match the - * current content of the packet. - */ - virtual void setErrorControl() = 0; + /** + * This is a getter for a pointer to the packet's Application data. + * + * These are the bytes that follow after the Data Field Header. They form + * the packet's application data. + * @return A pointer to the PUS Application Data. + */ + virtual const uint8_t* getApplicationData() const = 0; + /** + * This method calculates the size of the PUS Application data field. + * + * It takes the information stored in the CCSDS Packet Data Length field + * and subtracts the Data Field Header size and the CRC size. + * @return The size of the PUS Application Data (without Error Control + * field) + */ + virtual uint16_t getApplicationDataSize() const = 0; + /** + * This getter returns the Error Control Field of the packet. + * + * The field is placed after any possible Application Data. If no + * Application Data is present there's still an Error Control field. It is + * supposed to be a 16bit-CRC. + * @return The PUS Error Control + */ + virtual uint16_t getErrorControl() const = 0; + /** + * With this method, the Error Control Field is updated to match the + * current content of the packet. + */ + virtual void setErrorControl() = 0; - /** - * Calculate full packet length from application data length. - * @param appDataLen - * @return - */ - virtual size_t calculateFullPacketLength(size_t appDataLen) const = 0; + /** + * Calculate full packet length from application data length. + * @param appDataLen + * @return + */ + virtual size_t calculateFullPacketLength(size_t appDataLen) const = 0; - /** - * This is a debugging helper method that prints the whole packet content - * to the screen. - */ - void print(); + /** + * This is a debugging helper method that prints the whole packet content + * to the screen. + */ + void print(); -protected: - - /** - * With this method, the packet data pointer can be redirected to another - * location. - * This call overwrites the parent's setData method to set both its - * @c tc_data pointer and the parent's @c data pointer. - * - * @param p_data A pointer to another PUS Telecommand Packet. - */ - virtual ReturnValue_t setData(uint8_t* pData, size_t maxSize, - void* args = nullptr) override = 0; + protected: + /** + * With this method, the packet data pointer can be redirected to another + * location. + * This call overwrites the parent's setData method to set both its + * @c tc_data pointer and the parent's @c data pointer. + * + * @param p_data A pointer to another PUS Telecommand Packet. + */ + virtual ReturnValue_t setData(uint8_t* pData, size_t maxSize, void* args = nullptr) override = 0; }; - #endif /* TMTCPACKET_PUS_TCPACKETBASE_H_ */ diff --git a/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredBase.cpp b/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredBase.cpp index 35bfdfeb..8cc38c5f 100644 --- a/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredBase.cpp +++ b/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredBase.cpp @@ -1,70 +1,61 @@ #include "fsfw/tmtcpacket/pus/tc/TcPacketStoredBase.h" -#include "fsfw/objectmanager/ObjectManager.h" -#include "fsfw/serviceinterface/ServiceInterface.h" -#include "fsfw/objectmanager/frameworkObjects.h" - #include +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/objectmanager/frameworkObjects.h" +#include "fsfw/serviceinterface/ServiceInterface.h" + StorageManagerIF* TcPacketStoredBase::store = nullptr; TcPacketStoredBase::TcPacketStoredBase() { - this->storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; - this->checkAndSetStore(); - + this->storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; + this->checkAndSetStore(); } -TcPacketStoredBase::~TcPacketStoredBase() { -} +TcPacketStoredBase::~TcPacketStoredBase() {} -ReturnValue_t TcPacketStoredBase::getData(const uint8_t ** dataPtr, - size_t* dataSize) { - auto result = this->store->getData(storeAddress, dataPtr, dataSize); - if(result != HasReturnvaluesIF::RETURN_OK) { +ReturnValue_t TcPacketStoredBase::getData(const uint8_t** dataPtr, size_t* dataSize) { + auto result = this->store->getData(storeAddress, dataPtr, dataSize); + if (result != HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "TcPacketStoredBase: Could not get data!" << std::endl; + sif::warning << "TcPacketStoredBase: Could not get data!" << std::endl; #else - sif::printWarning("TcPacketStoredBase: Could not get data!\n"); + sif::printWarning("TcPacketStoredBase: Could not get data!\n"); #endif - } - return result; + } + return result; } - - bool TcPacketStoredBase::checkAndSetStore() { + if (this->store == nullptr) { + this->store = ObjectManager::instance()->get(objects::TC_STORE); if (this->store == nullptr) { - this->store = ObjectManager::instance()->get(objects::TC_STORE); - if (this->store == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "TcPacketStoredBase::TcPacketStoredBase: TC Store not found!" - << std::endl; + sif::error << "TcPacketStoredBase::TcPacketStoredBase: TC Store not found!" << std::endl; #endif - return false; - } + return false; } - return true; + } + return true; } void TcPacketStoredBase::setStoreAddress(store_address_t setAddress, - RedirectableDataPointerIF* packet) { - this->storeAddress = setAddress; - const uint8_t* tempData = nullptr; - size_t tempSize; - ReturnValue_t status = StorageManagerIF::RETURN_FAILED; - if (this->checkAndSetStore()) { - status = this->store->getData(this->storeAddress, &tempData, &tempSize); - } + RedirectableDataPointerIF* packet) { + this->storeAddress = setAddress; + const uint8_t* tempData = nullptr; + size_t tempSize; + ReturnValue_t status = StorageManagerIF::RETURN_FAILED; + if (this->checkAndSetStore()) { + status = this->store->getData(this->storeAddress, &tempData, &tempSize); + } - if (status == StorageManagerIF::RETURN_OK) { - packet->setData(const_cast(tempData), tempSize); - } - else { - packet->setData(nullptr, -1); - this->storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; - } + if (status == StorageManagerIF::RETURN_OK) { + packet->setData(const_cast(tempData), tempSize); + } else { + packet->setData(nullptr, -1); + this->storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; + } } -store_address_t TcPacketStoredBase::getStoreAddress() { - return this->storeAddress; -} +store_address_t TcPacketStoredBase::getStoreAddress() { return this->storeAddress; } diff --git a/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredBase.h b/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredBase.h index 045d40d8..86f0d94e 100644 --- a/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredBase.h +++ b/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredBase.h @@ -8,77 +8,76 @@ * Base class for telecommand packets like CFDP or PUS packets. * @ingroup tmtcpackets */ -class TcPacketStoredBase: public TcPacketStoredIF { -public: - /** - * This is a default constructor which does not set the data pointer to initialize - * with an empty cached store address - */ - TcPacketStoredBase(); - /** - * Constructor to set to an existing store address. - * @param setAddress - */ - TcPacketStoredBase(store_address_t setAddress); - /** - * Another constructor to create a TcPacket from a raw packet stream. - * Takes the data and adds it unchecked to the TcStore. - * @param data Pointer to the complete TC Space Packet. - * @param Size size of the packet. - */ - TcPacketStoredBase(const uint8_t* data, uint32_t size); +class TcPacketStoredBase : public TcPacketStoredIF { + public: + /** + * This is a default constructor which does not set the data pointer to initialize + * with an empty cached store address + */ + TcPacketStoredBase(); + /** + * Constructor to set to an existing store address. + * @param setAddress + */ + TcPacketStoredBase(store_address_t setAddress); + /** + * Another constructor to create a TcPacket from a raw packet stream. + * Takes the data and adds it unchecked to the TcStore. + * @param data Pointer to the complete TC Space Packet. + * @param Size size of the packet. + */ + TcPacketStoredBase(const uint8_t* data, uint32_t size); - virtual~ TcPacketStoredBase(); + virtual ~TcPacketStoredBase(); - /** - * Getter function for the raw data. - * @param dataPtr [out] Pointer to the data pointer to set - * @param dataSize [out] Address of size to set. - * @return -@c RETURN_OK if data was retrieved successfully. - */ - ReturnValue_t getData(const uint8_t ** dataPtr, size_t* dataSize) override; + /** + * Getter function for the raw data. + * @param dataPtr [out] Pointer to the data pointer to set + * @param dataSize [out] Address of size to set. + * @return -@c RETURN_OK if data was retrieved successfully. + */ + ReturnValue_t getData(const uint8_t** dataPtr, size_t* dataSize) override; - void setStoreAddress(store_address_t setAddress, RedirectableDataPointerIF* packet) override; - store_address_t getStoreAddress() override; + void setStoreAddress(store_address_t setAddress, RedirectableDataPointerIF* packet) override; + store_address_t getStoreAddress() override; - /** - * With this call, the packet is deleted. - * It removes itself from the store and sets its data pointer to NULL. - * @return returncode from deleting the data. - */ - virtual ReturnValue_t deletePacket() = 0; + /** + * With this call, the packet is deleted. + * It removes itself from the store and sets its data pointer to NULL. + * @return returncode from deleting the data. + */ + virtual ReturnValue_t deletePacket() = 0; - /** - * This method performs a size check. - * It reads the stored size and compares it with the size entered in the - * packet header. This class is the optimal place for such a check as it - * has access to both the header data and the store. - * @return true if size is correct, false if packet is not registered in - * store or size is incorrect. - */ - virtual bool isSizeCorrect() = 0; + /** + * This method performs a size check. + * It reads the stored size and compares it with the size entered in the + * packet header. This class is the optimal place for such a check as it + * has access to both the header data and the store. + * @return true if size is correct, false if packet is not registered in + * store or size is incorrect. + */ + virtual bool isSizeCorrect() = 0; -protected: - /** - * This is a pointer to the store all instances of the class use. - * If the store is not yet set (i.e. @c store is NULL), every constructor - * call tries to set it and throws an error message in case of failures. - * The default store is objects::TC_STORE. - */ - static StorageManagerIF* store; - /** - * The address where the packet data of the object instance is stored. - */ - store_address_t storeAddress; - /** - * A helper method to check if a store is assigned to the class. - * If not, the method tries to retrieve the store from the global - * ObjectManager. - * @return @li @c true if the store is linked or could be created. - * @li @c false otherwise. - */ - bool checkAndSetStore(); + protected: + /** + * This is a pointer to the store all instances of the class use. + * If the store is not yet set (i.e. @c store is NULL), every constructor + * call tries to set it and throws an error message in case of failures. + * The default store is objects::TC_STORE. + */ + static StorageManagerIF* store; + /** + * The address where the packet data of the object instance is stored. + */ + store_address_t storeAddress; + /** + * A helper method to check if a store is assigned to the class. + * If not, the method tries to retrieve the store from the global + * ObjectManager. + * @return @li @c true if the store is linked or could be created. + * @li @c false otherwise. + */ + bool checkAndSetStore(); }; - #endif /* TMTCPACKET_PUS_TcPacketStoredBase_H_ */ diff --git a/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredIF.h b/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredIF.h index 4beafedc..ac4019cd 100644 --- a/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredIF.h +++ b/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredIF.h @@ -2,32 +2,31 @@ #define FSFW_TMTCPACKET_PUS_TCPACKETSTOREDIF_H_ #include + #include "TcPacketPusBase.h" -#include "fsfw/storagemanager/storeAddress.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "fsfw/storagemanager/storeAddress.h" class TcPacketStoredIF { -public: - virtual~TcPacketStoredIF() {}; + public: + virtual ~TcPacketStoredIF(){}; - /** - * With this call, the stored packet can be set to another packet in a store. This is useful - * if the packet is a class member and used for more than one packet. - * @param setAddress The new packet id to link to. - */ - virtual void setStoreAddress(store_address_t setAddress, RedirectableDataPointerIF* packet) = 0; + /** + * With this call, the stored packet can be set to another packet in a store. This is useful + * if the packet is a class member and used for more than one packet. + * @param setAddress The new packet id to link to. + */ + virtual void setStoreAddress(store_address_t setAddress, RedirectableDataPointerIF* packet) = 0; - virtual store_address_t getStoreAddress() = 0; + virtual store_address_t getStoreAddress() = 0; - /** - * Getter function for the raw data. - * @param dataPtr [out] Pointer to the data pointer to set - * @param dataSize [out] Address of size to set. - * @return -@c RETURN_OK if data was retrieved successfully. - */ - virtual ReturnValue_t getData(const uint8_t ** dataPtr, size_t* dataSize) = 0; + /** + * Getter function for the raw data. + * @param dataPtr [out] Pointer to the data pointer to set + * @param dataSize [out] Address of size to set. + * @return -@c RETURN_OK if data was retrieved successfully. + */ + virtual ReturnValue_t getData(const uint8_t** dataPtr, size_t* dataSize) = 0; }; - - #endif /* FSFW_TMTCPACKET_PUS_TCPACKETSTOREDIF_H_ */ diff --git a/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredPus.cpp b/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredPus.cpp index f1ad13e1..153ad863 100644 --- a/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredPus.cpp +++ b/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredPus.cpp @@ -1,85 +1,78 @@ #include "fsfw/tmtcpacket/pus/tc/TcPacketStoredPus.h" -#include "fsfw/serviceinterface/ServiceInterface.h" - #include -TcPacketStoredPus::TcPacketStoredPus(uint16_t apid, uint8_t service, - uint8_t subservice, uint8_t sequenceCount, const uint8_t* data, - size_t size, uint8_t ack) : - TcPacketPus(nullptr) { - this->storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; - if (not this->checkAndSetStore()) { - return; - } - uint8_t* pData = nullptr; - ReturnValue_t returnValue = this->store->getFreeElement(&this->storeAddress, - (TC_PACKET_MIN_SIZE + size), &pData); - if (returnValue != this->store->RETURN_OK) { +#include "fsfw/serviceinterface/ServiceInterface.h" + +TcPacketStoredPus::TcPacketStoredPus(uint16_t apid, uint8_t service, uint8_t subservice, + uint8_t sequenceCount, const uint8_t* data, size_t size, + uint8_t ack) + : TcPacketPus(nullptr) { + this->storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; + if (not this->checkAndSetStore()) { + return; + } + uint8_t* pData = nullptr; + ReturnValue_t returnValue = + this->store->getFreeElement(&this->storeAddress, (TC_PACKET_MIN_SIZE + size), &pData); + if (returnValue != this->store->RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "TcPacketStoredBase: Could not get free element from store!" - << std::endl; + sif::warning << "TcPacketStoredBase: Could not get free element from store!" << std::endl; #endif - return; - } - this->setData(pData, TC_PACKET_MIN_SIZE + size); + return; + } + this->setData(pData, TC_PACKET_MIN_SIZE + size); #if FSFW_USE_PUS_C_TELECOMMANDS == 1 - pus::PusVersion pusVersion = pus::PusVersion::PUS_C_VERSION; + pus::PusVersion pusVersion = pus::PusVersion::PUS_C_VERSION; #else - pus::PusVersion pusVersion = pus::PusVersion::PUS_A_VERSION; + pus::PusVersion pusVersion = pus::PusVersion::PUS_A_VERSION; #endif - initializeTcPacket(apid, sequenceCount, ack, service, subservice, pusVersion); - std::memcpy(&tcData->appData, data, size); - this->setPacketDataLength( - size + sizeof(PUSTcDataFieldHeader) + CRC_SIZE - 1); - this->setErrorControl(); + initializeTcPacket(apid, sequenceCount, ack, service, subservice, pusVersion); + std::memcpy(&tcData->appData, data, size); + this->setPacketDataLength(size + sizeof(PUSTcDataFieldHeader) + CRC_SIZE - 1); + this->setErrorControl(); } -TcPacketStoredPus::TcPacketStoredPus(): TcPacketStoredBase(), TcPacketPus(nullptr) { +TcPacketStoredPus::TcPacketStoredPus() : TcPacketStoredBase(), TcPacketPus(nullptr) {} + +TcPacketStoredPus::TcPacketStoredPus(store_address_t setAddress) : TcPacketPus(nullptr) { + TcPacketStoredBase::setStoreAddress(setAddress, this); } -TcPacketStoredPus::TcPacketStoredPus(store_address_t setAddress): TcPacketPus(nullptr) { - TcPacketStoredBase::setStoreAddress(setAddress, this); -} - -TcPacketStoredPus::TcPacketStoredPus(const uint8_t* data, size_t size): TcPacketPus(data) { - if (this->getFullSize() != size) { - return; - } - if (this->checkAndSetStore()) { - ReturnValue_t status = store->addData(&storeAddress, data, size); - if (status != HasReturnvaluesIF::RETURN_OK) { - this->setData(nullptr, size); - } - const uint8_t* storePtr = nullptr; - // Repoint base data pointer to the data in the store. - store->getData(storeAddress, &storePtr, &size); - this->setData(const_cast(storePtr), size); +TcPacketStoredPus::TcPacketStoredPus(const uint8_t* data, size_t size) : TcPacketPus(data) { + if (this->getFullSize() != size) { + return; + } + if (this->checkAndSetStore()) { + ReturnValue_t status = store->addData(&storeAddress, data, size); + if (status != HasReturnvaluesIF::RETURN_OK) { + this->setData(nullptr, size); } + const uint8_t* storePtr = nullptr; + // Repoint base data pointer to the data in the store. + store->getData(storeAddress, &storePtr, &size); + this->setData(const_cast(storePtr), size); + } } ReturnValue_t TcPacketStoredPus::deletePacket() { - ReturnValue_t result = this->store->deleteData(this->storeAddress); - this->storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; - // To circumvent size checks - this->setData(nullptr, -1); - return result; -} - -TcPacketPusBase* TcPacketStoredPus::getPacketBase() { - return this; + ReturnValue_t result = this->store->deleteData(this->storeAddress); + this->storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; + // To circumvent size checks + this->setData(nullptr, -1); + return result; } +TcPacketPusBase* TcPacketStoredPus::getPacketBase() { return this; } bool TcPacketStoredPus::isSizeCorrect() { - const uint8_t* temp_data = nullptr; - size_t temp_size; - ReturnValue_t status = this->store->getData(this->storeAddress, &temp_data, - &temp_size); - if (status == StorageManagerIF::RETURN_OK) { - if (this->getFullSize() == temp_size) { - return true; - } + const uint8_t* temp_data = nullptr; + size_t temp_size; + ReturnValue_t status = this->store->getData(this->storeAddress, &temp_data, &temp_size); + if (status == StorageManagerIF::RETURN_OK) { + if (this->getFullSize() == temp_size) { + return true; } - return false; + } + return false; } diff --git a/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredPus.h b/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredPus.h index f0434b33..45dec293 100644 --- a/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredPus.h +++ b/src/fsfw/tmtcpacket/pus/tc/TcPacketStoredPus.h @@ -1,53 +1,48 @@ #ifndef FSFW_TMTCPACKET_PUS_TCPACKETSTOREDPUSA_H_ #define FSFW_TMTCPACKET_PUS_TCPACKETSTOREDPUSA_H_ -#include "TcPacketStoredBase.h" #include "TcPacketPus.h" +#include "TcPacketStoredBase.h" -class TcPacketStoredPus: - public TcPacketStoredBase, - public TcPacketPus { -public: - /** - * With this constructor, new space is allocated in the packet store and - * a new PUS Telecommand Packet is created there. - * Packet Application Data passed in data is copied into the packet. - * @param apid Sets the packet's APID field. - * @param service Sets the packet's Service ID field. - * This specifies the destination service. - * @param subservice Sets the packet's Service Subtype field. - * This specifies the destination sub-service. - * @param sequence_count Sets the packet's Source Sequence Count field. - * @param data The data to be copied to the Application Data Field. - * @param size The amount of data to be copied. - * @param ack Set's the packet's Ack field, which specifies - * number of verification packets returned - * for this command. - */ - TcPacketStoredPus(uint16_t apid, uint8_t service, uint8_t subservice, - uint8_t sequence_count = 0, const uint8_t* data = nullptr, - size_t size = 0, uint8_t ack = TcPacketPusBase::ACK_ALL); - /** - * Create stored packet with existing data. - * @param data - * @param size - */ - TcPacketStoredPus(const uint8_t* data, size_t size); - /** - * Create stored packet from existing packet in store - * @param setAddress - */ - TcPacketStoredPus(store_address_t setAddress); - TcPacketStoredPus(); +class TcPacketStoredPus : public TcPacketStoredBase, public TcPacketPus { + public: + /** + * With this constructor, new space is allocated in the packet store and + * a new PUS Telecommand Packet is created there. + * Packet Application Data passed in data is copied into the packet. + * @param apid Sets the packet's APID field. + * @param service Sets the packet's Service ID field. + * This specifies the destination service. + * @param subservice Sets the packet's Service Subtype field. + * This specifies the destination sub-service. + * @param sequence_count Sets the packet's Source Sequence Count field. + * @param data The data to be copied to the Application Data Field. + * @param size The amount of data to be copied. + * @param ack Set's the packet's Ack field, which specifies + * number of verification packets returned + * for this command. + */ + TcPacketStoredPus(uint16_t apid, uint8_t service, uint8_t subservice, uint8_t sequence_count = 0, + const uint8_t* data = nullptr, size_t size = 0, + uint8_t ack = TcPacketPusBase::ACK_ALL); + /** + * Create stored packet with existing data. + * @param data + * @param size + */ + TcPacketStoredPus(const uint8_t* data, size_t size); + /** + * Create stored packet from existing packet in store + * @param setAddress + */ + TcPacketStoredPus(store_address_t setAddress); + TcPacketStoredPus(); - ReturnValue_t deletePacket() override; - TcPacketPusBase* getPacketBase(); + ReturnValue_t deletePacket() override; + TcPacketPusBase* getPacketBase(); -private: - - bool isSizeCorrect() override; + private: + bool isSizeCorrect() override; }; - - #endif /* FSFW_TMTCPACKET_PUS_TCPACKETSTOREDPUSA_H_ */ diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketBase.cpp b/src/fsfw/tmtcpacket/pus/tm/TmPacketBase.cpp index d448fe5e..bc761d0d 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketBase.cpp +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketBase.cpp @@ -1,67 +1,65 @@ #include "fsfw/tmtcpacket/pus/tm/TmPacketBase.h" +#include + #include "fsfw/globalfunctions/CRC.h" #include "fsfw/globalfunctions/arrayprinter.h" #include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/timemanager/CCSDSTime.h" -#include - TimeStamperIF* TmPacketBase::timeStamper = nullptr; object_id_t TmPacketBase::timeStamperId = objects::NO_OBJECT; -TmPacketBase::TmPacketBase(uint8_t* setData): SpacePacketBase(setData) {} +TmPacketBase::TmPacketBase(uint8_t* setData) : SpacePacketBase(setData) {} TmPacketBase::~TmPacketBase() { - //Nothing to do. + // Nothing to do. } - uint16_t TmPacketBase::getSourceDataSize() { - return getPacketDataLength() - getDataFieldSize() - CRC_SIZE + 1; + return getPacketDataLength() - getDataFieldSize() - CRC_SIZE + 1; } uint16_t TmPacketBase::getErrorControl() { - uint32_t size = getSourceDataSize() + CRC_SIZE; - uint8_t* p_to_buffer = getSourceData(); - return (p_to_buffer[size - 2] << 8) + p_to_buffer[size - 1]; + uint32_t size = getSourceDataSize() + CRC_SIZE; + uint8_t* p_to_buffer = getSourceData(); + return (p_to_buffer[size - 2] << 8) + p_to_buffer[size - 1]; } void TmPacketBase::setErrorControl() { - uint32_t full_size = getFullSize(); - uint16_t crc = CRC::crc16ccitt(getWholeData(), full_size - CRC_SIZE); - uint32_t size = getSourceDataSize(); - getSourceData()[size] = (crc & 0XFF00) >> 8; // CRCH - getSourceData()[size + 1] = (crc) & 0X00FF; // CRCL + uint32_t full_size = getFullSize(); + uint16_t crc = CRC::crc16ccitt(getWholeData(), full_size - CRC_SIZE); + uint32_t size = getSourceDataSize(); + getSourceData()[size] = (crc & 0XFF00) >> 8; // CRCH + getSourceData()[size + 1] = (crc)&0X00FF; // CRCL } ReturnValue_t TmPacketBase::getPacketTime(timeval* timestamp) const { - size_t tempSize = 0; - return CCSDSTime::convertFromCcsds(timestamp, getPacketTimeRaw(), - &tempSize, getTimestampSize()); + size_t tempSize = 0; + return CCSDSTime::convertFromCcsds(timestamp, getPacketTimeRaw(), &tempSize, getTimestampSize()); } bool TmPacketBase::checkAndSetStamper() { + if (timeStamper == NULL) { + timeStamper = ObjectManager::instance()->get(timeStamperId); if (timeStamper == NULL) { - timeStamper = ObjectManager::instance()->get(timeStamperId); - if (timeStamper == NULL) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "TmPacketBase::checkAndSetStamper: Stamper not found!" << std::endl; + sif::warning << "TmPacketBase::checkAndSetStamper: Stamper not found!" << std::endl; #else - sif::printWarning("TmPacketBase::checkAndSetStamper: Stamper not found!\n"); + sif::printWarning("TmPacketBase::checkAndSetStamper: Stamper not found!\n"); #endif - return false; - } + return false; } - return true; + } + return true; } void TmPacketBase::print() { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TmPacketBase::print:" << std::endl; + sif::info << "TmPacketBase::print:" << std::endl; #else - sif::printInfo("TmPacketBase::print:\n"); + sif::printInfo("TmPacketBase::print:\n"); #endif - arrayprinter::print(getWholeData(), getFullSize()); + arrayprinter::print(getWholeData(), getFullSize()); } diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketBase.h b/src/fsfw/tmtcpacket/pus/tm/TmPacketBase.h index 31bfe3c8..72f3abd4 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketBase.h +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketBase.h @@ -1,10 +1,10 @@ #ifndef TMTCPACKET_PUS_TMPACKETBASE_H_ #define TMTCPACKET_PUS_TMPACKETBASE_H_ -#include "fsfw/tmtcpacket/SpacePacketBase.h" -#include "fsfw/timemanager/TimeStamperIF.h" -#include "fsfw/timemanager/Clock.h" #include "fsfw/objectmanager/SystemObjectIF.h" +#include "fsfw/timemanager/Clock.h" +#include "fsfw/timemanager/TimeStamperIF.h" +#include "fsfw/tmtcpacket/SpacePacketBase.h" namespace Factory { @@ -12,7 +12,6 @@ void setStaticFrameworkObjectIds(); } - /** * This class is the basic data handler for any ECSS PUS Telemetry packet. * @@ -25,113 +24,112 @@ void setStaticFrameworkObjectIds(); * @ingroup tmtcpackets */ class TmPacketBase : public SpacePacketBase { - friend void (Factory::setStaticFrameworkObjectIds)(); -public: + friend void(Factory::setStaticFrameworkObjectIds)(); - //! Maximum size of a TM Packet in this mission. - //! TODO: Make this dependant on a config variable. - static const uint32_t MISSION_TM_PACKET_MAX_SIZE = 2048; + public: + //! Maximum size of a TM Packet in this mission. + //! TODO: Make this dependant on a config variable. + static const uint32_t MISSION_TM_PACKET_MAX_SIZE = 2048; - /** - * This is the default constructor. - * It sets its internal data pointer to the address passed and also - * forwards the data pointer to the parent SpacePacketBase class. - * @param set_address The position where the packet data lies. - */ - TmPacketBase( uint8_t* setData ); - /** - * This is the empty default destructor. - */ - virtual ~TmPacketBase(); + /** + * This is the default constructor. + * It sets its internal data pointer to the address passed and also + * forwards the data pointer to the parent SpacePacketBase class. + * @param set_address The position where the packet data lies. + */ + TmPacketBase(uint8_t* setData); + /** + * This is the empty default destructor. + */ + virtual ~TmPacketBase(); - /** - * This is a getter for the packet's PUS Service ID, which is the second - * byte of the Data Field Header. - * @return The packet's PUS Service ID. - */ - virtual uint8_t getService() = 0; - /** - * This is a getter for the packet's PUS Service Subtype, which is the - * third byte of the Data Field Header. - * @return The packet's PUS Service Subtype. - */ - virtual uint8_t getSubService() = 0; - /** - * This is a getter for a pointer to the packet's Source data. - * - * These are the bytes that follow after the Data Field Header. They form - * the packet's source data. - * @return A pointer to the PUS Source Data. - */ - virtual uint8_t* getSourceData() = 0; - /** - * This method calculates the size of the PUS Source data field. - * - * It takes the information stored in the CCSDS Packet Data Length field - * and subtracts the Data Field Header size and the CRC size. - * @return The size of the PUS Source Data (without Error Control field) - */ - virtual uint16_t getSourceDataSize() = 0; + /** + * This is a getter for the packet's PUS Service ID, which is the second + * byte of the Data Field Header. + * @return The packet's PUS Service ID. + */ + virtual uint8_t getService() = 0; + /** + * This is a getter for the packet's PUS Service Subtype, which is the + * third byte of the Data Field Header. + * @return The packet's PUS Service Subtype. + */ + virtual uint8_t getSubService() = 0; + /** + * This is a getter for a pointer to the packet's Source data. + * + * These are the bytes that follow after the Data Field Header. They form + * the packet's source data. + * @return A pointer to the PUS Source Data. + */ + virtual uint8_t* getSourceData() = 0; + /** + * This method calculates the size of the PUS Source data field. + * + * It takes the information stored in the CCSDS Packet Data Length field + * and subtracts the Data Field Header size and the CRC size. + * @return The size of the PUS Source Data (without Error Control field) + */ + virtual uint16_t getSourceDataSize() = 0; - /** - * Get size of data field which can differ based on implementation - * @return - */ - virtual uint16_t getDataFieldSize() = 0; + /** + * Get size of data field which can differ based on implementation + * @return + */ + virtual uint16_t getDataFieldSize() = 0; - virtual size_t getPacketMinimumSize() const = 0; + virtual size_t getPacketMinimumSize() const = 0; - /** - * Interprets the "time"-field in the secondary header and returns it in - * timeval format. - * @return Converted timestamp of packet. - */ - virtual ReturnValue_t getPacketTime(timeval* timestamp) const; - /** - * Returns a raw pointer to the beginning of the time field. - * @return Raw pointer to time field. - */ - virtual uint8_t* getPacketTimeRaw() const = 0; + /** + * Interprets the "time"-field in the secondary header and returns it in + * timeval format. + * @return Converted timestamp of packet. + */ + virtual ReturnValue_t getPacketTime(timeval* timestamp) const; + /** + * Returns a raw pointer to the beginning of the time field. + * @return Raw pointer to time field. + */ + virtual uint8_t* getPacketTimeRaw() const = 0; - virtual size_t getTimestampSize() const = 0; + virtual size_t getTimestampSize() const = 0; - /** - * This is a debugging helper method that prints the whole packet content - * to the screen. - */ - void print(); - /** - * With this method, the Error Control Field is updated to match the - * current content of the packet. This method is not protected because - * a recalculation by the user might be necessary when manipulating fields - * like the sequence count. - */ - void setErrorControl(); - /** - * This getter returns the Error Control Field of the packet. - * - * The field is placed after any possible Source Data. If no - * Source Data is present there's still an Error Control field. It is - * supposed to be a 16bit-CRC. - * @return The PUS Error Control - */ - uint16_t getErrorControl(); + /** + * This is a debugging helper method that prints the whole packet content + * to the screen. + */ + void print(); + /** + * With this method, the Error Control Field is updated to match the + * current content of the packet. This method is not protected because + * a recalculation by the user might be necessary when manipulating fields + * like the sequence count. + */ + void setErrorControl(); + /** + * This getter returns the Error Control Field of the packet. + * + * The field is placed after any possible Source Data. If no + * Source Data is present there's still an Error Control field. It is + * supposed to be a 16bit-CRC. + * @return The PUS Error Control + */ + uint16_t getErrorControl(); -protected: - /** - * The timeStamper is responsible for adding a timestamp to the packet. - * It is initialized lazy. - */ - static TimeStamperIF* timeStamper; - //! The ID to use when looking for a time stamper. - static object_id_t timeStamperId; + protected: + /** + * The timeStamper is responsible for adding a timestamp to the packet. + * It is initialized lazy. + */ + static TimeStamperIF* timeStamper; + //! The ID to use when looking for a time stamper. + static object_id_t timeStamperId; - /** - * Checks if a time stamper is available and tries to set it if not. - * @return Returns false if setting failed. - */ - bool checkAndSetStamper(); + /** + * Checks if a time stamper is available and tries to set it if not. + * @return Returns false if setting failed. + */ + bool checkAndSetStamper(); }; - #endif /* TMTCPACKET_PUS_TMPACKETBASE_H_ */ diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketMinimal.cpp b/src/fsfw/tmtcpacket/pus/tm/TmPacketMinimal.cpp index 25e159da..388a4098 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketMinimal.cpp +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketMinimal.cpp @@ -1,46 +1,40 @@ #include "fsfw/tmtcpacket/pus/tm/TmPacketMinimal.h" -#include "fsfw/tmtcpacket/pus/PacketTimestampInterpreterIF.h" #include #include -TmPacketMinimal::TmPacketMinimal(const uint8_t* set_data) : SpacePacketBase( set_data ) { - this->tm_data = (TmPacketMinimalPointer*)set_data; +#include "fsfw/tmtcpacket/pus/PacketTimestampInterpreterIF.h" + +TmPacketMinimal::TmPacketMinimal(const uint8_t* set_data) : SpacePacketBase(set_data) { + this->tm_data = (TmPacketMinimalPointer*)set_data; } -TmPacketMinimal::~TmPacketMinimal() { -} +TmPacketMinimal::~TmPacketMinimal() {} -uint8_t TmPacketMinimal::getService() { - return tm_data->data_field.service_type; -} +uint8_t TmPacketMinimal::getService() { return tm_data->data_field.service_type; } -uint8_t TmPacketMinimal::getSubService() { - return tm_data->data_field.service_subtype; -} +uint8_t TmPacketMinimal::getSubService() { return tm_data->data_field.service_subtype; } -uint8_t TmPacketMinimal::getPacketSubcounter() { - return tm_data->data_field.subcounter; -} +uint8_t TmPacketMinimal::getPacketSubcounter() { return tm_data->data_field.subcounter; } ReturnValue_t TmPacketMinimal::getPacketTime(timeval* timestamp) { - if (timestampInterpreter == NULL) { - return HasReturnvaluesIF::RETURN_FAILED; - } - return timestampInterpreter->getPacketTime(this, timestamp); + if (timestampInterpreter == NULL) { + return HasReturnvaluesIF::RETURN_FAILED; + } + return timestampInterpreter->getPacketTime(this, timestamp); } ReturnValue_t TmPacketMinimal::getPacketTimeRaw(const uint8_t** timePtr, uint32_t* size) { - if (timestampInterpreter == NULL) { - return HasReturnvaluesIF::RETURN_FAILED; - } - return timestampInterpreter->getPacketTimeRaw(this, timePtr, size); + if (timestampInterpreter == NULL) { + return HasReturnvaluesIF::RETURN_FAILED; + } + return timestampInterpreter->getPacketTimeRaw(this, timePtr, size); } void TmPacketMinimal::setInterpretTimestampObject(PacketTimestampInterpreterIF* interpreter) { - if (TmPacketMinimal::timestampInterpreter == NULL) { - TmPacketMinimal::timestampInterpreter = interpreter; - } + if (TmPacketMinimal::timestampInterpreter == NULL) { + TmPacketMinimal::timestampInterpreter = interpreter; + } } PacketTimestampInterpreterIF* TmPacketMinimal::timestampInterpreter = NULL; diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketMinimal.h b/src/fsfw/tmtcpacket/pus/tm/TmPacketMinimal.h index 08daa584..dc9c33ae 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketMinimal.h +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketMinimal.h @@ -1,9 +1,8 @@ #ifndef FRAMEWORK_TMTCPACKET_PUS_TMPACKETMINIMAL_H_ #define FRAMEWORK_TMTCPACKET_PUS_TMPACKETMINIMAL_H_ - -#include "../../SpacePacketBase.h" #include "../../../returnvalues/HasReturnvaluesIF.h" +#include "../../SpacePacketBase.h" struct timeval; class PacketTimestampInterpreterIF; @@ -14,71 +13,70 @@ class PacketTimestampInterpreterIF; * secondary headers. */ class TmPacketMinimal : public SpacePacketBase { -public: - /** - * This is the default constructor. - * It sets its internal data pointer to the address passed and also - * forwards the data pointer to the parent SpacePacketBase class. - * @param set_address The position where the packet data lies. - */ - TmPacketMinimal( const uint8_t* set_data ); - /** - * This is the empty default destructor. - */ - virtual ~TmPacketMinimal(); - /** - * This is a getter for the packet's PUS Service ID, which is the second - * byte of the Data Field Header. - * @return The packet's PUS Service ID. - */ - uint8_t getService(); - /** - * This is a getter for the packet's PUS Service Subtype, which is the - * third byte of the Data Field Header. - * @return The packet's PUS Service Subtype. - */ - uint8_t getSubService(); - /** - * Returns the subcounter. - * @return the subcounter of the Data Field Header. - */ - uint8_t getPacketSubcounter(); - struct PUSTmMinimalHeader { - uint8_t version_type_ack; - uint8_t service_type; - uint8_t service_subtype; - uint8_t subcounter; - }; + public: + /** + * This is the default constructor. + * It sets its internal data pointer to the address passed and also + * forwards the data pointer to the parent SpacePacketBase class. + * @param set_address The position where the packet data lies. + */ + TmPacketMinimal(const uint8_t* set_data); + /** + * This is the empty default destructor. + */ + virtual ~TmPacketMinimal(); + /** + * This is a getter for the packet's PUS Service ID, which is the second + * byte of the Data Field Header. + * @return The packet's PUS Service ID. + */ + uint8_t getService(); + /** + * This is a getter for the packet's PUS Service Subtype, which is the + * third byte of the Data Field Header. + * @return The packet's PUS Service Subtype. + */ + uint8_t getSubService(); + /** + * Returns the subcounter. + * @return the subcounter of the Data Field Header. + */ + uint8_t getPacketSubcounter(); + struct PUSTmMinimalHeader { + uint8_t version_type_ack; + uint8_t service_type; + uint8_t service_subtype; + uint8_t subcounter; + }; - ReturnValue_t getPacketTime(timeval* timestamp); + ReturnValue_t getPacketTime(timeval* timestamp); - ReturnValue_t getPacketTimeRaw(const uint8_t** timePtr, uint32_t* size); + ReturnValue_t getPacketTimeRaw(const uint8_t** timePtr, uint32_t* size); - static void setInterpretTimestampObject(PacketTimestampInterpreterIF* interpreter); - /** - * This struct defines the data structure of a PUS Telecommand Packet when - * accessed via a pointer. - * @ingroup tmtcpackets - */ - struct TmPacketMinimalPointer { - CCSDSPrimaryHeader primary; - PUSTmMinimalHeader data_field; - uint8_t rest; - }; - //Must include a checksum and is therefore at least one larger than the above struct. - static const uint16_t MINIMUM_SIZE = sizeof(TmPacketMinimalPointer) +1; -protected: - /** - * A pointer to a structure which defines the data structure of - * the packet's data. - * - * To be hardware-safe, all elements are of byte size. - */ - TmPacketMinimalPointer* tm_data; + static void setInterpretTimestampObject(PacketTimestampInterpreterIF* interpreter); + /** + * This struct defines the data structure of a PUS Telecommand Packet when + * accessed via a pointer. + * @ingroup tmtcpackets + */ + struct TmPacketMinimalPointer { + CCSDSPrimaryHeader primary; + PUSTmMinimalHeader data_field; + uint8_t rest; + }; + // Must include a checksum and is therefore at least one larger than the above struct. + static const uint16_t MINIMUM_SIZE = sizeof(TmPacketMinimalPointer) + 1; - static PacketTimestampInterpreterIF* timestampInterpreter; + protected: + /** + * A pointer to a structure which defines the data structure of + * the packet's data. + * + * To be hardware-safe, all elements are of byte size. + */ + TmPacketMinimalPointer* tm_data; + + static PacketTimestampInterpreterIF* timestampInterpreter; }; - - #endif /* FRAMEWORK_TMTCPACKET_PUS_TMPACKETMINIMAL_H_ */ diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketPusA.cpp b/src/fsfw/tmtcpacket/pus/tm/TmPacketPusA.cpp index 933a6b4c..e8f71717 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketPusA.cpp +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketPusA.cpp @@ -1,87 +1,68 @@ -#include "../definitions.h" #include "TmPacketPusA.h" -#include "TmPacketBase.h" +#include + +#include "../definitions.h" +#include "TmPacketBase.h" #include "fsfw/globalfunctions/CRC.h" #include "fsfw/globalfunctions/arrayprinter.h" #include "fsfw/objectmanager/ObjectManagerIF.h" #include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/timemanager/CCSDSTime.h" -#include - - TmPacketPusA::TmPacketPusA(uint8_t* setData) : TmPacketBase(setData) { - tmData = reinterpret_cast(setData); + tmData = reinterpret_cast(setData); } TmPacketPusA::~TmPacketPusA() { - //Nothing to do. + // Nothing to do. } -uint8_t TmPacketPusA::getService() { - return tmData->data_field.service_type; -} +uint8_t TmPacketPusA::getService() { return tmData->data_field.service_type; } -uint8_t TmPacketPusA::getSubService() { - return tmData->data_field.service_subtype; -} +uint8_t TmPacketPusA::getSubService() { return tmData->data_field.service_subtype; } -uint8_t* TmPacketPusA::getSourceData() { - return &tmData->data; -} +uint8_t* TmPacketPusA::getSourceData() { return &tmData->data; } uint16_t TmPacketPusA::getSourceDataSize() { - return getPacketDataLength() - sizeof(tmData->data_field) - - CRC_SIZE + 1; + return getPacketDataLength() - sizeof(tmData->data_field) - CRC_SIZE + 1; } ReturnValue_t TmPacketPusA::setData(uint8_t* p_Data, size_t maxSize, void* args) { - ReturnValue_t result = SpacePacketBase::setData(p_Data, maxSize); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - tmData = reinterpret_cast(const_cast(p_Data)); - return HasReturnvaluesIF::RETURN_OK; + ReturnValue_t result = SpacePacketBase::setData(p_Data, maxSize); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + tmData = reinterpret_cast(const_cast(p_Data)); + return HasReturnvaluesIF::RETURN_OK; } +size_t TmPacketPusA::getPacketMinimumSize() const { return TM_PACKET_MIN_SIZE; } -size_t TmPacketPusA::getPacketMinimumSize() const { - return TM_PACKET_MIN_SIZE; -} +uint16_t TmPacketPusA::getDataFieldSize() { return sizeof(PUSTmDataFieldHeaderPusA); } -uint16_t TmPacketPusA::getDataFieldSize() { - return sizeof(PUSTmDataFieldHeaderPusA); -} +uint8_t* TmPacketPusA::getPacketTimeRaw() const { return tmData->data_field.time; } -uint8_t* TmPacketPusA::getPacketTimeRaw() const { - return tmData->data_field.time; +void TmPacketPusA::initializeTmPacket(uint16_t apid, uint8_t service, uint8_t subservice, + uint8_t packetSubcounter) { + // Set primary header: + initSpacePacketHeader(false, true, apid); + // Set data Field Header: + // First, set to zero. + memset(&tmData->data_field, 0, sizeof(tmData->data_field)); -} - -void TmPacketPusA::initializeTmPacket(uint16_t apid, uint8_t service, - uint8_t subservice, uint8_t packetSubcounter) { - //Set primary header: - initSpacePacketHeader(false, true, apid); - //Set data Field Header: - //First, set to zero. - memset(&tmData->data_field, 0, sizeof(tmData->data_field)); - - tmData->data_field.version_type_ack = pus::PusVersion::PUS_A_VERSION << 4; - tmData->data_field.service_type = service; - tmData->data_field.service_subtype = subservice; - tmData->data_field.subcounter = packetSubcounter; - //Timestamp packet - if (TmPacketBase::checkAndSetStamper()) { - timeStamper->addTimeStamp(tmData->data_field.time, - sizeof(tmData->data_field.time)); - } + tmData->data_field.version_type_ack = pus::PusVersion::PUS_A_VERSION << 4; + tmData->data_field.service_type = service; + tmData->data_field.service_subtype = subservice; + tmData->data_field.subcounter = packetSubcounter; + // Timestamp packet + if (TmPacketBase::checkAndSetStamper()) { + timeStamper->addTimeStamp(tmData->data_field.time, sizeof(tmData->data_field.time)); + } } void TmPacketPusA::setSourceDataSize(uint16_t size) { - setPacketDataLength(size + sizeof(PUSTmDataFieldHeaderPusA) + CRC_SIZE - 1); + setPacketDataLength(size + sizeof(PUSTmDataFieldHeaderPusA) + CRC_SIZE - 1); } -size_t TmPacketPusA::getTimestampSize() const { - return sizeof(tmData->data_field.time); -} +size_t TmPacketPusA::getTimestampSize() const { return sizeof(tmData->data_field.time); } diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketPusA.h b/src/fsfw/tmtcpacket/pus/tm/TmPacketPusA.h index 9bb01890..a84547ff 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketPusA.h +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketPusA.h @@ -2,12 +2,12 @@ #define FSFW_TMTCPACKET_PUS_TMPACKETPUSA_H_ #include "TmPacketBase.h" -#include "fsfw/tmtcpacket/SpacePacketBase.h" -#include "fsfw/timemanager/TimeStamperIF.h" -#include "fsfw/timemanager/Clock.h" #include "fsfw/objectmanager/SystemObjectIF.h" +#include "fsfw/timemanager/Clock.h" +#include "fsfw/timemanager/TimeStamperIF.h" +#include "fsfw/tmtcpacket/SpacePacketBase.h" -namespace Factory{ +namespace Factory { void setStaticFrameworkObjectIds(); } @@ -19,12 +19,12 @@ void setStaticFrameworkObjectIds(); * @ingroup tmtcpackets */ struct PUSTmDataFieldHeaderPusA { - uint8_t version_type_ack; - uint8_t service_type; - uint8_t service_subtype; - uint8_t subcounter; - // uint8_t destination; - uint8_t time[TimeStamperIF::MISSION_TIMESTAMP_SIZE]; + uint8_t version_type_ack; + uint8_t service_type; + uint8_t service_subtype; + uint8_t subcounter; + // uint8_t destination; + uint8_t time[TimeStamperIF::MISSION_TIMESTAMP_SIZE]; }; /** @@ -33,97 +33,97 @@ struct PUSTmDataFieldHeaderPusA { * @ingroup tmtcpackets */ struct TmPacketPointerPusA { - CCSDSPrimaryHeader primary; - PUSTmDataFieldHeaderPusA data_field; - uint8_t data; + CCSDSPrimaryHeader primary; + PUSTmDataFieldHeaderPusA data_field; + uint8_t data; }; /** * PUS A packet implementation * @ingroup tmtcpackets */ -class TmPacketPusA: public TmPacketBase { - friend void (Factory::setStaticFrameworkObjectIds)(); -public: - /** - * This constant defines the minimum size of a valid PUS Telemetry Packet. - */ - static const uint32_t TM_PACKET_MIN_SIZE = (sizeof(CCSDSPrimaryHeader) + - sizeof(PUSTmDataFieldHeaderPusA) + 2); - //! Maximum size of a TM Packet in this mission. - static const uint32_t MISSION_TM_PACKET_MAX_SIZE = fsfwconfig::FSFW_MAX_TM_PACKET_SIZE; +class TmPacketPusA : public TmPacketBase { + friend void(Factory::setStaticFrameworkObjectIds)(); - /** - * This is the default constructor. - * It sets its internal data pointer to the address passed and also - * forwards the data pointer to the parent SpacePacketBase class. - * @param set_address The position where the packet data lies. - */ - TmPacketPusA( uint8_t* setData ); - /** - * This is the empty default destructor. - */ - virtual ~TmPacketPusA(); + public: + /** + * This constant defines the minimum size of a valid PUS Telemetry Packet. + */ + static const uint32_t TM_PACKET_MIN_SIZE = + (sizeof(CCSDSPrimaryHeader) + sizeof(PUSTmDataFieldHeaderPusA) + 2); + //! Maximum size of a TM Packet in this mission. + static const uint32_t MISSION_TM_PACKET_MAX_SIZE = fsfwconfig::FSFW_MAX_TM_PACKET_SIZE; - /* TmPacketBase implementations */ - uint8_t getService() override; - uint8_t getSubService() override; - uint8_t* getSourceData() override; - uint16_t getSourceDataSize() override; - uint16_t getDataFieldSize() override; + /** + * This is the default constructor. + * It sets its internal data pointer to the address passed and also + * forwards the data pointer to the parent SpacePacketBase class. + * @param set_address The position where the packet data lies. + */ + TmPacketPusA(uint8_t* setData); + /** + * This is the empty default destructor. + */ + virtual ~TmPacketPusA(); - /** - * Returns a raw pointer to the beginning of the time field. - * @return Raw pointer to time field. - */ - uint8_t* getPacketTimeRaw() const override; - size_t getTimestampSize() const override; + /* TmPacketBase implementations */ + uint8_t getService() override; + uint8_t getSubService() override; + uint8_t* getSourceData() override; + uint16_t getSourceDataSize() override; + uint16_t getDataFieldSize() override; - size_t getPacketMinimumSize() const override; + /** + * Returns a raw pointer to the beginning of the time field. + * @return Raw pointer to time field. + */ + uint8_t* getPacketTimeRaw() const override; + size_t getTimestampSize() const override; -protected: - /** - * A pointer to a structure which defines the data structure of - * the packet's data. - * - * To be hardware-safe, all elements are of byte size. - */ - TmPacketPointerPusA* tmData; + size_t getPacketMinimumSize() const override; - /** - * Initializes the Tm Packet header. - * Does set the timestamp (to now), but not the error control field. - * @param apid APID used. - * @param service PUS Service - * @param subservice PUS Subservice - * @param packetSubcounter Additional subcounter used. - */ - void initializeTmPacket(uint16_t apid, uint8_t service, uint8_t subservice, - uint8_t packetSubcounter); + protected: + /** + * A pointer to a structure which defines the data structure of + * the packet's data. + * + * To be hardware-safe, all elements are of byte size. + */ + TmPacketPointerPusA* tmData; - /** - * With this method, the packet data pointer can be redirected to another - * location. - * - * This call overwrites the parent's setData method to set both its - * @c tc_data pointer and the parent's @c data pointer. - * - * @param p_data A pointer to another PUS Telemetry Packet. - */ - ReturnValue_t setData(uint8_t* pData, size_t maxSize, - void* args = nullptr) override; + /** + * Initializes the Tm Packet header. + * Does set the timestamp (to now), but not the error control field. + * @param apid APID used. + * @param service PUS Service + * @param subservice PUS Subservice + * @param packetSubcounter Additional subcounter used. + */ + void initializeTmPacket(uint16_t apid, uint8_t service, uint8_t subservice, + uint8_t packetSubcounter); - /** - * In case data was filled manually (almost never the case). - * @param size Size of source data (without CRC and data filed header!). - */ - void setSourceDataSize(uint16_t size); + /** + * With this method, the packet data pointer can be redirected to another + * location. + * + * This call overwrites the parent's setData method to set both its + * @c tc_data pointer and the parent's @c data pointer. + * + * @param p_data A pointer to another PUS Telemetry Packet. + */ + ReturnValue_t setData(uint8_t* pData, size_t maxSize, void* args = nullptr) override; - /** - * Checks if a time stamper is available and tries to set it if not. - * @return Returns false if setting failed. - */ - bool checkAndSetStamper(); + /** + * In case data was filled manually (almost never the case). + * @param size Size of source data (without CRC and data filed header!). + */ + void setSourceDataSize(uint16_t size); + + /** + * Checks if a time stamper is available and tries to set it if not. + * @return Returns false if setting failed. + */ + bool checkAndSetStamper(); }; #endif /* FSFW_TMTCPACKET_PUS_TMPACKETPUSA_H_ */ diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketPusC.cpp b/src/fsfw/tmtcpacket/pus/tm/TmPacketPusC.cpp index f33a896a..ab690414 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketPusC.cpp +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketPusC.cpp @@ -1,100 +1,82 @@ -#include "../definitions.h" #include "TmPacketPusC.h" -#include "TmPacketBase.h" +#include + +#include "../definitions.h" +#include "TmPacketBase.h" #include "fsfw/globalfunctions/CRC.h" #include "fsfw/globalfunctions/arrayprinter.h" #include "fsfw/objectmanager/ObjectManagerIF.h" #include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/timemanager/CCSDSTime.h" -#include - - TmPacketPusC::TmPacketPusC(uint8_t* setData) : TmPacketBase(setData) { - tmData = reinterpret_cast(setData); + tmData = reinterpret_cast(setData); } TmPacketPusC::~TmPacketPusC() { - //Nothing to do. + // Nothing to do. } -uint8_t TmPacketPusC::getService() { - return tmData->dataField.serviceType; -} +uint8_t TmPacketPusC::getService() { return tmData->dataField.serviceType; } -uint8_t TmPacketPusC::getSubService() { - return tmData->dataField.serviceSubtype; -} +uint8_t TmPacketPusC::getSubService() { return tmData->dataField.serviceSubtype; } -uint8_t* TmPacketPusC::getSourceData() { - return &tmData->data; -} +uint8_t* TmPacketPusC::getSourceData() { return &tmData->data; } uint16_t TmPacketPusC::getSourceDataSize() { - return getPacketDataLength() - sizeof(tmData->dataField) - CRC_SIZE + 1; + return getPacketDataLength() - sizeof(tmData->dataField) - CRC_SIZE + 1; } ReturnValue_t TmPacketPusC::setData(uint8_t* p_Data, size_t maxSize, void* args) { - ReturnValue_t result = SpacePacketBase::setData(p_Data, maxSize); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if(maxSize < sizeof(TmPacketPointerPusC)) { - return HasReturnvaluesIF::RETURN_OK; - } - tmData = reinterpret_cast(const_cast(p_Data)); + ReturnValue_t result = SpacePacketBase::setData(p_Data, maxSize); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (maxSize < sizeof(TmPacketPointerPusC)) { return HasReturnvaluesIF::RETURN_OK; + } + tmData = reinterpret_cast(const_cast(p_Data)); + return HasReturnvaluesIF::RETURN_OK; } +size_t TmPacketPusC::getPacketMinimumSize() const { return TM_PACKET_MIN_SIZE; } -size_t TmPacketPusC::getPacketMinimumSize() const { - return TM_PACKET_MIN_SIZE; -} +uint16_t TmPacketPusC::getDataFieldSize() { return sizeof(PUSTmDataFieldHeaderPusC); } -uint16_t TmPacketPusC::getDataFieldSize() { - return sizeof(PUSTmDataFieldHeaderPusC); -} +uint8_t* TmPacketPusC::getPacketTimeRaw() const { return tmData->dataField.time; } -uint8_t* TmPacketPusC::getPacketTimeRaw() const{ - return tmData->dataField.time; +ReturnValue_t TmPacketPusC::initializeTmPacket(uint16_t apid, uint8_t service, uint8_t subservice, + uint16_t packetSubcounter, uint16_t destinationId, + uint8_t timeRefField) { + // Set primary header: + ReturnValue_t result = initSpacePacketHeader(false, true, apid); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + // Set data Field Header: + // First, set to zero. + memset(&tmData->dataField, 0, sizeof(tmData->dataField)); -} - -ReturnValue_t TmPacketPusC::initializeTmPacket(uint16_t apid, uint8_t service, - uint8_t subservice, uint16_t packetSubcounter, uint16_t destinationId, - uint8_t timeRefField) { - //Set primary header: - ReturnValue_t result = initSpacePacketHeader(false, true, apid); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - //Set data Field Header: - //First, set to zero. - memset(&tmData->dataField, 0, sizeof(tmData->dataField)); - - /* Only account for last 4 bytes for time reference field */ - timeRefField &= 0b1111; - tmData->dataField.versionTimeReferenceField = - (pus::PusVersion::PUS_C_VERSION << 4) | timeRefField; - tmData->dataField.serviceType = service; - tmData->dataField.serviceSubtype = subservice; - tmData->dataField.subcounterMsb = packetSubcounter << 8 & 0xff; - tmData->dataField.subcounterLsb = packetSubcounter & 0xff; - tmData->dataField.destinationIdMsb = destinationId << 8 & 0xff; - tmData->dataField.destinationIdLsb = destinationId & 0xff; - //Timestamp packet - if (TmPacketBase::checkAndSetStamper()) { - timeStamper->addTimeStamp(tmData->dataField.time, - sizeof(tmData->dataField.time)); - } - return HasReturnvaluesIF::RETURN_OK; + /* Only account for last 4 bytes for time reference field */ + timeRefField &= 0b1111; + tmData->dataField.versionTimeReferenceField = + (pus::PusVersion::PUS_C_VERSION << 4) | timeRefField; + tmData->dataField.serviceType = service; + tmData->dataField.serviceSubtype = subservice; + tmData->dataField.subcounterMsb = packetSubcounter << 8 & 0xff; + tmData->dataField.subcounterLsb = packetSubcounter & 0xff; + tmData->dataField.destinationIdMsb = destinationId << 8 & 0xff; + tmData->dataField.destinationIdLsb = destinationId & 0xff; + // Timestamp packet + if (TmPacketBase::checkAndSetStamper()) { + timeStamper->addTimeStamp(tmData->dataField.time, sizeof(tmData->dataField.time)); + } + return HasReturnvaluesIF::RETURN_OK; } void TmPacketPusC::setSourceDataSize(uint16_t size) { - setPacketDataLength(size + sizeof(PUSTmDataFieldHeaderPusC) + CRC_SIZE - 1); + setPacketDataLength(size + sizeof(PUSTmDataFieldHeaderPusC) + CRC_SIZE - 1); } -size_t TmPacketPusC::getTimestampSize() const { - return sizeof(tmData->dataField.time); -} +size_t TmPacketPusC::getTimestampSize() const { return sizeof(tmData->dataField.time); } diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketPusC.h b/src/fsfw/tmtcpacket/pus/tm/TmPacketPusC.h index b3780183..bbd69693 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketPusC.h +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketPusC.h @@ -2,12 +2,12 @@ #define FSFW_TMTCPACKET_PUS_TMPACKETPUSC_H_ #include "TmPacketBase.h" -#include "fsfw/tmtcpacket/SpacePacketBase.h" -#include "fsfw/timemanager/TimeStamperIF.h" -#include "fsfw/timemanager/Clock.h" #include "fsfw/objectmanager/SystemObjectIF.h" +#include "fsfw/timemanager/Clock.h" +#include "fsfw/timemanager/TimeStamperIF.h" +#include "fsfw/tmtcpacket/SpacePacketBase.h" -namespace Factory{ +namespace Factory { void setStaticFrameworkObjectIds(); } @@ -19,14 +19,14 @@ void setStaticFrameworkObjectIds(); * @ingroup tmtcpackets */ struct PUSTmDataFieldHeaderPusC { - uint8_t versionTimeReferenceField; - uint8_t serviceType; - uint8_t serviceSubtype; - uint8_t subcounterMsb; - uint8_t subcounterLsb; - uint8_t destinationIdMsb; - uint8_t destinationIdLsb; - uint8_t time[TimeStamperIF::MISSION_TIMESTAMP_SIZE]; + uint8_t versionTimeReferenceField; + uint8_t serviceType; + uint8_t serviceSubtype; + uint8_t subcounterMsb; + uint8_t subcounterLsb; + uint8_t destinationIdMsb; + uint8_t destinationIdLsb; + uint8_t time[TimeStamperIF::MISSION_TIMESTAMP_SIZE]; }; /** @@ -35,91 +35,92 @@ struct PUSTmDataFieldHeaderPusC { * @ingroup tmtcpackets */ struct TmPacketPointerPusC { - CCSDSPrimaryHeader primary; - PUSTmDataFieldHeaderPusC dataField; - uint8_t data; + CCSDSPrimaryHeader primary; + PUSTmDataFieldHeaderPusC dataField; + uint8_t data; }; /** * PUS A packet implementation * @ingroup tmtcpackets */ -class TmPacketPusC: public TmPacketBase { - friend void (Factory::setStaticFrameworkObjectIds)(); -public: - /** - * This constant defines the minimum size of a valid PUS Telemetry Packet. - */ - static const uint32_t TM_PACKET_MIN_SIZE = (sizeof(CCSDSPrimaryHeader) + - sizeof(PUSTmDataFieldHeaderPusC) + 2); - //! Maximum size of a TM Packet in this mission. - static const uint32_t MISSION_TM_PACKET_MAX_SIZE = fsfwconfig::FSFW_MAX_TM_PACKET_SIZE; +class TmPacketPusC : public TmPacketBase { + friend void(Factory::setStaticFrameworkObjectIds)(); - /** - * This is the default constructor. - * It sets its internal data pointer to the address passed and also - * forwards the data pointer to the parent SpacePacketBase class. - * @param set_address The position where the packet data lies. - */ - TmPacketPusC( uint8_t* setData ); - /** - * This is the empty default destructor. - */ - virtual ~TmPacketPusC(); + public: + /** + * This constant defines the minimum size of a valid PUS Telemetry Packet. + */ + static const uint32_t TM_PACKET_MIN_SIZE = + (sizeof(CCSDSPrimaryHeader) + sizeof(PUSTmDataFieldHeaderPusC) + 2); + //! Maximum size of a TM Packet in this mission. + static const uint32_t MISSION_TM_PACKET_MAX_SIZE = fsfwconfig::FSFW_MAX_TM_PACKET_SIZE; - /* TmPacketBase implementations */ - uint8_t getService() override; - uint8_t getSubService() override; - uint8_t* getSourceData() override; - uint16_t getSourceDataSize() override; - uint16_t getDataFieldSize() override; + /** + * This is the default constructor. + * It sets its internal data pointer to the address passed and also + * forwards the data pointer to the parent SpacePacketBase class. + * @param set_address The position where the packet data lies. + */ + TmPacketPusC(uint8_t* setData); + /** + * This is the empty default destructor. + */ + virtual ~TmPacketPusC(); - /** - * Returns a raw pointer to the beginning of the time field. - * @return Raw pointer to time field. - */ - uint8_t* getPacketTimeRaw() const override; - size_t getTimestampSize() const override; + /* TmPacketBase implementations */ + uint8_t getService() override; + uint8_t getSubService() override; + uint8_t* getSourceData() override; + uint16_t getSourceDataSize() override; + uint16_t getDataFieldSize() override; - size_t getPacketMinimumSize() const override; + /** + * Returns a raw pointer to the beginning of the time field. + * @return Raw pointer to time field. + */ + uint8_t* getPacketTimeRaw() const override; + size_t getTimestampSize() const override; -protected: - /** - * A pointer to a structure which defines the data structure of - * the packet's data. - * - * To be hardware-safe, all elements are of byte size. - */ - TmPacketPointerPusC* tmData; + size_t getPacketMinimumSize() const override; - /** - * Initializes the Tm Packet header. - * Does set the timestamp (to now), but not the error control field. - * @param apid APID used. - * @param service PUS Service - * @param subservice PUS Subservice - * @param packetSubcounter Additional subcounter used. - */ - ReturnValue_t initializeTmPacket(uint16_t apid, uint8_t service, uint8_t subservice, - uint16_t packetSubcounter, uint16_t destinationId = 0, uint8_t timeRefField = 0); + protected: + /** + * A pointer to a structure which defines the data structure of + * the packet's data. + * + * To be hardware-safe, all elements are of byte size. + */ + TmPacketPointerPusC* tmData; - /** - * With this method, the packet data pointer can be redirected to another - * location. - * - * This call overwrites the parent's setData method to set both its - * @c tc_data pointer and the parent's @c data pointer. - * - * @param pData A pointer to another PUS Telemetry Packet. - */ - ReturnValue_t setData(uint8_t* pData, size_t maxSize, void* args = nullptr) override; + /** + * Initializes the Tm Packet header. + * Does set the timestamp (to now), but not the error control field. + * @param apid APID used. + * @param service PUS Service + * @param subservice PUS Subservice + * @param packetSubcounter Additional subcounter used. + */ + ReturnValue_t initializeTmPacket(uint16_t apid, uint8_t service, uint8_t subservice, + uint16_t packetSubcounter, uint16_t destinationId = 0, + uint8_t timeRefField = 0); - /** - * In case data was filled manually (almost never the case). - * @param size Size of source data (without CRC and data filed header!). - */ - void setSourceDataSize(uint16_t size); + /** + * With this method, the packet data pointer can be redirected to another + * location. + * + * This call overwrites the parent's setData method to set both its + * @c tc_data pointer and the parent's @c data pointer. + * + * @param pData A pointer to another PUS Telemetry Packet. + */ + ReturnValue_t setData(uint8_t* pData, size_t maxSize, void* args = nullptr) override; + /** + * In case data was filled manually (almost never the case). + * @param size Size of source data (without CRC and data filed header!). + */ + void setSourceDataSize(uint16_t size); }; #endif /* FSFW_TMTCPACKET_PUS_TMPACKETPUSC_H_ */ diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketStored.h b/src/fsfw/tmtcpacket/pus/tm/TmPacketStored.h index fadda561..de10655f 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketStored.h +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketStored.h @@ -9,5 +9,4 @@ #include "TmPacketStoredPusA.h" #endif - #endif /* FSFW_TMTCPACKET_PUS_TMPACKETSTORED_H_ */ diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredBase.cpp b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredBase.cpp index f2cc5a67..4d37bf46 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredBase.cpp +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredBase.cpp @@ -1,124 +1,121 @@ #include "fsfw/tmtcpacket/pus/tm/TmPacketStoredBase.h" +#include + #include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/tmtcservices/TmTcMessage.h" -#include - StorageManagerIF *TmPacketStoredBase::store = nullptr; InternalErrorReporterIF *TmPacketStoredBase::internalErrorReporter = nullptr; -TmPacketStoredBase::TmPacketStoredBase(store_address_t setAddress): storeAddress(setAddress) { - setStoreAddress(storeAddress); +TmPacketStoredBase::TmPacketStoredBase(store_address_t setAddress) : storeAddress(setAddress) { + setStoreAddress(storeAddress); } -TmPacketStoredBase::TmPacketStoredBase() { -} +TmPacketStoredBase::TmPacketStoredBase() {} +TmPacketStoredBase::~TmPacketStoredBase() {} -TmPacketStoredBase::~TmPacketStoredBase() { -} - -store_address_t TmPacketStoredBase::getStoreAddress() { - return storeAddress; -} +store_address_t TmPacketStoredBase::getStoreAddress() { return storeAddress; } void TmPacketStoredBase::deletePacket() { - store->deleteData(storeAddress); - storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; - setData(nullptr, -1); + store->deleteData(storeAddress); + storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; + setData(nullptr, -1); } void TmPacketStoredBase::setStoreAddress(store_address_t setAddress) { - storeAddress = setAddress; - const uint8_t* tempData = nullptr; - size_t tempSize; - if (not checkAndSetStore()) { - return; - } - ReturnValue_t status = store->getData(storeAddress, &tempData, &tempSize); - if (status == StorageManagerIF::RETURN_OK) { - setData(const_cast(tempData), tempSize); - } else { - setData(nullptr, -1); - storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; - } + storeAddress = setAddress; + const uint8_t *tempData = nullptr; + size_t tempSize; + if (not checkAndSetStore()) { + return; + } + ReturnValue_t status = store->getData(storeAddress, &tempData, &tempSize); + if (status == StorageManagerIF::RETURN_OK) { + setData(const_cast(tempData), tempSize); + } else { + setData(nullptr, -1); + storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; + } } bool TmPacketStoredBase::checkAndSetStore() { + if (store == nullptr) { + store = ObjectManager::instance()->get(objects::TM_STORE); if (store == nullptr) { - store = ObjectManager::instance()->get(objects::TM_STORE); - if (store == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "TmPacketStored::TmPacketStored: TM Store not found!" - << std::endl; + sif::error << "TmPacketStored::TmPacketStored: TM Store not found!" << std::endl; #endif - return false; - } + return false; } - return true; + } + return true; } ReturnValue_t TmPacketStoredBase::sendPacket(MessageQueueId_t destination, - MessageQueueId_t sentFrom, bool doErrorReporting) { - if (getAllTmData() == nullptr) { - //SHOULDDO: More decent code. - return HasReturnvaluesIF::RETURN_FAILED; + MessageQueueId_t sentFrom, bool doErrorReporting) { + if (getAllTmData() == nullptr) { + // SHOULDDO: More decent code. + return HasReturnvaluesIF::RETURN_FAILED; + } + TmTcMessage tmMessage(getStoreAddress()); + ReturnValue_t result = MessageQueueSenderIF::sendMessage(destination, &tmMessage, sentFrom); + if (result != HasReturnvaluesIF::RETURN_OK) { + deletePacket(); + if (doErrorReporting) { + checkAndReportLostTm(); } - TmTcMessage tmMessage(getStoreAddress()); - ReturnValue_t result = MessageQueueSenderIF::sendMessage(destination, - &tmMessage, sentFrom); - if (result != HasReturnvaluesIF::RETURN_OK) { - deletePacket(); - if (doErrorReporting) { - checkAndReportLostTm(); - } - return result; - } - //SHOULDDO: In many cases, some counter is incremented for successfully sent packets. The check is often not done, but just incremented. - return HasReturnvaluesIF::RETURN_OK; - + return result; + } + // SHOULDDO: In many cases, some counter is incremented for successfully sent packets. The check + // is often not done, but just incremented. + return HasReturnvaluesIF::RETURN_OK; } void TmPacketStoredBase::checkAndReportLostTm() { - if (internalErrorReporter == nullptr) { - internalErrorReporter = ObjectManager::instance()->get( - objects::INTERNAL_ERROR_REPORTER); - } - if (internalErrorReporter != nullptr) { - internalErrorReporter->lostTm(); - } + if (internalErrorReporter == nullptr) { + internalErrorReporter = + ObjectManager::instance()->get(objects::INTERNAL_ERROR_REPORTER); + } + if (internalErrorReporter != nullptr) { + internalErrorReporter->lostTm(); + } } void TmPacketStoredBase::handleStoreFailure(const char *const packetType, ReturnValue_t result, - size_t sizeToReserve) { - checkAndReportLostTm(); + size_t sizeToReserve) { + checkAndReportLostTm(); #if FSFW_VERBOSE_LEVEL >= 1 - switch(result) { + switch (result) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - case(StorageManagerIF::DATA_STORAGE_FULL): { - sif::warning << "TmPacketStoredPus" << packetType << ": " << - "Store full for packet with size" << sizeToReserve << std::endl; - break; + case (StorageManagerIF::DATA_STORAGE_FULL): { + sif::warning << "TmPacketStoredPus" << packetType << ": " + << "Store full for packet with size" << sizeToReserve << std::endl; + break; } - case(StorageManagerIF::DATA_TOO_LARGE): { - sif::warning << "TmPacketStoredPus" << packetType << ": Data with size " << - sizeToReserve << " too large" << std::endl; - break; + case (StorageManagerIF::DATA_TOO_LARGE): { + sif::warning << "TmPacketStoredPus" << packetType << ": Data with size " << sizeToReserve + << " too large" << std::endl; + break; } #else - case(StorageManagerIF::DATA_STORAGE_FULL): { - sif::printWarning("TmPacketStoredPus%s: Store full for packet with " - "size %d\n", packetType, sizeToReserve); - break; + case (StorageManagerIF::DATA_STORAGE_FULL): { + sif::printWarning( + "TmPacketStoredPus%s: Store full for packet with " + "size %d\n", + packetType, sizeToReserve); + break; } - case(StorageManagerIF::DATA_TOO_LARGE): { - sif::printWarning("TmPacketStoredPus%s: Data with size " - "%d too large\n", packetType, sizeToReserve); - break; + case (StorageManagerIF::DATA_TOO_LARGE): { + sif::printWarning( + "TmPacketStoredPus%s: Data with size " + "%d too large\n", + packetType, sizeToReserve); + break; } #endif - } + } #endif } diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredBase.h b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredBase.h index 372b1e63..1732f000 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredBase.h +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredBase.h @@ -1,15 +1,14 @@ #ifndef FSFW_TMTCPACKET_PUS_TMPACKETSTOREDBASE_H_ #define FSFW_TMTCPACKET_PUS_TMPACKETSTOREDBASE_H_ -#include "fsfw/FSFW.h" #include "TmPacketBase.h" -#include "TmPacketStoredBase.h" #include "TmPacketPusA.h" - -#include "fsfw/serialize/SerializeIF.h" -#include "fsfw/storagemanager/StorageManagerIF.h" +#include "TmPacketStoredBase.h" +#include "fsfw/FSFW.h" #include "fsfw/internalerror/InternalErrorReporterIF.h" #include "fsfw/ipc/MessageQueueSenderIF.h" +#include "fsfw/serialize/SerializeIF.h" +#include "fsfw/storagemanager/StorageManagerIF.h" /** * This class generates a ECSS PUS Telemetry packet within a given @@ -21,71 +20,68 @@ * packets in a store with the help of a storeAddress. * @ingroup tmtcpackets */ -class TmPacketStoredBase: virtual public RedirectableDataPointerIF { -public: - /** - * This is a default constructor which does not set the data pointer. - * However, it does try to set the packet store. - */ - TmPacketStoredBase( store_address_t setAddress ); - TmPacketStoredBase(); +class TmPacketStoredBase : virtual public RedirectableDataPointerIF { + public: + /** + * This is a default constructor which does not set the data pointer. + * However, it does try to set the packet store. + */ + TmPacketStoredBase(store_address_t setAddress); + TmPacketStoredBase(); - virtual ~TmPacketStoredBase(); + virtual ~TmPacketStoredBase(); - virtual uint8_t* getAllTmData() = 0; + virtual uint8_t* getAllTmData() = 0; - /** - * This is a getter for the current store address of the packet. - * @return The current store address. The (raw) value is - * @c StorageManagerIF::INVALID_ADDRESS if - * the packet is not linked. - */ - store_address_t getStoreAddress(); - /** - * With this call, the packet is deleted. - * It removes itself from the store and sets its data pointer to NULL. - */ - void deletePacket(); - /** - * With this call, a packet can be linked to another store. This is useful - * if the packet is a class member and used for more than one packet. - * @param setAddress The new packet id to link to. - */ - void setStoreAddress(store_address_t setAddress); + /** + * This is a getter for the current store address of the packet. + * @return The current store address. The (raw) value is + * @c StorageManagerIF::INVALID_ADDRESS if + * the packet is not linked. + */ + store_address_t getStoreAddress(); + /** + * With this call, the packet is deleted. + * It removes itself from the store and sets its data pointer to NULL. + */ + void deletePacket(); + /** + * With this call, a packet can be linked to another store. This is useful + * if the packet is a class member and used for more than one packet. + * @param setAddress The new packet id to link to. + */ + void setStoreAddress(store_address_t setAddress); - ReturnValue_t sendPacket(MessageQueueId_t destination, MessageQueueId_t sentFrom, - bool doErrorReporting = true); + ReturnValue_t sendPacket(MessageQueueId_t destination, MessageQueueId_t sentFrom, + bool doErrorReporting = true); -protected: - /** - * This is a pointer to the store all instances of the class use. - * If the store is not yet set (i.e. @c store is NULL), every constructor - * call tries to set it and throws an error message in case of failures. - * The default store is objects::TM_STORE. - */ - static StorageManagerIF* store; + protected: + /** + * This is a pointer to the store all instances of the class use. + * If the store is not yet set (i.e. @c store is NULL), every constructor + * call tries to set it and throws an error message in case of failures. + * The default store is objects::TM_STORE. + */ + static StorageManagerIF* store; - static InternalErrorReporterIF *internalErrorReporter; + static InternalErrorReporterIF* internalErrorReporter; - /** - * The address where the packet data of the object instance is stored. - */ - store_address_t storeAddress; - /** - * A helper method to check if a store is assigned to the class. - * If not, the method tries to retrieve the store from the global - * ObjectManager. - * @return @li @c true if the store is linked or could be created. - * @li @c false otherwise. - */ - bool checkAndSetStore(); + /** + * The address where the packet data of the object instance is stored. + */ + store_address_t storeAddress; + /** + * A helper method to check if a store is assigned to the class. + * If not, the method tries to retrieve the store from the global + * ObjectManager. + * @return @li @c true if the store is linked or could be created. + * @li @c false otherwise. + */ + bool checkAndSetStore(); - void checkAndReportLostTm(); + void checkAndReportLostTm(); - void handleStoreFailure(const char* const packetType, ReturnValue_t result, - size_t sizeToReserve); + void handleStoreFailure(const char* const packetType, ReturnValue_t result, size_t sizeToReserve); }; - #endif /* FSFW_TMTCPACKET_PUS_TMPACKETSTOREDBASE_H_ */ - diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusA.cpp b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusA.cpp index b4b396b5..37ba63f3 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusA.cpp +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusA.cpp @@ -1,80 +1,73 @@ #include "fsfw/tmtcpacket/pus/tm/TmPacketStoredPusA.h" +#include + #include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/tmtcservices/TmTcMessage.h" -#include +TmPacketStoredPusA::TmPacketStoredPusA(store_address_t setAddress) + : TmPacketStoredBase(setAddress), TmPacketPusA(nullptr) {} -TmPacketStoredPusA::TmPacketStoredPusA(store_address_t setAddress): - TmPacketStoredBase(setAddress), TmPacketPusA(nullptr){ +TmPacketStoredPusA::TmPacketStoredPusA(uint16_t apid, uint8_t service, uint8_t subservice, + uint8_t packetSubcounter, const uint8_t *data, uint32_t size, + const uint8_t *headerData, uint32_t headerSize) + : TmPacketPusA(nullptr) { + storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; + if (not TmPacketStoredBase::checkAndSetStore()) { + return; + } + uint8_t *pData = nullptr; + size_t sizeToReserve = getPacketMinimumSize() + size + headerSize; + ReturnValue_t returnValue = store->getFreeElement(&storeAddress, sizeToReserve, &pData); + + if (returnValue != store->RETURN_OK) { + handleStoreFailure("A", returnValue, sizeToReserve); + return; + } + setData(pData, sizeToReserve); + initializeTmPacket(apid, service, subservice, packetSubcounter); + memcpy(getSourceData(), headerData, headerSize); + memcpy(getSourceData() + headerSize, data, size); + setPacketDataLength(size + headerSize + sizeof(PUSTmDataFieldHeaderPusA) + CRC_SIZE - 1); } -TmPacketStoredPusA::TmPacketStoredPusA(uint16_t apid, uint8_t service, - uint8_t subservice, uint8_t packetSubcounter, const uint8_t *data, - uint32_t size, const uint8_t *headerData, uint32_t headerSize): - TmPacketPusA(nullptr) { - storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; - if (not TmPacketStoredBase::checkAndSetStore()) { - return; - } - uint8_t *pData = nullptr; - size_t sizeToReserve = getPacketMinimumSize() + size + headerSize; - ReturnValue_t returnValue = store->getFreeElement(&storeAddress, - sizeToReserve, &pData); - - if (returnValue != store->RETURN_OK) { - handleStoreFailure("A", returnValue, sizeToReserve); - return; - } - setData(pData, sizeToReserve); - initializeTmPacket(apid, service, subservice, packetSubcounter); - memcpy(getSourceData(), headerData, headerSize); - memcpy(getSourceData() + headerSize, data, size); - setPacketDataLength(size + headerSize + sizeof(PUSTmDataFieldHeaderPusA) + CRC_SIZE - 1); +TmPacketStoredPusA::TmPacketStoredPusA(uint16_t apid, uint8_t service, uint8_t subservice, + uint8_t packetSubcounter, SerializeIF *content, + SerializeIF *header) + : TmPacketPusA(nullptr) { + storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; + if (not TmPacketStoredBase::checkAndSetStore()) { + return; + } + size_t sourceDataSize = 0; + if (content != nullptr) { + sourceDataSize += content->getSerializedSize(); + } + if (header != nullptr) { + sourceDataSize += header->getSerializedSize(); + } + uint8_t *pData = nullptr; + size_t sizeToReserve = getPacketMinimumSize() + sourceDataSize; + ReturnValue_t returnValue = store->getFreeElement(&storeAddress, sizeToReserve, &pData); + if (returnValue != store->RETURN_OK) { + handleStoreFailure("A", returnValue, sizeToReserve); + return; + } + setData(pData, sizeToReserve); + initializeTmPacket(apid, service, subservice, packetSubcounter); + uint8_t *putDataHere = getSourceData(); + size_t size = 0; + if (header != nullptr) { + header->serialize(&putDataHere, &size, sourceDataSize, SerializeIF::Endianness::BIG); + } + if (content != nullptr) { + content->serialize(&putDataHere, &size, sourceDataSize, SerializeIF::Endianness::BIG); + } + setPacketDataLength(sourceDataSize + sizeof(PUSTmDataFieldHeaderPusA) + CRC_SIZE - 1); } -TmPacketStoredPusA::TmPacketStoredPusA(uint16_t apid, uint8_t service, - uint8_t subservice, uint8_t packetSubcounter, SerializeIF *content, - SerializeIF *header) : - TmPacketPusA(nullptr) { - storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; - if (not TmPacketStoredBase::checkAndSetStore()) { - return; - } - size_t sourceDataSize = 0; - if (content != nullptr) { - sourceDataSize += content->getSerializedSize(); - } - if (header != nullptr) { - sourceDataSize += header->getSerializedSize(); - } - uint8_t *pData = nullptr; - size_t sizeToReserve = getPacketMinimumSize() + sourceDataSize; - ReturnValue_t returnValue = store->getFreeElement(&storeAddress, - sizeToReserve, &pData); - if (returnValue != store->RETURN_OK) { - handleStoreFailure("A", returnValue, sizeToReserve); - return; - } - setData(pData, sizeToReserve); - initializeTmPacket(apid, service, subservice, packetSubcounter); - uint8_t *putDataHere = getSourceData(); - size_t size = 0; - if (header != nullptr) { - header->serialize(&putDataHere, &size, sourceDataSize, - SerializeIF::Endianness::BIG); - } - if (content != nullptr) { - content->serialize(&putDataHere, &size, sourceDataSize, - SerializeIF::Endianness::BIG); - } - setPacketDataLength(sourceDataSize + sizeof(PUSTmDataFieldHeaderPusA) + CRC_SIZE - 1); -} +uint8_t *TmPacketStoredPusA::getAllTmData() { return getWholeData(); } -uint8_t* TmPacketStoredPusA::getAllTmData() { - return getWholeData(); -} - -ReturnValue_t TmPacketStoredPusA::setData(uint8_t *newPointer, size_t maxSize, void* args) { - return TmPacketPusA::setData(newPointer, maxSize); +ReturnValue_t TmPacketStoredPusA::setData(uint8_t *newPointer, size_t maxSize, void *args) { + return TmPacketPusA::setData(newPointer, maxSize); } diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusA.h b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusA.h index 6fa80949..f2db99e9 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusA.h +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusA.h @@ -1,10 +1,11 @@ #ifndef FSFW_TMTCPACKET_PUS_TMPACKETSTORED_PUSA_H_ #define FSFW_TMTCPACKET_PUS_TMPACKETSTORED_PUSA_H_ -#include "TmPacketStoredBase.h" -#include "TmPacketPusA.h" #include +#include "TmPacketPusA.h" +#include "TmPacketStoredBase.h" + /** * This class generates a ECSS PUS A Telemetry packet within a given * intermediate storage. @@ -15,61 +16,54 @@ * packets in a store with the help of a storeAddress. * @ingroup tmtcpackets */ -class TmPacketStoredPusA: - public TmPacketStoredBase, - public TmPacketPusA { -public: - /** - * This is a default constructor which does not set the data pointer. - * However, it does try to set the packet store. - */ - TmPacketStoredPusA( store_address_t setAddress ); - /** - * With this constructor, new space is allocated in the packet store and - * a new PUS Telemetry Packet is created there. - * Packet Application Data passed in data is copied into the packet. - * The Application data is passed in two parts, first a header, then a - * data field. This allows building a Telemetry Packet from two separate - * data sources. - * @param apid Sets the packet's APID field. - * @param service Sets the packet's Service ID field. - * This specifies the source service. - * @param subservice Sets the packet's Service Subtype field. - * This specifies the source sub-service. - * @param packet_counter Sets the Packet counter field of this packet - * @param data The payload data to be copied to the - * Application Data Field - * @param size The amount of data to be copied. - * @param headerData The header Data of the Application field, - * will be copied in front of data - * @param headerSize The size of the headerDataF - */ - TmPacketStoredPusA( uint16_t apid, uint8_t service, uint8_t subservice, - uint8_t packet_counter = 0, const uint8_t* data = nullptr, - uint32_t size = 0, const uint8_t* headerData = nullptr, - uint32_t headerSize = 0); - /** - * Another ctor to directly pass structured content and header data to the - * packet to avoid additional buffers. - */ - TmPacketStoredPusA( uint16_t apid, uint8_t service, uint8_t subservice, - uint8_t packet_counter, SerializeIF* content, - SerializeIF* header = nullptr); +class TmPacketStoredPusA : public TmPacketStoredBase, public TmPacketPusA { + public: + /** + * This is a default constructor which does not set the data pointer. + * However, it does try to set the packet store. + */ + TmPacketStoredPusA(store_address_t setAddress); + /** + * With this constructor, new space is allocated in the packet store and + * a new PUS Telemetry Packet is created there. + * Packet Application Data passed in data is copied into the packet. + * The Application data is passed in two parts, first a header, then a + * data field. This allows building a Telemetry Packet from two separate + * data sources. + * @param apid Sets the packet's APID field. + * @param service Sets the packet's Service ID field. + * This specifies the source service. + * @param subservice Sets the packet's Service Subtype field. + * This specifies the source sub-service. + * @param packet_counter Sets the Packet counter field of this packet + * @param data The payload data to be copied to the + * Application Data Field + * @param size The amount of data to be copied. + * @param headerData The header Data of the Application field, + * will be copied in front of data + * @param headerSize The size of the headerDataF + */ + TmPacketStoredPusA(uint16_t apid, uint8_t service, uint8_t subservice, uint8_t packet_counter = 0, + const uint8_t* data = nullptr, uint32_t size = 0, + const uint8_t* headerData = nullptr, uint32_t headerSize = 0); + /** + * Another ctor to directly pass structured content and header data to the + * packet to avoid additional buffers. + */ + TmPacketStoredPusA(uint16_t apid, uint8_t service, uint8_t subservice, uint8_t packet_counter, + SerializeIF* content, SerializeIF* header = nullptr); - uint8_t* getAllTmData() override; - -private: - - /** - * Implementation required by base class - * @param newPointer - * @param maxSize - * @param args - * @return - */ - ReturnValue_t setData(uint8_t* newPointer, size_t maxSize, void* args = nullptr) override; + uint8_t* getAllTmData() override; + private: + /** + * Implementation required by base class + * @param newPointer + * @param maxSize + * @param args + * @return + */ + ReturnValue_t setData(uint8_t* newPointer, size_t maxSize, void* args = nullptr) override; }; - #endif /* FSFW_TMTCPACKET_PUS_TMPACKETSTORED_PUSA_H_ */ diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusC.cpp b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusC.cpp index 8d7dd9eb..9c170aa3 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusC.cpp +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusC.cpp @@ -1,82 +1,76 @@ #include "fsfw/tmtcpacket/pus/tm/TmPacketStoredPusC.h" +#include + #include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/tmtcservices/TmTcMessage.h" -#include +TmPacketStoredPusC::TmPacketStoredPusC(store_address_t setAddress) + : TmPacketStoredBase(setAddress), TmPacketPusC(nullptr) {} -TmPacketStoredPusC::TmPacketStoredPusC(store_address_t setAddress) : - TmPacketStoredBase(setAddress), TmPacketPusC(nullptr){ +TmPacketStoredPusC::TmPacketStoredPusC(uint16_t apid, uint8_t service, uint8_t subservice, + uint16_t packetSubcounter, const uint8_t *data, + uint32_t size, const uint8_t *headerData, + uint32_t headerSize, uint16_t destinationId, + uint8_t timeRefField) + : TmPacketPusC(nullptr) { + storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; + if (not TmPacketStoredBase::checkAndSetStore()) { + return; + } + uint8_t *pData = nullptr; + size_t sizeToReserve = getPacketMinimumSize() + size + headerSize; + ReturnValue_t returnValue = store->getFreeElement(&storeAddress, sizeToReserve, &pData); + + if (returnValue != store->RETURN_OK) { + handleStoreFailure("C", returnValue, sizeToReserve); + return; + } + setData(pData, sizeToReserve); + initializeTmPacket(apid, service, subservice, packetSubcounter, destinationId, timeRefField); + memcpy(getSourceData(), headerData, headerSize); + memcpy(getSourceData() + headerSize, data, size); + setPacketDataLength(size + headerSize + sizeof(PUSTmDataFieldHeaderPusC) + CRC_SIZE - 1); } -TmPacketStoredPusC::TmPacketStoredPusC(uint16_t apid, uint8_t service, - uint8_t subservice, uint16_t packetSubcounter, const uint8_t *data, - uint32_t size, const uint8_t *headerData, uint32_t headerSize, uint16_t destinationId, - uint8_t timeRefField) : - TmPacketPusC(nullptr) { - storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; - if (not TmPacketStoredBase::checkAndSetStore()) { - return; - } - uint8_t *pData = nullptr; - size_t sizeToReserve = getPacketMinimumSize() + size + headerSize; - ReturnValue_t returnValue = store->getFreeElement(&storeAddress, - sizeToReserve, &pData); - - if (returnValue != store->RETURN_OK) { - handleStoreFailure("C", returnValue, sizeToReserve); - return; - } - setData(pData, sizeToReserve); - initializeTmPacket(apid, service, subservice, packetSubcounter, destinationId, timeRefField); - memcpy(getSourceData(), headerData, headerSize); - memcpy(getSourceData() + headerSize, data, size); - setPacketDataLength(size + headerSize + sizeof(PUSTmDataFieldHeaderPusC) + CRC_SIZE - 1); +TmPacketStoredPusC::TmPacketStoredPusC(uint16_t apid, uint8_t service, uint8_t subservice, + uint16_t packetSubcounter, SerializeIF *content, + SerializeIF *header, uint16_t destinationId, + uint8_t timeRefField) + : TmPacketPusC(nullptr) { + storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; + if (not TmPacketStoredBase::checkAndSetStore()) { + return; + } + size_t sourceDataSize = 0; + if (content != nullptr) { + sourceDataSize += content->getSerializedSize(); + } + if (header != nullptr) { + sourceDataSize += header->getSerializedSize(); + } + uint8_t *pData = nullptr; + size_t sizeToReserve = getPacketMinimumSize() + sourceDataSize; + ReturnValue_t returnValue = store->getFreeElement(&storeAddress, sizeToReserve, &pData); + if (returnValue != store->RETURN_OK) { + handleStoreFailure("C", returnValue, sizeToReserve); + return; + } + TmPacketPusC::setData(pData, sizeToReserve); + initializeTmPacket(apid, service, subservice, packetSubcounter, destinationId, timeRefField); + uint8_t *putDataHere = getSourceData(); + size_t size = 0; + if (header != nullptr) { + header->serialize(&putDataHere, &size, sourceDataSize, SerializeIF::Endianness::BIG); + } + if (content != nullptr) { + content->serialize(&putDataHere, &size, sourceDataSize, SerializeIF::Endianness::BIG); + } + setPacketDataLength(sourceDataSize + sizeof(PUSTmDataFieldHeaderPusC) + CRC_SIZE - 1); } -TmPacketStoredPusC::TmPacketStoredPusC(uint16_t apid, uint8_t service, - uint8_t subservice, uint16_t packetSubcounter, SerializeIF *content, - SerializeIF *header, uint16_t destinationId, uint8_t timeRefField) : - TmPacketPusC(nullptr) { - storeAddress.raw = StorageManagerIF::INVALID_ADDRESS; - if (not TmPacketStoredBase::checkAndSetStore()) { - return; - } - size_t sourceDataSize = 0; - if (content != nullptr) { - sourceDataSize += content->getSerializedSize(); - } - if (header != nullptr) { - sourceDataSize += header->getSerializedSize(); - } - uint8_t *pData = nullptr; - size_t sizeToReserve = getPacketMinimumSize() + sourceDataSize; - ReturnValue_t returnValue = store->getFreeElement(&storeAddress, sizeToReserve, &pData); - if (returnValue != store->RETURN_OK) { - handleStoreFailure("C", returnValue, sizeToReserve); - return; - } - TmPacketPusC::setData(pData, sizeToReserve); - initializeTmPacket(apid, service, subservice, packetSubcounter, destinationId, timeRefField); - uint8_t *putDataHere = getSourceData(); - size_t size = 0; - if (header != nullptr) { - header->serialize(&putDataHere, &size, sourceDataSize, - SerializeIF::Endianness::BIG); - } - if (content != nullptr) { - content->serialize(&putDataHere, &size, sourceDataSize, - SerializeIF::Endianness::BIG); - } - setPacketDataLength( - sourceDataSize + sizeof(PUSTmDataFieldHeaderPusC) + CRC_SIZE - 1); -} +uint8_t *TmPacketStoredPusC::getAllTmData() { return getWholeData(); } -uint8_t* TmPacketStoredPusC::getAllTmData() { - return getWholeData(); -} - -ReturnValue_t TmPacketStoredPusC::setData(uint8_t *newPointer, size_t maxSize, - void* args) { - return TmPacketPusC::setData(newPointer, maxSize); +ReturnValue_t TmPacketStoredPusC::setData(uint8_t *newPointer, size_t maxSize, void *args) { + return TmPacketPusC::setData(newPointer, maxSize); } diff --git a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusC.h b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusC.h index cbf62b1b..ef84e238 100644 --- a/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusC.h +++ b/src/fsfw/tmtcpacket/pus/tm/TmPacketStoredPusC.h @@ -14,65 +14,59 @@ * packets in a store with the help of a storeAddress. * @ingroup tmtcpackets */ -class TmPacketStoredPusC: - public TmPacketStoredBase, - public TmPacketPusC { -public: - /** - * This is a default constructor which does not set the data pointer. - * However, it does try to set the packet store. - */ - TmPacketStoredPusC( store_address_t setAddress ); - /** - * With this constructor, new space is allocated in the packet store and - * a new PUS Telemetry Packet is created there. - * Packet Application Data passed in data is copied into the packet. - * The Application data is passed in two parts, first a header, then a - * data field. This allows building a Telemetry Packet from two separate - * data sources. - * @param apid Sets the packet's APID field. - * @param service Sets the packet's Service ID field. - * This specifies the source service. - * @param subservice Sets the packet's Service Subtype field. - * This specifies the source sub-service. - * @param packet_counter Sets the Packet counter field of this packet - * @param data The payload data to be copied to the - * Application Data Field - * @param size The amount of data to be copied. - * @param headerData The header Data of the Application field, - * will be copied in front of data - * @param headerSize The size of the headerDataF - * @param destinationId Destination ID containing the application process ID as specified - * by PUS C - * @param timeRefField 4 bit time reference field as specified by PUS C - */ - TmPacketStoredPusC( uint16_t apid, uint8_t service, uint8_t subservice, - uint16_t packetCounter = 0, const uint8_t* data = nullptr, - uint32_t size = 0, const uint8_t* headerData = nullptr, - uint32_t headerSize = 0, uint16_t destinationId = 0, uint8_t timeRefField = 0); - /** - * Another ctor to directly pass structured content and header data to the - * packet to avoid additional buffers. - */ - TmPacketStoredPusC( uint16_t apid, uint8_t service, uint8_t subservice, - uint16_t packetCounter, SerializeIF* content, - SerializeIF* header = nullptr, uint16_t destinationId = 0, uint8_t timeRefField = 0); +class TmPacketStoredPusC : public TmPacketStoredBase, public TmPacketPusC { + public: + /** + * This is a default constructor which does not set the data pointer. + * However, it does try to set the packet store. + */ + TmPacketStoredPusC(store_address_t setAddress); + /** + * With this constructor, new space is allocated in the packet store and + * a new PUS Telemetry Packet is created there. + * Packet Application Data passed in data is copied into the packet. + * The Application data is passed in two parts, first a header, then a + * data field. This allows building a Telemetry Packet from two separate + * data sources. + * @param apid Sets the packet's APID field. + * @param service Sets the packet's Service ID field. + * This specifies the source service. + * @param subservice Sets the packet's Service Subtype field. + * This specifies the source sub-service. + * @param packet_counter Sets the Packet counter field of this packet + * @param data The payload data to be copied to the + * Application Data Field + * @param size The amount of data to be copied. + * @param headerData The header Data of the Application field, + * will be copied in front of data + * @param headerSize The size of the headerDataF + * @param destinationId Destination ID containing the application process ID as specified + * by PUS C + * @param timeRefField 4 bit time reference field as specified by PUS C + */ + TmPacketStoredPusC(uint16_t apid, uint8_t service, uint8_t subservice, uint16_t packetCounter = 0, + const uint8_t* data = nullptr, uint32_t size = 0, + const uint8_t* headerData = nullptr, uint32_t headerSize = 0, + uint16_t destinationId = 0, uint8_t timeRefField = 0); + /** + * Another ctor to directly pass structured content and header data to the + * packet to avoid additional buffers. + */ + TmPacketStoredPusC(uint16_t apid, uint8_t service, uint8_t subservice, uint16_t packetCounter, + SerializeIF* content, SerializeIF* header = nullptr, + uint16_t destinationId = 0, uint8_t timeRefField = 0); - uint8_t* getAllTmData() override; - -private: - - /** - * Implementation required by base class - * @param newPointer - * @param maxSize - * @param args - * @return - */ - ReturnValue_t setData(uint8_t* newPointer, size_t maxSize, void* args = nullptr) override; + uint8_t* getAllTmData() override; + private: + /** + * Implementation required by base class + * @param newPointer + * @param maxSize + * @param args + * @return + */ + ReturnValue_t setData(uint8_t* newPointer, size_t maxSize, void* args = nullptr) override; }; - - #endif /* FSFW_TMTCPACKET_PUS_TMPACKETSTOREDPUSC_H_ */ diff --git a/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h b/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h index 7c871049..4186f4df 100644 --- a/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h +++ b/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h @@ -10,34 +10,31 @@ * and thus make the service id and the receiving message queue public. */ class AcceptsTelecommandsIF { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::ACCEPTS_TELECOMMANDS_IF; - static const ReturnValue_t ACTIVITY_STARTED = MAKE_RETURN_CODE(1); - static const ReturnValue_t INVALID_SUBSERVICE = MAKE_RETURN_CODE(2); - static const ReturnValue_t ILLEGAL_APPLICATION_DATA = MAKE_RETURN_CODE(3); - static const ReturnValue_t SEND_TM_FAILED = MAKE_RETURN_CODE(4); - static const ReturnValue_t TIMEOUT = MAKE_RETURN_CODE(5); - /** - * @brief The virtual destructor as it is mandatory for C++ interfaces. - */ - virtual ~AcceptsTelecommandsIF() { - - } - /** - * @brief Getter for the service id. - * @details Any receiving service (at least any PUS service) shall have a - * service ID. If the receiver can handle Telecommands, but for - * some reason has no service id, it shall return 0. - * @return The service ID or 0. - */ - virtual uint16_t getIdentifier() = 0; - /** - * @brief This method returns the message queue id of the telecommand - * receiving message queue. - * @return The telecommand reception message queue id. - */ - virtual MessageQueueId_t getRequestQueue() = 0; + public: + static const uint8_t INTERFACE_ID = CLASS_ID::ACCEPTS_TELECOMMANDS_IF; + static const ReturnValue_t ACTIVITY_STARTED = MAKE_RETURN_CODE(1); + static const ReturnValue_t INVALID_SUBSERVICE = MAKE_RETURN_CODE(2); + static const ReturnValue_t ILLEGAL_APPLICATION_DATA = MAKE_RETURN_CODE(3); + static const ReturnValue_t SEND_TM_FAILED = MAKE_RETURN_CODE(4); + static const ReturnValue_t TIMEOUT = MAKE_RETURN_CODE(5); + /** + * @brief The virtual destructor as it is mandatory for C++ interfaces. + */ + virtual ~AcceptsTelecommandsIF() {} + /** + * @brief Getter for the service id. + * @details Any receiving service (at least any PUS service) shall have a + * service ID. If the receiver can handle Telecommands, but for + * some reason has no service id, it shall return 0. + * @return The service ID or 0. + */ + virtual uint16_t getIdentifier() = 0; + /** + * @brief This method returns the message queue id of the telecommand + * receiving message queue. + * @return The telecommand reception message queue id. + */ + virtual MessageQueueId_t getRequestQueue() = 0; }; - #endif /* FRAMEWORK_TMTCSERVICES_ACCEPTSTELECOMMANDSIF_H_ */ diff --git a/src/fsfw/tmtcservices/AcceptsTelemetryIF.h b/src/fsfw/tmtcservices/AcceptsTelemetryIF.h index 43173d89..0e715130 100644 --- a/src/fsfw/tmtcservices/AcceptsTelemetryIF.h +++ b/src/fsfw/tmtcservices/AcceptsTelemetryIF.h @@ -9,19 +9,17 @@ * and thus make the service id and the receiving message queue public. */ class AcceptsTelemetryIF { -public: - /** - * @brief The virtual destructor as it is mandatory for C++ interfaces. - */ - virtual ~AcceptsTelemetryIF() { - } - /** - * @brief This method returns the message queue id of the telemetry - * receiving message queue. - * @return The telemetry reception message queue id. - */ - virtual MessageQueueId_t getReportReceptionQueue( - uint8_t virtualChannel = 0) = 0; + public: + /** + * @brief The virtual destructor as it is mandatory for C++ interfaces. + */ + virtual ~AcceptsTelemetryIF() {} + /** + * @brief This method returns the message queue id of the telemetry + * receiving message queue. + * @return The telemetry reception message queue id. + */ + virtual MessageQueueId_t getReportReceptionQueue(uint8_t virtualChannel = 0) = 0; }; #endif /* FSFW_TMTCSERVICES_ACCEPTSTELEMETRYIF_H_ */ diff --git a/src/fsfw/tmtcservices/AcceptsVerifyMessageIF.h b/src/fsfw/tmtcservices/AcceptsVerifyMessageIF.h index d16def4d..7e58187b 100644 --- a/src/fsfw/tmtcservices/AcceptsVerifyMessageIF.h +++ b/src/fsfw/tmtcservices/AcceptsVerifyMessageIF.h @@ -4,12 +4,9 @@ #include "../ipc/MessageQueueSenderIF.h" class AcceptsVerifyMessageIF { -public: - virtual ~AcceptsVerifyMessageIF() { - - } - virtual MessageQueueId_t getVerificationQueue() = 0; + public: + virtual ~AcceptsVerifyMessageIF() {} + virtual MessageQueueId_t getVerificationQueue() = 0; }; - #endif /* FSFW_TMTCSERVICES_ACCEPTSVERIFICATIONMESSAGEIF_H_ */ diff --git a/src/fsfw/tmtcservices/CommandingServiceBase.cpp b/src/fsfw/tmtcservices/CommandingServiceBase.cpp index 00fed415..bbdf8d2a 100644 --- a/src/fsfw/tmtcservices/CommandingServiceBase.cpp +++ b/src/fsfw/tmtcservices/CommandingServiceBase.cpp @@ -1,471 +1,428 @@ #include "fsfw/tmtcservices/CommandingServiceBase.h" -#include "fsfw/tmtcservices/AcceptsTelemetryIF.h" -#include "fsfw/tmtcservices/TmTcMessage.h" -#include "fsfw/tcdistribution/PUSDistributorIF.h" -#include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/ipc/QueueFactory.h" +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/tcdistribution/PUSDistributorIF.h" #include "fsfw/tmtcpacket/pus/tc.h" #include "fsfw/tmtcpacket/pus/tm.h" -#include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/tmtcservices/AcceptsTelemetryIF.h" +#include "fsfw/tmtcservices/TmTcMessage.h" object_id_t CommandingServiceBase::defaultPacketSource = objects::NO_OBJECT; object_id_t CommandingServiceBase::defaultPacketDestination = objects::NO_OBJECT; -CommandingServiceBase::CommandingServiceBase(object_id_t setObjectId, - uint16_t apid, uint8_t service, uint8_t numberOfParallelCommands, - uint16_t commandTimeoutSeconds, size_t queueDepth) : - SystemObject(setObjectId), apid(apid), service(service), - timeoutSeconds(commandTimeoutSeconds), - commandMap(numberOfParallelCommands) { - commandQueue = QueueFactory::instance()->createMessageQueue(queueDepth); - requestQueue = QueueFactory::instance()->createMessageQueue(queueDepth); +CommandingServiceBase::CommandingServiceBase(object_id_t setObjectId, uint16_t apid, + uint8_t service, uint8_t numberOfParallelCommands, + uint16_t commandTimeoutSeconds, size_t queueDepth) + : SystemObject(setObjectId), + apid(apid), + service(service), + timeoutSeconds(commandTimeoutSeconds), + commandMap(numberOfParallelCommands) { + commandQueue = QueueFactory::instance()->createMessageQueue(queueDepth); + requestQueue = QueueFactory::instance()->createMessageQueue(queueDepth); } void CommandingServiceBase::setPacketSource(object_id_t packetSource) { - this->packetSource = packetSource; + this->packetSource = packetSource; } -void CommandingServiceBase::setPacketDestination( - object_id_t packetDestination) { - this->packetDestination = packetDestination; +void CommandingServiceBase::setPacketDestination(object_id_t packetDestination) { + this->packetDestination = packetDestination; } - CommandingServiceBase::~CommandingServiceBase() { - QueueFactory::instance()->deleteMessageQueue(commandQueue); - QueueFactory::instance()->deleteMessageQueue(requestQueue); + QueueFactory::instance()->deleteMessageQueue(commandQueue); + QueueFactory::instance()->deleteMessageQueue(requestQueue); } - ReturnValue_t CommandingServiceBase::performOperation(uint8_t opCode) { - handleCommandQueue(); - handleRequestQueue(); - checkTimeout(); - doPeriodicOperation(); - return RETURN_OK; + handleCommandQueue(); + handleRequestQueue(); + checkTimeout(); + doPeriodicOperation(); + return RETURN_OK; } +uint16_t CommandingServiceBase::getIdentifier() { return service; } -uint16_t CommandingServiceBase::getIdentifier() { - return service; -} - - -MessageQueueId_t CommandingServiceBase::getRequestQueue() { - return requestQueue->getId(); -} - +MessageQueueId_t CommandingServiceBase::getRequestQueue() { return requestQueue->getId(); } ReturnValue_t CommandingServiceBase::initialize() { - ReturnValue_t result = SystemObject::initialize(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + ReturnValue_t result = SystemObject::initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - if(packetDestination == objects::NO_OBJECT) { - packetDestination = defaultPacketDestination; - } - AcceptsTelemetryIF* packetForwarding = - ObjectManager::instance()->get(packetDestination); + if (packetDestination == objects::NO_OBJECT) { + packetDestination = defaultPacketDestination; + } + AcceptsTelemetryIF* packetForwarding = + ObjectManager::instance()->get(packetDestination); - if(packetSource == objects::NO_OBJECT) { - packetSource = defaultPacketSource; - } - PUSDistributorIF* distributor = ObjectManager::instance()->get( - packetSource); + if (packetSource == objects::NO_OBJECT) { + packetSource = defaultPacketSource; + } + PUSDistributorIF* distributor = ObjectManager::instance()->get(packetSource); - if (packetForwarding == nullptr or distributor == nullptr) { + if (packetForwarding == nullptr or distributor == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "CommandingServiceBase::intialize: Packet source or " - "packet destination invalid!" << std::endl; + sif::error << "CommandingServiceBase::intialize: Packet source or " + "packet destination invalid!" + << std::endl; #endif - return ObjectManagerIF::CHILD_INIT_FAILED; - } + return ObjectManagerIF::CHILD_INIT_FAILED; + } - distributor->registerService(this); - requestQueue->setDefaultDestination( - packetForwarding->getReportReceptionQueue()); + distributor->registerService(this); + requestQueue->setDefaultDestination(packetForwarding->getReportReceptionQueue()); - IPCStore = ObjectManager::instance()->get(objects::IPC_STORE); - TCStore = ObjectManager::instance()->get(objects::TC_STORE); + IPCStore = ObjectManager::instance()->get(objects::IPC_STORE); + TCStore = ObjectManager::instance()->get(objects::TC_STORE); - if (IPCStore == nullptr or TCStore == nullptr) { + if (IPCStore == nullptr or TCStore == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "CommandingServiceBase::intialize: IPC store or TC store " - "not initialized yet!" << std::endl; + sif::error << "CommandingServiceBase::intialize: IPC store or TC store " + "not initialized yet!" + << std::endl; #endif - return ObjectManagerIF::CHILD_INIT_FAILED; - } - - return RETURN_OK; + return ObjectManagerIF::CHILD_INIT_FAILED; + } + return RETURN_OK; } void CommandingServiceBase::handleCommandQueue() { - CommandMessage reply; - ReturnValue_t result = RETURN_FAILED; - while(true) { - result = commandQueue->receiveMessage(&reply); - if (result == HasReturnvaluesIF::RETURN_OK) { - handleCommandMessage(&reply); - continue; - } - else if(result == MessageQueueIF::EMPTY) { - break; - } - else { + CommandMessage reply; + ReturnValue_t result = RETURN_FAILED; + while (true) { + result = commandQueue->receiveMessage(&reply); + if (result == HasReturnvaluesIF::RETURN_OK) { + handleCommandMessage(&reply); + continue; + } else if (result == MessageQueueIF::EMPTY) { + break; + } else { #if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "CommandingServiceBase::handleCommandQueue: Receiving message failed" - "with code" << result << std::endl; + sif::warning << "CommandingServiceBase::handleCommandQueue: Receiving message failed" + "with code" + << result << std::endl; #else - sif::printWarning("CommandingServiceBase::handleCommandQueue: Receiving message " - "failed with code %d\n", result); + sif::printWarning( + "CommandingServiceBase::handleCommandQueue: Receiving message " + "failed with code %d\n", + result); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */ - break; - } + break; } + } } - void CommandingServiceBase::handleCommandMessage(CommandMessage* reply) { - bool isStep = false; - CommandMessage nextCommand; - CommandMapIter iter = commandMap.find(reply->getSender()); + bool isStep = false; + CommandMessage nextCommand; + CommandMapIter iter = commandMap.find(reply->getSender()); - // handle unrequested reply first - if (reply->getSender() == MessageQueueIF::NO_QUEUE or - iter == commandMap.end()) { - handleUnrequestedReply(reply); - return; - } - nextCommand.setCommand(CommandMessage::CMD_NONE); + // handle unrequested reply first + if (reply->getSender() == MessageQueueIF::NO_QUEUE or iter == commandMap.end()) { + handleUnrequestedReply(reply); + return; + } + nextCommand.setCommand(CommandMessage::CMD_NONE); + // Implemented by child class, specifies what to do with reply. + ReturnValue_t result = handleReply(reply, iter->second.command, &iter->second.state, &nextCommand, + iter->second.objectId, &isStep); - // Implemented by child class, specifies what to do with reply. - ReturnValue_t result = handleReply(reply, iter->second.command, &iter->second.state, - &nextCommand, iter->second.objectId, &isStep); + /* If the child implementation does not implement special handling for + * rejected replies (RETURN_FAILED or INVALID_REPLY is returned), a + * failure verification will be generated with the reason as the + * return code and the initial command as failure parameter 1 */ + if ((reply->getCommand() == CommandMessage::REPLY_REJECTED) and + (result == RETURN_FAILED or result == INVALID_REPLY)) { + result = reply->getReplyRejectedReason(); + failureParameter1 = iter->second.command; + } - /* If the child implementation does not implement special handling for - * rejected replies (RETURN_FAILED or INVALID_REPLY is returned), a - * failure verification will be generated with the reason as the - * return code and the initial command as failure parameter 1 */ - if((reply->getCommand() == CommandMessage::REPLY_REJECTED) and - (result == RETURN_FAILED or result == INVALID_REPLY)) { - result = reply->getReplyRejectedReason(); - failureParameter1 = iter->second.command; - } - - switch (result) { + switch (result) { case EXECUTION_COMPLETE: case RETURN_OK: case NO_STEP_MESSAGE: - // handle result of reply handler implemented by developer. - handleReplyHandlerResult(result, iter, &nextCommand, reply, isStep); - break; + // handle result of reply handler implemented by developer. + handleReplyHandlerResult(result, iter, &nextCommand, reply, isStep); + break; case INVALID_REPLY: - //might be just an unrequested reply at a bad moment - handleUnrequestedReply(reply); - break; + // might be just an unrequested reply at a bad moment + handleUnrequestedReply(reply); + break; default: - if (isStep) { - verificationReporter.sendFailureReport( - tc_verification::PROGRESS_FAILURE, iter->second.tcInfo.ackFlags, - iter->second.tcInfo.tcPacketId, iter->second.tcInfo.tcSequenceControl, - result, ++iter->second.step, failureParameter1, - failureParameter2); - } else { - verificationReporter.sendFailureReport( - tc_verification::COMPLETION_FAILURE, iter->second.tcInfo.ackFlags, - iter->second.tcInfo.tcPacketId, iter->second.tcInfo.tcSequenceControl, - result, 0, failureParameter1, failureParameter2); - } - failureParameter1 = 0; - failureParameter2 = 0; - checkAndExecuteFifo(iter); - break; - } - + if (isStep) { + verificationReporter.sendFailureReport( + tc_verification::PROGRESS_FAILURE, iter->second.tcInfo.ackFlags, + iter->second.tcInfo.tcPacketId, iter->second.tcInfo.tcSequenceControl, result, + ++iter->second.step, failureParameter1, failureParameter2); + } else { + verificationReporter.sendFailureReport( + tc_verification::COMPLETION_FAILURE, iter->second.tcInfo.ackFlags, + iter->second.tcInfo.tcPacketId, iter->second.tcInfo.tcSequenceControl, result, 0, + failureParameter1, failureParameter2); + } + failureParameter1 = 0; + failureParameter2 = 0; + checkAndExecuteFifo(iter); + break; + } } -void CommandingServiceBase::handleReplyHandlerResult(ReturnValue_t result, - CommandMapIter iter, CommandMessage* nextCommand, - CommandMessage* reply, bool& isStep) { - iter->second.command = nextCommand->getCommand(); +void CommandingServiceBase::handleReplyHandlerResult(ReturnValue_t result, CommandMapIter iter, + CommandMessage* nextCommand, + CommandMessage* reply, bool& isStep) { + iter->second.command = nextCommand->getCommand(); - // In case a new command is to be sent immediately, this is performed here. - // If no new command is sent, only analyse reply result by initializing - // sendResult as RETURN_OK - ReturnValue_t sendResult = RETURN_OK; - if (nextCommand->getCommand() != CommandMessage::CMD_NONE) { - sendResult = commandQueue->sendMessage(reply->getSender(), - nextCommand); - } + // In case a new command is to be sent immediately, this is performed here. + // If no new command is sent, only analyse reply result by initializing + // sendResult as RETURN_OK + ReturnValue_t sendResult = RETURN_OK; + if (nextCommand->getCommand() != CommandMessage::CMD_NONE) { + sendResult = commandQueue->sendMessage(reply->getSender(), nextCommand); + } - if (sendResult == RETURN_OK) { - if (isStep and result != NO_STEP_MESSAGE) { - verificationReporter.sendSuccessReport( - tc_verification::PROGRESS_SUCCESS, - iter->second.tcInfo.ackFlags, iter->second.tcInfo.tcPacketId, - iter->second.tcInfo.tcSequenceControl, ++iter->second.step); - } - else { - verificationReporter.sendSuccessReport( - tc_verification::COMPLETION_SUCCESS, - iter->second.tcInfo.ackFlags, iter->second.tcInfo.tcPacketId, - iter->second.tcInfo.tcSequenceControl, 0); - checkAndExecuteFifo(iter); - } + if (sendResult == RETURN_OK) { + if (isStep and result != NO_STEP_MESSAGE) { + verificationReporter.sendSuccessReport( + tc_verification::PROGRESS_SUCCESS, iter->second.tcInfo.ackFlags, + iter->second.tcInfo.tcPacketId, iter->second.tcInfo.tcSequenceControl, + ++iter->second.step); + } else { + verificationReporter.sendSuccessReport( + tc_verification::COMPLETION_SUCCESS, iter->second.tcInfo.ackFlags, + iter->second.tcInfo.tcPacketId, iter->second.tcInfo.tcSequenceControl, 0); + checkAndExecuteFifo(iter); } - else { - if (isStep) { - nextCommand->clearCommandMessage(); - verificationReporter.sendFailureReport( - tc_verification::PROGRESS_FAILURE, iter->second.tcInfo.ackFlags, - iter->second.tcInfo.tcPacketId, - iter->second.tcInfo.tcSequenceControl, sendResult, - ++iter->second.step, failureParameter1, failureParameter2); - } else { - nextCommand->clearCommandMessage(); - verificationReporter.sendFailureReport( - tc_verification::COMPLETION_FAILURE, - iter->second.tcInfo.ackFlags, iter->second.tcInfo.tcPacketId, - iter->second.tcInfo.tcSequenceControl, sendResult, 0, - failureParameter1, failureParameter2); - } - failureParameter1 = 0; - failureParameter2 = 0; - checkAndExecuteFifo(iter); + } else { + if (isStep) { + nextCommand->clearCommandMessage(); + verificationReporter.sendFailureReport( + tc_verification::PROGRESS_FAILURE, iter->second.tcInfo.ackFlags, + iter->second.tcInfo.tcPacketId, iter->second.tcInfo.tcSequenceControl, sendResult, + ++iter->second.step, failureParameter1, failureParameter2); + } else { + nextCommand->clearCommandMessage(); + verificationReporter.sendFailureReport( + tc_verification::COMPLETION_FAILURE, iter->second.tcInfo.ackFlags, + iter->second.tcInfo.tcPacketId, iter->second.tcInfo.tcSequenceControl, sendResult, 0, + failureParameter1, failureParameter2); } + failureParameter1 = 0; + failureParameter2 = 0; + checkAndExecuteFifo(iter); + } } void CommandingServiceBase::handleRequestQueue() { - TmTcMessage message; - ReturnValue_t result; - store_address_t address; - TcPacketStoredPus packet; - MessageQueueId_t queue; - object_id_t objectId; - for (result = requestQueue->receiveMessage(&message); result == RETURN_OK; - result = requestQueue->receiveMessage(&message)) { - address = message.getStorageId(); - packet.setStoreAddress(address, &packet); - - if ((packet.getSubService() == 0) - or (isValidSubservice(packet.getSubService()) != RETURN_OK)) { - rejectPacket(tc_verification::START_FAILURE, &packet, INVALID_SUBSERVICE); - continue; - } - - result = getMessageQueueAndObject(packet.getSubService(), - packet.getApplicationData(), packet.getApplicationDataSize(), - &queue, &objectId); - if (result != HasReturnvaluesIF::RETURN_OK) { - rejectPacket(tc_verification::START_FAILURE, &packet, result); - continue; - } - - //Is a command already active for the target object? - CommandMapIter iter; - iter = commandMap.find(queue); - - if (iter != commandMap.end()) { - result = iter->second.fifo.insert(address); - if (result != RETURN_OK) { - rejectPacket(tc_verification::START_FAILURE, &packet, OBJECT_BUSY); - } - } else { - CommandInfo newInfo; //Info will be set by startExecution if neccessary - newInfo.objectId = objectId; - result = commandMap.insert(queue, newInfo, &iter); - if (result != RETURN_OK) { - rejectPacket(tc_verification::START_FAILURE, &packet, BUSY); - } else { - startExecution(&packet, iter); - } - } + TmTcMessage message; + ReturnValue_t result; + store_address_t address; + TcPacketStoredPus packet; + MessageQueueId_t queue; + object_id_t objectId; + for (result = requestQueue->receiveMessage(&message); result == RETURN_OK; + result = requestQueue->receiveMessage(&message)) { + address = message.getStorageId(); + packet.setStoreAddress(address, &packet); + if ((packet.getSubService() == 0) or (isValidSubservice(packet.getSubService()) != RETURN_OK)) { + rejectPacket(tc_verification::START_FAILURE, &packet, INVALID_SUBSERVICE); + continue; } + + result = getMessageQueueAndObject(packet.getSubService(), packet.getApplicationData(), + packet.getApplicationDataSize(), &queue, &objectId); + if (result != HasReturnvaluesIF::RETURN_OK) { + rejectPacket(tc_verification::START_FAILURE, &packet, result); + continue; + } + + // Is a command already active for the target object? + CommandMapIter iter; + iter = commandMap.find(queue); + + if (iter != commandMap.end()) { + result = iter->second.fifo.insert(address); + if (result != RETURN_OK) { + rejectPacket(tc_verification::START_FAILURE, &packet, OBJECT_BUSY); + } + } else { + CommandInfo newInfo; // Info will be set by startExecution if neccessary + newInfo.objectId = objectId; + result = commandMap.insert(queue, newInfo, &iter); + if (result != RETURN_OK) { + rejectPacket(tc_verification::START_FAILURE, &packet, BUSY); + } else { + startExecution(&packet, iter); + } + } + } } - -ReturnValue_t CommandingServiceBase::sendTmPacket(uint8_t subservice, - const uint8_t* data, size_t dataLen, const uint8_t* headerData, - size_t headerSize) { +ReturnValue_t CommandingServiceBase::sendTmPacket(uint8_t subservice, const uint8_t* data, + size_t dataLen, const uint8_t* headerData, + size_t headerSize) { #if FSFW_USE_PUS_C_TELEMETRY == 0 - TmPacketStoredPusA tmPacketStored(this->apid, this->service, subservice, - this->tmPacketCounter, data, dataLen, headerData, headerSize); + TmPacketStoredPusA tmPacketStored(this->apid, this->service, subservice, this->tmPacketCounter, + data, dataLen, headerData, headerSize); #else - TmPacketStoredPusC tmPacketStored(this->apid, this->service, subservice, - this->tmPacketCounter, data, dataLen, headerData, headerSize); + TmPacketStoredPusC tmPacketStored(this->apid, this->service, subservice, this->tmPacketCounter, + data, dataLen, headerData, headerSize); #endif - ReturnValue_t result = tmPacketStored.sendPacket( - requestQueue->getDefaultDestination(), requestQueue->getId()); - if (result == HasReturnvaluesIF::RETURN_OK) { - this->tmPacketCounter++; - } - return result; + ReturnValue_t result = + tmPacketStored.sendPacket(requestQueue->getDefaultDestination(), requestQueue->getId()); + if (result == HasReturnvaluesIF::RETURN_OK) { + this->tmPacketCounter++; + } + return result; } - -ReturnValue_t CommandingServiceBase::sendTmPacket(uint8_t subservice, - object_id_t objectId, const uint8_t *data, size_t dataLen) { - uint8_t buffer[sizeof(object_id_t)]; - uint8_t* pBuffer = buffer; - size_t size = 0; - SerializeAdapter::serialize(&objectId, &pBuffer, &size, - sizeof(object_id_t), SerializeIF::Endianness::BIG); +ReturnValue_t CommandingServiceBase::sendTmPacket(uint8_t subservice, object_id_t objectId, + const uint8_t* data, size_t dataLen) { + uint8_t buffer[sizeof(object_id_t)]; + uint8_t* pBuffer = buffer; + size_t size = 0; + SerializeAdapter::serialize(&objectId, &pBuffer, &size, sizeof(object_id_t), + SerializeIF::Endianness::BIG); #if FSFW_USE_PUS_C_TELEMETRY == 0 - TmPacketStoredPusA tmPacketStored(this->apid, this->service, subservice, - this->tmPacketCounter, data, dataLen, buffer, size); + TmPacketStoredPusA tmPacketStored(this->apid, this->service, subservice, this->tmPacketCounter, + data, dataLen, buffer, size); #else - TmPacketStoredPusC tmPacketStored(this->apid, this->service, subservice, - this->tmPacketCounter, data, dataLen, buffer, size); + TmPacketStoredPusC tmPacketStored(this->apid, this->service, subservice, this->tmPacketCounter, + data, dataLen, buffer, size); #endif - ReturnValue_t result = tmPacketStored.sendPacket( - requestQueue->getDefaultDestination(), requestQueue->getId()); - if (result == HasReturnvaluesIF::RETURN_OK) { - this->tmPacketCounter++; - } - return result; + ReturnValue_t result = + tmPacketStored.sendPacket(requestQueue->getDefaultDestination(), requestQueue->getId()); + if (result == HasReturnvaluesIF::RETURN_OK) { + this->tmPacketCounter++; + } + return result; } - -ReturnValue_t CommandingServiceBase::sendTmPacket(uint8_t subservice, - SerializeIF* content, SerializeIF* header) { +ReturnValue_t CommandingServiceBase::sendTmPacket(uint8_t subservice, SerializeIF* content, + SerializeIF* header) { #if FSFW_USE_PUS_C_TELEMETRY == 0 - TmPacketStoredPusA tmPacketStored(this->apid, this->service, subservice, - this->tmPacketCounter, content, header); + TmPacketStoredPusA tmPacketStored(this->apid, this->service, subservice, this->tmPacketCounter, + content, header); #else - TmPacketStoredPusC tmPacketStored(this->apid, this->service, subservice, - this->tmPacketCounter, content, header); + TmPacketStoredPusC tmPacketStored(this->apid, this->service, subservice, this->tmPacketCounter, + content, header); #endif - ReturnValue_t result = tmPacketStored.sendPacket( - requestQueue->getDefaultDestination(), requestQueue->getId()); - if (result == HasReturnvaluesIF::RETURN_OK) { - this->tmPacketCounter++; - } - return result; + ReturnValue_t result = + tmPacketStored.sendPacket(requestQueue->getDefaultDestination(), requestQueue->getId()); + if (result == HasReturnvaluesIF::RETURN_OK) { + this->tmPacketCounter++; + } + return result; } +void CommandingServiceBase::startExecution(TcPacketStoredPus* storedPacket, CommandMapIter iter) { + ReturnValue_t result = RETURN_OK; + CommandMessage command; + // TcPacketPusBase* tcPacketBase = storedPacket->getPacketBase(); + if (storedPacket == nullptr) { + return; + } + iter->second.subservice = storedPacket->getSubService(); + result = prepareCommand(&command, iter->second.subservice, storedPacket->getApplicationData(), + storedPacket->getApplicationDataSize(), &iter->second.state, + iter->second.objectId); -void CommandingServiceBase::startExecution(TcPacketStoredPus* storedPacket, - CommandMapIter iter) { - ReturnValue_t result = RETURN_OK; - CommandMessage command; - //TcPacketPusBase* tcPacketBase = storedPacket->getPacketBase(); - if(storedPacket == nullptr) { - return; - } - iter->second.subservice = storedPacket->getSubService(); - result = prepareCommand(&command, iter->second.subservice, - storedPacket->getApplicationData(), - storedPacket->getApplicationDataSize(), &iter->second.state, - iter->second.objectId); - - ReturnValue_t sendResult = RETURN_OK; - switch (result) { + ReturnValue_t sendResult = RETURN_OK; + switch (result) { case RETURN_OK: - if (command.getCommand() != CommandMessage::CMD_NONE) { - sendResult = commandQueue->sendMessage(iter.value->first, - &command); - } - if (sendResult == RETURN_OK) { - Clock::getUptime(&iter->second.uptimeOfStart); - iter->second.step = 0; - iter->second.subservice = storedPacket->getSubService(); - iter->second.command = command.getCommand(); - iter->second.tcInfo.ackFlags = storedPacket->getAcknowledgeFlags(); - iter->second.tcInfo.tcPacketId = storedPacket->getPacketId(); - iter->second.tcInfo.tcSequenceControl = - storedPacket->getPacketSequenceControl(); - acceptPacket(tc_verification::START_SUCCESS, storedPacket); - } else { - command.clearCommandMessage(); - rejectPacket(tc_verification::START_FAILURE, storedPacket, sendResult); - checkAndExecuteFifo(iter); - } - break; - case EXECUTION_COMPLETE: - if (command.getCommand() != CommandMessage::CMD_NONE) { - //Fire-and-forget command. - sendResult = commandQueue->sendMessage(iter.value->first, - &command); - } - if (sendResult == RETURN_OK) { - verificationReporter.sendSuccessReport(tc_verification::START_SUCCESS, - storedPacket->getPacketBase()); - acceptPacket(tc_verification::COMPLETION_SUCCESS, storedPacket); - checkAndExecuteFifo(iter); - } else { - command.clearCommandMessage(); - rejectPacket(tc_verification::START_FAILURE, storedPacket, sendResult); - checkAndExecuteFifo(iter); - } - break; - default: - rejectPacket(tc_verification::START_FAILURE, storedPacket, result); + if (command.getCommand() != CommandMessage::CMD_NONE) { + sendResult = commandQueue->sendMessage(iter.value->first, &command); + } + if (sendResult == RETURN_OK) { + Clock::getUptime(&iter->second.uptimeOfStart); + iter->second.step = 0; + iter->second.subservice = storedPacket->getSubService(); + iter->second.command = command.getCommand(); + iter->second.tcInfo.ackFlags = storedPacket->getAcknowledgeFlags(); + iter->second.tcInfo.tcPacketId = storedPacket->getPacketId(); + iter->second.tcInfo.tcSequenceControl = storedPacket->getPacketSequenceControl(); + acceptPacket(tc_verification::START_SUCCESS, storedPacket); + } else { + command.clearCommandMessage(); + rejectPacket(tc_verification::START_FAILURE, storedPacket, sendResult); checkAndExecuteFifo(iter); - break; - } + } + break; + case EXECUTION_COMPLETE: + if (command.getCommand() != CommandMessage::CMD_NONE) { + // Fire-and-forget command. + sendResult = commandQueue->sendMessage(iter.value->first, &command); + } + if (sendResult == RETURN_OK) { + verificationReporter.sendSuccessReport(tc_verification::START_SUCCESS, + storedPacket->getPacketBase()); + acceptPacket(tc_verification::COMPLETION_SUCCESS, storedPacket); + checkAndExecuteFifo(iter); + } else { + command.clearCommandMessage(); + rejectPacket(tc_verification::START_FAILURE, storedPacket, sendResult); + checkAndExecuteFifo(iter); + } + break; + default: + rejectPacket(tc_verification::START_FAILURE, storedPacket, result); + checkAndExecuteFifo(iter); + break; + } } - -void CommandingServiceBase::rejectPacket(uint8_t reportId, - TcPacketStoredPus* packet, ReturnValue_t errorCode) { - verificationReporter.sendFailureReport(reportId, dynamic_cast(packet), - errorCode); - packet->deletePacket(); +void CommandingServiceBase::rejectPacket(uint8_t reportId, TcPacketStoredPus* packet, + ReturnValue_t errorCode) { + verificationReporter.sendFailureReport(reportId, dynamic_cast(packet), + errorCode); + packet->deletePacket(); } - -void CommandingServiceBase::acceptPacket(uint8_t reportId, - TcPacketStoredPus* packet) { - verificationReporter.sendSuccessReport(reportId, dynamic_cast(packet)); - packet->deletePacket(); +void CommandingServiceBase::acceptPacket(uint8_t reportId, TcPacketStoredPus* packet) { + verificationReporter.sendSuccessReport(reportId, dynamic_cast(packet)); + packet->deletePacket(); } - void CommandingServiceBase::checkAndExecuteFifo(CommandMapIter& iter) { - store_address_t address; - if (iter->second.fifo.retrieve(&address) != RETURN_OK) { - commandMap.erase(&iter); - } else { - TcPacketStoredPus newPacket(address); - startExecution(&newPacket, iter); - } + store_address_t address; + if (iter->second.fifo.retrieve(&address) != RETURN_OK) { + commandMap.erase(&iter); + } else { + TcPacketStoredPus newPacket(address); + startExecution(&newPacket, iter); + } } - void CommandingServiceBase::handleUnrequestedReply(CommandMessage* reply) { - reply->clearCommandMessage(); + reply->clearCommandMessage(); } +inline void CommandingServiceBase::doPeriodicOperation() {} -inline void CommandingServiceBase::doPeriodicOperation() { -} - -MessageQueueId_t CommandingServiceBase::getCommandQueue() { - return commandQueue->getId(); -} +MessageQueueId_t CommandingServiceBase::getCommandQueue() { return commandQueue->getId(); } void CommandingServiceBase::checkTimeout() { - uint32_t uptime; - Clock::getUptime(&uptime); - CommandMapIter iter; - for (iter = commandMap.begin(); iter != commandMap.end(); ++iter) { - if ((iter->second.uptimeOfStart + (timeoutSeconds * 1000)) < uptime) { - verificationReporter.sendFailureReport( - tc_verification::COMPLETION_FAILURE, iter->second.tcInfo.ackFlags, - iter->second.tcInfo.tcPacketId, iter->second.tcInfo.tcSequenceControl, - TIMEOUT); - checkAndExecuteFifo(iter); - } + uint32_t uptime; + Clock::getUptime(&uptime); + CommandMapIter iter; + for (iter = commandMap.begin(); iter != commandMap.end(); ++iter) { + if ((iter->second.uptimeOfStart + (timeoutSeconds * 1000)) < uptime) { + verificationReporter.sendFailureReport( + tc_verification::COMPLETION_FAILURE, iter->second.tcInfo.ackFlags, + iter->second.tcInfo.tcPacketId, iter->second.tcInfo.tcSequenceControl, TIMEOUT); + checkAndExecuteFifo(iter); } + } } -void CommandingServiceBase::setTaskIF(PeriodicTaskIF* task_) { - executingTask = task_; -} +void CommandingServiceBase::setTaskIF(PeriodicTaskIF* task_) { executingTask = task_; } diff --git a/src/fsfw/tmtcservices/CommandingServiceBase.h b/src/fsfw/tmtcservices/CommandingServiceBase.h index d9b1b5ef..0ae19505 100644 --- a/src/fsfw/tmtcservices/CommandingServiceBase.h +++ b/src/fsfw/tmtcservices/CommandingServiceBase.h @@ -4,20 +4,19 @@ #include "AcceptsTelecommandsIF.h" #include "VerificationReporter.h" #include "fsfw/FSFW.h" - +#include "fsfw/container/FIFO.h" +#include "fsfw/container/FixedMap.h" +#include "fsfw/ipc/CommandMessage.h" +#include "fsfw/ipc/MessageQueueIF.h" #include "fsfw/objectmanager/SystemObject.h" +#include "fsfw/serialize/SerializeIF.h" #include "fsfw/storagemanager/StorageManagerIF.h" #include "fsfw/tasks/ExecutableObjectIF.h" -#include "fsfw/ipc/MessageQueueIF.h" -#include "fsfw/ipc/CommandMessage.h" -#include "fsfw/container/FixedMap.h" -#include "fsfw/container/FIFO.h" -#include "fsfw/serialize/SerializeIF.h" class TcPacketStoredBase; class TcPacketStoredPus; -namespace Factory{ +namespace Factory { void setStaticFrameworkObjectIds(); } @@ -35,334 +34,328 @@ void setStaticFrameworkObjectIds(); * @author gaisser * @ingroup pus_services */ -class CommandingServiceBase: public SystemObject, -public AcceptsTelecommandsIF, -public ExecutableObjectIF, -public HasReturnvaluesIF { - friend void (Factory::setStaticFrameworkObjectIds)(); -public: - // We could make this configurable via preprocessor and the FSFWConfig file. - static constexpr uint8_t COMMAND_INFO_FIFO_DEPTH = - fsfwconfig::FSFW_CSB_FIFO_DEPTH; +class CommandingServiceBase : public SystemObject, + public AcceptsTelecommandsIF, + public ExecutableObjectIF, + public HasReturnvaluesIF { + friend void(Factory::setStaticFrameworkObjectIds)(); - static const uint8_t INTERFACE_ID = CLASS_ID::COMMAND_SERVICE_BASE; + public: + // We could make this configurable via preprocessor and the FSFWConfig file. + static constexpr uint8_t COMMAND_INFO_FIFO_DEPTH = fsfwconfig::FSFW_CSB_FIFO_DEPTH; - static const ReturnValue_t EXECUTION_COMPLETE = MAKE_RETURN_CODE(1); - static const ReturnValue_t NO_STEP_MESSAGE = MAKE_RETURN_CODE(2); - static const ReturnValue_t OBJECT_BUSY = MAKE_RETURN_CODE(3); - static const ReturnValue_t BUSY = MAKE_RETURN_CODE(4); - static const ReturnValue_t INVALID_TC = MAKE_RETURN_CODE(5); - static const ReturnValue_t INVALID_OBJECT = MAKE_RETURN_CODE(6); - static const ReturnValue_t INVALID_REPLY = MAKE_RETURN_CODE(7); + static const uint8_t INTERFACE_ID = CLASS_ID::COMMAND_SERVICE_BASE; - /** - * Class constructor. Initializes two important MessageQueues: - * commandQueue for command reception and requestQueue for device reception - * @param setObjectId - * @param apid - * @param service - * @param numberOfParallelCommands - * @param commandTimeout_seconds - * @param setPacketSource - * @param setPacketDestination - * @param queueDepth - */ - CommandingServiceBase(object_id_t setObjectId, uint16_t apid, - uint8_t service, uint8_t numberOfParallelCommands, - uint16_t commandTimeoutSeconds, size_t queueDepth = 20); - virtual ~CommandingServiceBase(); + static const ReturnValue_t EXECUTION_COMPLETE = MAKE_RETURN_CODE(1); + static const ReturnValue_t NO_STEP_MESSAGE = MAKE_RETURN_CODE(2); + static const ReturnValue_t OBJECT_BUSY = MAKE_RETURN_CODE(3); + static const ReturnValue_t BUSY = MAKE_RETURN_CODE(4); + static const ReturnValue_t INVALID_TC = MAKE_RETURN_CODE(5); + static const ReturnValue_t INVALID_OBJECT = MAKE_RETURN_CODE(6); + static const ReturnValue_t INVALID_REPLY = MAKE_RETURN_CODE(7); - /** - * This setter can be used to set the packet source individually instead - * of using the default static framework ID set in the factory. - * This should be called at object initialization and not during run-time! - * @param packetSource - */ - void setPacketSource(object_id_t packetSource); - /** - * This setter can be used to set the packet destination individually - * instead of using the default static framework ID set in the factory. - * This should be called at object initialization and not during run-time! - * @param packetDestination - */ - void setPacketDestination(object_id_t packetDestination); + /** + * Class constructor. Initializes two important MessageQueues: + * commandQueue for command reception and requestQueue for device reception + * @param setObjectId + * @param apid + * @param service + * @param numberOfParallelCommands + * @param commandTimeout_seconds + * @param setPacketSource + * @param setPacketDestination + * @param queueDepth + */ + CommandingServiceBase(object_id_t setObjectId, uint16_t apid, uint8_t service, + uint8_t numberOfParallelCommands, uint16_t commandTimeoutSeconds, + size_t queueDepth = 20); + virtual ~CommandingServiceBase(); - /*** - * This is the periodically called function. - * Handle request queue for external commands. - * Handle command Queue for internal commands. - * @param opCode is unused here at the moment - * @return RETURN_OK - */ - virtual ReturnValue_t performOperation(uint8_t opCode) override; + /** + * This setter can be used to set the packet source individually instead + * of using the default static framework ID set in the factory. + * This should be called at object initialization and not during run-time! + * @param packetSource + */ + void setPacketSource(object_id_t packetSource); + /** + * This setter can be used to set the packet destination individually + * instead of using the default static framework ID set in the factory. + * This should be called at object initialization and not during run-time! + * @param packetDestination + */ + void setPacketDestination(object_id_t packetDestination); - virtual uint16_t getIdentifier(); + /*** + * This is the periodically called function. + * Handle request queue for external commands. + * Handle command Queue for internal commands. + * @param opCode is unused here at the moment + * @return RETURN_OK + */ + virtual ReturnValue_t performOperation(uint8_t opCode) override; - /** - * Returns the requestQueue MessageQueueId_t - * - * The requestQueue is the queue for external commands (TC) - * - * @return requestQueue messageQueueId_t - */ - virtual MessageQueueId_t getRequestQueue(); + virtual uint16_t getIdentifier(); - /** - * Returns the commandQueue MessageQueueId_t - * - * Remember the CommandQueue is the queue for internal communication - * @return commandQueue messageQueueId_t - */ - virtual MessageQueueId_t getCommandQueue(); + /** + * Returns the requestQueue MessageQueueId_t + * + * The requestQueue is the queue for external commands (TC) + * + * @return requestQueue messageQueueId_t + */ + virtual MessageQueueId_t getRequestQueue(); - virtual ReturnValue_t initialize() override; + /** + * Returns the commandQueue MessageQueueId_t + * + * Remember the CommandQueue is the queue for internal communication + * @return commandQueue messageQueueId_t + */ + virtual MessageQueueId_t getCommandQueue(); - /** - * Implementation of ExecutableObjectIF function - * - * Used to setup the reference of the task, that executes this component - * @param task Pointer to the taskIF of this task - */ - virtual void setTaskIF(PeriodicTaskIF* task) override; + virtual ReturnValue_t initialize() override; -protected: - /** - * Check the target subservice - * @param subservice[in] - * @return - * -@c RETURN_OK Subservice valid, continue message handling - * -@c INVALID_SUBSERVICE if service is not known, rejects packet. - */ - virtual ReturnValue_t isValidSubservice(uint8_t subservice) = 0; + /** + * Implementation of ExecutableObjectIF function + * + * Used to setup the reference of the task, that executes this component + * @param task Pointer to the taskIF of this task + */ + virtual void setTaskIF(PeriodicTaskIF* task) override; - /** - * Once a TC Request is valid, the existence of the destination and its - * target interface is checked and retrieved. The target message queue ID - * can then be acquired by using the target interface. - * @param subservice - * @param tcData Application Data of TC Packet - * @param tcDataLen - * @param id MessageQueue ID is stored here - * @param objectId Object ID is extracted and stored here - * @return - * - @c RETURN_OK Cotinue message handling - * - @c RETURN_FAILED Reject the packet and generates a start failure - * verification - */ - virtual ReturnValue_t getMessageQueueAndObject(uint8_t subservice, - const uint8_t *tcData, size_t tcDataLen, MessageQueueId_t *id, - object_id_t *objectId) = 0; + protected: + /** + * Check the target subservice + * @param subservice[in] + * @return + * -@c RETURN_OK Subservice valid, continue message handling + * -@c INVALID_SUBSERVICE if service is not known, rejects packet. + */ + virtual ReturnValue_t isValidSubservice(uint8_t subservice) = 0; - /** - * After the Message Queue and Object ID are determined, the command is - * prepared by using an implementation specific CommandMessage type - * which is sent to the target object. It contains all necessary information - * for the device to execute telecommands. - * @param message [out] message which can be set and is sent to the object - * @param subservice Subservice of the current communication - * @param tcData Application data of command - * @param tcDataLen Application data length - * @param state [out/in] Setable state of the communication. - * communication - * @param objectId Target object ID - * @return - * - @c RETURN_OK to generate a verification start message - * - @c EXECUTION_COMPELTE Fire-and-forget command. Generate a completion - * verification message. - * - @c Anything else rejects the packets and generates a start failure - * verification. - */ - virtual ReturnValue_t prepareCommand(CommandMessage* message, - uint8_t subservice, const uint8_t *tcData, size_t tcDataLen, - uint32_t *state, object_id_t objectId) = 0; + /** + * Once a TC Request is valid, the existence of the destination and its + * target interface is checked and retrieved. The target message queue ID + * can then be acquired by using the target interface. + * @param subservice + * @param tcData Application Data of TC Packet + * @param tcDataLen + * @param id MessageQueue ID is stored here + * @param objectId Object ID is extracted and stored here + * @return + * - @c RETURN_OK Cotinue message handling + * - @c RETURN_FAILED Reject the packet and generates a start failure + * verification + */ + virtual ReturnValue_t getMessageQueueAndObject(uint8_t subservice, const uint8_t* tcData, + size_t tcDataLen, MessageQueueId_t* id, + object_id_t* objectId) = 0; - /** - * This function is implemented by child services to specify how replies - * to a command from another software component are handled. - * @param reply - * This is the reply in form of a generic read-only command message. - * @param previousCommand - * Command_t of related command - * @param state [out/in] - * Additional parameter which can be used to pass state information. - * State of the communication - * @param optionalNextCommand [out] - * An optional next command which can be set in this function - * @param objectId Source object ID - * @param isStep Flag value to mark steps of command execution - * @return - * - @c RETURN_OK, @c EXECUTION_COMPLETE or @c NO_STEP_MESSAGE to - * generate TC verification success - * - @c INVALID_REPLY Calls handleUnrequestedReply - * - Anything else triggers a TC verification failure. If RETURN_FAILED or - * INVALID_REPLY is returned and the command ID is - * CommandMessage::REPLY_REJECTED, a failure verification message with - * the reason as the error parameter and the initial command as - * failure parameter 1 is generated. - */ - virtual ReturnValue_t handleReply(const CommandMessage* reply, - Command_t previousCommand, uint32_t *state, - CommandMessage* optionalNextCommand, object_id_t objectId, - bool *isStep) = 0; + /** + * After the Message Queue and Object ID are determined, the command is + * prepared by using an implementation specific CommandMessage type + * which is sent to the target object. It contains all necessary information + * for the device to execute telecommands. + * @param message [out] message which can be set and is sent to the object + * @param subservice Subservice of the current communication + * @param tcData Application data of command + * @param tcDataLen Application data length + * @param state [out/in] Setable state of the communication. + * communication + * @param objectId Target object ID + * @return + * - @c RETURN_OK to generate a verification start message + * - @c EXECUTION_COMPELTE Fire-and-forget command. Generate a completion + * verification message. + * - @c Anything else rejects the packets and generates a start failure + * verification. + */ + virtual ReturnValue_t prepareCommand(CommandMessage* message, uint8_t subservice, + const uint8_t* tcData, size_t tcDataLen, uint32_t* state, + object_id_t objectId) = 0; - /** - * This function can be overidden to handle unrequested reply, - * when the reply sender ID is unknown or is not found is the command map. - * The default implementation will clear the command message and all - * its contents. - * @param reply - * Reply which is non-const so the default implementation can clear the - * message. - */ - virtual void handleUnrequestedReply(CommandMessage* reply); + /** + * This function is implemented by child services to specify how replies + * to a command from another software component are handled. + * @param reply + * This is the reply in form of a generic read-only command message. + * @param previousCommand + * Command_t of related command + * @param state [out/in] + * Additional parameter which can be used to pass state information. + * State of the communication + * @param optionalNextCommand [out] + * An optional next command which can be set in this function + * @param objectId Source object ID + * @param isStep Flag value to mark steps of command execution + * @return + * - @c RETURN_OK, @c EXECUTION_COMPLETE or @c NO_STEP_MESSAGE to + * generate TC verification success + * - @c INVALID_REPLY Calls handleUnrequestedReply + * - Anything else triggers a TC verification failure. If RETURN_FAILED or + * INVALID_REPLY is returned and the command ID is + * CommandMessage::REPLY_REJECTED, a failure verification message with + * the reason as the error parameter and the initial command as + * failure parameter 1 is generated. + */ + virtual ReturnValue_t handleReply(const CommandMessage* reply, Command_t previousCommand, + uint32_t* state, CommandMessage* optionalNextCommand, + object_id_t objectId, bool* isStep) = 0; - virtual void doPeriodicOperation(); + /** + * This function can be overidden to handle unrequested reply, + * when the reply sender ID is unknown or is not found is the command map. + * The default implementation will clear the command message and all + * its contents. + * @param reply + * Reply which is non-const so the default implementation can clear the + * message. + */ + virtual void handleUnrequestedReply(CommandMessage* reply); - struct CommandInfo: public SerializeIF{ - struct tcInfo { - uint8_t ackFlags; - uint16_t tcPacketId; - uint16_t tcSequenceControl; - } tcInfo; - uint32_t uptimeOfStart; - uint8_t step; - uint8_t subservice; - uint32_t state; - Command_t command; - object_id_t objectId; - FIFO fifo; + virtual void doPeriodicOperation(); - virtual ReturnValue_t serialize(uint8_t **buffer, size_t *size, - size_t maxSize, Endianness streamEndianness) const override{ - return HasReturnvaluesIF::RETURN_FAILED; - }; + struct CommandInfo : public SerializeIF { + struct tcInfo { + uint8_t ackFlags; + uint16_t tcPacketId; + uint16_t tcSequenceControl; + } tcInfo; + uint32_t uptimeOfStart; + uint8_t step; + uint8_t subservice; + uint32_t state; + Command_t command; + object_id_t objectId; + FIFO fifo; - virtual size_t getSerializedSize() const override { - return 0; - }; - - virtual ReturnValue_t deSerialize(const uint8_t **buffer, size_t *size, - Endianness streamEndianness) override { - return HasReturnvaluesIF::RETURN_FAILED; - }; + virtual ReturnValue_t serialize(uint8_t** buffer, size_t* size, size_t maxSize, + Endianness streamEndianness) const override { + return HasReturnvaluesIF::RETURN_FAILED; }; - using CommandMapIter = FixedMap::Iterator; + virtual size_t getSerializedSize() const override { return 0; }; - const uint16_t apid; + virtual ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size, + Endianness streamEndianness) override { + return HasReturnvaluesIF::RETURN_FAILED; + }; + }; - const uint8_t service; + using CommandMapIter = FixedMap::Iterator; - const uint16_t timeoutSeconds; + const uint16_t apid; - uint8_t tmPacketCounter = 0; + const uint8_t service; - StorageManagerIF *IPCStore = nullptr; + const uint16_t timeoutSeconds; - StorageManagerIF *TCStore = nullptr; + uint8_t tmPacketCounter = 0; - MessageQueueIF* commandQueue = nullptr; + StorageManagerIF* IPCStore = nullptr; - MessageQueueIF* requestQueue = nullptr; + StorageManagerIF* TCStore = nullptr; - VerificationReporter verificationReporter; + MessageQueueIF* commandQueue = nullptr; - FixedMap commandMap; + MessageQueueIF* requestQueue = nullptr; - /* May be set be children to return a more precise failure condition. */ - uint32_t failureParameter1 = 0; - uint32_t failureParameter2 = 0; + VerificationReporter verificationReporter; - static object_id_t defaultPacketSource; - object_id_t packetSource = objects::NO_OBJECT; - static object_id_t defaultPacketDestination; - object_id_t packetDestination = objects::NO_OBJECT; + FixedMap commandMap; - /** - * Pointer to the task which executes this component, - * is invalid before setTaskIF was called. - */ - PeriodicTaskIF* executingTask = nullptr; + /* May be set be children to return a more precise failure condition. */ + uint32_t failureParameter1 = 0; + uint32_t failureParameter2 = 0; - /** - * @brief Send TM data from pointer to data. - * If a header is supplied it is added before data - * @param subservice Number of subservice - * @param data Pointer to the data in the Packet - * @param dataLen Lenght of data in the Packet - * @param headerData HeaderData will be placed before data - * @param headerSize Size of HeaderData - */ - ReturnValue_t sendTmPacket(uint8_t subservice, const uint8_t *data, - size_t dataLen, const uint8_t* headerData = nullptr, - size_t headerSize = 0); + static object_id_t defaultPacketSource; + object_id_t packetSource = objects::NO_OBJECT; + static object_id_t defaultPacketDestination; + object_id_t packetDestination = objects::NO_OBJECT; - /** - * @brief To send TM packets of objects that still need to be serialized - * and consist of an object ID with appended data. - * @param subservice Number of subservice - * @param objectId ObjectId is placed before data - * @param data Data to append to the packet - * @param dataLen Length of Data - */ - ReturnValue_t sendTmPacket(uint8_t subservice, object_id_t objectId, - const uint8_t *data, size_t dataLen); + /** + * Pointer to the task which executes this component, + * is invalid before setTaskIF was called. + */ + PeriodicTaskIF* executingTask = nullptr; - /** - * @brief To send packets which are contained inside a class implementing - * SerializeIF. - * @param subservice Number of subservice - * @param content This is a pointer to the serialized packet - * @param header Serialize IF header which will be placed before content - */ - ReturnValue_t sendTmPacket(uint8_t subservice, SerializeIF* content, - SerializeIF* header = nullptr); + /** + * @brief Send TM data from pointer to data. + * If a header is supplied it is added before data + * @param subservice Number of subservice + * @param data Pointer to the data in the Packet + * @param dataLen Lenght of data in the Packet + * @param headerData HeaderData will be placed before data + * @param headerSize Size of HeaderData + */ + ReturnValue_t sendTmPacket(uint8_t subservice, const uint8_t* data, size_t dataLen, + const uint8_t* headerData = nullptr, size_t headerSize = 0); - void checkAndExecuteFifo(CommandMapIter& iter); + /** + * @brief To send TM packets of objects that still need to be serialized + * and consist of an object ID with appended data. + * @param subservice Number of subservice + * @param objectId ObjectId is placed before data + * @param data Data to append to the packet + * @param dataLen Length of Data + */ + ReturnValue_t sendTmPacket(uint8_t subservice, object_id_t objectId, const uint8_t* data, + size_t dataLen); - private: - /** - * This method handles internal execution of a command, - * once it has been started by @sa{startExecution()} in the request - * queue handler. - * It handles replies generated by the devices and relayed by the specific - * service implementation. This means that it determines further course of - * action depending on the return values specified in the service - * implementation. - * This includes the generation of TC verification messages. Note that - * the static framework object ID @c VerificationReporter::messageReceiver - * needs to be set. - * - TM[1,5] Step Successs - * - TM[1,6] Step Failure - * - TM[1,7] Completion Success - * - TM[1,8] Completion Failure - */ - void handleCommandQueue(); + /** + * @brief To send packets which are contained inside a class implementing + * SerializeIF. + * @param subservice Number of subservice + * @param content This is a pointer to the serialized packet + * @param header Serialize IF header which will be placed before content + */ + ReturnValue_t sendTmPacket(uint8_t subservice, SerializeIF* content, + SerializeIF* header = nullptr); - /** - * @brief Handler function for request queue - * @details - * Sequence of request queue handling: - * isValidSubservice -> getMessageQueueAndObject -> startExecution - * Generates a Start Success Reports TM[1,3] in subfunction - * @sa{startExecution()} or a Start Failure Report TM[1,4] by using the - * TC Verification Service. - */ - void handleRequestQueue(); + void checkAndExecuteFifo(CommandMapIter& iter); - void rejectPacket(uint8_t reportId, TcPacketStoredPus* packet, - ReturnValue_t errorCode); + private: + /** + * This method handles internal execution of a command, + * once it has been started by @sa{startExecution()} in the request + * queue handler. + * It handles replies generated by the devices and relayed by the specific + * service implementation. This means that it determines further course of + * action depending on the return values specified in the service + * implementation. + * This includes the generation of TC verification messages. Note that + * the static framework object ID @c VerificationReporter::messageReceiver + * needs to be set. + * - TM[1,5] Step Successs + * - TM[1,6] Step Failure + * - TM[1,7] Completion Success + * - TM[1,8] Completion Failure + */ + void handleCommandQueue(); - void acceptPacket(uint8_t reportId, TcPacketStoredPus* packet); + /** + * @brief Handler function for request queue + * @details + * Sequence of request queue handling: + * isValidSubservice -> getMessageQueueAndObject -> startExecution + * Generates a Start Success Reports TM[1,3] in subfunction + * @sa{startExecution()} or a Start Failure Report TM[1,4] by using the + * TC Verification Service. + */ + void handleRequestQueue(); - void startExecution(TcPacketStoredPus* storedPacket, CommandMapIter iter); + void rejectPacket(uint8_t reportId, TcPacketStoredPus* packet, ReturnValue_t errorCode); - void handleCommandMessage(CommandMessage* reply); - void handleReplyHandlerResult(ReturnValue_t result, CommandMapIter iter, - CommandMessage* nextCommand, CommandMessage* reply, bool& isStep); + void acceptPacket(uint8_t reportId, TcPacketStoredPus* packet); - void checkTimeout(); + void startExecution(TcPacketStoredPus* storedPacket, CommandMapIter iter); + + void handleCommandMessage(CommandMessage* reply); + void handleReplyHandlerResult(ReturnValue_t result, CommandMapIter iter, + CommandMessage* nextCommand, CommandMessage* reply, bool& isStep); + + void checkTimeout(); }; #endif /* FSFW_TMTCSERVICES_COMMANDINGSERVICEBASE_H_ */ diff --git a/src/fsfw/tmtcservices/PusServiceBase.cpp b/src/fsfw/tmtcservices/PusServiceBase.cpp index 191acd9c..3af2b82c 100644 --- a/src/fsfw/tmtcservices/PusServiceBase.cpp +++ b/src/fsfw/tmtcservices/PusServiceBase.cpp @@ -1,133 +1,116 @@ #include "fsfw/tmtcservices/PusServiceBase.h" + +#include "fsfw/ipc/QueueFactory.h" +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/tcdistribution/PUSDistributorIF.h" #include "fsfw/tmtcservices/AcceptsTelemetryIF.h" #include "fsfw/tmtcservices/PusVerificationReport.h" #include "fsfw/tmtcservices/TmTcMessage.h" -#include "fsfw/objectmanager/ObjectManager.h" -#include "fsfw/serviceinterface/ServiceInterface.h" -#include "fsfw/tcdistribution/PUSDistributorIF.h" -#include "fsfw/ipc/QueueFactory.h" - object_id_t PusServiceBase::packetSource = 0; object_id_t PusServiceBase::packetDestination = 0; -PusServiceBase::PusServiceBase(object_id_t setObjectId, uint16_t setApid, - uint8_t setServiceId): - SystemObject(setObjectId), apid(setApid), serviceId(setServiceId) { - requestQueue = QueueFactory::instance()-> - createMessageQueue(PUS_SERVICE_MAX_RECEPTION); +PusServiceBase::PusServiceBase(object_id_t setObjectId, uint16_t setApid, uint8_t setServiceId) + : SystemObject(setObjectId), apid(setApid), serviceId(setServiceId) { + requestQueue = QueueFactory::instance()->createMessageQueue(PUS_SERVICE_MAX_RECEPTION); } -PusServiceBase::~PusServiceBase() { - QueueFactory::instance()->deleteMessageQueue(requestQueue); -} +PusServiceBase::~PusServiceBase() { QueueFactory::instance()->deleteMessageQueue(requestQueue); } ReturnValue_t PusServiceBase::performOperation(uint8_t opCode) { - handleRequestQueue(); - ReturnValue_t result = this->performService(); - if (result != RETURN_OK) { + handleRequestQueue(); + ReturnValue_t result = this->performService(); + if (result != RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "PusService " << (uint16_t) this->serviceId - << ": performService returned with " << (int16_t) result - << std::endl; + sif::error << "PusService " << (uint16_t)this->serviceId << ": performService returned with " + << (int16_t)result << std::endl; #endif - return RETURN_FAILED; - } - return RETURN_OK; + return RETURN_FAILED; + } + return RETURN_OK; } -void PusServiceBase::setTaskIF(PeriodicTaskIF* taskHandle) { - this->taskHandle = taskHandle; -} +void PusServiceBase::setTaskIF(PeriodicTaskIF* taskHandle) { this->taskHandle = taskHandle; } void PusServiceBase::handleRequestQueue() { - TmTcMessage message; - ReturnValue_t result = RETURN_FAILED; - for (uint8_t count = 0; count < PUS_SERVICE_MAX_RECEPTION; count++) { - ReturnValue_t status = this->requestQueue->receiveMessage(&message); - // if(status != MessageQueueIF::EMPTY) { + TmTcMessage message; + ReturnValue_t result = RETURN_FAILED; + for (uint8_t count = 0; count < PUS_SERVICE_MAX_RECEPTION; count++) { + ReturnValue_t status = this->requestQueue->receiveMessage(&message); + // if(status != MessageQueueIF::EMPTY) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - // sif::debug << "PusServiceBase::performOperation: Receiving from " - // << "MQ ID: " << std::hex << "0x" << std::setw(8) - // << std::setfill('0') << this->requestQueue->getId() - // << std::dec << " returned: " << status << std::setfill(' ') - // << std::endl; + // sif::debug << "PusServiceBase::performOperation: Receiving from " + // << "MQ ID: " << std::hex << "0x" << std::setw(8) + // << std::setfill('0') << this->requestQueue->getId() + // << std::dec << " returned: " << status << std::setfill(' ') + // << std::endl; #endif - // } + // } - if (status == RETURN_OK) { - this->currentPacket.setStoreAddress(message.getStorageId(), ¤tPacket); - //info << "Service " << (uint16_t) this->serviceId << - // ": new packet!" << std::endl; + if (status == RETURN_OK) { + this->currentPacket.setStoreAddress(message.getStorageId(), ¤tPacket); + // info << "Service " << (uint16_t) this->serviceId << + // ": new packet!" << std::endl; - result = this->handleRequest(currentPacket.getSubService()); + result = this->handleRequest(currentPacket.getSubService()); - // debug << "Service " << (uint16_t)this->serviceId << - // ": handleRequest returned: " << (int)return_code << std::endl; - if (result == RETURN_OK) { - this->verifyReporter.sendSuccessReport( - tc_verification::COMPLETION_SUCCESS, &this->currentPacket); - } - else { - this->verifyReporter.sendFailureReport( - tc_verification::COMPLETION_FAILURE, &this->currentPacket, - result, 0, errorParameter1, errorParameter2); - } - this->currentPacket.deletePacket(); - errorParameter1 = 0; - errorParameter2 = 0; - } - else if (status == MessageQueueIF::EMPTY) { - status = RETURN_OK; - // debug << "PusService " << (uint16_t)this->serviceId << - // ": no new packet." << std::endl; - break; - } - else { + // debug << "Service " << (uint16_t)this->serviceId << + // ": handleRequest returned: " << (int)return_code << std::endl; + if (result == RETURN_OK) { + this->verifyReporter.sendSuccessReport(tc_verification::COMPLETION_SUCCESS, + &this->currentPacket); + } else { + this->verifyReporter.sendFailureReport(tc_verification::COMPLETION_FAILURE, + &this->currentPacket, result, 0, errorParameter1, + errorParameter2); + } + this->currentPacket.deletePacket(); + errorParameter1 = 0; + errorParameter2 = 0; + } else if (status == MessageQueueIF::EMPTY) { + status = RETURN_OK; + // debug << "PusService " << (uint16_t)this->serviceId << + // ": no new packet." << std::endl; + break; + } else { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "PusServiceBase::performOperation: Service " - << this->serviceId << ": Error receiving packet. Code: " - << std::hex << status << std::dec << std::endl; + sif::error << "PusServiceBase::performOperation: Service " << this->serviceId + << ": Error receiving packet. Code: " << std::hex << status << std::dec + << std::endl; #endif - } } + } } -uint16_t PusServiceBase::getIdentifier() { - return this->serviceId; -} +uint16_t PusServiceBase::getIdentifier() { return this->serviceId; } -MessageQueueId_t PusServiceBase::getRequestQueue() { - return this->requestQueue->getId(); -} +MessageQueueId_t PusServiceBase::getRequestQueue() { return this->requestQueue->getId(); } ReturnValue_t PusServiceBase::initialize() { - ReturnValue_t result = SystemObject::initialize(); - if (result != RETURN_OK) { - return result; - } - AcceptsTelemetryIF* destService = ObjectManager::instance()->get( - packetDestination); - PUSDistributorIF* distributor = ObjectManager::instance()->get( - packetSource); - if (destService == nullptr or distributor == nullptr) { + ReturnValue_t result = SystemObject::initialize(); + if (result != RETURN_OK) { + return result; + } + AcceptsTelemetryIF* destService = + ObjectManager::instance()->get(packetDestination); + PUSDistributorIF* distributor = ObjectManager::instance()->get(packetSource); + if (destService == nullptr or distributor == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "PusServiceBase::PusServiceBase: Service " - << this->serviceId << ": Configuration error. Make sure " - << "packetSource and packetDestination are defined correctly" - << std::endl; + sif::error << "PusServiceBase::PusServiceBase: Service " << this->serviceId + << ": Configuration error. Make sure " + << "packetSource and packetDestination are defined correctly" << std::endl; #endif - return ObjectManagerIF::CHILD_INIT_FAILED; - } - this->requestQueue->setDefaultDestination( - destService->getReportReceptionQueue()); - distributor->registerService(this); - return HasReturnvaluesIF::RETURN_OK; + return ObjectManagerIF::CHILD_INIT_FAILED; + } + this->requestQueue->setDefaultDestination(destService->getReportReceptionQueue()); + distributor->registerService(this); + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t PusServiceBase::initializeAfterTaskCreation() { - // If task parameters, for example task frequency are required, this - // function should be overriden and the system object task IF can - // be used to get those parameters. - return HasReturnvaluesIF::RETURN_OK; + // If task parameters, for example task frequency are required, this + // function should be overriden and the system object task IF can + // be used to get those parameters. + return HasReturnvaluesIF::RETURN_OK; } diff --git a/src/fsfw/tmtcservices/PusServiceBase.h b/src/fsfw/tmtcservices/PusServiceBase.h index ec338331..9db1bef0 100644 --- a/src/fsfw/tmtcservices/PusServiceBase.h +++ b/src/fsfw/tmtcservices/PusServiceBase.h @@ -4,15 +4,14 @@ #include "AcceptsTelecommandsIF.h" #include "VerificationCodes.h" #include "VerificationReporter.h" - +#include "fsfw/ipc/MessageQueueIF.h" #include "fsfw/objectmanager/ObjectManagerIF.h" #include "fsfw/objectmanager/SystemObject.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" #include "fsfw/tasks/ExecutableObjectIF.h" #include "fsfw/tmtcpacket/pus/tc.h" -#include "fsfw/ipc/MessageQueueIF.h" -namespace Factory{ +namespace Factory { void setStaticFrameworkObjectIds(); } @@ -35,126 +34,128 @@ void setStaticFrameworkObjectIds(); * @ingroup pus_services */ class PusServiceBase : public ExecutableObjectIF, -public AcceptsTelecommandsIF, -public SystemObject, -public HasReturnvaluesIF { - friend void (Factory::setStaticFrameworkObjectIds)(); -public: - /** - * @brief The passed values are set, but inter-object initialization is - * done in the initialize method. - * @param setObjectId - * The system object identifier of this Service instance. - * @param setApid - * The APID the Service is instantiated for. - * @param setServiceId - * The Service Identifier as specified in ECSS PUS. - */ - PusServiceBase( object_id_t setObjectId, uint16_t setApid, - uint8_t setServiceId); - /** - * The destructor is empty. - */ - virtual ~PusServiceBase(); - /** - * @brief The handleRequest method shall handle any kind of Telecommand - * Request immediately. - * @details - * Implemetations can take the Telecommand in currentPacket and perform - * any kind of operation. - * They may send additional "Start Success (1,3)" messages with the - * verifyReporter, but Completion Success or Failure Reports are generated - * automatically after execution of this method. - * - * If a Telecommand can not be executed within one call cycle, - * this Base class is not the right parent. - * - * The child class may add additional error information by setting - * #errorParameters which aren attached to the generated verification - * message. - * - * Subservice checking should be implemented in this method. - * - * @return The returned status_code is directly taken as main error code - * in the Verification Report. - * On success, RETURN_OK shall be returned. - */ - virtual ReturnValue_t handleRequest(uint8_t subservice) = 0; - /** - * In performService, implementations can handle periodic, - * non-TC-triggered activities. - * The performService method is always called. - * @return Currently, everything other that RETURN_OK only triggers - * diagnostic output. - */ - virtual ReturnValue_t performService() = 0; - /** - * This method implements the typical activity of a simple PUS Service. - * It checks for new requests, and, if found, calls handleRequest, sends - * completion verification messages and deletes - * the TC requests afterwards. - * performService is always executed afterwards. - * @return @c RETURN_OK if the periodic performService was successful. - * @c RETURN_FAILED else. - */ - ReturnValue_t performOperation(uint8_t opCode) override; - virtual uint16_t getIdentifier() override; - MessageQueueId_t getRequestQueue() override; - virtual ReturnValue_t initialize() override; + public AcceptsTelecommandsIF, + public SystemObject, + public HasReturnvaluesIF { + friend void(Factory::setStaticFrameworkObjectIds)(); - virtual void setTaskIF(PeriodicTaskIF* taskHandle) override; - virtual ReturnValue_t initializeAfterTaskCreation() override; -protected: - /** - * @brief Handle to the underlying task - * @details - * Will be set by setTaskIF(), which is called on task creation. - */ - PeriodicTaskIF* taskHandle = nullptr; - /** - * The APID of this instance of the Service. - */ - uint16_t apid; - /** - * The Service Identifier. - */ - uint8_t serviceId; - /** - * One of two error parameters for additional error information. - */ - uint32_t errorParameter1 = 0; - /** - * One of two error parameters for additional error information. - */ - uint32_t errorParameter2 = 0; - /** - * This is a complete instance of the telecommand reception queue - * of the class. It is initialized on construction of the class. - */ - MessageQueueIF* requestQueue = nullptr; - /** - * An instance of the VerificationReporter class, that simplifies - * sending any kind of verification message to the TC Verification Service. - */ - VerificationReporter verifyReporter; - /** - * The current Telecommand to be processed. - * It is deleted after handleRequest was executed. - */ - TcPacketStoredPus currentPacket; + public: + /** + * @brief The passed values are set, but inter-object initialization is + * done in the initialize method. + * @param setObjectId + * The system object identifier of this Service instance. + * @param setApid + * The APID the Service is instantiated for. + * @param setServiceId + * The Service Identifier as specified in ECSS PUS. + */ + PusServiceBase(object_id_t setObjectId, uint16_t setApid, uint8_t setServiceId); + /** + * The destructor is empty. + */ + virtual ~PusServiceBase(); + /** + * @brief The handleRequest method shall handle any kind of Telecommand + * Request immediately. + * @details + * Implemetations can take the Telecommand in currentPacket and perform + * any kind of operation. + * They may send additional "Start Success (1,3)" messages with the + * verifyReporter, but Completion Success or Failure Reports are generated + * automatically after execution of this method. + * + * If a Telecommand can not be executed within one call cycle, + * this Base class is not the right parent. + * + * The child class may add additional error information by setting + * #errorParameters which aren attached to the generated verification + * message. + * + * Subservice checking should be implemented in this method. + * + * @return The returned status_code is directly taken as main error code + * in the Verification Report. + * On success, RETURN_OK shall be returned. + */ + virtual ReturnValue_t handleRequest(uint8_t subservice) = 0; + /** + * In performService, implementations can handle periodic, + * non-TC-triggered activities. + * The performService method is always called. + * @return Currently, everything other that RETURN_OK only triggers + * diagnostic output. + */ + virtual ReturnValue_t performService() = 0; + /** + * This method implements the typical activity of a simple PUS Service. + * It checks for new requests, and, if found, calls handleRequest, sends + * completion verification messages and deletes + * the TC requests afterwards. + * performService is always executed afterwards. + * @return @c RETURN_OK if the periodic performService was successful. + * @c RETURN_FAILED else. + */ + ReturnValue_t performOperation(uint8_t opCode) override; + virtual uint16_t getIdentifier() override; + MessageQueueId_t getRequestQueue() override; + virtual ReturnValue_t initialize() override; - static object_id_t packetSource; + virtual void setTaskIF(PeriodicTaskIF* taskHandle) override; + virtual ReturnValue_t initializeAfterTaskCreation() override; - static object_id_t packetDestination; -private: - /** - * This constant sets the maximum number of packets accepted per call. - * Remember that one packet must be completely handled in one - * #handleRequest call. - */ - static const uint8_t PUS_SERVICE_MAX_RECEPTION = 10; + protected: + /** + * @brief Handle to the underlying task + * @details + * Will be set by setTaskIF(), which is called on task creation. + */ + PeriodicTaskIF* taskHandle = nullptr; + /** + * The APID of this instance of the Service. + */ + uint16_t apid; + /** + * The Service Identifier. + */ + uint8_t serviceId; + /** + * One of two error parameters for additional error information. + */ + uint32_t errorParameter1 = 0; + /** + * One of two error parameters for additional error information. + */ + uint32_t errorParameter2 = 0; + /** + * This is a complete instance of the telecommand reception queue + * of the class. It is initialized on construction of the class. + */ + MessageQueueIF* requestQueue = nullptr; + /** + * An instance of the VerificationReporter class, that simplifies + * sending any kind of verification message to the TC Verification Service. + */ + VerificationReporter verifyReporter; + /** + * The current Telecommand to be processed. + * It is deleted after handleRequest was executed. + */ + TcPacketStoredPus currentPacket; - void handleRequestQueue(); + static object_id_t packetSource; + + static object_id_t packetDestination; + + private: + /** + * This constant sets the maximum number of packets accepted per call. + * Remember that one packet must be completely handled in one + * #handleRequest call. + */ + static const uint8_t PUS_SERVICE_MAX_RECEPTION = 10; + + void handleRequestQueue(); }; #endif /* FSFW_TMTCSERVICES_PUSSERVICEBASE_H_ */ diff --git a/src/fsfw/tmtcservices/PusVerificationReport.cpp b/src/fsfw/tmtcservices/PusVerificationReport.cpp index 827486ce..aefc35c4 100644 --- a/src/fsfw/tmtcservices/PusVerificationReport.cpp +++ b/src/fsfw/tmtcservices/PusVerificationReport.cpp @@ -1,138 +1,115 @@ -#include "fsfw/serialize/SerializeAdapter.h" #include "fsfw/tmtcservices/PusVerificationReport.h" -PusVerificationMessage::PusVerificationMessage() { +#include "fsfw/serialize/SerializeAdapter.h" + +PusVerificationMessage::PusVerificationMessage() {} + +PusVerificationMessage::PusVerificationMessage(uint8_t set_report_id, uint8_t ackFlags, + uint16_t tcPacketId, uint16_t tcSequenceControl, + ReturnValue_t set_error_code, uint8_t set_step, + uint32_t parameter1, uint32_t parameter2) { + uint8_t* data = this->getBuffer(); + data[messageSize] = set_report_id; + messageSize += sizeof(set_report_id); + data[messageSize] = ackFlags; + messageSize += sizeof(ackFlags); + memcpy(&data[messageSize], &tcPacketId, sizeof(tcPacketId)); + messageSize += sizeof(tcPacketId); + memcpy(&data[messageSize], &tcSequenceControl, sizeof(tcSequenceControl)); + messageSize += sizeof(tcSequenceControl); + data[messageSize] = set_step; + messageSize += sizeof(set_step); + memcpy(&data[messageSize], &set_error_code, sizeof(set_error_code)); + messageSize += sizeof(set_error_code); + memcpy(&data[messageSize], ¶meter1, sizeof(parameter1)); + messageSize += sizeof(parameter1); + memcpy(&data[messageSize], ¶meter2, sizeof(parameter2)); + messageSize += sizeof(parameter2); } -PusVerificationMessage::PusVerificationMessage(uint8_t set_report_id, - uint8_t ackFlags, uint16_t tcPacketId, uint16_t tcSequenceControl, - ReturnValue_t set_error_code, uint8_t set_step, uint32_t parameter1, - uint32_t parameter2) { - uint8_t *data = this->getBuffer(); - data[messageSize] = set_report_id; - messageSize += sizeof(set_report_id); - data[messageSize] = ackFlags; - messageSize += sizeof(ackFlags); - memcpy(&data[messageSize], &tcPacketId, sizeof(tcPacketId)); - messageSize += sizeof(tcPacketId); - memcpy(&data[messageSize], &tcSequenceControl, sizeof(tcSequenceControl)); - messageSize += sizeof(tcSequenceControl); - data[messageSize] = set_step; - messageSize += sizeof(set_step); - memcpy(&data[messageSize], &set_error_code, sizeof(set_error_code)); - messageSize += sizeof(set_error_code); - memcpy(&data[messageSize], ¶meter1, sizeof(parameter1)); - messageSize += sizeof(parameter1); - memcpy(&data[messageSize], ¶meter2, sizeof(parameter2)); - messageSize += sizeof(parameter2); -} +uint8_t PusVerificationMessage::getReportId() { return getContent()->reportId; } -uint8_t PusVerificationMessage::getReportId() { - - return getContent()->reportId; -} - -uint8_t PusVerificationMessage::getAckFlags() { - - return getContent()->ackFlags; -} +uint8_t PusVerificationMessage::getAckFlags() { return getContent()->ackFlags; } uint16_t PusVerificationMessage::getTcPacketId() { - - uint16_t tcPacketId; - memcpy(&tcPacketId, &getContent()->packetId_0, sizeof(tcPacketId)); - return tcPacketId; + uint16_t tcPacketId; + memcpy(&tcPacketId, &getContent()->packetId_0, sizeof(tcPacketId)); + return tcPacketId; } uint16_t PusVerificationMessage::getTcSequenceControl() { - - uint16_t tcSequenceControl; - memcpy(&tcSequenceControl, &getContent()->tcSequenceControl_0, - sizeof(tcSequenceControl)); - return tcSequenceControl; + uint16_t tcSequenceControl; + memcpy(&tcSequenceControl, &getContent()->tcSequenceControl_0, sizeof(tcSequenceControl)); + return tcSequenceControl; } -uint8_t PusVerificationMessage::getStep() { - - return getContent()->step; -} +uint8_t PusVerificationMessage::getStep() { return getContent()->step; } ReturnValue_t PusVerificationMessage::getErrorCode() { - ReturnValue_t errorCode; - memcpy(&errorCode, &getContent()->error_code_0, sizeof(errorCode)); - return errorCode; + ReturnValue_t errorCode; + memcpy(&errorCode, &getContent()->error_code_0, sizeof(errorCode)); + return errorCode; } PusVerificationMessage::verifciationMessageContent* PusVerificationMessage::getContent() { - return (verifciationMessageContent*) this->getData(); + return (verifciationMessageContent*)this->getData(); } uint32_t PusVerificationMessage::getParameter1() { - uint32_t parameter; - memcpy(¶meter, &getContent()->parameter1_0, sizeof(parameter)); - return parameter; + uint32_t parameter; + memcpy(¶meter, &getContent()->parameter1_0, sizeof(parameter)); + return parameter; } uint32_t PusVerificationMessage::getParameter2() { - uint32_t parameter; - memcpy(¶meter, &getContent()->parameter2_0, sizeof(parameter)); - return parameter; + uint32_t parameter; + memcpy(¶meter, &getContent()->parameter2_0, sizeof(parameter)); + return parameter; } -PusSuccessReport::PusSuccessReport(uint16_t setPacketId, - uint16_t setSequenceControl, uint8_t setStep) : - reportSize(0), pBuffer(reportBuffer) { - //Serialization won't fail, because we know the necessary max-size of the buffer. - SerializeAdapter::serialize(&setPacketId, &pBuffer, &reportSize, - sizeof(reportBuffer), SerializeIF::Endianness::BIG); - SerializeAdapter::serialize(&setSequenceControl, &pBuffer, &reportSize, - sizeof(reportBuffer), SerializeIF::Endianness::BIG); - if (setStep != 0) { - SerializeAdapter::serialize(&setStep, &pBuffer, &reportSize, - sizeof(reportBuffer), SerializeIF::Endianness::BIG); - } +PusSuccessReport::PusSuccessReport(uint16_t setPacketId, uint16_t setSequenceControl, + uint8_t setStep) + : reportSize(0), pBuffer(reportBuffer) { + // Serialization won't fail, because we know the necessary max-size of the buffer. + SerializeAdapter::serialize(&setPacketId, &pBuffer, &reportSize, sizeof(reportBuffer), + SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(&setSequenceControl, &pBuffer, &reportSize, sizeof(reportBuffer), + SerializeIF::Endianness::BIG); + if (setStep != 0) { + SerializeAdapter::serialize(&setStep, &pBuffer, &reportSize, sizeof(reportBuffer), + SerializeIF::Endianness::BIG); + } } -PusSuccessReport::~PusSuccessReport() { +PusSuccessReport::~PusSuccessReport() {} +uint32_t PusSuccessReport::getSize() { return reportSize; } + +uint8_t* PusSuccessReport::getReport() { return reportBuffer; } + +PusFailureReport::PusFailureReport(uint16_t setPacketId, uint16_t setSequenceControl, + ReturnValue_t setErrorCode, uint8_t setStep, uint32_t parameter1, + uint32_t parameter2) + : reportSize(0), pBuffer(reportBuffer) { + // Serialization won't fail, because we know the necessary max-size of the buffer. + SerializeAdapter::serialize(&setPacketId, &pBuffer, &reportSize, sizeof(reportBuffer), + SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(&setSequenceControl, &pBuffer, &reportSize, sizeof(reportBuffer), + SerializeIF::Endianness::BIG); + if (setStep != 0) { + SerializeAdapter::serialize(&setStep, &pBuffer, &reportSize, sizeof(reportBuffer), + SerializeIF::Endianness::BIG); + } + SerializeAdapter::serialize(&setErrorCode, &pBuffer, &reportSize, sizeof(reportBuffer), + SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(¶meter1, &pBuffer, &reportSize, sizeof(reportBuffer), + SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(¶meter2, &pBuffer, &reportSize, sizeof(reportBuffer), + SerializeIF::Endianness::BIG); } -uint32_t PusSuccessReport::getSize() { - return reportSize; -} +PusFailureReport::~PusFailureReport() {} -uint8_t* PusSuccessReport::getReport() { - return reportBuffer; -} +size_t PusFailureReport::getSize() { return reportSize; } -PusFailureReport::PusFailureReport(uint16_t setPacketId, - uint16_t setSequenceControl, ReturnValue_t setErrorCode, - uint8_t setStep, uint32_t parameter1, uint32_t parameter2) : - reportSize(0), pBuffer(reportBuffer) { - //Serialization won't fail, because we know the necessary max-size of the buffer. - SerializeAdapter::serialize(&setPacketId, &pBuffer, &reportSize, - sizeof(reportBuffer), SerializeIF::Endianness::BIG); - SerializeAdapter::serialize(&setSequenceControl, &pBuffer, &reportSize, - sizeof(reportBuffer), SerializeIF::Endianness::BIG); - if (setStep != 0) { - SerializeAdapter::serialize(&setStep, &pBuffer, &reportSize, - sizeof(reportBuffer), SerializeIF::Endianness::BIG); - } - SerializeAdapter::serialize(&setErrorCode, &pBuffer, &reportSize, - sizeof(reportBuffer), SerializeIF::Endianness::BIG); - SerializeAdapter::serialize(¶meter1, &pBuffer, &reportSize, - sizeof(reportBuffer), SerializeIF::Endianness::BIG); - SerializeAdapter::serialize(¶meter2, &pBuffer, &reportSize, - sizeof(reportBuffer), SerializeIF::Endianness::BIG); -} - -PusFailureReport::~PusFailureReport() { -} - -size_t PusFailureReport::getSize() { - return reportSize; -} - -uint8_t* PusFailureReport::getReport() { - return reportBuffer; -} +uint8_t* PusFailureReport::getReport() { return reportBuffer; } diff --git a/src/fsfw/tmtcservices/PusVerificationReport.h b/src/fsfw/tmtcservices/PusVerificationReport.h index bc9793d9..60c01d55 100644 --- a/src/fsfw/tmtcservices/PusVerificationReport.h +++ b/src/fsfw/tmtcservices/PusVerificationReport.h @@ -2,78 +2,77 @@ #define FSFW_TMTCSERVICES_PUSVERIFICATIONREPORT_H_ #include "VerificationCodes.h" - #include "fsfw/ipc/MessageQueueMessage.h" -#include "fsfw/tmtcpacket/pus/tc/TcPacketPusBase.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "fsfw/tmtcpacket/pus/tc/TcPacketPusBase.h" -class PusVerificationMessage: public MessageQueueMessage { -private: - struct verifciationMessageContent { - uint8_t reportId; - uint8_t ackFlags; - uint8_t packetId_0; - uint8_t packetId_1; - uint8_t tcSequenceControl_0; - uint8_t tcSequenceControl_1; - uint8_t step; - uint8_t error_code_0; - uint8_t error_code_1; - uint8_t parameter1_0; - uint8_t parameter1_1; - uint8_t parameter1_2; - uint8_t parameter1_3; - uint8_t parameter2_0; - uint8_t parameter2_1; - uint8_t parameter2_2; - uint8_t parameter2_3; - }; - verifciationMessageContent* getContent(); -public: - static const uint8_t VERIFICATION_MIN_SIZE = 6; - PusVerificationMessage(); +class PusVerificationMessage : public MessageQueueMessage { + private: + struct verifciationMessageContent { + uint8_t reportId; + uint8_t ackFlags; + uint8_t packetId_0; + uint8_t packetId_1; + uint8_t tcSequenceControl_0; + uint8_t tcSequenceControl_1; + uint8_t step; + uint8_t error_code_0; + uint8_t error_code_1; + uint8_t parameter1_0; + uint8_t parameter1_1; + uint8_t parameter1_2; + uint8_t parameter1_3; + uint8_t parameter2_0; + uint8_t parameter2_1; + uint8_t parameter2_2; + uint8_t parameter2_3; + }; + verifciationMessageContent* getContent(); - PusVerificationMessage(uint8_t set_report_id, uint8_t ackFlags, - uint16_t tcPacketId, uint16_t tcSequenceControl, - ReturnValue_t set_error_code = 0, uint8_t set_step = 0, - uint32_t parameter1 = 0, uint32_t parameter2 = 0); - uint8_t getReportId(); - uint8_t getAckFlags(); - uint16_t getTcPacketId(); - uint16_t getTcSequenceControl(); - ReturnValue_t getErrorCode(); - uint8_t getStep(); - uint32_t getParameter1(); - uint32_t getParameter2(); + public: + static const uint8_t VERIFICATION_MIN_SIZE = 6; + PusVerificationMessage(); + + PusVerificationMessage(uint8_t set_report_id, uint8_t ackFlags, uint16_t tcPacketId, + uint16_t tcSequenceControl, ReturnValue_t set_error_code = 0, + uint8_t set_step = 0, uint32_t parameter1 = 0, uint32_t parameter2 = 0); + uint8_t getReportId(); + uint8_t getAckFlags(); + uint16_t getTcPacketId(); + uint16_t getTcSequenceControl(); + ReturnValue_t getErrorCode(); + uint8_t getStep(); + uint32_t getParameter1(); + uint32_t getParameter2(); }; class PusSuccessReport { -private: - static const uint16_t MAX_SIZE = 7; - uint8_t reportBuffer[MAX_SIZE]; - size_t reportSize; - uint8_t * pBuffer; -public: - PusSuccessReport(uint16_t setPacketId, uint16_t setSequenceControl, - uint8_t set_step = 0); - ~PusSuccessReport(); - uint32_t getSize(); - uint8_t* getReport(); + private: + static const uint16_t MAX_SIZE = 7; + uint8_t reportBuffer[MAX_SIZE]; + size_t reportSize; + uint8_t* pBuffer; + + public: + PusSuccessReport(uint16_t setPacketId, uint16_t setSequenceControl, uint8_t set_step = 0); + ~PusSuccessReport(); + uint32_t getSize(); + uint8_t* getReport(); }; class PusFailureReport { -private: - static const uint16_t MAX_SIZE = 16; - uint8_t reportBuffer[MAX_SIZE]; - size_t reportSize; - uint8_t * pBuffer; -public: - PusFailureReport(uint16_t setPacketId, uint16_t setSequenceControl, - ReturnValue_t setErrorCode, uint8_t setStep = 0, - uint32_t parameter1 = 0, uint32_t parameter2 = 0); - ~PusFailureReport(); - size_t getSize(); - uint8_t* getReport(); + private: + static const uint16_t MAX_SIZE = 16; + uint8_t reportBuffer[MAX_SIZE]; + size_t reportSize; + uint8_t* pBuffer; + + public: + PusFailureReport(uint16_t setPacketId, uint16_t setSequenceControl, ReturnValue_t setErrorCode, + uint8_t setStep = 0, uint32_t parameter1 = 0, uint32_t parameter2 = 0); + ~PusFailureReport(); + size_t getSize(); + uint8_t* getReport(); }; #endif /* FSFW_TMTCSERVICES_PUSVERIFICATIONREPORT_H_ */ diff --git a/src/fsfw/tmtcservices/SourceSequenceCounter.h b/src/fsfw/tmtcservices/SourceSequenceCounter.h index 2b30a53f..e981a945 100644 --- a/src/fsfw/tmtcservices/SourceSequenceCounter.h +++ b/src/fsfw/tmtcservices/SourceSequenceCounter.h @@ -4,21 +4,21 @@ #include "../tmtcpacket/SpacePacketBase.h" class SourceSequenceCounter { -private: - uint16_t sequenceCount; -public: - SourceSequenceCounter() : sequenceCount(0) {} - void increment() { - sequenceCount = (sequenceCount+1) % (SpacePacketBase::LIMIT_SEQUENCE_COUNT); - } - void decrement() { - sequenceCount = (sequenceCount-1) % (SpacePacketBase::LIMIT_SEQUENCE_COUNT); - } - uint16_t get() { return this->sequenceCount; } - void reset(uint16_t toValue = 0) { - sequenceCount = toValue % (SpacePacketBase::LIMIT_SEQUENCE_COUNT); - } + private: + uint16_t sequenceCount; + + public: + SourceSequenceCounter() : sequenceCount(0) {} + void increment() { + sequenceCount = (sequenceCount + 1) % (SpacePacketBase::LIMIT_SEQUENCE_COUNT); + } + void decrement() { + sequenceCount = (sequenceCount - 1) % (SpacePacketBase::LIMIT_SEQUENCE_COUNT); + } + uint16_t get() { return this->sequenceCount; } + void reset(uint16_t toValue = 0) { + sequenceCount = toValue % (SpacePacketBase::LIMIT_SEQUENCE_COUNT); + } }; - #endif /* FSFW_TMTCSERVICES_SOURCESEQUENCECOUNTER_H_ */ diff --git a/src/fsfw/tmtcservices/SpacePacketParser.cpp b/src/fsfw/tmtcservices/SpacePacketParser.cpp index 3d442458..4c10ae9e 100644 --- a/src/fsfw/tmtcservices/SpacePacketParser.cpp +++ b/src/fsfw/tmtcservices/SpacePacketParser.cpp @@ -1,77 +1,75 @@ #include -#include +#include + #include -SpacePacketParser::SpacePacketParser(std::vector validPacketIds): - validPacketIds(validPacketIds) { +SpacePacketParser::SpacePacketParser(std::vector validPacketIds) + : validPacketIds(validPacketIds) {} + +ReturnValue_t SpacePacketParser::parseSpacePackets(const uint8_t* buffer, const size_t maxSize, + size_t& startIndex, size_t& foundSize) { + const uint8_t** tempPtr = &buffer; + size_t readLen = 0; + return parseSpacePackets(tempPtr, maxSize, startIndex, foundSize, readLen); } -ReturnValue_t SpacePacketParser::parseSpacePackets(const uint8_t *buffer, - const size_t maxSize, size_t& startIndex, size_t& foundSize) { - const uint8_t** tempPtr = &buffer; - size_t readLen = 0; - return parseSpacePackets(tempPtr, maxSize, startIndex, foundSize, readLen); -} - -ReturnValue_t SpacePacketParser::parseSpacePackets(const uint8_t **buffer, const size_t maxSize, - size_t &startIndex, size_t &foundSize, size_t& readLen) { - if(buffer == nullptr or maxSize < 5) { +ReturnValue_t SpacePacketParser::parseSpacePackets(const uint8_t** buffer, const size_t maxSize, + size_t& startIndex, size_t& foundSize, + size_t& readLen) { + if (buffer == nullptr or maxSize < 5) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "SpacePacketParser::parseSpacePackets: Frame invalid" << std::endl; + sif::warning << "SpacePacketParser::parseSpacePackets: Frame invalid" << std::endl; #else - sif::printWarning("SpacePacketParser::parseSpacePackets: Frame invalid\n"); + sif::printWarning("SpacePacketParser::parseSpacePackets: Frame invalid\n"); #endif - return HasReturnvaluesIF::RETURN_FAILED; - } - const uint8_t* bufPtr = *buffer; + return HasReturnvaluesIF::RETURN_FAILED; + } + const uint8_t* bufPtr = *buffer; - auto verifyLengthField = [&](size_t idx) { - uint16_t lengthField = bufPtr[idx + 4] << 8 | bufPtr[idx + 5]; - size_t packetSize = lengthField + 7; - startIndex = idx; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - if(lengthField == 0) { - // Skip whole header for now - foundSize = 6; - result = NO_PACKET_FOUND; - } - else if(packetSize + idx > maxSize) { - // Don't increment buffer and read length here, user has to decide what to do - foundSize = packetSize; - return SPLIT_PACKET; - } - else { - foundSize = packetSize; - } - *buffer += foundSize; - readLen += idx + foundSize; - return result; - }; - - size_t idx = 0; - // Space packet ID as start marker - if(validPacketIds.size() > 0) { - while(idx < maxSize - 5) { - uint16_t currentPacketId = bufPtr[idx] << 8 | bufPtr[idx + 1]; - if(std::find(validPacketIds.begin(), validPacketIds.end(), currentPacketId) != - validPacketIds.end()) { - if(idx + 5 >= maxSize) { - return SPLIT_PACKET; - } - return verifyLengthField(idx); - } - else { - idx++; - } - } - startIndex = 0; - foundSize = maxSize; - *buffer += foundSize; - readLen += foundSize; - return NO_PACKET_FOUND; + auto verifyLengthField = [&](size_t idx) { + uint16_t lengthField = bufPtr[idx + 4] << 8 | bufPtr[idx + 5]; + size_t packetSize = lengthField + 7; + startIndex = idx; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + if (lengthField == 0) { + // Skip whole header for now + foundSize = 6; + result = NO_PACKET_FOUND; + } else if (packetSize + idx > maxSize) { + // Don't increment buffer and read length here, user has to decide what to do + foundSize = packetSize; + return SPLIT_PACKET; + } else { + foundSize = packetSize; } - // Assume that the user verified a valid start of a space packet - else { + *buffer += foundSize; + readLen += idx + foundSize; + return result; + }; + + size_t idx = 0; + // Space packet ID as start marker + if (validPacketIds.size() > 0) { + while (idx < maxSize - 5) { + uint16_t currentPacketId = bufPtr[idx] << 8 | bufPtr[idx + 1]; + if (std::find(validPacketIds.begin(), validPacketIds.end(), currentPacketId) != + validPacketIds.end()) { + if (idx + 5 >= maxSize) { + return SPLIT_PACKET; + } return verifyLengthField(idx); + } else { + idx++; + } } + startIndex = 0; + foundSize = maxSize; + *buffer += foundSize; + readLen += foundSize; + return NO_PACKET_FOUND; + } + // Assume that the user verified a valid start of a space packet + else { + return verifyLengthField(idx); + } } diff --git a/src/fsfw/tmtcservices/SpacePacketParser.h b/src/fsfw/tmtcservices/SpacePacketParser.h index bed3369b..f0a9e8e2 100644 --- a/src/fsfw/tmtcservices/SpacePacketParser.h +++ b/src/fsfw/tmtcservices/SpacePacketParser.h @@ -1,12 +1,12 @@ #ifndef FRAMEWORK_TMTCSERVICES_PUSPARSER_H_ #define FRAMEWORK_TMTCSERVICES_PUSPARSER_H_ +#include +#include + #include "fsfw/container/DynamicFIFO.h" #include "fsfw/returnvalues/FwClassIds.h" -#include -#include - /** * @brief This small helper class scans a given buffer for space packets. * Can be used if space packets are serialized in a tightly packed frame. @@ -16,63 +16,64 @@ * @author R. Mueller */ class SpacePacketParser { -public: - //! The first entry is the index inside the buffer while the second index - //! is the size of the PUS packet starting at that index. - using IndexSizePair = std::pair; + public: + //! The first entry is the index inside the buffer while the second index + //! is the size of the PUS packet starting at that index. + using IndexSizePair = std::pair; - static constexpr uint8_t INTERFACE_ID = CLASS_ID::SPACE_PACKET_PARSER; - static constexpr ReturnValue_t NO_PACKET_FOUND = MAKE_RETURN_CODE(0x00); - static constexpr ReturnValue_t SPLIT_PACKET = MAKE_RETURN_CODE(0x01); + static constexpr uint8_t INTERFACE_ID = CLASS_ID::SPACE_PACKET_PARSER; + static constexpr ReturnValue_t NO_PACKET_FOUND = MAKE_RETURN_CODE(0x00); + static constexpr ReturnValue_t SPLIT_PACKET = MAKE_RETURN_CODE(0x01); - /** - * @brief Parser constructor. - * @param validPacketIds This vector contains the allowed 16-bit TC packet ID start markers - * The parser will search for these stark markers to detect the start of a space packet. - * It is also possible to pass an empty vector here, but this is not recommended. - * If an empty vector is passed, the parser will assume that the start of the given stream - * contains the start of a new space packet. - */ - SpacePacketParser(std::vector validPacketIds); + /** + * @brief Parser constructor. + * @param validPacketIds This vector contains the allowed 16-bit TC packet ID start markers + * The parser will search for these stark markers to detect the start of a space packet. + * It is also possible to pass an empty vector here, but this is not recommended. + * If an empty vector is passed, the parser will assume that the start of the given stream + * contains the start of a new space packet. + */ + SpacePacketParser(std::vector validPacketIds); - /** - * Parse a given frame for space packets but also increment the given buffer and assign the - * total number of bytes read so far - * @param buffer Parser will look for space packets in this buffer - * @param maxSize Maximum size of the buffer - * @param startIndex Start index of a found space packet - * @param foundSize Found size of the space packet - * @param readLen Length read so far. This value is incremented by the number of parsed - * bytes which also includes the size of a found packet - * -@c NO_PACKET_FOUND if no packet was found in the given buffer or the length field is - * invalid. foundSize will be set to the size of the space packet header. buffer and - * readLen will be incremented accordingly. - * -@c SPLIT_PACKET if a packet was found but the detected size exceeds maxSize. foundSize - * will be set to the detected packet size and startIndex will be set to the start of the - * detected packet. buffer and read length will not be incremented but the found length - * will be assigned. - * -@c RETURN_OK if a packet was found - */ - ReturnValue_t parseSpacePackets(const uint8_t **buffer, const size_t maxSize, - size_t& startIndex, size_t& foundSize, size_t& readLen); + /** + * Parse a given frame for space packets but also increment the given buffer and assign the + * total number of bytes read so far + * @param buffer Parser will look for space packets in this buffer + * @param maxSize Maximum size of the buffer + * @param startIndex Start index of a found space packet + * @param foundSize Found size of the space packet + * @param readLen Length read so far. This value is incremented by the number of parsed + * bytes which also includes the size of a found packet + * -@c NO_PACKET_FOUND if no packet was found in the given buffer or the length field is + * invalid. foundSize will be set to the size of the space packet header. buffer and + * readLen will be incremented accordingly. + * -@c SPLIT_PACKET if a packet was found but the detected size exceeds maxSize. foundSize + * will be set to the detected packet size and startIndex will be set to the start of the + * detected packet. buffer and read length will not be incremented but the found length + * will be assigned. + * -@c RETURN_OK if a packet was found + */ + ReturnValue_t parseSpacePackets(const uint8_t** buffer, const size_t maxSize, size_t& startIndex, + size_t& foundSize, size_t& readLen); - /** - * Parse a given frame for space packets - * @param buffer Parser will look for space packets in this buffer - * @param maxSize Maximum size of the buffer - * @param startIndex Start index of a found space packet - * @param foundSize Found size of the space packet - * -@c NO_PACKET_FOUND if no packet was found in the given buffer or the length field is - * invalid. foundSize will be set to the size of the space packet header - * -@c SPLIT_PACKET if a packet was found but the detected size exceeds maxSize. foundSize - * will be set to the detected packet size and startIndex will be set to the start of the - * detected packet - * -@c RETURN_OK if a packet was found - */ - ReturnValue_t parseSpacePackets(const uint8_t* buffer, const size_t maxSize, - size_t& startIndex, size_t& foundSize); -private: - std::vector validPacketIds; + /** + * Parse a given frame for space packets + * @param buffer Parser will look for space packets in this buffer + * @param maxSize Maximum size of the buffer + * @param startIndex Start index of a found space packet + * @param foundSize Found size of the space packet + * -@c NO_PACKET_FOUND if no packet was found in the given buffer or the length field is + * invalid. foundSize will be set to the size of the space packet header + * -@c SPLIT_PACKET if a packet was found but the detected size exceeds maxSize. foundSize + * will be set to the detected packet size and startIndex will be set to the start of the + * detected packet + * -@c RETURN_OK if a packet was found + */ + ReturnValue_t parseSpacePackets(const uint8_t* buffer, const size_t maxSize, size_t& startIndex, + size_t& foundSize); + + private: + std::vector validPacketIds; }; #endif /* FRAMEWORK_TMTCSERVICES_PUSPARSER_H_ */ diff --git a/src/fsfw/tmtcservices/TmTcBridge.cpp b/src/fsfw/tmtcservices/TmTcBridge.cpp index 7346cfe2..8ea67119 100644 --- a/src/fsfw/tmtcservices/TmTcBridge.cpp +++ b/src/fsfw/tmtcservices/TmTcBridge.cpp @@ -1,276 +1,260 @@ #include "fsfw/tmtcservices/TmTcBridge.h" -#include "fsfw/objectmanager/ObjectManager.h" -#include "fsfw/ipc/QueueFactory.h" -#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/globalfunctions/arrayprinter.h" +#include "fsfw/ipc/QueueFactory.h" +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/serviceinterface/ServiceInterface.h" #define TMTCBRIDGE_WIRETAPPING 0 -TmTcBridge::TmTcBridge(object_id_t objectId, object_id_t tcDestination, - object_id_t tmStoreId, object_id_t tcStoreId): - SystemObject(objectId),tmStoreId(tmStoreId), tcStoreId(tcStoreId), - tcDestination(tcDestination) +TmTcBridge::TmTcBridge(object_id_t objectId, object_id_t tcDestination, object_id_t tmStoreId, + object_id_t tcStoreId) + : SystemObject(objectId), + tmStoreId(tmStoreId), + tcStoreId(tcStoreId), + tcDestination(tcDestination) { - tmTcReceptionQueue = QueueFactory::instance()-> - createMessageQueue(TMTC_RECEPTION_QUEUE_DEPTH); + tmTcReceptionQueue = QueueFactory::instance()->createMessageQueue(TMTC_RECEPTION_QUEUE_DEPTH); } -TmTcBridge::~TmTcBridge() { - QueueFactory::instance()->deleteMessageQueue(tmTcReceptionQueue); -} +TmTcBridge::~TmTcBridge() { QueueFactory::instance()->deleteMessageQueue(tmTcReceptionQueue); } -ReturnValue_t TmTcBridge::setNumberOfSentPacketsPerCycle( - uint8_t sentPacketsPerCycle) { - if(sentPacketsPerCycle <= LIMIT_STORED_DATA_SENT_PER_CYCLE) { - this->sentPacketsPerCycle = sentPacketsPerCycle; - return RETURN_OK; - } - else { +ReturnValue_t TmTcBridge::setNumberOfSentPacketsPerCycle(uint8_t sentPacketsPerCycle) { + if (sentPacketsPerCycle <= LIMIT_STORED_DATA_SENT_PER_CYCLE) { + this->sentPacketsPerCycle = sentPacketsPerCycle; + return RETURN_OK; + } else { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "TmTcBridge::setNumberOfSentPacketsPerCycle: Number of " - << "packets sent per cycle exceeds limits. " - << "Keeping default value." << std::endl; + sif::warning << "TmTcBridge::setNumberOfSentPacketsPerCycle: Number of " + << "packets sent per cycle exceeds limits. " + << "Keeping default value." << std::endl; #endif - return RETURN_FAILED; - } + return RETURN_FAILED; + } } -ReturnValue_t TmTcBridge::setMaxNumberOfPacketsStored( - uint8_t maxNumberOfPacketsStored) { - if(maxNumberOfPacketsStored <= LIMIT_DOWNLINK_PACKETS_STORED) { - this->maxNumberOfPacketsStored = maxNumberOfPacketsStored; - return RETURN_OK; - } - else { +ReturnValue_t TmTcBridge::setMaxNumberOfPacketsStored(uint8_t maxNumberOfPacketsStored) { + if (maxNumberOfPacketsStored <= LIMIT_DOWNLINK_PACKETS_STORED) { + this->maxNumberOfPacketsStored = maxNumberOfPacketsStored; + return RETURN_OK; + } else { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "TmTcBridge::setMaxNumberOfPacketsStored: Number of " - << "packets stored exceeds limits. " - << "Keeping default value." << std::endl; + sif::warning << "TmTcBridge::setMaxNumberOfPacketsStored: Number of " + << "packets stored exceeds limits. " + << "Keeping default value." << std::endl; #endif - return RETURN_FAILED; - } + return RETURN_FAILED; + } } ReturnValue_t TmTcBridge::initialize() { - tcStore = ObjectManager::instance()->get(tcStoreId); - if (tcStore == nullptr) { + tcStore = ObjectManager::instance()->get(tcStoreId); + if (tcStore == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "TmTcBridge::initialize: TC store invalid. Make sure" - "it is created and set up properly." << std::endl; + sif::error << "TmTcBridge::initialize: TC store invalid. Make sure" + "it is created and set up properly." + << std::endl; #endif - return ObjectManagerIF::CHILD_INIT_FAILED; - } - tmStore = ObjectManager::instance()->get(tmStoreId); - if (tmStore == nullptr) { + return ObjectManagerIF::CHILD_INIT_FAILED; + } + tmStore = ObjectManager::instance()->get(tmStoreId); + if (tmStore == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "TmTcBridge::initialize: TM store invalid. Make sure" - "it is created and set up properly." << std::endl; + sif::error << "TmTcBridge::initialize: TM store invalid. Make sure" + "it is created and set up properly." + << std::endl; #endif - return ObjectManagerIF::CHILD_INIT_FAILED; - } - AcceptsTelecommandsIF* tcDistributor = - ObjectManager::instance()->get(tcDestination); - if (tcDistributor == nullptr) { + return ObjectManagerIF::CHILD_INIT_FAILED; + } + AcceptsTelecommandsIF* tcDistributor = + ObjectManager::instance()->get(tcDestination); + if (tcDistributor == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "TmTcBridge::initialize: TC Distributor invalid" - << std::endl; + sif::error << "TmTcBridge::initialize: TC Distributor invalid" << std::endl; #endif - return ObjectManagerIF::CHILD_INIT_FAILED; - } + return ObjectManagerIF::CHILD_INIT_FAILED; + } - tmFifo = new DynamicFIFO(maxNumberOfPacketsStored); + tmFifo = new DynamicFIFO(maxNumberOfPacketsStored); - tmTcReceptionQueue->setDefaultDestination(tcDistributor->getRequestQueue()); - return RETURN_OK; + tmTcReceptionQueue->setDefaultDestination(tcDistributor->getRequestQueue()); + return RETURN_OK; } ReturnValue_t TmTcBridge::performOperation(uint8_t operationCode) { - ReturnValue_t result; - result = handleTc(); - if(result != RETURN_OK) { + ReturnValue_t result; + result = handleTc(); + if (result != RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "TmTcBridge::performOperation: " - << "Error handling TCs" << std::endl; + sif::debug << "TmTcBridge::performOperation: " + << "Error handling TCs" << std::endl; #endif - } - result = handleTm(); - if (result != RETURN_OK) { + } + result = handleTm(); + if (result != RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::debug << "TmTcBridge::performOperation: " - << "Error handling TMs" << std::endl; + sif::debug << "TmTcBridge::performOperation: " + << "Error handling TMs" << std::endl; #endif - } - return result; + } + return result; } -ReturnValue_t TmTcBridge::handleTc() { - return HasReturnvaluesIF::RETURN_OK; -} +ReturnValue_t TmTcBridge::handleTc() { return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t TmTcBridge::handleTm() { - ReturnValue_t status = HasReturnvaluesIF::RETURN_OK; - ReturnValue_t result = handleTmQueue(); - if(result != RETURN_OK) { + ReturnValue_t status = HasReturnvaluesIF::RETURN_OK; + ReturnValue_t result = handleTmQueue(); + if (result != RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "TmTcBridge::handleTm: Error handling TM queue with error code 0x" << - std::hex << result << std::dec << "!" << std::endl; + sif::error << "TmTcBridge::handleTm: Error handling TM queue with error code 0x" << std::hex + << result << std::dec << "!" << std::endl; #endif - status = result; - } + status = result; + } - if(tmStored and communicationLinkUp and - (packetSentCounter < sentPacketsPerCycle)) { - result = handleStoredTm(); - if(result != RETURN_OK) { + if (tmStored and communicationLinkUp and (packetSentCounter < sentPacketsPerCycle)) { + result = handleStoredTm(); + if (result != RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "TmTcBridge::handleTm: Error handling stored TMs!" << std::endl; + sif::error << "TmTcBridge::handleTm: Error handling stored TMs!" << std::endl; #endif - status = result; - } - } - packetSentCounter = 0; - return status; + status = result; + } + } + packetSentCounter = 0; + return status; } ReturnValue_t TmTcBridge::handleTmQueue() { - TmTcMessage message; - const uint8_t* data = nullptr; - size_t size = 0; - ReturnValue_t status = HasReturnvaluesIF::RETURN_OK; - for (ReturnValue_t result = tmTcReceptionQueue->receiveMessage(&message); - result == HasReturnvaluesIF::RETURN_OK; - result = tmTcReceptionQueue->receiveMessage(&message)) - { - + TmTcMessage message; + const uint8_t* data = nullptr; + size_t size = 0; + ReturnValue_t status = HasReturnvaluesIF::RETURN_OK; + for (ReturnValue_t result = tmTcReceptionQueue->receiveMessage(&message); + result == HasReturnvaluesIF::RETURN_OK; + result = tmTcReceptionQueue->receiveMessage(&message)) { #if FSFW_VERBOSE_LEVEL >= 3 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "Sent packet counter: " << static_cast(packetSentCounter) << std::endl; + sif::info << "Sent packet counter: " << static_cast(packetSentCounter) << std::endl; #else - sif::printInfo("Sent packet counter: %d\n", packetSentCounter); + sif::printInfo("Sent packet counter: %d\n", packetSentCounter); #endif #endif /* FSFW_VERBOSE_LEVEL >= 3 */ - if(communicationLinkUp == false or - packetSentCounter >= sentPacketsPerCycle) { - storeDownlinkData(&message); - continue; - } + if (communicationLinkUp == false or packetSentCounter >= sentPacketsPerCycle) { + storeDownlinkData(&message); + continue; + } - result = tmStore->getData(message.getStorageId(), &data, &size); - if (result != HasReturnvaluesIF::RETURN_OK) { - status = result; - continue; - } + result = tmStore->getData(message.getStorageId(), &data, &size); + if (result != HasReturnvaluesIF::RETURN_OK) { + status = result; + continue; + } - result = sendTm(data, size); - if (result != HasReturnvaluesIF::RETURN_OK) { - status = result; - } - else { - tmStore->deleteData(message.getStorageId()); - packetSentCounter++; - } - } - return status; + result = sendTm(data, size); + if (result != HasReturnvaluesIF::RETURN_OK) { + status = result; + } else { + tmStore->deleteData(message.getStorageId()); + packetSentCounter++; + } + } + return status; } -ReturnValue_t TmTcBridge::storeDownlinkData(TmTcMessage *message) { - store_address_t storeId = 0; - if(tmFifo == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } +ReturnValue_t TmTcBridge::storeDownlinkData(TmTcMessage* message) { + store_address_t storeId = 0; + if (tmFifo == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } - if(tmFifo->full()) { + if (tmFifo->full()) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "TmTcBridge::storeDownlinkData: TM downlink max. number " - "of stored packet IDs reached!" << std::endl; + sif::warning << "TmTcBridge::storeDownlinkData: TM downlink max. number " + "of stored packet IDs reached!" + << std::endl; #else - sif::printWarning("TmTcBridge::storeDownlinkData: TM downlink max. number " - "of stored packet IDs reached!\n"); + sif::printWarning( + "TmTcBridge::storeDownlinkData: TM downlink max. number " + "of stored packet IDs reached!\n"); #endif - if(overwriteOld) { - tmFifo->retrieve(&storeId); - tmStore->deleteData(storeId); - } - else { - return HasReturnvaluesIF::RETURN_FAILED; - } - } + if (overwriteOld) { + tmFifo->retrieve(&storeId); + tmStore->deleteData(storeId); + } else { + return HasReturnvaluesIF::RETURN_FAILED; + } + } - storeId = message->getStorageId(); - tmFifo->insert(storeId); - tmStored = true; - return RETURN_OK; + storeId = message->getStorageId(); + tmFifo->insert(storeId); + tmStored = true; + return RETURN_OK; } ReturnValue_t TmTcBridge::handleStoredTm() { - ReturnValue_t status = RETURN_OK; - while(not tmFifo->empty() and packetSentCounter < sentPacketsPerCycle) { + ReturnValue_t status = RETURN_OK; + while (not tmFifo->empty() and packetSentCounter < sentPacketsPerCycle) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - //sif::info << "TMTC Bridge: Sending stored TM data. There are " - // << (int) tmFifo->size() << " left to send\r\n" << std::flush; + // sif::info << "TMTC Bridge: Sending stored TM data. There are " + // << (int) tmFifo->size() << " left to send\r\n" << std::flush; #endif - store_address_t storeId; - const uint8_t* data = nullptr; - size_t size = 0; - tmFifo->retrieve(&storeId); - ReturnValue_t result = tmStore->getData(storeId, &data, &size); - if(result != HasReturnvaluesIF::RETURN_OK) { - status = result; - } + store_address_t storeId; + const uint8_t* data = nullptr; + size_t size = 0; + tmFifo->retrieve(&storeId); + ReturnValue_t result = tmStore->getData(storeId, &data, &size); + if (result != HasReturnvaluesIF::RETURN_OK) { + status = result; + } - result = sendTm(data,size); - if(result != RETURN_OK) { + result = sendTm(data, size); + if (result != RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "TMTC Bridge: Could not send stored downlink data" - << std::endl; + sif::error << "TMTC Bridge: Could not send stored downlink data" << std::endl; #endif - status = result; - } - packetSentCounter ++; + status = result; + } + packetSentCounter++; - if(tmFifo->empty()) { - tmStored = false; - } - tmStore->deleteData(storeId); - } - return status; + if (tmFifo->empty()) { + tmStored = false; + } + tmStore->deleteData(storeId); + } + return status; } void TmTcBridge::registerCommConnect() { - if(not communicationLinkUp) { - communicationLinkUp = true; - } + if (not communicationLinkUp) { + communicationLinkUp = true; + } } void TmTcBridge::registerCommDisconnect() { - if(communicationLinkUp) { - communicationLinkUp = false; - } + if (communicationLinkUp) { + communicationLinkUp = false; + } } MessageQueueId_t TmTcBridge::getReportReceptionQueue(uint8_t virtualChannel) { - return tmTcReceptionQueue->getId(); + return tmTcReceptionQueue->getId(); } - -void TmTcBridge::printData(uint8_t * data, size_t dataLen) { - arrayprinter::print(data, dataLen); -} +void TmTcBridge::printData(uint8_t* data, size_t dataLen) { arrayprinter::print(data, dataLen); } uint16_t TmTcBridge::getIdentifier() { - // This is no PUS service, so we just return 0 - return 0; + // This is no PUS service, so we just return 0 + return 0; } MessageQueueId_t TmTcBridge::getRequestQueue() { - // Default implementation: Relay TC messages to TC distributor directly. - return tmTcReceptionQueue->getDefaultDestination(); + // Default implementation: Relay TC messages to TC distributor directly. + return tmTcReceptionQueue->getDefaultDestination(); } -void TmTcBridge::setFifoToOverwriteOldData(bool overwriteOld) { - this->overwriteOld = overwriteOld; -} +void TmTcBridge::setFifoToOverwriteOldData(bool overwriteOld) { this->overwriteOld = overwriteOld; } diff --git a/src/fsfw/tmtcservices/TmTcBridge.h b/src/fsfw/tmtcservices/TmTcBridge.h index 4980caff..237f1f3e 100644 --- a/src/fsfw/tmtcservices/TmTcBridge.h +++ b/src/fsfw/tmtcservices/TmTcBridge.h @@ -1,161 +1,156 @@ #ifndef FSFW_TMTCSERVICES_TMTCBRIDGE_H_ #define FSFW_TMTCSERVICES_TMTCBRIDGE_H_ -#include "AcceptsTelemetryIF.h" #include "AcceptsTelecommandsIF.h" - -#include "fsfw/objectmanager/SystemObject.h" -#include "fsfw/tasks/ExecutableObjectIF.h" -#include "fsfw/ipc/MessageQueueIF.h" -#include "fsfw/storagemanager/StorageManagerIF.h" +#include "AcceptsTelemetryIF.h" #include "fsfw/container/DynamicFIFO.h" +#include "fsfw/ipc/MessageQueueIF.h" +#include "fsfw/objectmanager/SystemObject.h" +#include "fsfw/storagemanager/StorageManagerIF.h" +#include "fsfw/tasks/ExecutableObjectIF.h" #include "fsfw/tmtcservices/TmTcMessage.h" class TmTcBridge : public AcceptsTelemetryIF, - public AcceptsTelecommandsIF, - public ExecutableObjectIF, - public HasReturnvaluesIF, - public SystemObject { -public: - static constexpr uint8_t TMTC_RECEPTION_QUEUE_DEPTH = 20; - static constexpr uint8_t LIMIT_STORED_DATA_SENT_PER_CYCLE = 15; - static constexpr uint8_t LIMIT_DOWNLINK_PACKETS_STORED = 200; + public AcceptsTelecommandsIF, + public ExecutableObjectIF, + public HasReturnvaluesIF, + public SystemObject { + public: + static constexpr uint8_t TMTC_RECEPTION_QUEUE_DEPTH = 20; + static constexpr uint8_t LIMIT_STORED_DATA_SENT_PER_CYCLE = 15; + static constexpr uint8_t LIMIT_DOWNLINK_PACKETS_STORED = 200; - static constexpr uint8_t DEFAULT_STORED_DATA_SENT_PER_CYCLE = 5; - static constexpr uint8_t DEFAULT_DOWNLINK_PACKETS_STORED = 10; + static constexpr uint8_t DEFAULT_STORED_DATA_SENT_PER_CYCLE = 5; + static constexpr uint8_t DEFAULT_DOWNLINK_PACKETS_STORED = 10; - TmTcBridge(object_id_t objectId, object_id_t tcDestination, - object_id_t tmStoreId, object_id_t tcStoreId); - virtual ~TmTcBridge(); + TmTcBridge(object_id_t objectId, object_id_t tcDestination, object_id_t tmStoreId, + object_id_t tcStoreId); + virtual ~TmTcBridge(); - /** - * Set number of packets sent per performOperation().Please note that this - * value must be smaller than MAX_STORED_DATA_SENT_PER_CYCLE - * @param sentPacketsPerCycle - * @return -@c RETURN_OK if value was set successfully - * -@c RETURN_FAILED otherwise, stored value stays the same - */ - ReturnValue_t setNumberOfSentPacketsPerCycle(uint8_t sentPacketsPerCycle); + /** + * Set number of packets sent per performOperation().Please note that this + * value must be smaller than MAX_STORED_DATA_SENT_PER_CYCLE + * @param sentPacketsPerCycle + * @return -@c RETURN_OK if value was set successfully + * -@c RETURN_FAILED otherwise, stored value stays the same + */ + ReturnValue_t setNumberOfSentPacketsPerCycle(uint8_t sentPacketsPerCycle); - /** - * Set number of packets sent per performOperation().Please note that this - * value must be smaller than MAX_DOWNLINK_PACKETS_STORED - * @param sentPacketsPerCycle - * @return -@c RETURN_OK if value was set successfully - * -@c RETURN_FAILED otherwise, stored value stays the same - */ - ReturnValue_t setMaxNumberOfPacketsStored(uint8_t maxNumberOfPacketsStored); + /** + * Set number of packets sent per performOperation().Please note that this + * value must be smaller than MAX_DOWNLINK_PACKETS_STORED + * @param sentPacketsPerCycle + * @return -@c RETURN_OK if value was set successfully + * -@c RETURN_FAILED otherwise, stored value stays the same + */ + ReturnValue_t setMaxNumberOfPacketsStored(uint8_t maxNumberOfPacketsStored); - /** - * This will set up the bridge to overwrite old data in the FIFO. - * @param overwriteOld - */ - void setFifoToOverwriteOldData(bool overwriteOld); + /** + * This will set up the bridge to overwrite old data in the FIFO. + * @param overwriteOld + */ + void setFifoToOverwriteOldData(bool overwriteOld); - virtual void registerCommConnect(); - virtual void registerCommDisconnect(); + virtual void registerCommConnect(); + virtual void registerCommDisconnect(); - /** - * Initializes necessary FSFW components for the TMTC Bridge - * @return - */ - virtual ReturnValue_t initialize() override; + /** + * Initializes necessary FSFW components for the TMTC Bridge + * @return + */ + virtual ReturnValue_t initialize() override; - /** - * @brief Handles TMTC reception - */ - virtual ReturnValue_t performOperation(uint8_t operationCode = 0) override; + /** + * @brief Handles TMTC reception + */ + virtual ReturnValue_t performOperation(uint8_t operationCode = 0) override; + /** AcceptsTelemetryIF override */ + virtual MessageQueueId_t getReportReceptionQueue(uint8_t virtualChannel = 0) override; - /** AcceptsTelemetryIF override */ - virtual MessageQueueId_t getReportReceptionQueue( - uint8_t virtualChannel = 0) override; + /** AcceptsTelecommandsIF override */ + virtual uint16_t getIdentifier() override; + virtual MessageQueueId_t getRequestQueue() override; - /** AcceptsTelecommandsIF override */ - virtual uint16_t getIdentifier() override; - virtual MessageQueueId_t getRequestQueue() override; + protected: + //! Cached for initialize function. + object_id_t tmStoreId = objects::NO_OBJECT; + object_id_t tcStoreId = objects::NO_OBJECT; + object_id_t tcDestination = objects::NO_OBJECT; -protected: - //! Cached for initialize function. - object_id_t tmStoreId = objects::NO_OBJECT; - object_id_t tcStoreId = objects::NO_OBJECT; - object_id_t tcDestination = objects::NO_OBJECT; + //! Used to send and receive TMTC messages. + //! The TmTcMessage class is used to transport messages between tasks. + MessageQueueIF* tmTcReceptionQueue = nullptr; - //! Used to send and receive TMTC messages. - //! The TmTcMessage class is used to transport messages between tasks. - MessageQueueIF* tmTcReceptionQueue = nullptr; + StorageManagerIF* tmStore = nullptr; + StorageManagerIF* tcStore = nullptr; - StorageManagerIF* tmStore = nullptr; - StorageManagerIF* tcStore = nullptr; + //! Used to specify whether communication link is up. Will be true + //! by default, so telemetry will be handled immediately. + bool communicationLinkUp = true; + bool tmStored = false; + bool overwriteOld = true; + uint8_t packetSentCounter = 0; - //! Used to specify whether communication link is up. Will be true - //! by default, so telemetry will be handled immediately. - bool communicationLinkUp = true; - bool tmStored = false; - bool overwriteOld = true; - uint8_t packetSentCounter = 0; + /** + * @brief Handle TC reception + * @details + * Default implementation provided, but is empty. + * In most cases, TC reception will be handled in a separate task anyway. + * @return + */ + virtual ReturnValue_t handleTc(); - /** - * @brief Handle TC reception - * @details - * Default implementation provided, but is empty. - * In most cases, TC reception will be handled in a separate task anyway. - * @return - */ - virtual ReturnValue_t handleTc(); + /** + * Handle Telemetry. Default implementation provided. + * Calls sendTm() + * @return + */ + virtual ReturnValue_t handleTm(); - /** - * Handle Telemetry. Default implementation provided. - * Calls sendTm() - * @return - */ - virtual ReturnValue_t handleTm(); + /** + * Read the TM Queue and send TM if necessary. + * Default implementation provided + * @return + */ + virtual ReturnValue_t handleTmQueue(); - /** - * Read the TM Queue and send TM if necessary. - * Default implementation provided - * @return - */ - virtual ReturnValue_t handleTmQueue(); + /** + * Send stored data if communication link is active + * @return + */ + virtual ReturnValue_t handleStoredTm(); - /** - * Send stored data if communication link is active - * @return - */ - virtual ReturnValue_t handleStoredTm(); + /** + * Implemented by child class. Perform sending of Telemetry by implementing + * communication drivers or wrappers, e.g. serial communication or a socket + * call. + * @param data + * @param dataLen + * @return + */ + virtual ReturnValue_t sendTm(const uint8_t* data, size_t dataLen) = 0; - /** - * Implemented by child class. Perform sending of Telemetry by implementing - * communication drivers or wrappers, e.g. serial communication or a socket - * call. - * @param data - * @param dataLen - * @return - */ - virtual ReturnValue_t sendTm(const uint8_t * data, size_t dataLen) = 0; + /** + * Store data to be sent later if communication link is not up. + * @param message + * @return + */ + virtual ReturnValue_t storeDownlinkData(TmTcMessage* message); - /** - * Store data to be sent later if communication link is not up. - * @param message - * @return - */ - virtual ReturnValue_t storeDownlinkData(TmTcMessage * message); + /** + * Print data as hexidecimal array + * @param data + * @param dataLen + */ + void printData(uint8_t* data, size_t dataLen); - - /** - * Print data as hexidecimal array - * @param data - * @param dataLen - */ - void printData(uint8_t * data, size_t dataLen); - - /** - * This FIFO can be used to store downlink data which can not be sent at the moment. - */ - DynamicFIFO* tmFifo = nullptr; - uint8_t sentPacketsPerCycle = DEFAULT_STORED_DATA_SENT_PER_CYCLE; - uint8_t maxNumberOfPacketsStored = DEFAULT_DOWNLINK_PACKETS_STORED; + /** + * This FIFO can be used to store downlink data which can not be sent at the moment. + */ + DynamicFIFO* tmFifo = nullptr; + uint8_t sentPacketsPerCycle = DEFAULT_STORED_DATA_SENT_PER_CYCLE; + uint8_t maxNumberOfPacketsStored = DEFAULT_DOWNLINK_PACKETS_STORED; }; - #endif /* FSFW_TMTCSERVICES_TMTCBRIDGE_H_ */ diff --git a/src/fsfw/tmtcservices/TmTcMessage.cpp b/src/fsfw/tmtcservices/TmTcMessage.cpp index 9dbd8fd8..ca76760f 100644 --- a/src/fsfw/tmtcservices/TmTcMessage.cpp +++ b/src/fsfw/tmtcservices/TmTcMessage.cpp @@ -2,29 +2,25 @@ #include +TmTcMessage::TmTcMessage() { this->messageSize += sizeof(store_address_t); } -TmTcMessage::TmTcMessage() { - this->messageSize += sizeof(store_address_t); -} - -TmTcMessage::~TmTcMessage() { -} +TmTcMessage::~TmTcMessage() {} store_address_t TmTcMessage::getStorageId() { - store_address_t temp_id; - memcpy(&temp_id, this->getData(), sizeof(store_address_t) ); - return temp_id; + store_address_t temp_id; + memcpy(&temp_id, this->getData(), sizeof(store_address_t)); + return temp_id; } TmTcMessage::TmTcMessage(store_address_t storeId) { - this->messageSize += sizeof(store_address_t); - this->setStorageId(storeId); + this->messageSize += sizeof(store_address_t); + this->setStorageId(storeId); } size_t TmTcMessage::getMinimumMessageSize() const { - return this->HEADER_SIZE + sizeof(store_address_t); + return this->HEADER_SIZE + sizeof(store_address_t); } void TmTcMessage::setStorageId(store_address_t storeId) { - memcpy(this->getData(), &storeId, sizeof(store_address_t) ); + memcpy(this->getData(), &storeId, sizeof(store_address_t)); } diff --git a/src/fsfw/tmtcservices/TmTcMessage.h b/src/fsfw/tmtcservices/TmTcMessage.h index 5e6647fe..a0f67894 100644 --- a/src/fsfw/tmtcservices/TmTcMessage.h +++ b/src/fsfw/tmtcservices/TmTcMessage.h @@ -13,38 +13,39 @@ * @ingroup message_queue */ class TmTcMessage : public MessageQueueMessage { -protected: - /** - * @brief This call always returns the same fixed size of the message. - * @return Returns HEADER_SIZE + @c sizeof(store_address_t). - */ - size_t getMinimumMessageSize() const override; -public: - /** - * @brief In the default constructor, only the message_size is set. - */ - TmTcMessage(); - /** - * @brief With this constructor, the passed packet id is directly put - * into the message. - * @param packet_id The packet id to put into the message. - */ - TmTcMessage( store_address_t packetId ); - /** - * @brief The class's destructor is empty. - */ - ~TmTcMessage(); - /** - * @brief This getter returns the packet id in the correct format. - * @return Returns the packet id. - */ - store_address_t getStorageId(); - /** - * @brief In some cases it might be useful to have a setter for packet id - * as well. - * @param packetId The packet id to put into the message. - */ - void setStorageId( store_address_t packetId ); + protected: + /** + * @brief This call always returns the same fixed size of the message. + * @return Returns HEADER_SIZE + @c sizeof(store_address_t). + */ + size_t getMinimumMessageSize() const override; + + public: + /** + * @brief In the default constructor, only the message_size is set. + */ + TmTcMessage(); + /** + * @brief With this constructor, the passed packet id is directly put + * into the message. + * @param packet_id The packet id to put into the message. + */ + TmTcMessage(store_address_t packetId); + /** + * @brief The class's destructor is empty. + */ + ~TmTcMessage(); + /** + * @brief This getter returns the packet id in the correct format. + * @return Returns the packet id. + */ + store_address_t getStorageId(); + /** + * @brief In some cases it might be useful to have a setter for packet id + * as well. + * @param packetId The packet id to put into the message. + */ + void setStorageId(store_address_t packetId); }; #endif /* FSFW_TMTCSERVICES_TMTCMESSAGE_H_ */ diff --git a/src/fsfw/tmtcservices/VerificationCodes.h b/src/fsfw/tmtcservices/VerificationCodes.h index 35ad6819..73edbc1d 100644 --- a/src/fsfw/tmtcservices/VerificationCodes.h +++ b/src/fsfw/tmtcservices/VerificationCodes.h @@ -4,25 +4,25 @@ namespace tc_verification { enum verification_flags { - NONE = 0b0000, - ACCEPTANCE = 0b0001, - START = 0b0010, - PROGRESS = 0b0100, - COMPLETION = 0b1000 + NONE = 0b0000, + ACCEPTANCE = 0b0001, + START = 0b0010, + PROGRESS = 0b0100, + COMPLETION = 0b1000 }; enum subservice_ids { - NOTHING_TO_REPORT = 0, - ACCEPTANCE_SUCCESS = 1, - ACCEPTANCE_FAILURE = 2, - START_SUCCESS = 3, - START_FAILURE = 4, - PROGRESS_SUCCESS = 5, - PROGRESS_FAILURE = 6, - COMPLETION_SUCCESS = 7, - COMPLETION_FAILURE = 8, + NOTHING_TO_REPORT = 0, + ACCEPTANCE_SUCCESS = 1, + ACCEPTANCE_FAILURE = 2, + START_SUCCESS = 3, + START_FAILURE = 4, + PROGRESS_SUCCESS = 5, + PROGRESS_FAILURE = 6, + COMPLETION_SUCCESS = 7, + COMPLETION_FAILURE = 8, }; -} +} // namespace tc_verification #endif /* VERIFICATIONCODES_H_ */ diff --git a/src/fsfw/tmtcservices/VerificationReporter.cpp b/src/fsfw/tmtcservices/VerificationReporter.cpp index b885cccf..9d06adc4 100644 --- a/src/fsfw/tmtcservices/VerificationReporter.cpp +++ b/src/fsfw/tmtcservices/VerificationReporter.cpp @@ -1,125 +1,112 @@ #include "fsfw/tmtcservices/VerificationReporter.h" + +#include "fsfw/ipc/MessageQueueIF.h" +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/objectmanager/frameworkObjects.h" +#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/tmtcservices/AcceptsVerifyMessageIF.h" #include "fsfw/tmtcservices/PusVerificationReport.h" -#include "fsfw/objectmanager/ObjectManager.h" -#include "fsfw/ipc/MessageQueueIF.h" -#include "fsfw/serviceinterface/ServiceInterface.h" -#include "fsfw/objectmanager/frameworkObjects.h" +object_id_t VerificationReporter::messageReceiver = objects::PUS_SERVICE_1_VERIFICATION; -object_id_t VerificationReporter::messageReceiver = - objects::PUS_SERVICE_1_VERIFICATION; - -VerificationReporter::VerificationReporter() : - acknowledgeQueue(MessageQueueIF::NO_QUEUE) { -} +VerificationReporter::VerificationReporter() : acknowledgeQueue(MessageQueueIF::NO_QUEUE) {} VerificationReporter::~VerificationReporter() {} -void VerificationReporter::sendSuccessReport(uint8_t set_report_id, - TcPacketPusBase* currentPacket, uint8_t set_step) { - if (acknowledgeQueue == MessageQueueIF::NO_QUEUE) { - this->initialize(); - } - if(currentPacket == nullptr) { - return; - } - PusVerificationMessage message(set_report_id, - currentPacket->getAcknowledgeFlags(), - currentPacket->getPacketId(), - currentPacket->getPacketSequenceControl(), 0, set_step); - ReturnValue_t status = MessageQueueSenderIF::sendMessage(acknowledgeQueue, - &message); - if (status != HasReturnvaluesIF::RETURN_OK) { +void VerificationReporter::sendSuccessReport(uint8_t set_report_id, TcPacketPusBase* currentPacket, + uint8_t set_step) { + if (acknowledgeQueue == MessageQueueIF::NO_QUEUE) { + this->initialize(); + } + if (currentPacket == nullptr) { + return; + } + PusVerificationMessage message(set_report_id, currentPacket->getAcknowledgeFlags(), + currentPacket->getPacketId(), + currentPacket->getPacketSequenceControl(), 0, set_step); + ReturnValue_t status = MessageQueueSenderIF::sendMessage(acknowledgeQueue, &message); + if (status != HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "VerificationReporter::sendSuccessReport: Error writing " - << "to queue. Code: " << std::hex << status << std::dec - << std::endl; + sif::error << "VerificationReporter::sendSuccessReport: Error writing " + << "to queue. Code: " << std::hex << status << std::dec << std::endl; #endif - } + } } -void VerificationReporter::sendSuccessReport(uint8_t set_report_id, - uint8_t ackFlags, uint16_t tcPacketId, uint16_t tcSequenceControl, - uint8_t set_step) { - if (acknowledgeQueue == MessageQueueIF::NO_QUEUE) { - this->initialize(); - } - PusVerificationMessage message(set_report_id, ackFlags, tcPacketId, - tcSequenceControl, 0, set_step); - ReturnValue_t status = MessageQueueSenderIF::sendMessage(acknowledgeQueue, - &message); - if (status != HasReturnvaluesIF::RETURN_OK) { +void VerificationReporter::sendSuccessReport(uint8_t set_report_id, uint8_t ackFlags, + uint16_t tcPacketId, uint16_t tcSequenceControl, + uint8_t set_step) { + if (acknowledgeQueue == MessageQueueIF::NO_QUEUE) { + this->initialize(); + } + PusVerificationMessage message(set_report_id, ackFlags, tcPacketId, tcSequenceControl, 0, + set_step); + ReturnValue_t status = MessageQueueSenderIF::sendMessage(acknowledgeQueue, &message); + if (status != HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "VerificationReporter::sendSuccessReport: Error writing " - << "to queue. Code: " << std::hex << status << std::dec - << std::endl; + sif::error << "VerificationReporter::sendSuccessReport: Error writing " + << "to queue. Code: " << std::hex << status << std::dec << std::endl; #endif - } + } } -void VerificationReporter::sendFailureReport(uint8_t report_id, - TcPacketPusBase* currentPacket, ReturnValue_t error_code, uint8_t step, - uint32_t parameter1, uint32_t parameter2) { - if (acknowledgeQueue == MessageQueueIF::NO_QUEUE) { - this->initialize(); - } - if(currentPacket == nullptr) { - return; - } - PusVerificationMessage message(report_id, - currentPacket->getAcknowledgeFlags(), - currentPacket->getPacketId(), - currentPacket->getPacketSequenceControl(), error_code, step, - parameter1, parameter2); - ReturnValue_t status = MessageQueueSenderIF::sendMessage(acknowledgeQueue, - &message); - if (status != HasReturnvaluesIF::RETURN_OK) { +void VerificationReporter::sendFailureReport(uint8_t report_id, TcPacketPusBase* currentPacket, + ReturnValue_t error_code, uint8_t step, + uint32_t parameter1, uint32_t parameter2) { + if (acknowledgeQueue == MessageQueueIF::NO_QUEUE) { + this->initialize(); + } + if (currentPacket == nullptr) { + return; + } + PusVerificationMessage message( + report_id, currentPacket->getAcknowledgeFlags(), currentPacket->getPacketId(), + currentPacket->getPacketSequenceControl(), error_code, step, parameter1, parameter2); + ReturnValue_t status = MessageQueueSenderIF::sendMessage(acknowledgeQueue, &message); + if (status != HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "VerificationReporter::sendFailureReport: Error writing " - << "to queue. Code: " << std::hex << "0x" << status << std::dec - << std::endl; + sif::error << "VerificationReporter::sendFailureReport: Error writing " + << "to queue. Code: " << std::hex << "0x" << status << std::dec << std::endl; #endif - } + } } -void VerificationReporter::sendFailureReport(uint8_t report_id, - uint8_t ackFlags, uint16_t tcPacketId, uint16_t tcSequenceControl, - ReturnValue_t error_code, uint8_t step, uint32_t parameter1, - uint32_t parameter2) { - if (acknowledgeQueue == MessageQueueIF::NO_QUEUE) { - this->initialize(); - } - PusVerificationMessage message(report_id, ackFlags, tcPacketId, - tcSequenceControl, error_code, step, parameter1, parameter2); - ReturnValue_t status = MessageQueueSenderIF::sendMessage(acknowledgeQueue, - &message); - if (status != HasReturnvaluesIF::RETURN_OK) { +void VerificationReporter::sendFailureReport(uint8_t report_id, uint8_t ackFlags, + uint16_t tcPacketId, uint16_t tcSequenceControl, + ReturnValue_t error_code, uint8_t step, + uint32_t parameter1, uint32_t parameter2) { + if (acknowledgeQueue == MessageQueueIF::NO_QUEUE) { + this->initialize(); + } + PusVerificationMessage message(report_id, ackFlags, tcPacketId, tcSequenceControl, error_code, + step, parameter1, parameter2); + ReturnValue_t status = MessageQueueSenderIF::sendMessage(acknowledgeQueue, &message); + if (status != HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "VerificationReporter::sendFailureReport: Error writing " - << "to queue. Code: " << std::hex << "0x" << status << std::dec - << std::endl; + sif::error << "VerificationReporter::sendFailureReport: Error writing " + << "to queue. Code: " << std::hex << "0x" << status << std::dec << std::endl; #endif - } + } } void VerificationReporter::initialize() { - if(messageReceiver == objects::NO_OBJECT) { + if (messageReceiver == objects::NO_OBJECT) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "VerificationReporter::initialize: Verification message" - " receiver object ID not set yet in Factory!" << std::endl; + sif::warning << "VerificationReporter::initialize: Verification message" + " receiver object ID not set yet in Factory!" + << std::endl; #endif - return; - } - AcceptsVerifyMessageIF* temp = ObjectManager::instance()->get( - messageReceiver); - if (temp == nullptr) { + return; + } + AcceptsVerifyMessageIF* temp = + ObjectManager::instance()->get(messageReceiver); + if (temp == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "VerificationReporter::initialize: Message " - << "receiver invalid. Make sure it is set up properly and " - << "implementsAcceptsVerifyMessageIF" << std::endl; + sif::error << "VerificationReporter::initialize: Message " + << "receiver invalid. Make sure it is set up properly and " + << "implementsAcceptsVerifyMessageIF" << std::endl; #endif - return; - } - this->acknowledgeQueue = temp->getVerificationQueue(); + return; + } + this->acknowledgeQueue = temp->getVerificationQueue(); } diff --git a/src/fsfw/tmtcservices/VerificationReporter.h b/src/fsfw/tmtcservices/VerificationReporter.h index d57cc791..c29afd60 100644 --- a/src/fsfw/tmtcservices/VerificationReporter.h +++ b/src/fsfw/tmtcservices/VerificationReporter.h @@ -4,7 +4,7 @@ #include "PusVerificationReport.h" #include "fsfw/objectmanager/ObjectManagerIF.h" -namespace Factory{ +namespace Factory { void setStaticFrameworkObjectIds(); } @@ -20,31 +20,29 @@ void setStaticFrameworkObjectIds(); * */ class VerificationReporter { - friend void (Factory::setStaticFrameworkObjectIds)(); -public: - VerificationReporter(); - virtual ~VerificationReporter(); + friend void(Factory::setStaticFrameworkObjectIds)(); - void sendSuccessReport( uint8_t set_report_id, TcPacketPusBase* current_packet, - uint8_t set_step = 0 ); - void sendSuccessReport(uint8_t set_report_id, uint8_t ackFlags, - uint16_t tcPacketId, uint16_t tcSequenceControl, - uint8_t set_step = 0); + public: + VerificationReporter(); + virtual ~VerificationReporter(); - void sendFailureReport( uint8_t report_id, TcPacketPusBase* current_packet, - ReturnValue_t error_code = 0, - uint8_t step = 0, uint32_t parameter1 = 0, - uint32_t parameter2 = 0 ); - void sendFailureReport(uint8_t report_id, - uint8_t ackFlags, uint16_t tcPacketId, uint16_t tcSequenceControl, - ReturnValue_t error_code = 0, uint8_t step = 0, - uint32_t parameter1 = 0, uint32_t parameter2 = 0); + void sendSuccessReport(uint8_t set_report_id, TcPacketPusBase* current_packet, + uint8_t set_step = 0); + void sendSuccessReport(uint8_t set_report_id, uint8_t ackFlags, uint16_t tcPacketId, + uint16_t tcSequenceControl, uint8_t set_step = 0); - void initialize(); + void sendFailureReport(uint8_t report_id, TcPacketPusBase* current_packet, + ReturnValue_t error_code = 0, uint8_t step = 0, uint32_t parameter1 = 0, + uint32_t parameter2 = 0); + void sendFailureReport(uint8_t report_id, uint8_t ackFlags, uint16_t tcPacketId, + uint16_t tcSequenceControl, ReturnValue_t error_code = 0, uint8_t step = 0, + uint32_t parameter1 = 0, uint32_t parameter2 = 0); -private: - static object_id_t messageReceiver; - MessageQueueId_t acknowledgeQueue; + void initialize(); + + private: + static object_id_t messageReceiver; + MessageQueueId_t acknowledgeQueue; }; #endif /* FSFW_TMTCSERVICES_VERIFICATIONREPORTER_H_ */ diff --git a/tests/src/fsfw_tests/integration/assemblies/TestAssembly.cpp b/tests/src/fsfw_tests/integration/assemblies/TestAssembly.cpp index 0ead4bfd..a0313f96 100644 --- a/tests/src/fsfw_tests/integration/assemblies/TestAssembly.cpp +++ b/tests/src/fsfw_tests/integration/assemblies/TestAssembly.cpp @@ -2,200 +2,179 @@ #include - TestAssembly::TestAssembly(object_id_t objectId, object_id_t parentId, object_id_t testDevice0, - object_id_t testDevice1): - AssemblyBase(objectId, parentId), deviceHandler0Id(testDevice0), - deviceHandler1Id(testDevice1) { - ModeListEntry newModeListEntry; - newModeListEntry.setObject(testDevice0); - newModeListEntry.setMode(MODE_OFF); - newModeListEntry.setSubmode(SUBMODE_NONE); + object_id_t testDevice1) + : AssemblyBase(objectId, parentId), + deviceHandler0Id(testDevice0), + deviceHandler1Id(testDevice1) { + ModeListEntry newModeListEntry; + newModeListEntry.setObject(testDevice0); + newModeListEntry.setMode(MODE_OFF); + newModeListEntry.setSubmode(SUBMODE_NONE); - commandTable.insert(newModeListEntry); + commandTable.insert(newModeListEntry); - newModeListEntry.setObject(testDevice1); - newModeListEntry.setMode(MODE_OFF); - newModeListEntry.setSubmode(SUBMODE_NONE); - - commandTable.insert(newModeListEntry); + newModeListEntry.setObject(testDevice1); + newModeListEntry.setMode(MODE_OFF); + newModeListEntry.setSubmode(SUBMODE_NONE); + commandTable.insert(newModeListEntry); } -TestAssembly::~TestAssembly() { -} +TestAssembly::~TestAssembly() {} -ReturnValue_t TestAssembly::commandChildren(Mode_t mode, - Submode_t submode) { +ReturnValue_t TestAssembly::commandChildren(Mode_t mode, Submode_t submode) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TestAssembly: Received command to go to mode " << mode << - " submode " << (int) submode << std::endl; + sif::info << "TestAssembly: Received command to go to mode " << mode << " submode " + << (int)submode << std::endl; #else - sif::printInfo("TestAssembly: Received command to go to mode %d submode %d\n", mode, submode); + sif::printInfo("TestAssembly: Received command to go to mode %d submode %d\n", mode, submode); #endif - ReturnValue_t result = RETURN_OK; - if(mode == MODE_OFF){ - commandTable[0].setMode(MODE_OFF); - commandTable[0].setSubmode(SUBMODE_NONE); - commandTable[1].setMode(MODE_OFF); - commandTable[1].setSubmode(SUBMODE_NONE); - } - else if(mode == DeviceHandlerIF::MODE_NORMAL) { - if(submode == submodes::SINGLE){ - commandTable[0].setMode(MODE_OFF); - commandTable[0].setSubmode(SUBMODE_NONE); - commandTable[1].setMode(MODE_OFF); - commandTable[1].setSubmode(SUBMODE_NONE); - // We try to prefer 0 here but we try to switch to 1 even if it might fail - if(isDeviceAvailable(deviceHandler0Id)) { - if (childrenMap[deviceHandler0Id].mode == MODE_ON) { - commandTable[0].setMode(mode); - commandTable[0].setSubmode(SUBMODE_NONE); - } - else { - commandTable[0].setMode(MODE_ON); - commandTable[0].setSubmode(SUBMODE_NONE); - result = NEED_SECOND_STEP; - } - } - else { - if (childrenMap[deviceHandler1Id].mode == MODE_ON) { - commandTable[1].setMode(mode); - commandTable[1].setSubmode(SUBMODE_NONE); - } - else{ - commandTable[1].setMode(MODE_ON); - commandTable[1].setSubmode(SUBMODE_NONE); - result = NEED_SECOND_STEP; - } - } - } - else{ - // Dual Mode Normal - if (childrenMap[deviceHandler0Id].mode == MODE_ON) { - commandTable[0].setMode(mode); - commandTable[0].setSubmode(SUBMODE_NONE); - } - else{ - commandTable[0].setMode(MODE_ON); - commandTable[0].setSubmode(SUBMODE_NONE); - result = NEED_SECOND_STEP; - } - if (childrenMap[deviceHandler1Id].mode == MODE_ON) { - commandTable[1].setMode(mode); - commandTable[1].setSubmode(SUBMODE_NONE); - } - else{ - commandTable[1].setMode(MODE_ON); - commandTable[1].setSubmode(SUBMODE_NONE); - result = NEED_SECOND_STEP; - } - } - } - else{ - //Mode ON - if(submode == submodes::SINGLE){ - commandTable[0].setMode(MODE_OFF); - commandTable[0].setSubmode(SUBMODE_NONE); - commandTable[1].setMode(MODE_OFF); - commandTable[1].setSubmode(SUBMODE_NONE); - // We try to prefer 0 here but we try to switch to 1 even if it might fail - if(isDeviceAvailable(deviceHandler0Id)){ - commandTable[0].setMode(MODE_ON); - commandTable[0].setSubmode(SUBMODE_NONE); - } - else{ - commandTable[1].setMode(MODE_ON); - commandTable[1].setSubmode(SUBMODE_NONE); - } - } - else{ - commandTable[0].setMode(MODE_ON); - commandTable[0].setSubmode(SUBMODE_NONE); - commandTable[1].setMode(MODE_ON); - commandTable[1].setSubmode(SUBMODE_NONE); - } - } + ReturnValue_t result = RETURN_OK; + if (mode == MODE_OFF) { + commandTable[0].setMode(MODE_OFF); + commandTable[0].setSubmode(SUBMODE_NONE); + commandTable[1].setMode(MODE_OFF); + commandTable[1].setSubmode(SUBMODE_NONE); + } else if (mode == DeviceHandlerIF::MODE_NORMAL) { + if (submode == submodes::SINGLE) { + commandTable[0].setMode(MODE_OFF); + commandTable[0].setSubmode(SUBMODE_NONE); + commandTable[1].setMode(MODE_OFF); + commandTable[1].setSubmode(SUBMODE_NONE); + // We try to prefer 0 here but we try to switch to 1 even if it might fail + if (isDeviceAvailable(deviceHandler0Id)) { + if (childrenMap[deviceHandler0Id].mode == MODE_ON) { + commandTable[0].setMode(mode); + commandTable[0].setSubmode(SUBMODE_NONE); + } else { + commandTable[0].setMode(MODE_ON); + commandTable[0].setSubmode(SUBMODE_NONE); + result = NEED_SECOND_STEP; + } + } else { + if (childrenMap[deviceHandler1Id].mode == MODE_ON) { + commandTable[1].setMode(mode); + commandTable[1].setSubmode(SUBMODE_NONE); + } else { + commandTable[1].setMode(MODE_ON); + commandTable[1].setSubmode(SUBMODE_NONE); + result = NEED_SECOND_STEP; + } + } + } else { + // Dual Mode Normal + if (childrenMap[deviceHandler0Id].mode == MODE_ON) { + commandTable[0].setMode(mode); + commandTable[0].setSubmode(SUBMODE_NONE); + } else { + commandTable[0].setMode(MODE_ON); + commandTable[0].setSubmode(SUBMODE_NONE); + result = NEED_SECOND_STEP; + } + if (childrenMap[deviceHandler1Id].mode == MODE_ON) { + commandTable[1].setMode(mode); + commandTable[1].setSubmode(SUBMODE_NONE); + } else { + commandTable[1].setMode(MODE_ON); + commandTable[1].setSubmode(SUBMODE_NONE); + result = NEED_SECOND_STEP; + } + } + } else { + // Mode ON + if (submode == submodes::SINGLE) { + commandTable[0].setMode(MODE_OFF); + commandTable[0].setSubmode(SUBMODE_NONE); + commandTable[1].setMode(MODE_OFF); + commandTable[1].setSubmode(SUBMODE_NONE); + // We try to prefer 0 here but we try to switch to 1 even if it might fail + if (isDeviceAvailable(deviceHandler0Id)) { + commandTable[0].setMode(MODE_ON); + commandTable[0].setSubmode(SUBMODE_NONE); + } else { + commandTable[1].setMode(MODE_ON); + commandTable[1].setSubmode(SUBMODE_NONE); + } + } else { + commandTable[0].setMode(MODE_ON); + commandTable[0].setSubmode(SUBMODE_NONE); + commandTable[1].setMode(MODE_ON); + commandTable[1].setSubmode(SUBMODE_NONE); + } + } - - - HybridIterator iter(commandTable.begin(), - commandTable.end()); - executeTable(iter); - return result; + HybridIterator iter(commandTable.begin(), commandTable.end()); + executeTable(iter); + return result; } -ReturnValue_t TestAssembly::isModeCombinationValid(Mode_t mode, - Submode_t submode) { - switch (mode) { - case MODE_OFF: - if (submode == SUBMODE_NONE) { - return RETURN_OK; - } else { - return INVALID_SUBMODE; - } - case DeviceHandlerIF::MODE_NORMAL: - case MODE_ON: - if (submode < 3) { - return RETURN_OK; - } else { - return INVALID_SUBMODE; - } - } - return INVALID_MODE; +ReturnValue_t TestAssembly::isModeCombinationValid(Mode_t mode, Submode_t submode) { + switch (mode) { + case MODE_OFF: + if (submode == SUBMODE_NONE) { + return RETURN_OK; + } else { + return INVALID_SUBMODE; + } + case DeviceHandlerIF::MODE_NORMAL: + case MODE_ON: + if (submode < 3) { + return RETURN_OK; + } else { + return INVALID_SUBMODE; + } + } + return INVALID_MODE; } ReturnValue_t TestAssembly::initialize() { - ReturnValue_t result = AssemblyBase::initialize(); - if(result != RETURN_OK){ - return result; - } - handler0 = ObjectManager::instance()->get(deviceHandler0Id); - handler1 = ObjectManager::instance()->get(deviceHandler1Id); - if((handler0 == nullptr) or (handler1 == nullptr)){ - return HasReturnvaluesIF::RETURN_FAILED; - } + ReturnValue_t result = AssemblyBase::initialize(); + if (result != RETURN_OK) { + return result; + } + handler0 = ObjectManager::instance()->get(deviceHandler0Id); + handler1 = ObjectManager::instance()->get(deviceHandler1Id); + if ((handler0 == nullptr) or (handler1 == nullptr)) { + return HasReturnvaluesIF::RETURN_FAILED; + } - handler0->setParentQueue(this->getCommandQueue()); - handler1->setParentQueue(this->getCommandQueue()); + handler0->setParentQueue(this->getCommandQueue()); + handler1->setParentQueue(this->getCommandQueue()); - - result = registerChild(deviceHandler0Id); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = registerChild(deviceHandler1Id); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return result; + result = registerChild(deviceHandler0Id); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = registerChild(deviceHandler1Id); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return result; } -ReturnValue_t TestAssembly::checkChildrenStateOn( - Mode_t wantedMode, Submode_t wantedSubmode) { - if(submode == submodes::DUAL){ - for(const auto& info:childrenMap) { - if(info.second.mode != wantedMode or info.second.mode != wantedSubmode){ - return NOT_ENOUGH_CHILDREN_IN_CORRECT_STATE; - } - } - return RETURN_OK; - } - else if(submode == submodes::SINGLE) { - for(const auto& info:childrenMap) { - if(info.second.mode == wantedMode and info.second.mode != wantedSubmode){ - return RETURN_OK; - } - } - } - return INVALID_SUBMODE; +ReturnValue_t TestAssembly::checkChildrenStateOn(Mode_t wantedMode, Submode_t wantedSubmode) { + if (submode == submodes::DUAL) { + for (const auto& info : childrenMap) { + if (info.second.mode != wantedMode or info.second.mode != wantedSubmode) { + return NOT_ENOUGH_CHILDREN_IN_CORRECT_STATE; + } + } + return RETURN_OK; + } else if (submode == submodes::SINGLE) { + for (const auto& info : childrenMap) { + if (info.second.mode == wantedMode and info.second.mode != wantedSubmode) { + return RETURN_OK; + } + } + } + return INVALID_SUBMODE; } bool TestAssembly::isDeviceAvailable(object_id_t object) { - if(healthHelper.healthTable->getHealth(object) == HasHealthIF::HEALTHY){ - return true; - } - else{ - return false; - } + if (healthHelper.healthTable->getHealth(object) == HasHealthIF::HEALTHY) { + return true; + } else { + return false; + } } diff --git a/tests/src/fsfw_tests/integration/assemblies/TestAssembly.h b/tests/src/fsfw_tests/integration/assemblies/TestAssembly.h index 3cc6f450..6042f54e 100644 --- a/tests/src/fsfw_tests/integration/assemblies/TestAssembly.h +++ b/tests/src/fsfw_tests/integration/assemblies/TestAssembly.h @@ -2,55 +2,51 @@ #define MISSION_ASSEMBLIES_TESTASSEMBLY_H_ #include + #include "../devices/TestDeviceHandler.h" -class TestAssembly: public AssemblyBase { -public: - TestAssembly(object_id_t objectId, object_id_t parentId, object_id_t testDevice0, - object_id_t testDevice1); - virtual ~TestAssembly(); - ReturnValue_t initialize() override; +class TestAssembly : public AssemblyBase { + public: + TestAssembly(object_id_t objectId, object_id_t parentId, object_id_t testDevice0, + object_id_t testDevice1); + virtual ~TestAssembly(); + ReturnValue_t initialize() override; - enum submodes: Submode_t{ - SINGLE = 0, - DUAL = 1 - }; + enum submodes : Submode_t { SINGLE = 0, DUAL = 1 }; -protected: - /** - * Command children to reach [mode,submode] combination - * Can be done by setting #commandsOutstanding correctly, - * or using executeTable() - * @param mode - * @param submode - * @return - * - @c RETURN_OK if ok - * - @c NEED_SECOND_STEP if children need to be commanded again - */ - ReturnValue_t commandChildren(Mode_t mode, Submode_t submode) override; - /** - * Check whether desired assembly mode was achieved by checking the modes - * or/and health states of child device handlers. - * The assembly template class will also call this function if a health - * or mode change of a child device handler was detected. - * @param wantedMode - * @param wantedSubmode - * @return - */ - ReturnValue_t isModeCombinationValid(Mode_t mode, Submode_t submode) - override; + protected: + /** + * Command children to reach [mode,submode] combination + * Can be done by setting #commandsOutstanding correctly, + * or using executeTable() + * @param mode + * @param submode + * @return + * - @c RETURN_OK if ok + * - @c NEED_SECOND_STEP if children need to be commanded again + */ + ReturnValue_t commandChildren(Mode_t mode, Submode_t submode) override; + /** + * Check whether desired assembly mode was achieved by checking the modes + * or/and health states of child device handlers. + * The assembly template class will also call this function if a health + * or mode change of a child device handler was detected. + * @param wantedMode + * @param wantedSubmode + * @return + */ + ReturnValue_t isModeCombinationValid(Mode_t mode, Submode_t submode) override; - ReturnValue_t checkChildrenStateOn(Mode_t wantedMode, - Submode_t wantedSubmode) override; -private: - FixedArrayList commandTable; - object_id_t deviceHandler0Id = 0; - object_id_t deviceHandler1Id = 0; - TestDevice* handler0 = nullptr; - TestDevice* handler1 = nullptr; + ReturnValue_t checkChildrenStateOn(Mode_t wantedMode, Submode_t wantedSubmode) override; + private: + FixedArrayList commandTable; + object_id_t deviceHandler0Id = 0; + object_id_t deviceHandler1Id = 0; + TestDevice* handler0 = nullptr; + TestDevice* handler1 = nullptr; - bool isDeviceAvailable(object_id_t object); + bool isDeviceAvailable(object_id_t object); }; #endif /* MISSION_ASSEMBLIES_TESTASSEMBLY_H_ */ diff --git a/tests/src/fsfw_tests/integration/controller/TestController.cpp b/tests/src/fsfw_tests/integration/controller/TestController.cpp index 8c2c9330..03f24311 100644 --- a/tests/src/fsfw_tests/integration/controller/TestController.cpp +++ b/tests/src/fsfw_tests/integration/controller/TestController.cpp @@ -4,45 +4,34 @@ #include #include -TestController::TestController(object_id_t objectId, object_id_t parentId, - size_t commandQueueDepth): - ExtendedControllerBase(objectId, parentId, commandQueueDepth) { -} +TestController::TestController(object_id_t objectId, object_id_t parentId, size_t commandQueueDepth) + : ExtendedControllerBase(objectId, parentId, commandQueueDepth) {} -TestController::~TestController() { -} +TestController::~TestController() {} ReturnValue_t TestController::handleCommandMessage(CommandMessage *message) { - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } -void TestController::performControlOperation() { +void TestController::performControlOperation() {} -} - -void TestController::handleChangedDataset(sid_t sid, store_address_t storeId, bool* clearMessage) { - -} +void TestController::handleChangedDataset(sid_t sid, store_address_t storeId, bool *clearMessage) {} void TestController::handleChangedPoolVariable(gp_id_t globPoolId, store_address_t storeId, - bool* clearMessage) { -} + bool *clearMessage) {} -LocalPoolDataSetBase* TestController::getDataSetHandle(sid_t sid) { - return nullptr; -} +LocalPoolDataSetBase *TestController::getDataSetHandle(sid_t sid) { return nullptr; } ReturnValue_t TestController::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, - LocalDataPoolManager &poolManager) { - return HasReturnvaluesIF::RETURN_OK; + LocalDataPoolManager &poolManager) { + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t TestController::initializeAfterTaskCreation() { - return ExtendedControllerBase::initializeAfterTaskCreation(); + return ExtendedControllerBase::initializeAfterTaskCreation(); } ReturnValue_t TestController::checkModeCommand(Mode_t mode, Submode_t submode, - uint32_t *msToReachTheMode) { - return HasReturnvaluesIF::RETURN_OK; + uint32_t *msToReachTheMode) { + return HasReturnvaluesIF::RETURN_OK; } - diff --git a/tests/src/fsfw_tests/integration/controller/TestController.h b/tests/src/fsfw_tests/integration/controller/TestController.h index 7d94367d..9898371f 100644 --- a/tests/src/fsfw_tests/integration/controller/TestController.h +++ b/tests/src/fsfw_tests/integration/controller/TestController.h @@ -1,38 +1,36 @@ #ifndef MISSION_CONTROLLER_TESTCONTROLLER_H_ #define MISSION_CONTROLLER_TESTCONTROLLER_H_ -#include "../devices/devicedefinitions/testDeviceDefinitions.h" #include +#include "../devices/devicedefinitions/testDeviceDefinitions.h" -class TestController: - public ExtendedControllerBase { -public: - TestController(object_id_t objectId, object_id_t parentId, size_t commandQueueDepth = 10); - virtual~ TestController(); -protected: +class TestController : public ExtendedControllerBase { + public: + TestController(object_id_t objectId, object_id_t parentId, size_t commandQueueDepth = 10); + virtual ~TestController(); - // Extended Controller Base overrides - ReturnValue_t handleCommandMessage(CommandMessage *message) override; - void performControlOperation() override; + protected: + // Extended Controller Base overrides + ReturnValue_t handleCommandMessage(CommandMessage* message) override; + void performControlOperation() override; - // HasLocalDatapoolIF callbacks - virtual void handleChangedDataset(sid_t sid, store_address_t storeId, - bool* clearMessage) override; - virtual void handleChangedPoolVariable(gp_id_t globPoolId, store_address_t storeId, - bool* clearMessage) override; + // HasLocalDatapoolIF callbacks + virtual void handleChangedDataset(sid_t sid, store_address_t storeId, + bool* clearMessage) override; + virtual void handleChangedPoolVariable(gp_id_t globPoolId, store_address_t storeId, + bool* clearMessage) override; - LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override; - ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, - LocalDataPoolManager& poolManager) override; + LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) override; - ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, - uint32_t *msToReachTheMode) override; + ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, + uint32_t* msToReachTheMode) override; - ReturnValue_t initializeAfterTaskCreation() override; + ReturnValue_t initializeAfterTaskCreation() override; -private: + private: }; - #endif /* MISSION_CONTROLLER_TESTCONTROLLER_H_ */ diff --git a/tests/src/fsfw_tests/integration/controller/ctrldefinitions/testCtrlDefinitions.h b/tests/src/fsfw_tests/integration/controller/ctrldefinitions/testCtrlDefinitions.h index 7bf045df..2c84ee7c 100644 --- a/tests/src/fsfw_tests/integration/controller/ctrldefinitions/testCtrlDefinitions.h +++ b/tests/src/fsfw_tests/integration/controller/ctrldefinitions/testCtrlDefinitions.h @@ -1,18 +1,16 @@ #ifndef MISSION_CONTROLLER_CTRLDEFINITIONS_TESTCTRLDEFINITIONS_H_ #define MISSION_CONTROLLER_CTRLDEFINITIONS_TESTCTRLDEFINITIONS_H_ -#include #include +#include namespace testcontroller { -enum sourceObjectIds: object_id_t { - DEVICE_0_ID = objects::TEST_DEVICE_HANDLER_0, - DEVICE_1_ID = objects::TEST_DEVICE_HANDLER_1, +enum sourceObjectIds : object_id_t { + DEVICE_0_ID = objects::TEST_DEVICE_HANDLER_0, + DEVICE_1_ID = objects::TEST_DEVICE_HANDLER_1, }; } - - #endif /* MISSION_CONTROLLER_CTRLDEFINITIONS_TESTCTRLDEFINITIONS_H_ */ diff --git a/tests/src/fsfw_tests/integration/devices/TestCookie.cpp b/tests/src/fsfw_tests/integration/devices/TestCookie.cpp index 91098f80..71703b73 100644 --- a/tests/src/fsfw_tests/integration/devices/TestCookie.cpp +++ b/tests/src/fsfw_tests/integration/devices/TestCookie.cpp @@ -1,14 +1,10 @@ #include "TestCookie.h" -TestCookie::TestCookie(address_t address, size_t replyMaxLen): - address(address), replyMaxLen(replyMaxLen) {} +TestCookie::TestCookie(address_t address, size_t replyMaxLen) + : address(address), replyMaxLen(replyMaxLen) {} TestCookie::~TestCookie() {} -address_t TestCookie::getAddress() const { - return address; -} +address_t TestCookie::getAddress() const { return address; } -size_t TestCookie::getReplyMaxLen() const { - return replyMaxLen; -} +size_t TestCookie::getReplyMaxLen() const { return replyMaxLen; } diff --git a/tests/src/fsfw_tests/integration/devices/TestCookie.h b/tests/src/fsfw_tests/integration/devices/TestCookie.h index 5dac3f25..e5de88e5 100644 --- a/tests/src/fsfw_tests/integration/devices/TestCookie.h +++ b/tests/src/fsfw_tests/integration/devices/TestCookie.h @@ -2,21 +2,23 @@ #define MISSION_DEVICES_TESTCOOKIE_H_ #include + #include /** * @brief Really simple cookie which does not do a lot. */ -class TestCookie: public CookieIF { -public: - TestCookie(address_t address, size_t maxReplyLen); - virtual ~TestCookie(); +class TestCookie : public CookieIF { + public: + TestCookie(address_t address, size_t maxReplyLen); + virtual ~TestCookie(); - address_t getAddress() const; - size_t getReplyMaxLen() const; -private: - address_t address = 0; - size_t replyMaxLen = 0; + address_t getAddress() const; + size_t getReplyMaxLen() const; + + private: + address_t address = 0; + size_t replyMaxLen = 0; }; #endif /* MISSION_DEVICES_TESTCOOKIE_H_ */ diff --git a/tests/src/fsfw_tests/integration/devices/TestDeviceHandler.cpp b/tests/src/fsfw_tests/integration/devices/TestDeviceHandler.cpp index 46138c56..41098723 100644 --- a/tests/src/fsfw_tests/integration/devices/TestDeviceHandler.cpp +++ b/tests/src/fsfw_tests/integration/devices/TestDeviceHandler.cpp @@ -1,798 +1,797 @@ #include "TestDeviceHandler.h" -#include "FSFWConfig.h" - -#include "fsfw/datapool/PoolReadGuard.h" #include -TestDevice::TestDevice(object_id_t objectId, object_id_t comIF, - CookieIF * cookie, testdevice::DeviceIndex deviceIdx, bool fullInfoPrintout, - bool changingDataset): - DeviceHandlerBase(objectId, comIF, cookie), deviceIdx(deviceIdx), - dataset(this), fullInfoPrintout(fullInfoPrintout) { -} +#include "FSFWConfig.h" +#include "fsfw/datapool/PoolReadGuard.h" + +TestDevice::TestDevice(object_id_t objectId, object_id_t comIF, CookieIF* cookie, + testdevice::DeviceIndex deviceIdx, bool fullInfoPrintout, + bool changingDataset) + : DeviceHandlerBase(objectId, comIF, cookie), + deviceIdx(deviceIdx), + dataset(this), + fullInfoPrintout(fullInfoPrintout) {} TestDevice::~TestDevice() {} void TestDevice::performOperationHook() { - if(periodicPrintout) { + if (periodicPrintout) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TestDevice" << deviceIdx << "::performOperationHook: Alive!" << std::endl; + sif::info << "TestDevice" << deviceIdx << "::performOperationHook: Alive!" << std::endl; #else - sif::printInfo("TestDevice%d::performOperationHook: Alive!", deviceIdx); + sif::printInfo("TestDevice%d::performOperationHook: Alive!", deviceIdx); #endif - } + } - if(oneShot) { - oneShot = false; - } + if (oneShot) { + oneShot = false; + } } - void TestDevice::doStartUp() { - if(fullInfoPrintout) { + if (fullInfoPrintout) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TestDevice" << deviceIdx << "::doStartUp: Switching On" << std::endl; + sif::info << "TestDevice" << deviceIdx << "::doStartUp: Switching On" << std::endl; #else - sif::printInfo("TestDevice%d::doStartUp: Switching On\n", static_cast(deviceIdx)); + sif::printInfo("TestDevice%d::doStartUp: Switching On\n", static_cast(deviceIdx)); #endif - } + } - setMode(_MODE_TO_ON); - return; + setMode(_MODE_TO_ON); + return; } - void TestDevice::doShutDown() { - if(fullInfoPrintout) { + if (fullInfoPrintout) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TestDevice" << deviceIdx << "::doShutDown: Switching Off" << std::endl; + sif::info << "TestDevice" << deviceIdx << "::doShutDown: Switching Off" << std::endl; #else - sif::printInfo("TestDevice%d::doShutDown: Switching Off\n", static_cast(deviceIdx)); + sif::printInfo("TestDevice%d::doShutDown: Switching Off\n", static_cast(deviceIdx)); #endif - } + } - setMode(_MODE_SHUT_DOWN); - return; + setMode(_MODE_SHUT_DOWN); + return; } - ReturnValue_t TestDevice::buildNormalDeviceCommand(DeviceCommandId_t* id) { - using namespace testdevice; - *id = TEST_NORMAL_MODE_CMD; - if(DeviceHandlerBase::isAwaitingReply()) { - return NOTHING_TO_SEND; - } - return buildCommandFromCommand(*id, nullptr, 0); + using namespace testdevice; + *id = TEST_NORMAL_MODE_CMD; + if (DeviceHandlerBase::isAwaitingReply()) { + return NOTHING_TO_SEND; + } + return buildCommandFromCommand(*id, nullptr, 0); } ReturnValue_t TestDevice::buildTransitionDeviceCommand(DeviceCommandId_t* id) { - if(mode == _MODE_TO_ON) { - if(fullInfoPrintout) { + if (mode == _MODE_TO_ON) { + if (fullInfoPrintout) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TestDevice" << deviceIdx << "::buildTransitionDeviceCommand: Was called" - " from _MODE_TO_ON mode" << std::endl; + sif::info << "TestDevice" << deviceIdx + << "::buildTransitionDeviceCommand: Was called" + " from _MODE_TO_ON mode" + << std::endl; #else - sif::printInfo("TestDevice%d::buildTransitionDeviceCommand: " - "Was called from _MODE_TO_ON mode\n", deviceIdx); + sif::printInfo( + "TestDevice%d::buildTransitionDeviceCommand: " + "Was called from _MODE_TO_ON mode\n", + deviceIdx); #endif - } - } - if(mode == _MODE_TO_NORMAL) { - if(fullInfoPrintout) { + } + if (mode == _MODE_TO_NORMAL) { + if (fullInfoPrintout) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TestDevice" << deviceIdx << "::buildTransitionDeviceCommand: Was called " - "from _MODE_TO_NORMAL mode" << std::endl; + sif::info << "TestDevice" << deviceIdx + << "::buildTransitionDeviceCommand: Was called " + "from _MODE_TO_NORMAL mode" + << std::endl; #else - sif::printInfo("TestDevice%d::buildTransitionDeviceCommand: Was called from " - " _MODE_TO_NORMAL mode\n", deviceIdx); + sif::printInfo( + "TestDevice%d::buildTransitionDeviceCommand: Was called from " + " _MODE_TO_NORMAL mode\n", + deviceIdx); #endif - } - - setMode(MODE_NORMAL); } - if(mode == _MODE_SHUT_DOWN) { - if(fullInfoPrintout) { + + setMode(MODE_NORMAL); + } + if (mode == _MODE_SHUT_DOWN) { + if (fullInfoPrintout) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TestDevice" << deviceIdx << "::buildTransitionDeviceCommand: Was called " - "from _MODE_SHUT_DOWN mode" << std::endl; + sif::info << "TestDevice" << deviceIdx + << "::buildTransitionDeviceCommand: Was called " + "from _MODE_SHUT_DOWN mode" + << std::endl; #else - sif::printInfo("TestDevice%d::buildTransitionDeviceCommand: Was called from " - "_MODE_SHUT_DOWN mode\n", deviceIdx); + sif::printInfo( + "TestDevice%d::buildTransitionDeviceCommand: Was called from " + "_MODE_SHUT_DOWN mode\n", + deviceIdx); #endif - } - - setMode(MODE_OFF); } - return NOTHING_TO_SEND; + + setMode(MODE_OFF); + } + return NOTHING_TO_SEND; } void TestDevice::doTransition(Mode_t modeFrom, Submode_t submodeFrom) { - if(mode == _MODE_TO_NORMAL) { - if(fullInfoPrintout) { + if (mode == _MODE_TO_NORMAL) { + if (fullInfoPrintout) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TestDevice" << deviceIdx << "::doTransition: Custom transition to " - "normal mode" << std::endl; + sif::info << "TestDevice" << deviceIdx + << "::doTransition: Custom transition to " + "normal mode" + << std::endl; #else - sif::printInfo("TestDevice%d::doTransition: Custom transition to normal mode\n", - deviceIdx); + sif::printInfo("TestDevice%d::doTransition: Custom transition to normal mode\n", deviceIdx); #endif - } + } - } - else { - DeviceHandlerBase::doTransition(modeFrom, submodeFrom); - } + } else { + DeviceHandlerBase::doTransition(modeFrom, submodeFrom); + } } -ReturnValue_t TestDevice::buildCommandFromCommand( - DeviceCommandId_t deviceCommand, const uint8_t* commandData, - size_t commandDataLen) { - using namespace testdevice; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - switch(deviceCommand) { - case(TEST_NORMAL_MODE_CMD): { - commandSent = true; - result = buildNormalModeCommand(deviceCommand, commandData, commandDataLen); - break; +ReturnValue_t TestDevice::buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t* commandData, + size_t commandDataLen) { + using namespace testdevice; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + switch (deviceCommand) { + case (TEST_NORMAL_MODE_CMD): { + commandSent = true; + result = buildNormalModeCommand(deviceCommand, commandData, commandDataLen); + break; } - case(TEST_COMMAND_0): { - commandSent = true; - result = buildTestCommand0(deviceCommand, commandData, commandDataLen); - break; + case (TEST_COMMAND_0): { + commandSent = true; + result = buildTestCommand0(deviceCommand, commandData, commandDataLen); + break; } - case(TEST_COMMAND_1): { - commandSent = true; - result = buildTestCommand1(deviceCommand, commandData, commandDataLen); - break; + case (TEST_COMMAND_1): { + commandSent = true; + result = buildTestCommand1(deviceCommand, commandData, commandDataLen); + break; } - case(TEST_NOTIF_SNAPSHOT_VAR): { - if(changingDatasets) { - changingDatasets = false; - } + case (TEST_NOTIF_SNAPSHOT_VAR): { + if (changingDatasets) { + changingDatasets = false; + } - PoolReadGuard readHelper(&dataset.testUint8Var); - if(deviceIdx == testdevice::DeviceIndex::DEVICE_0) { - /* This will trigger a variable notification to the demo controller */ - dataset.testUint8Var = 220; - dataset.testUint8Var.setValid(true); - } - else if(deviceIdx == testdevice::DeviceIndex::DEVICE_1) { - /* This will trigger a variable snapshot to the demo controller */ - dataset.testUint8Var = 30; - dataset.testUint8Var.setValid(true); - } + PoolReadGuard readHelper(&dataset.testUint8Var); + if (deviceIdx == testdevice::DeviceIndex::DEVICE_0) { + /* This will trigger a variable notification to the demo controller */ + dataset.testUint8Var = 220; + dataset.testUint8Var.setValid(true); + } else if (deviceIdx == testdevice::DeviceIndex::DEVICE_1) { + /* This will trigger a variable snapshot to the demo controller */ + dataset.testUint8Var = 30; + dataset.testUint8Var.setValid(true); + } - break; + break; } - case(TEST_NOTIF_SNAPSHOT_SET): { - if(changingDatasets) { - changingDatasets = false; - } + case (TEST_NOTIF_SNAPSHOT_SET): { + if (changingDatasets) { + changingDatasets = false; + } - PoolReadGuard readHelper(&dataset.testFloat3Vec); + PoolReadGuard readHelper(&dataset.testFloat3Vec); - if(deviceIdx == testdevice::DeviceIndex::DEVICE_0) { - /* This will trigger a variable notification to the demo controller */ - dataset.testFloat3Vec.value[0] = 60; - dataset.testFloat3Vec.value[1] = 70; - dataset.testFloat3Vec.value[2] = 55; - dataset.testFloat3Vec.setValid(true); - } - else if(deviceIdx == testdevice::DeviceIndex::DEVICE_1) { - /* This will trigger a variable notification to the demo controller */ - dataset.testFloat3Vec.value[0] = -60; - dataset.testFloat3Vec.value[1] = -70; - dataset.testFloat3Vec.value[2] = -55; - dataset.testFloat3Vec.setValid(true); - } - break; + if (deviceIdx == testdevice::DeviceIndex::DEVICE_0) { + /* This will trigger a variable notification to the demo controller */ + dataset.testFloat3Vec.value[0] = 60; + dataset.testFloat3Vec.value[1] = 70; + dataset.testFloat3Vec.value[2] = 55; + dataset.testFloat3Vec.setValid(true); + } else if (deviceIdx == testdevice::DeviceIndex::DEVICE_1) { + /* This will trigger a variable notification to the demo controller */ + dataset.testFloat3Vec.value[0] = -60; + dataset.testFloat3Vec.value[1] = -70; + dataset.testFloat3Vec.value[2] = -55; + dataset.testFloat3Vec.setValid(true); + } + break; } default: - result = DeviceHandlerIF::COMMAND_NOT_SUPPORTED; - } - return result; + result = DeviceHandlerIF::COMMAND_NOT_SUPPORTED; + } + return result; } - ReturnValue_t TestDevice::buildNormalModeCommand(DeviceCommandId_t deviceCommand, - const uint8_t* commandData, size_t commandDataLen) { - if(fullInfoPrintout) { + const uint8_t* commandData, + size_t commandDataLen) { + if (fullInfoPrintout) { #if OBSW_VERBOSE_LEVEL >= 3 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TestDevice::buildTestCommand1: Building normal command" << std::endl; + sif::info << "TestDevice::buildTestCommand1: Building normal command" << std::endl; #else - sif::printInfo("TestDevice::buildTestCommand1: Building command from TEST_COMMAND_1\n"); + sif::printInfo("TestDevice::buildTestCommand1: Building command from TEST_COMMAND_1\n"); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* OBSW_VERBOSE_LEVEL >= 3 */ - } + } - if(commandDataLen > MAX_BUFFER_SIZE - sizeof(DeviceCommandId_t)) { - return DeviceHandlerIF::INVALID_NUMBER_OR_LENGTH_OF_PARAMETERS; - } - /* The command is passed on in the command buffer as it is */ - passOnCommand(deviceCommand, commandData, commandDataLen); - return RETURN_OK; + if (commandDataLen > MAX_BUFFER_SIZE - sizeof(DeviceCommandId_t)) { + return DeviceHandlerIF::INVALID_NUMBER_OR_LENGTH_OF_PARAMETERS; + } + /* The command is passed on in the command buffer as it is */ + passOnCommand(deviceCommand, commandData, commandDataLen); + return RETURN_OK; } ReturnValue_t TestDevice::buildTestCommand0(DeviceCommandId_t deviceCommand, - const uint8_t* commandData, size_t commandDataLen) { - using namespace testdevice; - if(fullInfoPrintout) { + const uint8_t* commandData, size_t commandDataLen) { + using namespace testdevice; + if (fullInfoPrintout) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TestDevice" << deviceIdx << "::buildTestCommand0: Executing simple command " - " with completion reply" << std::endl; + sif::info << "TestDevice" << deviceIdx + << "::buildTestCommand0: Executing simple command " + " with completion reply" + << std::endl; #else - sif::printInfo("TestDevice%d::buildTestCommand0: Executing simple command with " - "completion reply\n", deviceIdx); + sif::printInfo( + "TestDevice%d::buildTestCommand0: Executing simple command with " + "completion reply\n", + deviceIdx); #endif - } + } - if(commandDataLen > MAX_BUFFER_SIZE - sizeof(DeviceCommandId_t)) { - return DeviceHandlerIF::INVALID_NUMBER_OR_LENGTH_OF_PARAMETERS; - } + if (commandDataLen > MAX_BUFFER_SIZE - sizeof(DeviceCommandId_t)) { + return DeviceHandlerIF::INVALID_NUMBER_OR_LENGTH_OF_PARAMETERS; + } - /* The command is passed on in the command buffer as it is */ - passOnCommand(deviceCommand, commandData, commandDataLen); - return RETURN_OK; + /* The command is passed on in the command buffer as it is */ + passOnCommand(deviceCommand, commandData, commandDataLen); + return RETURN_OK; } ReturnValue_t TestDevice::buildTestCommand1(DeviceCommandId_t deviceCommand, - const uint8_t* commandData, - size_t commandDataLen) { - using namespace testdevice; - if(commandDataLen < 7) { - return DeviceHandlerIF::INVALID_NUMBER_OR_LENGTH_OF_PARAMETERS; - } - if(fullInfoPrintout) { + const uint8_t* commandData, size_t commandDataLen) { + using namespace testdevice; + if (commandDataLen < 7) { + return DeviceHandlerIF::INVALID_NUMBER_OR_LENGTH_OF_PARAMETERS; + } + if (fullInfoPrintout) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TestDevice" << deviceIdx << "::buildTestCommand1: Executing command with " - "data reply" << std::endl; + sif::info << "TestDevice" << deviceIdx + << "::buildTestCommand1: Executing command with " + "data reply" + << std::endl; #else - sif::printInfo("TestDevice%d:buildTestCommand1: Executing command with data reply\n", - deviceIdx); + sif::printInfo("TestDevice%d:buildTestCommand1: Executing command with data reply\n", + deviceIdx); #endif - } + } - deviceCommand = EndianConverter::convertBigEndian(deviceCommand); - memcpy(commandBuffer, &deviceCommand, sizeof(deviceCommand)); + deviceCommand = EndianConverter::convertBigEndian(deviceCommand); + memcpy(commandBuffer, &deviceCommand, sizeof(deviceCommand)); - /* Assign and check parameters */ - uint16_t parameter1 = 0; - size_t size = commandDataLen; - ReturnValue_t result = SerializeAdapter::deSerialize(¶meter1, - &commandData, &size, SerializeIF::Endianness::BIG); - if(result == HasReturnvaluesIF::RETURN_FAILED) { - return result; - } + /* Assign and check parameters */ + uint16_t parameter1 = 0; + size_t size = commandDataLen; + ReturnValue_t result = + SerializeAdapter::deSerialize(¶meter1, &commandData, &size, SerializeIF::Endianness::BIG); + if (result == HasReturnvaluesIF::RETURN_FAILED) { + return result; + } - /* Parameter 1 needs to be correct */ - if(parameter1 != testdevice::COMMAND_1_PARAM1) { - return DeviceHandlerIF::INVALID_COMMAND_PARAMETER; - } - uint64_t parameter2 = 0; - result = SerializeAdapter::deSerialize(¶meter2, - &commandData, &size, SerializeIF::Endianness::BIG); - if(parameter2!= testdevice::COMMAND_1_PARAM2){ - return DeviceHandlerIF::INVALID_COMMAND_PARAMETER; - } + /* Parameter 1 needs to be correct */ + if (parameter1 != testdevice::COMMAND_1_PARAM1) { + return DeviceHandlerIF::INVALID_COMMAND_PARAMETER; + } + uint64_t parameter2 = 0; + result = + SerializeAdapter::deSerialize(¶meter2, &commandData, &size, SerializeIF::Endianness::BIG); + if (parameter2 != testdevice::COMMAND_1_PARAM2) { + return DeviceHandlerIF::INVALID_COMMAND_PARAMETER; + } - /* Pass on the parameters to the Echo IF */ - commandBuffer[4] = (parameter1 & 0xFF00) >> 8; - commandBuffer[5] = (parameter1 & 0xFF); - parameter2 = EndianConverter::convertBigEndian(parameter2); - memcpy(commandBuffer + 6, ¶meter2, sizeof(parameter2)); - rawPacket = commandBuffer; - rawPacketLen = sizeof(deviceCommand) + sizeof(parameter1) + - sizeof(parameter2); - return RETURN_OK; + /* Pass on the parameters to the Echo IF */ + commandBuffer[4] = (parameter1 & 0xFF00) >> 8; + commandBuffer[5] = (parameter1 & 0xFF); + parameter2 = EndianConverter::convertBigEndian(parameter2); + memcpy(commandBuffer + 6, ¶meter2, sizeof(parameter2)); + rawPacket = commandBuffer; + rawPacketLen = sizeof(deviceCommand) + sizeof(parameter1) + sizeof(parameter2); + return RETURN_OK; } -void TestDevice::passOnCommand(DeviceCommandId_t command, const uint8_t *commandData, - size_t commandDataLen) { - DeviceCommandId_t deviceCommandBe = EndianConverter::convertBigEndian(command); - memcpy(commandBuffer, &deviceCommandBe, sizeof(deviceCommandBe)); - memcpy(commandBuffer + 4, commandData, commandDataLen); - rawPacket = commandBuffer; - rawPacketLen = sizeof(deviceCommandBe) + commandDataLen; +void TestDevice::passOnCommand(DeviceCommandId_t command, const uint8_t* commandData, + size_t commandDataLen) { + DeviceCommandId_t deviceCommandBe = EndianConverter::convertBigEndian(command); + memcpy(commandBuffer, &deviceCommandBe, sizeof(deviceCommandBe)); + memcpy(commandBuffer + 4, commandData, commandDataLen); + rawPacket = commandBuffer; + rawPacketLen = sizeof(deviceCommandBe) + commandDataLen; } void TestDevice::fillCommandAndReplyMap() { - namespace td = testdevice; - insertInCommandAndReplyMap(testdevice::TEST_NORMAL_MODE_CMD, 5, &dataset); - insertInCommandAndReplyMap(testdevice::TEST_COMMAND_0, 5); - insertInCommandAndReplyMap(testdevice::TEST_COMMAND_1, 5); + namespace td = testdevice; + insertInCommandAndReplyMap(testdevice::TEST_NORMAL_MODE_CMD, 5, &dataset); + insertInCommandAndReplyMap(testdevice::TEST_COMMAND_0, 5); + insertInCommandAndReplyMap(testdevice::TEST_COMMAND_1, 5); - /* No reply expected for these commands */ - insertInCommandMap(td::TEST_NOTIF_SNAPSHOT_SET); - insertInCommandMap(td::TEST_NOTIF_SNAPSHOT_VAR); + /* No reply expected for these commands */ + insertInCommandMap(td::TEST_NOTIF_SNAPSHOT_SET); + insertInCommandMap(td::TEST_NOTIF_SNAPSHOT_VAR); } +ReturnValue_t TestDevice::scanForReply(const uint8_t* start, size_t len, DeviceCommandId_t* foundId, + size_t* foundLen) { + using namespace testdevice; -ReturnValue_t TestDevice::scanForReply(const uint8_t *start, size_t len, - DeviceCommandId_t *foundId, size_t *foundLen) { - using namespace testdevice; + /* Unless a command was sent explicitely, we don't expect any replies and ignore this + the packet. On a real device, there might be replies which are sent without a previous + command. */ + if (not commandSent) { + return DeviceHandlerBase::IGNORE_FULL_PACKET; + } else { + commandSent = false; + } - /* Unless a command was sent explicitely, we don't expect any replies and ignore this - the packet. On a real device, there might be replies which are sent without a previous - command. */ - if(not commandSent) { - return DeviceHandlerBase::IGNORE_FULL_PACKET; - } - else { - commandSent = false; - } + if (len < sizeof(object_id_t)) { + return DeviceHandlerIF::LENGTH_MISSMATCH; + } - if(len < sizeof(object_id_t)) { - return DeviceHandlerIF::LENGTH_MISSMATCH; - } + size_t size = len; + ReturnValue_t result = + SerializeAdapter::deSerialize(foundId, &start, &size, SerializeIF::Endianness::BIG); + if (result != RETURN_OK) { + return result; + } - size_t size = len; - ReturnValue_t result = SerializeAdapter::deSerialize(foundId, &start, &size, - SerializeIF::Endianness::BIG); - if (result != RETURN_OK) { - return result; - } + DeviceCommandId_t pendingCmd = this->getPendingCommand(); - DeviceCommandId_t pendingCmd = this->getPendingCommand(); - - switch(pendingCmd) { - - case(TEST_NORMAL_MODE_CMD): { - if(fullInfoPrintout) { + switch (pendingCmd) { + case (TEST_NORMAL_MODE_CMD): { + if (fullInfoPrintout) { #if OBSW_VERBOSE_LEVEL >= 3 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TestDevice::scanForReply: Reply for normal commnand (ID " << - TEST_NORMAL_MODE_CMD << ") received!" << std::endl; + sif::info << "TestDevice::scanForReply: Reply for normal commnand (ID " + << TEST_NORMAL_MODE_CMD << ") received!" << std::endl; #else - sif::printInfo("TestDevice%d::scanForReply: Reply for normal command (ID %d) " - "received!\n", deviceIdx, TEST_NORMAL_MODE_CMD); + sif::printInfo( + "TestDevice%d::scanForReply: Reply for normal command (ID %d) " + "received!\n", + deviceIdx, TEST_NORMAL_MODE_CMD); #endif #endif - } + } - *foundLen = len; - *foundId = pendingCmd; - return RETURN_OK; + *foundLen = len; + *foundId = pendingCmd; + return RETURN_OK; } - case(TEST_COMMAND_0): { - if(len < TEST_COMMAND_0_SIZE) { - return DeviceHandlerIF::LENGTH_MISSMATCH; - } - if(fullInfoPrintout) { + case (TEST_COMMAND_0): { + if (len < TEST_COMMAND_0_SIZE) { + return DeviceHandlerIF::LENGTH_MISSMATCH; + } + if (fullInfoPrintout) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TestDevice" << deviceIdx << "::scanForReply: Reply for simple command " - "(ID " << TEST_COMMAND_0 << ") received!" << std::endl; + sif::info << "TestDevice" << deviceIdx + << "::scanForReply: Reply for simple command " + "(ID " + << TEST_COMMAND_0 << ") received!" << std::endl; #else - sif::printInfo("TestDevice%d::scanForReply: Reply for simple command (ID %d) " - "received!\n", deviceIdx, TEST_COMMAND_0); + sif::printInfo( + "TestDevice%d::scanForReply: Reply for simple command (ID %d) " + "received!\n", + deviceIdx, TEST_COMMAND_0); #endif - } + } - *foundLen = TEST_COMMAND_0_SIZE; - *foundId = pendingCmd; - return RETURN_OK; + *foundLen = TEST_COMMAND_0_SIZE; + *foundId = pendingCmd; + return RETURN_OK; } - case(TEST_COMMAND_1): { - if(fullInfoPrintout) { + case (TEST_COMMAND_1): { + if (fullInfoPrintout) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TestDevice" << deviceIdx << "::scanForReply: Reply for data command " - "(ID " << TEST_COMMAND_1 << ") received!" << std::endl; + sif::info << "TestDevice" << deviceIdx + << "::scanForReply: Reply for data command " + "(ID " + << TEST_COMMAND_1 << ") received!" << std::endl; #else - sif::printInfo("TestDevice%d::scanForReply: Reply for data command (ID %d) " - "received\n", deviceIdx, TEST_COMMAND_1); + sif::printInfo( + "TestDevice%d::scanForReply: Reply for data command (ID %d) " + "received\n", + deviceIdx, TEST_COMMAND_1); #endif - } + } - *foundLen = len; - *foundId = pendingCmd; - return RETURN_OK; + *foundLen = len; + *foundId = pendingCmd; + return RETURN_OK; } default: - return DeviceHandlerIF::DEVICE_REPLY_INVALID; - } + return DeviceHandlerIF::DEVICE_REPLY_INVALID; + } } - -ReturnValue_t TestDevice::interpretDeviceReply(DeviceCommandId_t id, - const uint8_t* packet) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - switch(id) { +ReturnValue_t TestDevice::interpretDeviceReply(DeviceCommandId_t id, const uint8_t* packet) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + switch (id) { /* Periodic replies */ case testdevice::TEST_NORMAL_MODE_CMD: { - result = interpretingNormalModeReply(); - break; + result = interpretingNormalModeReply(); + break; } /* Simple reply */ case testdevice::TEST_COMMAND_0: { - result = interpretingTestReply0(id, packet); - break; + result = interpretingTestReply0(id, packet); + break; } /* Data reply */ case testdevice::TEST_COMMAND_1: { - result = interpretingTestReply1(id, packet); - break; + result = interpretingTestReply1(id, packet); + break; } default: - return DeviceHandlerIF::DEVICE_REPLY_INVALID; - } - return result; + return DeviceHandlerIF::DEVICE_REPLY_INVALID; + } + return result; } ReturnValue_t TestDevice::interpretingNormalModeReply() { - CommandMessage directReplyMessage; - if(changingDatasets) { - PoolReadGuard readHelper(&dataset); - if(dataset.testUint8Var.value == 0) { - dataset.testUint8Var.value = 10; - dataset.testUint32Var.value = 777; - dataset.testFloat3Vec.value[0] = 2.5; - dataset.testFloat3Vec.value[1] = -2.5; - dataset.testFloat3Vec.value[2] = 2.5; - dataset.setValidity(true, true); - } - else { - dataset.testUint8Var.value = 0; - dataset.testUint32Var.value = 0; - dataset.testFloat3Vec.value[0] = 0.0; - dataset.testFloat3Vec.value[1] = 0.0; - dataset.testFloat3Vec.value[2] = 0.0; - dataset.setValidity(false, true); - } - return RETURN_OK; - } - + CommandMessage directReplyMessage; + if (changingDatasets) { PoolReadGuard readHelper(&dataset); - if(dataset.testUint8Var.value == 0) { - /* Reset state */ - dataset.testUint8Var.value = 128; + if (dataset.testUint8Var.value == 0) { + dataset.testUint8Var.value = 10; + dataset.testUint32Var.value = 777; + dataset.testFloat3Vec.value[0] = 2.5; + dataset.testFloat3Vec.value[1] = -2.5; + dataset.testFloat3Vec.value[2] = 2.5; + dataset.setValidity(true, true); + } else { + dataset.testUint8Var.value = 0; + dataset.testUint32Var.value = 0; + dataset.testFloat3Vec.value[0] = 0.0; + dataset.testFloat3Vec.value[1] = 0.0; + dataset.testFloat3Vec.value[2] = 0.0; + dataset.setValidity(false, true); } - else if(dataset.testUint8Var.value > 200) { - if(not resetAfterChange) { - /* This will trigger an update notification to the controller */ - dataset.testUint8Var.setChanged(true); - resetAfterChange = true; - /* Decrement by 30 automatically. This will prevent any additional notifications. */ - dataset.testUint8Var.value -= 30; - } - } - /* If the value is greater than 0, it will be decremented in a linear way */ - else if(dataset.testUint8Var.value > 128) { - size_t sizeToDecrement = 0; - if(dataset.testUint8Var.value > 128 + 30) { - sizeToDecrement = 30; - } - else { - sizeToDecrement = dataset.testUint8Var.value - 128; - resetAfterChange = false; - } - dataset.testUint8Var.value -= sizeToDecrement; - } - else if(dataset.testUint8Var.value < 50) { - if(not resetAfterChange) { - /* This will trigger an update snapshot to the controller */ - dataset.testUint8Var.setChanged(true); - resetAfterChange = true; - } - else { - /* Increment by 30 automatically. */ - dataset.testUint8Var.value += 30; - } - } - /* Increment in linear way */ - else if(dataset.testUint8Var.value < 128) { - size_t sizeToIncrement = 0; - if(dataset.testUint8Var.value < 128 - 20) { - sizeToIncrement = 20; - } - else { - sizeToIncrement = 128 - dataset.testUint8Var.value; - resetAfterChange = false; - } - dataset.testUint8Var.value += sizeToIncrement; - } - - /* TODO: Same for vector */ - float vectorMean = (dataset.testFloat3Vec.value[0] + dataset.testFloat3Vec.value[1] + - dataset.testFloat3Vec.value[2]) / 3.0; - - /* Lambda (private local function) */ - auto sizeToAdd = [](bool tooHigh, float currentVal) { - if(tooHigh) { - if(currentVal - 20.0 > 10.0) { - return -10.0; - } - else { - return 20.0 - currentVal; - } - } - else { - if(std::abs(currentVal + 20.0) > 10.0) { - return 10.0; - } - else { - return -20.0 - currentVal; - } - } - }; - - if(vectorMean > 20.0 and std::abs(vectorMean - 20.0) > 1.0) { - if(not resetAfterChange) { - dataset.testFloat3Vec.setChanged(true); - resetAfterChange = true; - } - else { - float sizeToDecrementVal0 = 0; - float sizeToDecrementVal1 = 0; - float sizeToDecrementVal2 = 0; - - sizeToDecrementVal0 = sizeToAdd(true, dataset.testFloat3Vec.value[0]); - sizeToDecrementVal1 = sizeToAdd(true, dataset.testFloat3Vec.value[1]); - sizeToDecrementVal2 = sizeToAdd(true, dataset.testFloat3Vec.value[2]); - - dataset.testFloat3Vec.value[0] += sizeToDecrementVal0; - dataset.testFloat3Vec.value[1] += sizeToDecrementVal1; - dataset.testFloat3Vec.value[2] += sizeToDecrementVal2; - } - } - else if (vectorMean < -20.0 and std::abs(vectorMean + 20.0) < 1.0) { - if(not resetAfterChange) { - dataset.testFloat3Vec.setChanged(true); - resetAfterChange = true; - } - else { - float sizeToDecrementVal0 = 0; - float sizeToDecrementVal1 = 0; - float sizeToDecrementVal2 = 0; - - sizeToDecrementVal0 = sizeToAdd(false, dataset.testFloat3Vec.value[0]); - sizeToDecrementVal1 = sizeToAdd(false, dataset.testFloat3Vec.value[1]); - sizeToDecrementVal2 = sizeToAdd(false, dataset.testFloat3Vec.value[2]); - - dataset.testFloat3Vec.value[0] += sizeToDecrementVal0; - dataset.testFloat3Vec.value[1] += sizeToDecrementVal1; - dataset.testFloat3Vec.value[2] += sizeToDecrementVal2; - } - } - else { - if(resetAfterChange) { - resetAfterChange = false; - } - } - return RETURN_OK; + } + + PoolReadGuard readHelper(&dataset); + if (dataset.testUint8Var.value == 0) { + /* Reset state */ + dataset.testUint8Var.value = 128; + } else if (dataset.testUint8Var.value > 200) { + if (not resetAfterChange) { + /* This will trigger an update notification to the controller */ + dataset.testUint8Var.setChanged(true); + resetAfterChange = true; + /* Decrement by 30 automatically. This will prevent any additional notifications. */ + dataset.testUint8Var.value -= 30; + } + } + /* If the value is greater than 0, it will be decremented in a linear way */ + else if (dataset.testUint8Var.value > 128) { + size_t sizeToDecrement = 0; + if (dataset.testUint8Var.value > 128 + 30) { + sizeToDecrement = 30; + } else { + sizeToDecrement = dataset.testUint8Var.value - 128; + resetAfterChange = false; + } + dataset.testUint8Var.value -= sizeToDecrement; + } else if (dataset.testUint8Var.value < 50) { + if (not resetAfterChange) { + /* This will trigger an update snapshot to the controller */ + dataset.testUint8Var.setChanged(true); + resetAfterChange = true; + } else { + /* Increment by 30 automatically. */ + dataset.testUint8Var.value += 30; + } + } + /* Increment in linear way */ + else if (dataset.testUint8Var.value < 128) { + size_t sizeToIncrement = 0; + if (dataset.testUint8Var.value < 128 - 20) { + sizeToIncrement = 20; + } else { + sizeToIncrement = 128 - dataset.testUint8Var.value; + resetAfterChange = false; + } + dataset.testUint8Var.value += sizeToIncrement; + } + + /* TODO: Same for vector */ + float vectorMean = (dataset.testFloat3Vec.value[0] + dataset.testFloat3Vec.value[1] + + dataset.testFloat3Vec.value[2]) / + 3.0; + + /* Lambda (private local function) */ + auto sizeToAdd = [](bool tooHigh, float currentVal) { + if (tooHigh) { + if (currentVal - 20.0 > 10.0) { + return -10.0; + } else { + return 20.0 - currentVal; + } + } else { + if (std::abs(currentVal + 20.0) > 10.0) { + return 10.0; + } else { + return -20.0 - currentVal; + } + } + }; + + if (vectorMean > 20.0 and std::abs(vectorMean - 20.0) > 1.0) { + if (not resetAfterChange) { + dataset.testFloat3Vec.setChanged(true); + resetAfterChange = true; + } else { + float sizeToDecrementVal0 = 0; + float sizeToDecrementVal1 = 0; + float sizeToDecrementVal2 = 0; + + sizeToDecrementVal0 = sizeToAdd(true, dataset.testFloat3Vec.value[0]); + sizeToDecrementVal1 = sizeToAdd(true, dataset.testFloat3Vec.value[1]); + sizeToDecrementVal2 = sizeToAdd(true, dataset.testFloat3Vec.value[2]); + + dataset.testFloat3Vec.value[0] += sizeToDecrementVal0; + dataset.testFloat3Vec.value[1] += sizeToDecrementVal1; + dataset.testFloat3Vec.value[2] += sizeToDecrementVal2; + } + } else if (vectorMean < -20.0 and std::abs(vectorMean + 20.0) < 1.0) { + if (not resetAfterChange) { + dataset.testFloat3Vec.setChanged(true); + resetAfterChange = true; + } else { + float sizeToDecrementVal0 = 0; + float sizeToDecrementVal1 = 0; + float sizeToDecrementVal2 = 0; + + sizeToDecrementVal0 = sizeToAdd(false, dataset.testFloat3Vec.value[0]); + sizeToDecrementVal1 = sizeToAdd(false, dataset.testFloat3Vec.value[1]); + sizeToDecrementVal2 = sizeToAdd(false, dataset.testFloat3Vec.value[2]); + + dataset.testFloat3Vec.value[0] += sizeToDecrementVal0; + dataset.testFloat3Vec.value[1] += sizeToDecrementVal1; + dataset.testFloat3Vec.value[2] += sizeToDecrementVal2; + } + } else { + if (resetAfterChange) { + resetAfterChange = false; + } + } + + return RETURN_OK; } ReturnValue_t TestDevice::interpretingTestReply0(DeviceCommandId_t id, const uint8_t* packet) { - CommandMessage commandMessage; - if(fullInfoPrintout) { + CommandMessage commandMessage; + if (fullInfoPrintout) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TestDevice::interpretingTestReply0: Generating step and finish reply" << - std::endl; + sif::info << "TestDevice::interpretingTestReply0: Generating step and finish reply" + << std::endl; #else - sif::printInfo("TestDevice::interpretingTestReply0: Generating step and finish reply\n"); + sif::printInfo("TestDevice::interpretingTestReply0: Generating step and finish reply\n"); #endif - } + } - MessageQueueId_t commander = getCommanderQueueId(id); - /* Generate one step reply and the finish reply */ - actionHelper.step(1, commander, id); + MessageQueueId_t commander = getCommanderQueueId(id); + /* Generate one step reply and the finish reply */ + actionHelper.step(1, commander, id); + actionHelper.finish(true, commander, id); + + return RETURN_OK; +} + +ReturnValue_t TestDevice::interpretingTestReply1(DeviceCommandId_t id, const uint8_t* packet) { + CommandMessage directReplyMessage; + if (fullInfoPrintout) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::info << "TestDevice" << deviceIdx << "::interpretingReply1: Setting data reply" + << std::endl; +#else + sif::printInfo("TestDevice%d::interpretingReply1: Setting data reply\n", deviceIdx); +#endif + } + + MessageQueueId_t commander = getCommanderQueueId(id); + /* Send reply with data */ + ReturnValue_t result = + actionHelper.reportData(commander, id, packet, testdevice::TEST_COMMAND_1_SIZE, false); + + if (result != RETURN_OK) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::error << "TestDevice" << deviceIdx + << "::interpretingReply1: Sending data " + "reply failed!" + << std::endl; +#else + sif::printError("TestDevice%d::interpretingReply1: Sending data reply failed!\n", deviceIdx); +#endif + return result; + } + + if (result == HasReturnvaluesIF::RETURN_OK) { + /* Finish reply */ actionHelper.finish(true, commander, id); + } else { + /* Finish reply */ + actionHelper.finish(false, commander, id, result); + } - return RETURN_OK; + return RETURN_OK; } -ReturnValue_t TestDevice::interpretingTestReply1(DeviceCommandId_t id, - const uint8_t* packet) { - CommandMessage directReplyMessage; - if(fullInfoPrintout) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TestDevice" << deviceIdx << "::interpretingReply1: Setting data reply" << - std::endl; -#else - sif::printInfo("TestDevice%d::interpretingReply1: Setting data reply\n", deviceIdx); -#endif - } +uint32_t TestDevice::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 5000; } - MessageQueueId_t commander = getCommanderQueueId(id); - /* Send reply with data */ - ReturnValue_t result = actionHelper.reportData(commander, id, packet, - testdevice::TEST_COMMAND_1_SIZE, false); +void TestDevice::enableFullDebugOutput(bool enable) { this->fullInfoPrintout = enable; } - if (result != RETURN_OK) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "TestDevice" << deviceIdx << "::interpretingReply1: Sending data " - "reply failed!" << std::endl; -#else - sif::printError("TestDevice%d::interpretingReply1: Sending data reply failed!\n", - deviceIdx); -#endif - return result; - } +ReturnValue_t TestDevice::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) { + namespace td = testdevice; + localDataPoolMap.emplace(td::PoolIds::TEST_UINT8_ID, new PoolEntry({0})); + localDataPoolMap.emplace(td::PoolIds::TEST_UINT32_ID, new PoolEntry({0})); + localDataPoolMap.emplace(td::PoolIds::TEST_FLOAT_VEC_3_ID, new PoolEntry({0.0, 0.0, 0.0})); - if(result == HasReturnvaluesIF::RETURN_OK) { - /* Finish reply */ - actionHelper.finish(true, commander, id); - } - else { - /* Finish reply */ - actionHelper.finish(false, commander, id, result); - } - - return RETURN_OK; + sid_t sid(this->getObjectId(), td::TEST_SET_ID); + /* Subscribe for periodic HK packets but do not enable reporting for now. + Non-diangostic with a period of one second */ + poolManager.subscribeForPeriodicPacket(sid, false, 1.0, false); + return HasReturnvaluesIF::RETURN_OK; } -uint32_t TestDevice::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { - return 5000; -} - -void TestDevice::enableFullDebugOutput(bool enable) { - this->fullInfoPrintout = enable; -} - -ReturnValue_t TestDevice::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, - LocalDataPoolManager &poolManager) { - namespace td = testdevice; - localDataPoolMap.emplace(td::PoolIds::TEST_UINT8_ID, new PoolEntry({0})); - localDataPoolMap.emplace(td::PoolIds::TEST_UINT32_ID, new PoolEntry({0})); - localDataPoolMap.emplace(td::PoolIds::TEST_FLOAT_VEC_3_ID, - new PoolEntry({0.0, 0.0, 0.0})); - - sid_t sid(this->getObjectId(), td::TEST_SET_ID); - /* Subscribe for periodic HK packets but do not enable reporting for now. - Non-diangostic with a period of one second */ - poolManager.subscribeForPeriodicPacket(sid, false, 1.0, false); - return HasReturnvaluesIF::RETURN_OK; -} - - ReturnValue_t TestDevice::getParameter(uint8_t domainId, uint8_t uniqueId, - ParameterWrapper* parameterWrapper, const ParameterWrapper* newValues, - uint16_t startAtIndex) { - using namespace testdevice; - switch (uniqueId) { + ParameterWrapper* parameterWrapper, + const ParameterWrapper* newValues, uint16_t startAtIndex) { + using namespace testdevice; + switch (uniqueId) { case ParameterUniqueIds::TEST_UINT32_0: { - if(fullInfoPrintout) { - uint32_t newValue = 0; - ReturnValue_t result = newValues->getElement(&newValue, 0, 0); - if(result == HasReturnvaluesIF::RETURN_OK) { + if (fullInfoPrintout) { + uint32_t newValue = 0; + ReturnValue_t result = newValues->getElement(&newValue, 0, 0); + if (result == HasReturnvaluesIF::RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TestDevice" << deviceIdx << "::getParameter: Setting parameter 0 to " - "new value " << newValue << std::endl; + sif::info << "TestDevice" << deviceIdx + << "::getParameter: Setting parameter 0 to " + "new value " + << newValue << std::endl; #else - sif::printInfo("TestDevice%d::getParameter: Setting parameter 0 to new value %lu\n", - deviceIdx, static_cast(newValue)); + sif::printInfo("TestDevice%d::getParameter: Setting parameter 0 to new value %lu\n", + deviceIdx, static_cast(newValue)); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ - } } - parameterWrapper->set(testParameter0); - break; + } + parameterWrapper->set(testParameter0); + break; } case ParameterUniqueIds::TEST_INT32_1: { - if(fullInfoPrintout) { - int32_t newValue = 0; - ReturnValue_t result = newValues->getElement(&newValue, 0, 0); - if(result == HasReturnvaluesIF::RETURN_OK) { + if (fullInfoPrintout) { + int32_t newValue = 0; + ReturnValue_t result = newValues->getElement(&newValue, 0, 0); + if (result == HasReturnvaluesIF::RETURN_OK) { #if OBSW_DEVICE_HANDLER_PRINTOUT == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TestDevice" << deviceIdx << "::getParameter: Setting parameter 1 to " - "new value " << newValue << std::endl; + sif::info << "TestDevice" << deviceIdx + << "::getParameter: Setting parameter 1 to " + "new value " + << newValue << std::endl; #else - sif::printInfo("TestDevice%d::getParameter: Setting parameter 1 to new value %lu\n", - deviceIdx, static_cast(newValue)); + sif::printInfo("TestDevice%d::getParameter: Setting parameter 1 to new value %lu\n", + deviceIdx, static_cast(newValue)); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* OBSW_DEVICE_HANDLER_PRINTOUT == 1 */ - } } - parameterWrapper->set(testParameter1); - break; + } + parameterWrapper->set(testParameter1); + break; } case ParameterUniqueIds::TEST_FLOAT_VEC3_2: { - if(fullInfoPrintout) { - float newVector[3]; - if(newValues->getElement(newVector, 0, 0) != RETURN_OK or - newValues->getElement(newVector + 1, 0, 1) != RETURN_OK or - newValues->getElement(newVector + 2, 0, 2) != RETURN_OK) { - return HasReturnvaluesIF::RETURN_FAILED; - } + if (fullInfoPrintout) { + float newVector[3]; + if (newValues->getElement(newVector, 0, 0) != RETURN_OK or + newValues->getElement(newVector + 1, 0, 1) != RETURN_OK or + newValues->getElement(newVector + 2, 0, 2) != RETURN_OK) { + return HasReturnvaluesIF::RETURN_FAILED; + } #if OBSW_DEVICE_HANDLER_PRINTOUT == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TestDevice" << deviceIdx << "::getParameter: Setting parameter 3 to " - "(float vector with 3 entries) to new values [" << newVector[0] << ", " << - newVector[1] << ", " << newVector[2] << "]" << std::endl; + sif::info << "TestDevice" << deviceIdx + << "::getParameter: Setting parameter 3 to " + "(float vector with 3 entries) to new values [" + << newVector[0] << ", " << newVector[1] << ", " << newVector[2] << "]" + << std::endl; #else - sif::printInfo("TestDevice%d::getParameter: Setting parameter 3 to new values " - "[%f, %f, %f]\n", deviceIdx, newVector[0], newVector[1], newVector[2]); + sif::printInfo( + "TestDevice%d::getParameter: Setting parameter 3 to new values " + "[%f, %f, %f]\n", + deviceIdx, newVector[0], newVector[1], newVector[2]); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* OBSW_DEVICE_HANDLER_PRINTOUT == 1 */ - } - parameterWrapper->setVector(vectorFloatParams2); - break; + } + parameterWrapper->setVector(vectorFloatParams2); + break; } - case(ParameterUniqueIds::PERIODIC_PRINT_ENABLED): { - if(fullInfoPrintout) { - uint8_t enabled = 0; - ReturnValue_t result = newValues->getElement(&enabled, 0, 0); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - char const* printout = nullptr; - if (enabled) { - printout = "enabled"; - } - else { - printout = "disabled"; - } -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TestDevice" << deviceIdx << "::getParameter: Periodic printout " << - printout << std::endl; -#else - sif::printInfo("TestDevice%d::getParameter: Periodic printout %s", printout); -#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ - } - - parameterWrapper->set(periodicPrintout); - break; - } - case(ParameterUniqueIds::CHANGING_DATASETS): { - + case (ParameterUniqueIds::PERIODIC_PRINT_ENABLED): { + if (fullInfoPrintout) { uint8_t enabled = 0; ReturnValue_t result = newValues->getElement(&enabled, 0, 0); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; } - if(not enabled) { - PoolReadGuard readHelper(&dataset); - dataset.testUint8Var.value = 0; - dataset.testUint32Var.value = 0; - dataset.testFloat3Vec.value[0] = 0.0; - dataset.testFloat3Vec.value[0] = 0.0; - dataset.testFloat3Vec.value[1] = 0.0; + char const* printout = nullptr; + if (enabled) { + printout = "enabled"; + } else { + printout = "disabled"; } - - if(fullInfoPrintout) { - char const* printout = nullptr; - if (enabled) { - printout = "enabled"; - } - else { - printout = "disabled"; - } #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "TestDevice" << deviceIdx << "::getParameter: Changing datasets " << - printout << std::endl; + sif::info << "TestDevice" << deviceIdx << "::getParameter: Periodic printout " << printout + << std::endl; #else - sif::printInfo("TestDevice%d::getParameter: Changing datasets %s", printout); + sif::printInfo("TestDevice%d::getParameter: Periodic printout %s", printout); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ - } + } - parameterWrapper->set(changingDatasets); - break; + parameterWrapper->set(periodicPrintout); + break; + } + case (ParameterUniqueIds::CHANGING_DATASETS): { + uint8_t enabled = 0; + ReturnValue_t result = newValues->getElement(&enabled, 0, 0); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (not enabled) { + PoolReadGuard readHelper(&dataset); + dataset.testUint8Var.value = 0; + dataset.testUint32Var.value = 0; + dataset.testFloat3Vec.value[0] = 0.0; + dataset.testFloat3Vec.value[0] = 0.0; + dataset.testFloat3Vec.value[1] = 0.0; + } + + if (fullInfoPrintout) { + char const* printout = nullptr; + if (enabled) { + printout = "enabled"; + } else { + printout = "disabled"; + } +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::info << "TestDevice" << deviceIdx << "::getParameter: Changing datasets " << printout + << std::endl; +#else + sif::printInfo("TestDevice%d::getParameter: Changing datasets %s", printout); +#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ + } + + parameterWrapper->set(changingDatasets); + break; } default: - return INVALID_IDENTIFIER_ID; - } - return HasReturnvaluesIF::RETURN_OK; + return INVALID_IDENTIFIER_ID; + } + return HasReturnvaluesIF::RETURN_OK; } LocalPoolObjectBase* TestDevice::getPoolObjectHandle(lp_id_t localPoolId) { - namespace td = testdevice; - if (localPoolId == td::PoolIds::TEST_UINT8_ID) { - return &dataset.testUint8Var; - } - else if (localPoolId == td::PoolIds::TEST_UINT32_ID) { - return &dataset.testUint32Var; - } - else if(localPoolId == td::PoolIds::TEST_FLOAT_VEC_3_ID) { - return &dataset.testFloat3Vec; - } - else { - return nullptr; - } + namespace td = testdevice; + if (localPoolId == td::PoolIds::TEST_UINT8_ID) { + return &dataset.testUint8Var; + } else if (localPoolId == td::PoolIds::TEST_UINT32_ID) { + return &dataset.testUint32Var; + } else if (localPoolId == td::PoolIds::TEST_FLOAT_VEC_3_ID) { + return &dataset.testFloat3Vec; + } else { + return nullptr; + } } diff --git a/tests/src/fsfw_tests/integration/devices/TestDeviceHandler.h b/tests/src/fsfw_tests/integration/devices/TestDeviceHandler.h index 0eb47731..31931dad 100644 --- a/tests/src/fsfw_tests/integration/devices/TestDeviceHandler.h +++ b/tests/src/fsfw_tests/integration/devices/TestDeviceHandler.h @@ -2,7 +2,6 @@ #define TEST_TESTDEVICES_TESTDEVICEHANDLER_H_ #include "devicedefinitions/testDeviceDefinitions.h" - #include "fsfw/devicehandlers/DeviceHandlerBase.h" #include "fsfw/globalfunctions/PeriodicOperationDivider.h" #include "fsfw/timemanager/Countdown.h" @@ -22,121 +21,114 @@ * @author R. Mueller * @ingroup devices */ -class TestDevice: public DeviceHandlerBase { -public: - /** - * Build the test device in the factory. - * @param objectId This ID will be assigned to the test device handler. - * @param comIF The ID of the Communication IF used by test device handler. - * @param cookie Cookie object used by the test device handler. This is - * also used and passed to the comIF object. - * @param onImmediately This will start a transition to MODE_ON immediately - * so the device handler jumps into #doStartUp. Should only be used - * in development to reduce need of commanding while debugging. - * @param changingDataset - * Will be used later to change the local datasets containeds in the device. - */ - TestDevice(object_id_t objectId, object_id_t comIF, CookieIF * cookie, - testdevice::DeviceIndex deviceIdx = testdevice::DeviceIndex::DEVICE_0, - bool fullInfoPrintout = false, bool changingDataset = true); +class TestDevice : public DeviceHandlerBase { + public: + /** + * Build the test device in the factory. + * @param objectId This ID will be assigned to the test device handler. + * @param comIF The ID of the Communication IF used by test device handler. + * @param cookie Cookie object used by the test device handler. This is + * also used and passed to the comIF object. + * @param onImmediately This will start a transition to MODE_ON immediately + * so the device handler jumps into #doStartUp. Should only be used + * in development to reduce need of commanding while debugging. + * @param changingDataset + * Will be used later to change the local datasets containeds in the device. + */ + TestDevice(object_id_t objectId, object_id_t comIF, CookieIF* cookie, + testdevice::DeviceIndex deviceIdx = testdevice::DeviceIndex::DEVICE_0, + bool fullInfoPrintout = false, bool changingDataset = true); - /** - * This can be used to enable and disable a lot of demo print output. - * @param enable - */ - void enableFullDebugOutput(bool enable); + /** + * This can be used to enable and disable a lot of demo print output. + * @param enable + */ + void enableFullDebugOutput(bool enable); - virtual ~ TestDevice(); + virtual ~TestDevice(); - //! Size of internal buffer used for communication. - static constexpr uint8_t MAX_BUFFER_SIZE = 255; + //! Size of internal buffer used for communication. + static constexpr uint8_t MAX_BUFFER_SIZE = 255; - //! Unique index if the device handler is created multiple times. - testdevice::DeviceIndex deviceIdx = testdevice::DeviceIndex::DEVICE_0; + //! Unique index if the device handler is created multiple times. + testdevice::DeviceIndex deviceIdx = testdevice::DeviceIndex::DEVICE_0; -protected: - testdevice::TestDataSet dataset; - //! This is used to reset the dataset after a commanded change has been made. - bool resetAfterChange = false; - bool commandSent = false; + protected: + testdevice::TestDataSet dataset; + //! This is used to reset the dataset after a commanded change has been made. + bool resetAfterChange = false; + bool commandSent = false; - /** DeviceHandlerBase overrides (see DHB documentation) */ + /** DeviceHandlerBase overrides (see DHB documentation) */ - /** - * Hook into the DHB #performOperation call which is executed - * periodically. - */ - void performOperationHook() override; + /** + * Hook into the DHB #performOperation call which is executed + * periodically. + */ + void performOperationHook() override; - virtual void doStartUp() override; - virtual void doShutDown() override; + virtual void doStartUp() override; + virtual void doShutDown() override; - virtual ReturnValue_t buildNormalDeviceCommand( - DeviceCommandId_t * id) override; - virtual ReturnValue_t buildTransitionDeviceCommand( - DeviceCommandId_t * id) override; - virtual ReturnValue_t buildCommandFromCommand(DeviceCommandId_t - deviceCommand, const uint8_t * commandData, - size_t commandDataLen) override; + virtual ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t* id) override; + virtual ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t* id) override; + virtual ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t* commandData, + size_t commandDataLen) override; - virtual void fillCommandAndReplyMap() override; + virtual void fillCommandAndReplyMap() override; - virtual ReturnValue_t scanForReply(const uint8_t *start, size_t len, - DeviceCommandId_t *foundId, size_t *foundLen) override; - virtual ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, - const uint8_t *packet) override; - virtual uint32_t getTransitionDelayMs(Mode_t modeFrom, - Mode_t modeTo) override; + virtual ReturnValue_t scanForReply(const uint8_t* start, size_t len, DeviceCommandId_t* foundId, + size_t* foundLen) override; + virtual ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t* packet) override; + virtual uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; - virtual void doTransition(Mode_t modeFrom, Submode_t subModeFrom) override; + virtual void doTransition(Mode_t modeFrom, Submode_t subModeFrom) override; - virtual ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, - LocalDataPoolManager& poolManager) override; - virtual LocalPoolObjectBase* getPoolObjectHandle(lp_id_t localPoolId) override; + virtual ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) override; + virtual LocalPoolObjectBase* getPoolObjectHandle(lp_id_t localPoolId) override; - /* HasParametersIF overrides */ - virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, - ParameterWrapper *parameterWrapper, - const ParameterWrapper *newValues, uint16_t startAtIndex) override; + /* HasParametersIF overrides */ + virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, + ParameterWrapper* parameterWrapper, + const ParameterWrapper* newValues, + uint16_t startAtIndex) override; - uint8_t commandBuffer[MAX_BUFFER_SIZE]; + uint8_t commandBuffer[MAX_BUFFER_SIZE]; - bool fullInfoPrintout = false; - bool oneShot = true; + bool fullInfoPrintout = false; + bool oneShot = true; - /* Variables for parameter service */ - uint32_t testParameter0 = 0; - int32_t testParameter1 = -2; - float vectorFloatParams2[3] = {}; + /* Variables for parameter service */ + uint32_t testParameter0 = 0; + int32_t testParameter1 = -2; + float vectorFloatParams2[3] = {}; - /* Change device handler functionality, changeable via parameter service */ - uint8_t periodicPrintout = false; - uint8_t changingDatasets = false; + /* Change device handler functionality, changeable via parameter service */ + uint8_t periodicPrintout = false; + uint8_t changingDatasets = false; - ReturnValue_t buildNormalModeCommand(DeviceCommandId_t deviceCommand, - const uint8_t* commandData, size_t commandDataLen); - ReturnValue_t buildTestCommand0(DeviceCommandId_t deviceCommand, const uint8_t* commandData, - size_t commandDataLen); - ReturnValue_t buildTestCommand1(DeviceCommandId_t deviceCommand, const uint8_t* commandData, - size_t commandDataLen); - void passOnCommand(DeviceCommandId_t command, const uint8_t* commandData, - size_t commandDataLen); + ReturnValue_t buildNormalModeCommand(DeviceCommandId_t deviceCommand, const uint8_t* commandData, + size_t commandDataLen); + ReturnValue_t buildTestCommand0(DeviceCommandId_t deviceCommand, const uint8_t* commandData, + size_t commandDataLen); + ReturnValue_t buildTestCommand1(DeviceCommandId_t deviceCommand, const uint8_t* commandData, + size_t commandDataLen); + void passOnCommand(DeviceCommandId_t command, const uint8_t* commandData, size_t commandDataLen); - ReturnValue_t interpretingNormalModeReply(); - ReturnValue_t interpretingTestReply0(DeviceCommandId_t id, - const uint8_t* packet); - ReturnValue_t interpretingTestReply1(DeviceCommandId_t id, - const uint8_t* packet); - ReturnValue_t interpretingTestReply2(DeviceCommandId_t id, const uint8_t* packet); + ReturnValue_t interpretingNormalModeReply(); + ReturnValue_t interpretingTestReply0(DeviceCommandId_t id, const uint8_t* packet); + ReturnValue_t interpretingTestReply1(DeviceCommandId_t id, const uint8_t* packet); + ReturnValue_t interpretingTestReply2(DeviceCommandId_t id, const uint8_t* packet); - /* Some timer utilities */ - uint8_t divider1 = 2; - PeriodicOperationDivider opDivider1 = PeriodicOperationDivider(divider1); - uint8_t divider2 = 10; - PeriodicOperationDivider opDivider2 = PeriodicOperationDivider(divider2); - static constexpr uint32_t initTimeout = 2000; - Countdown countdown1 = Countdown(initTimeout); + /* Some timer utilities */ + uint8_t divider1 = 2; + PeriodicOperationDivider opDivider1 = PeriodicOperationDivider(divider1); + uint8_t divider2 = 10; + PeriodicOperationDivider opDivider2 = PeriodicOperationDivider(divider2); + static constexpr uint32_t initTimeout = 2000; + Countdown countdown1 = Countdown(initTimeout); }; - #endif /* TEST_TESTDEVICES_TESTDEVICEHANDLER_H_ */ diff --git a/tests/src/fsfw_tests/integration/devices/TestEchoComIF.cpp b/tests/src/fsfw_tests/integration/devices/TestEchoComIF.cpp index afb23a06..727381a2 100644 --- a/tests/src/fsfw_tests/integration/devices/TestEchoComIF.cpp +++ b/tests/src/fsfw_tests/integration/devices/TestEchoComIF.cpp @@ -1,86 +1,82 @@ #include "TestEchoComIF.h" -#include "TestCookie.h" #include #include -#include #include +#include +#include "TestCookie.h" -TestEchoComIF::TestEchoComIF(object_id_t objectId): - SystemObject(objectId) { -} +TestEchoComIF::TestEchoComIF(object_id_t objectId) : SystemObject(objectId) {} TestEchoComIF::~TestEchoComIF() {} -ReturnValue_t TestEchoComIF::initializeInterface(CookieIF * cookie) { - TestCookie* dummyCookie = dynamic_cast(cookie); - if(dummyCookie == nullptr) { +ReturnValue_t TestEchoComIF::initializeInterface(CookieIF *cookie) { + TestCookie *dummyCookie = dynamic_cast(cookie); + if (dummyCookie == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "TestEchoComIF::initializeInterface: Invalid cookie!" << std::endl; + sif::warning << "TestEchoComIF::initializeInterface: Invalid cookie!" << std::endl; #else - sif::printWarning("TestEchoComIF::initializeInterface: Invalid cookie!\n"); + sif::printWarning("TestEchoComIF::initializeInterface: Invalid cookie!\n"); #endif - return NULLPOINTER; - } + return NULLPOINTER; + } - auto resultPair = replyMap.emplace( - dummyCookie->getAddress(), ReplyBuffer(dummyCookie->getReplyMaxLen())); - if(not resultPair.second) { - return HasReturnvaluesIF::RETURN_FAILED; - } - return RETURN_OK; + auto resultPair = + replyMap.emplace(dummyCookie->getAddress(), ReplyBuffer(dummyCookie->getReplyMaxLen())); + if (not resultPair.second) { + return HasReturnvaluesIF::RETURN_FAILED; + } + return RETURN_OK; } -ReturnValue_t TestEchoComIF::sendMessage(CookieIF *cookie, - const uint8_t * sendData, size_t sendLen) { - TestCookie* dummyCookie = dynamic_cast(cookie); - if(dummyCookie == nullptr) { - return NULLPOINTER; - } +ReturnValue_t TestEchoComIF::sendMessage(CookieIF *cookie, const uint8_t *sendData, + size_t sendLen) { + TestCookie *dummyCookie = dynamic_cast(cookie); + if (dummyCookie == nullptr) { + return NULLPOINTER; + } - ReplyBuffer& replyBuffer = replyMap.find(dummyCookie->getAddress())->second; - if(sendLen > replyBuffer.capacity()) { + ReplyBuffer &replyBuffer = replyMap.find(dummyCookie->getAddress())->second; + if (sendLen > replyBuffer.capacity()) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "TestEchoComIF::sendMessage: Send length " << sendLen << " larger than " - "current reply buffer length!" << std::endl; + sif::warning << "TestEchoComIF::sendMessage: Send length " << sendLen + << " larger than " + "current reply buffer length!" + << std::endl; #else - sif::printWarning("TestEchoComIF::sendMessage: Send length %d larger than current " - "reply buffer length!\n", sendLen); + sif::printWarning( + "TestEchoComIF::sendMessage: Send length %d larger than current " + "reply buffer length!\n", + sendLen); #endif - return HasReturnvaluesIF::RETURN_FAILED; - } - replyBuffer.resize(sendLen); - memcpy(replyBuffer.data(), sendData, sendLen); - return RETURN_OK; + return HasReturnvaluesIF::RETURN_FAILED; + } + replyBuffer.resize(sendLen); + memcpy(replyBuffer.data(), sendData, sendLen); + return RETURN_OK; } -ReturnValue_t TestEchoComIF::getSendSuccess(CookieIF *cookie) { - return RETURN_OK; +ReturnValue_t TestEchoComIF::getSendSuccess(CookieIF *cookie) { return RETURN_OK; } + +ReturnValue_t TestEchoComIF::requestReceiveMessage(CookieIF *cookie, size_t requestLen) { + return RETURN_OK; } -ReturnValue_t TestEchoComIF::requestReceiveMessage(CookieIF *cookie, - size_t requestLen) { - return RETURN_OK; +ReturnValue_t TestEchoComIF::readReceivedMessage(CookieIF *cookie, uint8_t **buffer, size_t *size) { + TestCookie *dummyCookie = dynamic_cast(cookie); + if (dummyCookie == nullptr) { + return NULLPOINTER; + } + + ReplyBuffer &replyBuffer = replyMap.find(dummyCookie->getAddress())->second; + *buffer = replyBuffer.data(); + *size = replyBuffer.size(); + + dummyReplyCounter++; + if (dummyReplyCounter == 10) { + // add anything that needs to be read periodically by dummy handler + dummyReplyCounter = 0; + } + return RETURN_OK; } - -ReturnValue_t TestEchoComIF::readReceivedMessage(CookieIF *cookie, - uint8_t **buffer, size_t *size) { - TestCookie* dummyCookie = dynamic_cast(cookie); - if(dummyCookie == nullptr) { - return NULLPOINTER; - } - - ReplyBuffer& replyBuffer = replyMap.find(dummyCookie->getAddress())->second; - *buffer = replyBuffer.data(); - *size = replyBuffer.size(); - - dummyReplyCounter ++; - if(dummyReplyCounter == 10) { - // add anything that needs to be read periodically by dummy handler - dummyReplyCounter = 0; - } - return RETURN_OK; - -} - diff --git a/tests/src/fsfw_tests/integration/devices/TestEchoComIF.h b/tests/src/fsfw_tests/integration/devices/TestEchoComIF.h index 38270cfe..39b8010f 100644 --- a/tests/src/fsfw_tests/integration/devices/TestEchoComIF.h +++ b/tests/src/fsfw_tests/integration/devices/TestEchoComIF.h @@ -2,8 +2,8 @@ #define TEST_TESTDEVICES_TESTECHOCOMIF_H_ #include -#include #include +#include #include #include @@ -13,44 +13,40 @@ * @details Assign this com IF in the factory when creating the device handler * @ingroup test */ -class TestEchoComIF: public DeviceCommunicationIF, public SystemObject { -public: - TestEchoComIF(object_id_t objectId); - virtual ~TestEchoComIF(); +class TestEchoComIF : public DeviceCommunicationIF, public SystemObject { + public: + TestEchoComIF(object_id_t objectId); + virtual ~TestEchoComIF(); - /** - * DeviceCommunicationIF overrides - * (see DeviceCommunicationIF documentation - */ - ReturnValue_t initializeInterface(CookieIF * cookie) override; - ReturnValue_t sendMessage(CookieIF *cookie, const uint8_t * sendData, - size_t sendLen) override; - ReturnValue_t getSendSuccess(CookieIF *cookie) override; - ReturnValue_t requestReceiveMessage(CookieIF *cookie, - size_t requestLen) override; - ReturnValue_t readReceivedMessage(CookieIF *cookie, uint8_t **buffer, - size_t *size) override; + /** + * DeviceCommunicationIF overrides + * (see DeviceCommunicationIF documentation + */ + ReturnValue_t initializeInterface(CookieIF *cookie) override; + ReturnValue_t sendMessage(CookieIF *cookie, const uint8_t *sendData, size_t sendLen) override; + ReturnValue_t getSendSuccess(CookieIF *cookie) override; + ReturnValue_t requestReceiveMessage(CookieIF *cookie, size_t requestLen) override; + ReturnValue_t readReceivedMessage(CookieIF *cookie, uint8_t **buffer, size_t *size) override; -private: + private: + /** + * Send TM packet which contains received data as TM[17,130]. + * Wiretapping will do the same. + * @param data + * @param len + */ + void sendTmPacket(const uint8_t *data, uint32_t len); - /** - * Send TM packet which contains received data as TM[17,130]. - * Wiretapping will do the same. - * @param data - * @param len - */ - void sendTmPacket(const uint8_t *data,uint32_t len); + AcceptsTelemetryIF *funnel = nullptr; + MessageQueueIF *tmQueue = nullptr; + size_t replyMaxLen = 0; - AcceptsTelemetryIF* funnel = nullptr; - MessageQueueIF* tmQueue = nullptr; - size_t replyMaxLen = 0; + using ReplyBuffer = std::vector; + std::map replyMap; - using ReplyBuffer = std::vector; - std::map replyMap; + uint8_t dummyReplyCounter = 0; - uint8_t dummyReplyCounter = 0; - - uint16_t packetSubCounter = 0; + uint16_t packetSubCounter = 0; }; #endif /* TEST_TESTDEVICES_TESTECHOCOMIF_H_ */ diff --git a/tests/src/fsfw_tests/integration/devices/devicedefinitions/testDeviceDefinitions.h b/tests/src/fsfw_tests/integration/devices/devicedefinitions/testDeviceDefinitions.h index 1c112e3f..00db9bd3 100644 --- a/tests/src/fsfw_tests/integration/devices/devicedefinitions/testDeviceDefinitions.h +++ b/tests/src/fsfw_tests/integration/devices/devicedefinitions/testDeviceDefinitions.h @@ -6,18 +6,15 @@ namespace testdevice { -enum ParameterUniqueIds: uint8_t { - TEST_UINT32_0, - TEST_INT32_1, - TEST_FLOAT_VEC3_2, - PERIODIC_PRINT_ENABLED, - CHANGING_DATASETS +enum ParameterUniqueIds : uint8_t { + TEST_UINT32_0, + TEST_INT32_1, + TEST_FLOAT_VEC3_2, + PERIODIC_PRINT_ENABLED, + CHANGING_DATASETS }; -enum DeviceIndex: uint32_t { - DEVICE_0, - DEVICE_1 -}; +enum DeviceIndex : uint32_t { DEVICE_0, DEVICE_1 }; /** Normal mode command. This ID is also used to access the set variable via the housekeeping service */ @@ -59,39 +56,34 @@ static constexpr DeviceCommandId_t TEST_SNAPSHOT = 5; //! Generates a random value for variable 1 of the dataset. static constexpr DeviceCommandId_t GENERATE_SET_VAR_1_RNG_VALUE = 6; - /** * These parameters are sent back with the command ID as a data reply */ -static constexpr uint16_t COMMAND_1_PARAM1 = 0xBAB0; //!< param1, 2 bytes +static constexpr uint16_t COMMAND_1_PARAM1 = 0xBAB0; //!< param1, 2 bytes //! param2, 8 bytes static constexpr uint64_t COMMAND_1_PARAM2 = 0x000000524F42494E; static constexpr size_t TEST_COMMAND_0_SIZE = sizeof(TEST_COMMAND_0); -static constexpr size_t TEST_COMMAND_1_SIZE = sizeof(TEST_COMMAND_1) + sizeof(COMMAND_1_PARAM1) + - sizeof(COMMAND_1_PARAM2); +static constexpr size_t TEST_COMMAND_1_SIZE = + sizeof(TEST_COMMAND_1) + sizeof(COMMAND_1_PARAM1) + sizeof(COMMAND_1_PARAM2); -enum PoolIds: lp_id_t { - TEST_UINT8_ID = 0, - TEST_UINT32_ID = 1, - TEST_FLOAT_VEC_3_ID = 2 -}; +enum PoolIds : lp_id_t { TEST_UINT8_ID = 0, TEST_UINT32_ID = 1, TEST_FLOAT_VEC_3_ID = 2 }; static constexpr uint8_t TEST_SET_ID = TEST_NORMAL_MODE_CMD; -class TestDataSet: public StaticLocalDataSet<3> { -public: - TestDataSet(HasLocalDataPoolIF* owner): StaticLocalDataSet(owner, TEST_SET_ID) {} - TestDataSet(object_id_t owner): StaticLocalDataSet(sid_t(owner, TEST_SET_ID)) {} +class TestDataSet : public StaticLocalDataSet<3> { + public: + TestDataSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, TEST_SET_ID) {} + TestDataSet(object_id_t owner) : StaticLocalDataSet(sid_t(owner, TEST_SET_ID)) {} - lp_var_t testUint8Var = lp_var_t( - gp_id_t(this->getCreatorObjectId(), PoolIds::TEST_UINT8_ID), this); - lp_var_t testUint32Var = lp_var_t( - gp_id_t(this->getCreatorObjectId(), PoolIds::TEST_UINT32_ID), this); - lp_vec_t testFloat3Vec = lp_vec_t( - gp_id_t(this->getCreatorObjectId(), PoolIds::TEST_FLOAT_VEC_3_ID), this); + lp_var_t testUint8Var = + lp_var_t(gp_id_t(this->getCreatorObjectId(), PoolIds::TEST_UINT8_ID), this); + lp_var_t testUint32Var = + lp_var_t(gp_id_t(this->getCreatorObjectId(), PoolIds::TEST_UINT32_ID), this); + lp_vec_t testFloat3Vec = + lp_vec_t(gp_id_t(this->getCreatorObjectId(), PoolIds::TEST_FLOAT_VEC_3_ID), this); }; -} +} // namespace testdevice #endif /* MISSION_DEVICES_DEVICEDEFINITIONS_TESTDEVICEDEFINITIONS_H_ */ diff --git a/tests/src/fsfw_tests/integration/task/TestTask.cpp b/tests/src/fsfw_tests/integration/task/TestTask.cpp index b33bd51c..65e444e3 100644 --- a/tests/src/fsfw_tests/integration/task/TestTask.cpp +++ b/tests/src/fsfw_tests/integration/task/TestTask.cpp @@ -6,63 +6,58 @@ bool TestTask::oneShotAction = true; MutexIF* TestTask::testLock = nullptr; -TestTask::TestTask(object_id_t objectId): - SystemObject(objectId), testMode(testModes::A) { - if(testLock == nullptr) { - testLock = MutexFactory::instance()->createMutex(); - } - IPCStore = ObjectManager::instance()->get(objects::IPC_STORE); +TestTask::TestTask(object_id_t objectId) : SystemObject(objectId), testMode(testModes::A) { + if (testLock == nullptr) { + testLock = MutexFactory::instance()->createMutex(); + } + IPCStore = ObjectManager::instance()->get(objects::IPC_STORE); } -TestTask::~TestTask() { -} +TestTask::~TestTask() {} ReturnValue_t TestTask::performOperation(uint8_t operationCode) { - ReturnValue_t result = RETURN_OK; - testLock->lockMutex(MutexIF::TimeoutType::WAITING, 20); - if(oneShotAction) { - // Add code here which should only be run once - performOneShotAction(); - oneShotAction = false; - } - testLock->unlockMutex(); + ReturnValue_t result = RETURN_OK; + testLock->lockMutex(MutexIF::TimeoutType::WAITING, 20); + if (oneShotAction) { + // Add code here which should only be run once + performOneShotAction(); + oneShotAction = false; + } + testLock->unlockMutex(); - // Add code here which should only be run once per performOperation - performPeriodicAction(); + // Add code here which should only be run once per performOperation + performPeriodicAction(); - // Add code here which should only be run on alternating cycles. - if(testMode == testModes::A) { - performActionA(); - testMode = testModes::B; - } - else if(testMode == testModes::B) { - performActionB(); - testMode = testModes::A; - } - return result; + // Add code here which should only be run on alternating cycles. + if (testMode == testModes::A) { + performActionA(); + testMode = testModes::B; + } else if (testMode == testModes::B) { + performActionB(); + testMode = testModes::A; + } + return result; } ReturnValue_t TestTask::performOneShotAction() { - /* Everything here will only be performed once. */ - return HasReturnvaluesIF::RETURN_OK; + /* Everything here will only be performed once. */ + return HasReturnvaluesIF::RETURN_OK; } - ReturnValue_t TestTask::performPeriodicAction() { - /* This is performed each task cycle */ - ReturnValue_t result = RETURN_OK; - return result; + /* This is performed each task cycle */ + ReturnValue_t result = RETURN_OK; + return result; } ReturnValue_t TestTask::performActionA() { - /* This is performed each alternating task cycle */ - ReturnValue_t result = RETURN_OK; - return result; + /* This is performed each alternating task cycle */ + ReturnValue_t result = RETURN_OK; + return result; } ReturnValue_t TestTask::performActionB() { - /* This is performed each alternating task cycle */ - ReturnValue_t result = RETURN_OK; - return result; + /* This is performed each alternating task cycle */ + ReturnValue_t result = RETURN_OK; + return result; } - diff --git a/tests/src/fsfw_tests/integration/task/TestTask.h b/tests/src/fsfw_tests/integration/task/TestTask.h index e56b5581..557b50b2 100644 --- a/tests/src/fsfw_tests/integration/task/TestTask.h +++ b/tests/src/fsfw_tests/integration/task/TestTask.h @@ -1,9 +1,9 @@ #ifndef MISSION_DEMO_TESTTASK_H_ #define MISSION_DEMO_TESTTASK_H_ -#include #include #include +#include /** * @brief Test class for general C++ testing and any other code which will not be part of the @@ -11,33 +11,27 @@ * @details * Should not be used for board specific tests. Instead, a derived board test class should be used. */ -class TestTask : - public SystemObject, - public ExecutableObjectIF, - public HasReturnvaluesIF { -public: - TestTask(object_id_t objectId); - virtual ~TestTask(); - virtual ReturnValue_t performOperation(uint8_t operationCode = 0) override; +class TestTask : public SystemObject, public ExecutableObjectIF, public HasReturnvaluesIF { + public: + TestTask(object_id_t objectId); + virtual ~TestTask(); + virtual ReturnValue_t performOperation(uint8_t operationCode = 0) override; -protected: - virtual ReturnValue_t performOneShotAction(); - virtual ReturnValue_t performPeriodicAction(); - virtual ReturnValue_t performActionA(); - virtual ReturnValue_t performActionB(); + protected: + virtual ReturnValue_t performOneShotAction(); + virtual ReturnValue_t performPeriodicAction(); + virtual ReturnValue_t performActionA(); + virtual ReturnValue_t performActionB(); - enum testModes: uint8_t { - A, - B - }; + enum testModes : uint8_t { A, B }; - testModes testMode; - bool testFlag = false; + testModes testMode; + bool testFlag = false; -private: - static bool oneShotAction; - static MutexIF* testLock; - StorageManagerIF* IPCStore; + private: + static bool oneShotAction; + static MutexIF* testLock; + StorageManagerIF* IPCStore; }; #endif /* TESTTASK_H_ */ diff --git a/tests/src/fsfw_tests/internal/InternalUnitTester.cpp b/tests/src/fsfw_tests/internal/InternalUnitTester.cpp index 3c8eec1e..4e45d25b 100644 --- a/tests/src/fsfw_tests/internal/InternalUnitTester.cpp +++ b/tests/src/fsfw_tests/internal/InternalUnitTester.cpp @@ -1,45 +1,41 @@ #include "fsfw_tests/internal/InternalUnitTester.h" -#include "fsfw_tests/internal/UnittDefinitions.h" - -#include "fsfw_tests/internal/osal/testMq.h" -#include "fsfw_tests/internal/osal/testSemaphore.h" -#include "fsfw_tests/internal/osal/testMutex.h" -#include "fsfw_tests/internal/serialize/IntTestSerialization.h" -#include "fsfw_tests/internal/globalfunctions/TestArrayPrinter.h" #include +#include "fsfw_tests/internal/UnittDefinitions.h" +#include "fsfw_tests/internal/globalfunctions/TestArrayPrinter.h" +#include "fsfw_tests/internal/osal/testMq.h" +#include "fsfw_tests/internal/osal/testMutex.h" +#include "fsfw_tests/internal/osal/testSemaphore.h" +#include "fsfw_tests/internal/serialize/IntTestSerialization.h" + InternalUnitTester::InternalUnitTester() {} InternalUnitTester::~InternalUnitTester() {} ReturnValue_t InternalUnitTester::performTests( - const struct InternalUnitTester::TestConfig& testConfig) { + const struct InternalUnitTester::TestConfig& testConfig) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "Running internal unit tests.. Error messages might follow" << - std::endl; + sif::info << "Running internal unit tests.. Error messages might follow" << std::endl; #else - sif::printInfo("Running internal unit tests..\n"); + sif::printInfo("Running internal unit tests..\n"); #endif - testserialize::test_serialization(); - testmq::testMq(); - if(testConfig.testSemaphores) { - testsemaph::testBinSemaph(); - testsemaph::testCountingSemaph(); - } - testmutex::testMutex(); - if(testConfig.testArrayPrinter) { - arrayprinter::testArrayPrinter(); - } + testserialize::test_serialization(); + testmq::testMq(); + if (testConfig.testSemaphores) { + testsemaph::testBinSemaph(); + testsemaph::testCountingSemaph(); + } + testmutex::testMutex(); + if (testConfig.testArrayPrinter) { + arrayprinter::testArrayPrinter(); + } #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "Internal unit tests finished." << std::endl; + sif::info << "Internal unit tests finished." << std::endl; #else - sif::printInfo("Internal unit tests finished.\n"); + sif::printInfo("Internal unit tests finished.\n"); #endif - return RETURN_OK; + return RETURN_OK; } - - - diff --git a/tests/src/fsfw_tests/internal/InternalUnitTester.h b/tests/src/fsfw_tests/internal/InternalUnitTester.h index 433a0f1f..d6d7ca36 100644 --- a/tests/src/fsfw_tests/internal/InternalUnitTester.h +++ b/tests/src/fsfw_tests/internal/InternalUnitTester.h @@ -4,7 +4,6 @@ #include "UnittDefinitions.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" - /** * @brief Can be used for internal testing, for example for hardware specific * tests which can not be run on a host-machine. @@ -14,22 +13,21 @@ * which simply calls all other tests from other files manually. * Maybe there is a better way.. */ -class InternalUnitTester: public HasReturnvaluesIF { -public: - struct TestConfig { - bool testArrayPrinter = false; - bool testSemaphores = true; - }; +class InternalUnitTester : public HasReturnvaluesIF { + public: + struct TestConfig { + bool testArrayPrinter = false; + bool testSemaphores = true; + }; - InternalUnitTester(); - virtual~ InternalUnitTester(); + InternalUnitTester(); + virtual ~InternalUnitTester(); - /** - * Some function which calls all other tests - * @return - */ - virtual ReturnValue_t performTests(const struct InternalUnitTester::TestConfig& testConfig); + /** + * Some function which calls all other tests + * @return + */ + virtual ReturnValue_t performTests(const struct InternalUnitTester::TestConfig& testConfig); }; - #endif /* FRAMEWORK_TEST_UNITTESTCLASS_H_ */ diff --git a/tests/src/fsfw_tests/internal/UnittDefinitions.cpp b/tests/src/fsfw_tests/internal/UnittDefinitions.cpp index 7f754a0a..3322b1ad 100644 --- a/tests/src/fsfw_tests/internal/UnittDefinitions.cpp +++ b/tests/src/fsfw_tests/internal/UnittDefinitions.cpp @@ -1,11 +1,10 @@ #include "fsfw_tests/internal/UnittDefinitions.h" - ReturnValue_t unitt::put_error(std::string errorId) { +ReturnValue_t unitt::put_error(std::string errorId) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Unit Tester error: Failed at test ID " - << errorId << std::endl; + sif::error << "Unit Tester error: Failed at test ID " << errorId << std::endl; #else - sif::printError("Unit Tester error: Failed at test ID %s\n", errorId.c_str()); + sif::printError("Unit Tester error: Failed at test ID %s\n", errorId.c_str()); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ - return HasReturnvaluesIF::RETURN_FAILED; + return HasReturnvaluesIF::RETURN_FAILED; } diff --git a/tests/src/fsfw_tests/internal/UnittDefinitions.h b/tests/src/fsfw_tests/internal/UnittDefinitions.h index 7e7e06a6..11e83d22 100644 --- a/tests/src/fsfw_tests/internal/UnittDefinitions.h +++ b/tests/src/fsfw_tests/internal/UnittDefinitions.h @@ -1,35 +1,33 @@ #ifndef UNITTEST_INTERNAL_UNITTDEFINITIONS_H_ #define UNITTEST_INTERNAL_UNITTDEFINITIONS_H_ +#include +#include +#include + #include "fsfw/returnvalues/HasReturnvaluesIF.h" #include "fsfw/serviceinterface/ServiceInterface.h" -#include -#include -#include - namespace tv { // POD test values static const bool tv_bool = true; -static const uint8_t tv_uint8 {5}; -static const uint16_t tv_uint16 {283}; -static const uint32_t tv_uint32 {929221}; -static const uint64_t tv_uint64 {2929329429}; +static const uint8_t tv_uint8{5}; +static const uint16_t tv_uint16{283}; +static const uint32_t tv_uint32{929221}; +static const uint64_t tv_uint64{2929329429}; -static const int8_t tv_int8 {-16}; -static const int16_t tv_int16 {-829}; -static const int32_t tv_int32 {-2312}; +static const int8_t tv_int8{-16}; +static const int16_t tv_int16{-829}; +static const int32_t tv_int32{-2312}; -static const float tv_float {8.2149214}; +static const float tv_float{8.2149214}; static const float tv_sfloat = {-922.2321321}; -static const double tv_double {9.2132142141e8}; -static const double tv_sdouble {-2.2421e19}; -} +static const double tv_double{9.2132142141e8}; +static const double tv_sdouble{-2.2421e19}; +} // namespace tv namespace unitt { ReturnValue_t put_error(std::string errorId); } - - #endif /* UNITTEST_INTERNAL_UNITTDEFINITIONS_H_ */ diff --git a/tests/src/fsfw_tests/internal/globalfunctions/TestArrayPrinter.cpp b/tests/src/fsfw_tests/internal/globalfunctions/TestArrayPrinter.cpp index b4311343..2c50e9d4 100644 --- a/tests/src/fsfw_tests/internal/globalfunctions/TestArrayPrinter.cpp +++ b/tests/src/fsfw_tests/internal/globalfunctions/TestArrayPrinter.cpp @@ -1,29 +1,28 @@ #include "fsfw_tests/internal/globalfunctions/TestArrayPrinter.h" void arrayprinter::testArrayPrinter() { - { - const std::array testDataSmall = {0x01, 0x02, 0x03, 0x04, 0x05}; - arrayprinter::print(testDataSmall.data(), testDataSmall.size()); - arrayprinter::print(testDataSmall.data(), testDataSmall.size(), OutputType::DEC); - arrayprinter::print(testDataSmall.data(), testDataSmall.size(), OutputType::BIN); - } + { + const std::array testDataSmall = {0x01, 0x02, 0x03, 0x04, 0x05}; + arrayprinter::print(testDataSmall.data(), testDataSmall.size()); + arrayprinter::print(testDataSmall.data(), testDataSmall.size(), OutputType::DEC); + arrayprinter::print(testDataSmall.data(), testDataSmall.size(), OutputType::BIN); + } - { - std::array testDataMed; - for(size_t idx = 0; idx < testDataMed.size(); idx ++) { - testDataMed[idx] = testDataMed.size() - idx; - } - arrayprinter::print(testDataMed.data(), testDataMed.size()); - arrayprinter::print(testDataMed.data(), testDataMed.size(), OutputType::DEC, 8); + { + std::array testDataMed; + for (size_t idx = 0; idx < testDataMed.size(); idx++) { + testDataMed[idx] = testDataMed.size() - idx; } + arrayprinter::print(testDataMed.data(), testDataMed.size()); + arrayprinter::print(testDataMed.data(), testDataMed.size(), OutputType::DEC, 8); + } - { - std::array testDataLarge; - for(size_t idx = 0; idx < testDataLarge.size(); idx ++) { - testDataLarge[idx] = idx; - } - arrayprinter::print(testDataLarge.data(), testDataLarge.size()); - arrayprinter::print(testDataLarge.data(), testDataLarge.size(), OutputType::DEC); + { + std::array testDataLarge; + for (size_t idx = 0; idx < testDataLarge.size(); idx++) { + testDataLarge[idx] = idx; } - + arrayprinter::print(testDataLarge.data(), testDataLarge.size()); + arrayprinter::print(testDataLarge.data(), testDataLarge.size(), OutputType::DEC); + } } diff --git a/tests/src/fsfw_tests/internal/globalfunctions/TestArrayPrinter.h b/tests/src/fsfw_tests/internal/globalfunctions/TestArrayPrinter.h index 50b82ca0..6bb61763 100644 --- a/tests/src/fsfw_tests/internal/globalfunctions/TestArrayPrinter.h +++ b/tests/src/fsfw_tests/internal/globalfunctions/TestArrayPrinter.h @@ -2,6 +2,7 @@ #define FSFW_UNITTEST_INTERNAL_GLOBALFUNCTIONS_TESTARRAYPRINTER_H_ #include + #include namespace arrayprinter { diff --git a/tests/src/fsfw_tests/internal/osal/testMq.cpp b/tests/src/fsfw_tests/internal/osal/testMq.cpp index 8a252910..0f78dbb9 100644 --- a/tests/src/fsfw_tests/internal/osal/testMq.cpp +++ b/tests/src/fsfw_tests/internal/osal/testMq.cpp @@ -1,52 +1,50 @@ #include "testMq.h" -#include "fsfw_tests/internal/UnittDefinitions.h" #include #include #include +#include "fsfw_tests/internal/UnittDefinitions.h" + using retval = HasReturnvaluesIF; void testmq::testMq() { - std::string id = "[testMq]"; - MessageQueueIF* testSenderMq = - QueueFactory::instance()->createMessageQueue(1); - MessageQueueId_t testSenderMqId = testSenderMq->getId(); + std::string id = "[testMq]"; + MessageQueueIF* testSenderMq = QueueFactory::instance()->createMessageQueue(1); + MessageQueueId_t testSenderMqId = testSenderMq->getId(); - MessageQueueIF* testReceiverMq = - QueueFactory::instance()->createMessageQueue(1); - MessageQueueId_t testReceiverMqId = testReceiverMq->getId(); - std::array testData { 0 }; - testData[0] = 42; - MessageQueueMessage testMessage(testData.data(), 1); - testSenderMq->setDefaultDestination(testReceiverMqId); + MessageQueueIF* testReceiverMq = QueueFactory::instance()->createMessageQueue(1); + MessageQueueId_t testReceiverMqId = testReceiverMq->getId(); + std::array testData{0}; + testData[0] = 42; + MessageQueueMessage testMessage(testData.data(), 1); + testSenderMq->setDefaultDestination(testReceiverMqId); + auto result = testSenderMq->sendMessage(testReceiverMqId, &testMessage); + if (result != retval::RETURN_OK) { + unitt::put_error(id); + } + MessageQueueMessage recvMessage; + result = testReceiverMq->receiveMessage(&recvMessage); + if (result != retval::RETURN_OK or recvMessage.getData()[0] != 42) { + unitt::put_error(id); + } - auto result = testSenderMq->sendMessage(testReceiverMqId, &testMessage); - if(result != retval::RETURN_OK) { - unitt::put_error(id); - } - MessageQueueMessage recvMessage; - result = testReceiverMq->receiveMessage(&recvMessage); - if(result != retval::RETURN_OK or recvMessage.getData()[0] != 42) { - unitt::put_error(id); - } - - result = testSenderMq->sendMessage(testReceiverMqId, &testMessage); - if(result != retval::RETURN_OK) { - unitt::put_error(id); - } - MessageQueueId_t senderId = 0; - result = testReceiverMq->receiveMessage(&recvMessage,&senderId); - if(result != retval::RETURN_OK or recvMessage.getData()[0] != 42) { - unitt::put_error(id); - } - if(senderId != testSenderMqId) { - unitt::put_error(id); - } - senderId = testReceiverMq->getLastPartner(); - if(senderId != testSenderMqId) { - unitt::put_error(id); - } + result = testSenderMq->sendMessage(testReceiverMqId, &testMessage); + if (result != retval::RETURN_OK) { + unitt::put_error(id); + } + MessageQueueId_t senderId = 0; + result = testReceiverMq->receiveMessage(&recvMessage, &senderId); + if (result != retval::RETURN_OK or recvMessage.getData()[0] != 42) { + unitt::put_error(id); + } + if (senderId != testSenderMqId) { + unitt::put_error(id); + } + senderId = testReceiverMq->getLastPartner(); + if (senderId != testSenderMqId) { + unitt::put_error(id); + } } diff --git a/tests/src/fsfw_tests/internal/osal/testMq.h b/tests/src/fsfw_tests/internal/osal/testMq.h index bc12a9b0..ff66f215 100644 --- a/tests/src/fsfw_tests/internal/osal/testMq.h +++ b/tests/src/fsfw_tests/internal/osal/testMq.h @@ -5,5 +5,4 @@ namespace testmq { void testMq(); } - #endif /* UNITTEST_INTERNAL_INTESTMQ_H_ */ diff --git a/tests/src/fsfw_tests/internal/osal/testMutex.cpp b/tests/src/fsfw_tests/internal/osal/testMutex.cpp index 9b50121a..6206c31d 100644 --- a/tests/src/fsfw_tests/internal/osal/testMutex.cpp +++ b/tests/src/fsfw_tests/internal/osal/testMutex.cpp @@ -1,48 +1,48 @@ #include "testMutex.h" -#include "fsfw_tests/internal/UnittDefinitions.h" -#include "fsfw/platform.h" #include +#include "fsfw/platform.h" +#include "fsfw_tests/internal/UnittDefinitions.h" + #if defined PLATFORM_WIN || defined PLATFORM_UNIX -#include "fsfw/osal/host/Mutex.h" - -#include #include -#endif +#include +#include "fsfw/osal/host/Mutex.h" +#endif void testmutex::testMutex() { - std::string id = "[testMutex]"; - MutexIF* mutex = MutexFactory::instance()->createMutex(); - auto result = mutex->lockMutex(MutexIF::TimeoutType::POLLING); - if(result != HasReturnvaluesIF::RETURN_OK) { - unitt::put_error(id); - } - // timed_mutex from the C++ library specifies undefined behaviour if - // the timed mutex is locked twice from the same thread. - // TODO: we should pass a define like FSFW_OSAL_HOST to the build. + std::string id = "[testMutex]"; + MutexIF* mutex = MutexFactory::instance()->createMutex(); + auto result = mutex->lockMutex(MutexIF::TimeoutType::POLLING); + if (result != HasReturnvaluesIF::RETURN_OK) { + unitt::put_error(id); + } + // timed_mutex from the C++ library specifies undefined behaviour if + // the timed mutex is locked twice from the same thread. + // TODO: we should pass a define like FSFW_OSAL_HOST to the build. #if defined PLATFORM_WIN || defined PLATFORM_UNIX - // This calls the function from - // another thread and stores the returnvalue in a future. - auto future = std::async(&MutexIF::lockMutex, mutex, MutexIF::TimeoutType::WAITING, 1); - result = future.get(); + // This calls the function from + // another thread and stores the returnvalue in a future. + auto future = std::async(&MutexIF::lockMutex, mutex, MutexIF::TimeoutType::WAITING, 1); + result = future.get(); #else - result = mutex->lockMutex(MutexIF::TimeoutType::WAITING, 1); + result = mutex->lockMutex(MutexIF::TimeoutType::WAITING, 1); #endif - if(result != MutexIF::MUTEX_TIMEOUT) { - unitt::put_error(id); - } + if (result != MutexIF::MUTEX_TIMEOUT) { + unitt::put_error(id); + } - result = mutex->unlockMutex(); - if(result != HasReturnvaluesIF::RETURN_OK) { - unitt::put_error(id); - } + result = mutex->unlockMutex(); + if (result != HasReturnvaluesIF::RETURN_OK) { + unitt::put_error(id); + } #if !defined PLATFORM_WIN && !defined PLATFORM_UNIX - result = mutex->unlockMutex(); - if(result != MutexIF::CURR_THREAD_DOES_NOT_OWN_MUTEX) { - unitt::put_error(id); - } + result = mutex->unlockMutex(); + if (result != MutexIF::CURR_THREAD_DOES_NOT_OWN_MUTEX) { + unitt::put_error(id); + } #endif } diff --git a/tests/src/fsfw_tests/internal/osal/testMutex.h b/tests/src/fsfw_tests/internal/osal/testMutex.h index b467ea63..39ead92d 100644 --- a/tests/src/fsfw_tests/internal/osal/testMutex.h +++ b/tests/src/fsfw_tests/internal/osal/testMutex.h @@ -5,6 +5,4 @@ namespace testmutex { void testMutex(); } - - #endif /* UNITTEST_INTERNAL_INTTESTMUTEX_H_ */ diff --git a/tests/src/fsfw_tests/internal/osal/testSemaphore.cpp b/tests/src/fsfw_tests/internal/osal/testSemaphore.cpp index 458dcb04..a3e4c277 100644 --- a/tests/src/fsfw_tests/internal/osal/testSemaphore.cpp +++ b/tests/src/fsfw_tests/internal/osal/testSemaphore.cpp @@ -1,165 +1,155 @@ -#include "fsfw/FSFW.h" #include "testSemaphore.h" -#include "fsfw_tests/internal/UnittDefinitions.h" - -#include "fsfw/tasks/SemaphoreFactory.h" -#include "fsfw/serviceinterface/ServiceInterface.h" -#include "fsfw/timemanager/Stopwatch.h" #include +#include "fsfw/FSFW.h" +#include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/tasks/SemaphoreFactory.h" +#include "fsfw/timemanager/Stopwatch.h" +#include "fsfw_tests/internal/UnittDefinitions.h" + void testsemaph::testBinSemaph() { - std::string id = "[BinSemaphore]"; - SemaphoreIF* binSemaph = - SemaphoreFactory::instance()->createBinarySemaphore(); - if(binSemaph == nullptr) { - return; - } - testBinSemaphoreImplementation(binSemaph, id); - SemaphoreFactory::instance()->deleteSemaphore(binSemaph); + std::string id = "[BinSemaphore]"; + SemaphoreIF* binSemaph = SemaphoreFactory::instance()->createBinarySemaphore(); + if (binSemaph == nullptr) { + return; + } + testBinSemaphoreImplementation(binSemaph, id); + SemaphoreFactory::instance()->deleteSemaphore(binSemaph); #if defined FSFW_OSAL_FREERTOS - SemaphoreIF* binSemaphUsingTask = - SemaphoreFactory::instance()->createBinarySemaphore(1); - testBinSemaphoreImplementation(binSemaphUsingTask, id); - SemaphoreFactory::instance()->deleteSemaphore(binSemaphUsingTask); + SemaphoreIF* binSemaphUsingTask = SemaphoreFactory::instance()->createBinarySemaphore(1); + testBinSemaphoreImplementation(binSemaphUsingTask, id); + SemaphoreFactory::instance()->deleteSemaphore(binSemaphUsingTask); #endif } - void testsemaph::testCountingSemaph() { - std::string id = "[CountingSemaph]"; - { - // First test: create a binary semaphore by using a counting semaphore. - SemaphoreIF* countingSemaph = SemaphoreFactory::instance()-> - createCountingSemaphore(1,1); - if(countingSemaph == nullptr) { - return; - } - testBinSemaphoreImplementation(countingSemaph, id); - SemaphoreFactory::instance()->deleteSemaphore(countingSemaph); + std::string id = "[CountingSemaph]"; + { + // First test: create a binary semaphore by using a counting semaphore. + SemaphoreIF* countingSemaph = SemaphoreFactory::instance()->createCountingSemaphore(1, 1); + if (countingSemaph == nullptr) { + return; + } + testBinSemaphoreImplementation(countingSemaph, id); + SemaphoreFactory::instance()->deleteSemaphore(countingSemaph); #if defined FSFW_OSAL_FREERTOS - countingSemaph = SemaphoreFactory::instance()-> - createCountingSemaphore(1, 1, 1); - testBinSemaphoreImplementation(countingSemaph, id); - SemaphoreFactory::instance()->deleteSemaphore(countingSemaph); + countingSemaph = SemaphoreFactory::instance()->createCountingSemaphore(1, 1, 1); + testBinSemaphoreImplementation(countingSemaph, id); + SemaphoreFactory::instance()->deleteSemaphore(countingSemaph); #endif - } + } - { - // Second test: counting semaphore with count 3 and init count of 3. - SemaphoreIF* countingSemaph = SemaphoreFactory::instance()-> - createCountingSemaphore(3,3); - testCountingSemaphImplementation(countingSemaph, id); - SemaphoreFactory::instance()->deleteSemaphore(countingSemaph); + { + // Second test: counting semaphore with count 3 and init count of 3. + SemaphoreIF* countingSemaph = SemaphoreFactory::instance()->createCountingSemaphore(3, 3); + testCountingSemaphImplementation(countingSemaph, id); + SemaphoreFactory::instance()->deleteSemaphore(countingSemaph); #if defined FSFW_OSAL_FREERTOS - countingSemaph = SemaphoreFactory::instance()-> - createCountingSemaphore(3, 0, 1); - uint8_t semaphCount = countingSemaph->getSemaphoreCounter(); - if(semaphCount != 0) { - unitt::put_error(id); - } - // release 3 times in a row - for(int i = 0; i < 3; i++) { - auto result = countingSemaph->release(); - if(result != HasReturnvaluesIF::RETURN_OK) { - unitt::put_error(id); - } - } - testCountingSemaphImplementation(countingSemaph, id); - SemaphoreFactory::instance()->deleteSemaphore(countingSemaph); + countingSemaph = SemaphoreFactory::instance()->createCountingSemaphore(3, 0, 1); + uint8_t semaphCount = countingSemaph->getSemaphoreCounter(); + if (semaphCount != 0) { + unitt::put_error(id); + } + // release 3 times in a row + for (int i = 0; i < 3; i++) { + auto result = countingSemaph->release(); + if (result != HasReturnvaluesIF::RETURN_OK) { + unitt::put_error(id); + } + } + testCountingSemaphImplementation(countingSemaph, id); + SemaphoreFactory::instance()->deleteSemaphore(countingSemaph); #endif - } + } } +void testsemaph::testBinSemaphoreImplementation(SemaphoreIF* binSemaph, std::string id) { + uint8_t semaphCount = binSemaph->getSemaphoreCounter(); + if (semaphCount != 1) { + unitt::put_error(id); + } -void testsemaph::testBinSemaphoreImplementation(SemaphoreIF* binSemaph, - std::string id) { - uint8_t semaphCount = binSemaph->getSemaphoreCounter(); - if(semaphCount != 1) { - unitt::put_error(id); - } + ReturnValue_t result = binSemaph->release(); + if (result != SemaphoreIF::SEMAPHORE_NOT_OWNED) { + unitt::put_error(id); + } + result = binSemaph->acquire(SemaphoreIF::BLOCKING); + if (result != HasReturnvaluesIF::RETURN_OK) { + unitt::put_error(id); + } - ReturnValue_t result = binSemaph->release(); - if(result != SemaphoreIF::SEMAPHORE_NOT_OWNED) { - unitt::put_error(id); - } - result = binSemaph->acquire(SemaphoreIF::BLOCKING); - if(result != HasReturnvaluesIF::RETURN_OK) { - unitt::put_error(id); - } - - // There is not really a point in testing time related, the task - // might get interrupted.. - { - //Stopwatch stopwatch(false); - result = binSemaph->acquire(SemaphoreIF::TimeoutType::WAITING, 10); - //dur_millis_t time = stopwatch.stop(); + // There is not really a point in testing time related, the task + // might get interrupted.. + { + // Stopwatch stopwatch(false); + result = binSemaph->acquire(SemaphoreIF::TimeoutType::WAITING, 10); + // dur_millis_t time = stopwatch.stop(); // if(abs(time - 10) > 2) { #if FSFW_CPP_OSTREAM_ENABLED == 1 // sif::error << "UnitTester: Semaphore timeout measured incorrect." // << std::endl; #endif -// unitt::put_error(id); -// } - } + // unitt::put_error(id); + // } + } - if(result != SemaphoreIF::SEMAPHORE_TIMEOUT) { - unitt::put_error(id); - } + if (result != SemaphoreIF::SEMAPHORE_TIMEOUT) { + unitt::put_error(id); + } - semaphCount = binSemaph->getSemaphoreCounter(); - if(semaphCount != 0) { - unitt::put_error(id); - } + semaphCount = binSemaph->getSemaphoreCounter(); + if (semaphCount != 0) { + unitt::put_error(id); + } - result = binSemaph->release(); - if(result != HasReturnvaluesIF::RETURN_OK) { - unitt::put_error(id); - } + result = binSemaph->release(); + if (result != HasReturnvaluesIF::RETURN_OK) { + unitt::put_error(id); + } } -void testsemaph::testCountingSemaphImplementation(SemaphoreIF* countingSemaph, - std::string id) { - // check count getter function - uint8_t semaphCount = countingSemaph->getSemaphoreCounter(); - if(semaphCount != 3) { - unitt::put_error(id); - } - ReturnValue_t result = countingSemaph->release(); - if(result != SemaphoreIF::SEMAPHORE_NOT_OWNED) { - unitt::put_error(id); - } - // acquire 3 times in a row - for(int i = 0; i < 3; i++) { - result = countingSemaph->acquire(SemaphoreIF::BLOCKING); - if(result != HasReturnvaluesIF::RETURN_OK) { - unitt::put_error(id); - } - } +void testsemaph::testCountingSemaphImplementation(SemaphoreIF* countingSemaph, std::string id) { + // check count getter function + uint8_t semaphCount = countingSemaph->getSemaphoreCounter(); + if (semaphCount != 3) { + unitt::put_error(id); + } + ReturnValue_t result = countingSemaph->release(); + if (result != SemaphoreIF::SEMAPHORE_NOT_OWNED) { + unitt::put_error(id); + } + // acquire 3 times in a row + for (int i = 0; i < 3; i++) { + result = countingSemaph->acquire(SemaphoreIF::BLOCKING); + if (result != HasReturnvaluesIF::RETURN_OK) { + unitt::put_error(id); + } + } - { - Stopwatch stopwatch(false); - // attempt to take when count is 0, measure time - result = countingSemaph->acquire(SemaphoreIF::TimeoutType::WAITING, 10); - dur_millis_t time = stopwatch.stop(); - if(std::abs(static_cast(time - 10)) > 1) { - unitt::put_error(id); - } - } + { + Stopwatch stopwatch(false); + // attempt to take when count is 0, measure time + result = countingSemaph->acquire(SemaphoreIF::TimeoutType::WAITING, 10); + dur_millis_t time = stopwatch.stop(); + if (std::abs(static_cast(time - 10)) > 1) { + unitt::put_error(id); + } + } - if(result != SemaphoreIF::SEMAPHORE_TIMEOUT) { - unitt::put_error(id); - } + if (result != SemaphoreIF::SEMAPHORE_TIMEOUT) { + unitt::put_error(id); + } - // release 3 times in a row - for(int i = 0; i < 3; i++) { - result = countingSemaph->release(); - if(result != HasReturnvaluesIF::RETURN_OK) { - unitt::put_error(id); - } - } - // assert correct full count - if(countingSemaph->getSemaphoreCounter() != 3) { - unitt::put_error(id); - } + // release 3 times in a row + for (int i = 0; i < 3; i++) { + result = countingSemaph->release(); + if (result != HasReturnvaluesIF::RETURN_OK) { + unitt::put_error(id); + } + } + // assert correct full count + if (countingSemaph->getSemaphoreCounter() != 3) { + unitt::put_error(id); + } } diff --git a/tests/src/fsfw_tests/internal/osal/testSemaphore.h b/tests/src/fsfw_tests/internal/osal/testSemaphore.h index af26c131..b96f2d65 100644 --- a/tests/src/fsfw_tests/internal/osal/testSemaphore.h +++ b/tests/src/fsfw_tests/internal/osal/testSemaphore.h @@ -7,9 +7,7 @@ namespace testsemaph { void testBinSemaph(); void testBinSemaphoreImplementation(SemaphoreIF* binSemaph, std::string id); void testCountingSemaph(); -void testCountingSemaphImplementation(SemaphoreIF* countingSemaph, - std::string id); -} - +void testCountingSemaphImplementation(SemaphoreIF* countingSemaph, std::string id); +} // namespace testsemaph #endif /* UNITTEST_INTERNAL_INTTESTSEMAPHORE_H_ */ diff --git a/tests/src/fsfw_tests/internal/serialize/IntTestSerialization.cpp b/tests/src/fsfw_tests/internal/serialize/IntTestSerialization.cpp index 4720f706..8e1f2bdd 100644 --- a/tests/src/fsfw_tests/internal/serialize/IntTestSerialization.cpp +++ b/tests/src/fsfw_tests/internal/serialize/IntTestSerialization.cpp @@ -1,232 +1,210 @@ #include "fsfw_tests/internal/serialize/IntTestSerialization.h" -#include "fsfw_tests/internal/UnittDefinitions.h" -#include #include +#include #include #include +#include "fsfw_tests/internal/UnittDefinitions.h" + using retval = HasReturnvaluesIF; -std::array testserialize::test_array = { 0 }; +std::array testserialize::test_array = {0}; ReturnValue_t testserialize::test_serialization() { - // Here, we test all serialization tools. First test basic cases. - ReturnValue_t result = test_endianness_tools(); - if(result != retval::RETURN_OK) { - return result; - } - result = test_autoserialization(); - if(result != retval::RETURN_OK) { - return result; - } - result = test_serial_buffer_adapter(); - if(result != retval::RETURN_OK) { - return result; - } - return retval::RETURN_OK; + // Here, we test all serialization tools. First test basic cases. + ReturnValue_t result = test_endianness_tools(); + if (result != retval::RETURN_OK) { + return result; + } + result = test_autoserialization(); + if (result != retval::RETURN_OK) { + return result; + } + result = test_serial_buffer_adapter(); + if (result != retval::RETURN_OK) { + return result; + } + return retval::RETURN_OK; } ReturnValue_t testserialize::test_endianness_tools() { - std::string id = "[test_endianness_tools]"; - test_array[0] = 0; - test_array[1] = 0; - uint16_t two_byte_value = 1; - size_t size = 0; - uint8_t* p_array = test_array.data(); - SerializeAdapter::serialize(&two_byte_value, &p_array, &size, 2, - SerializeIF::Endianness::MACHINE); - // Little endian: Value one on first byte - if(test_array[0] != 1 and test_array[1] != 0) { - return unitt::put_error(id); + std::string id = "[test_endianness_tools]"; + test_array[0] = 0; + test_array[1] = 0; + uint16_t two_byte_value = 1; + size_t size = 0; + uint8_t* p_array = test_array.data(); + SerializeAdapter::serialize(&two_byte_value, &p_array, &size, 2, + SerializeIF::Endianness::MACHINE); + // Little endian: Value one on first byte + if (test_array[0] != 1 and test_array[1] != 0) { + return unitt::put_error(id); + } - } - - p_array = test_array.data(); - size = 0; - SerializeAdapter::serialize(&two_byte_value, &p_array, &size, 2, - SerializeIF::Endianness::BIG); - // Big endian: Value one on second byte - if(test_array[0] != 0 and test_array[1] != 1) { - return unitt::put_error(id); - } - return retval::RETURN_OK; + p_array = test_array.data(); + size = 0; + SerializeAdapter::serialize(&two_byte_value, &p_array, &size, 2, SerializeIF::Endianness::BIG); + // Big endian: Value one on second byte + if (test_array[0] != 0 and test_array[1] != 1) { + return unitt::put_error(id); + } + return retval::RETURN_OK; } ReturnValue_t testserialize::test_autoserialization() { - std::string id = "[test_autoserialization]"; - // Unit Test getSerializedSize - if(SerializeAdapter:: - getSerializedSize(&tv::tv_bool) != sizeof(tv::tv_bool) or - SerializeAdapter:: - getSerializedSize(&tv::tv_uint8) != sizeof(tv::tv_uint8) or - SerializeAdapter:: - getSerializedSize(&tv::tv_uint16) != sizeof(tv::tv_uint16) or - SerializeAdapter:: - getSerializedSize(&tv::tv_uint32) != sizeof(tv::tv_uint32) or - SerializeAdapter:: - getSerializedSize(&tv::tv_uint64) != sizeof(tv::tv_uint64) or - SerializeAdapter:: - getSerializedSize(&tv::tv_int8) != sizeof(tv::tv_int8) or - SerializeAdapter:: - getSerializedSize(&tv::tv_double) != sizeof(tv::tv_double) or - SerializeAdapter:: - getSerializedSize(&tv::tv_int16) != sizeof(tv::tv_int16) or - SerializeAdapter:: - getSerializedSize(&tv::tv_int32) != sizeof(tv::tv_int32) or - SerializeAdapter:: - getSerializedSize(&tv::tv_float) != sizeof(tv::tv_float)) - { - return unitt::put_error(id); - } + std::string id = "[test_autoserialization]"; + // Unit Test getSerializedSize + if (SerializeAdapter::getSerializedSize(&tv::tv_bool) != sizeof(tv::tv_bool) or + SerializeAdapter::getSerializedSize(&tv::tv_uint8) != sizeof(tv::tv_uint8) or + SerializeAdapter::getSerializedSize(&tv::tv_uint16) != sizeof(tv::tv_uint16) or + SerializeAdapter::getSerializedSize(&tv::tv_uint32) != sizeof(tv::tv_uint32) or + SerializeAdapter::getSerializedSize(&tv::tv_uint64) != sizeof(tv::tv_uint64) or + SerializeAdapter::getSerializedSize(&tv::tv_int8) != sizeof(tv::tv_int8) or + SerializeAdapter::getSerializedSize(&tv::tv_double) != sizeof(tv::tv_double) or + SerializeAdapter::getSerializedSize(&tv::tv_int16) != sizeof(tv::tv_int16) or + SerializeAdapter::getSerializedSize(&tv::tv_int32) != sizeof(tv::tv_int32) or + SerializeAdapter::getSerializedSize(&tv::tv_float) != sizeof(tv::tv_float)) { + return unitt::put_error(id); + } - size_t serialized_size = 0; - uint8_t * p_array = test_array.data(); + size_t serialized_size = 0; + uint8_t* p_array = test_array.data(); - SerializeAdapter::serialize(&tv::tv_bool, &p_array, - &serialized_size, test_array.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tv::tv_uint8, &p_array, - &serialized_size, test_array.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tv::tv_uint16, &p_array, - &serialized_size, test_array.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tv::tv_uint32, &p_array, - &serialized_size, test_array.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tv::tv_int8, &p_array, - &serialized_size, test_array.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tv::tv_int16, &p_array, - &serialized_size, test_array.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tv::tv_int32, &p_array, - &serialized_size, test_array.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tv::tv_uint64, &p_array, - &serialized_size, test_array.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tv::tv_float, &p_array, - &serialized_size, test_array.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tv::tv_double, &p_array, - &serialized_size, test_array.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tv::tv_sfloat, &p_array, - &serialized_size, test_array.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tv::tv_sdouble, &p_array, - &serialized_size, test_array.size(), SerializeIF::Endianness::MACHINE); - // expected size is 1 + 1 + 2 + 4 + 1 + 2 + 4 + 8 + 4 + 8 + 4 + 8 - if(serialized_size != 47) { - return unitt::put_error(id); - } + SerializeAdapter::serialize(&tv::tv_bool, &p_array, &serialized_size, test_array.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tv::tv_uint8, &p_array, &serialized_size, test_array.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tv::tv_uint16, &p_array, &serialized_size, test_array.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tv::tv_uint32, &p_array, &serialized_size, test_array.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tv::tv_int8, &p_array, &serialized_size, test_array.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tv::tv_int16, &p_array, &serialized_size, test_array.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tv::tv_int32, &p_array, &serialized_size, test_array.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tv::tv_uint64, &p_array, &serialized_size, test_array.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tv::tv_float, &p_array, &serialized_size, test_array.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tv::tv_double, &p_array, &serialized_size, test_array.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tv::tv_sfloat, &p_array, &serialized_size, test_array.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tv::tv_sdouble, &p_array, &serialized_size, test_array.size(), + SerializeIF::Endianness::MACHINE); + // expected size is 1 + 1 + 2 + 4 + 1 + 2 + 4 + 8 + 4 + 8 + 4 + 8 + if (serialized_size != 47) { + return unitt::put_error(id); + } - p_array = test_array.data(); - size_t remaining_size = serialized_size; - bool tv_bool; - uint8_t tv_uint8; - uint16_t tv_uint16; - uint32_t tv_uint32; - int8_t tv_int8; - int16_t tv_int16; - int32_t tv_int32; - uint64_t tv_uint64; - float tv_float; - double tv_double; - float tv_sfloat; - double tv_sdouble; + p_array = test_array.data(); + size_t remaining_size = serialized_size; + bool tv_bool; + uint8_t tv_uint8; + uint16_t tv_uint16; + uint32_t tv_uint32; + int8_t tv_int8; + int16_t tv_int16; + int32_t tv_int32; + uint64_t tv_uint64; + float tv_float; + double tv_double; + float tv_sfloat; + double tv_sdouble; - SerializeAdapter::deSerialize(&tv_bool, - const_cast(&p_array), &remaining_size, SerializeIF::Endianness::MACHINE); - SerializeAdapter::deSerialize(&tv_uint8, - const_cast(&p_array), &remaining_size, SerializeIF::Endianness::MACHINE); - SerializeAdapter::deSerialize(&tv_uint16, - const_cast(&p_array), &remaining_size, SerializeIF::Endianness::MACHINE); - SerializeAdapter::deSerialize(&tv_uint32, - const_cast(&p_array), &remaining_size, SerializeIF::Endianness::MACHINE); - SerializeAdapter::deSerialize(&tv_int8, - const_cast(&p_array), &remaining_size, SerializeIF::Endianness::MACHINE); - SerializeAdapter::deSerialize(&tv_int16, - const_cast(&p_array), &remaining_size, SerializeIF::Endianness::MACHINE); - SerializeAdapter::deSerialize(&tv_int32, - const_cast(&p_array), &remaining_size, SerializeIF::Endianness::MACHINE); - SerializeAdapter::deSerialize(&tv_uint64, - const_cast(&p_array), &remaining_size, SerializeIF::Endianness::MACHINE); - SerializeAdapter::deSerialize(&tv_float, - const_cast(&p_array), &remaining_size, SerializeIF::Endianness::MACHINE); - SerializeAdapter::deSerialize(&tv_double, - const_cast(&p_array), &remaining_size, SerializeIF::Endianness::MACHINE); - SerializeAdapter::deSerialize(&tv_sfloat, - const_cast(&p_array), &remaining_size, SerializeIF::Endianness::MACHINE); - SerializeAdapter::deSerialize(&tv_sdouble, - const_cast(&p_array), &remaining_size, SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tv_bool, const_cast(&p_array), &remaining_size, + SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tv_uint8, const_cast(&p_array), &remaining_size, + SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tv_uint16, const_cast(&p_array), &remaining_size, + SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tv_uint32, const_cast(&p_array), &remaining_size, + SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tv_int8, const_cast(&p_array), &remaining_size, + SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tv_int16, const_cast(&p_array), &remaining_size, + SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tv_int32, const_cast(&p_array), &remaining_size, + SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tv_uint64, const_cast(&p_array), &remaining_size, + SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tv_float, const_cast(&p_array), &remaining_size, + SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tv_double, const_cast(&p_array), &remaining_size, + SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tv_sfloat, const_cast(&p_array), &remaining_size, + SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tv_sdouble, const_cast(&p_array), &remaining_size, + SerializeIF::Endianness::MACHINE); - if(tv_bool != tv::tv_bool or tv_uint8 != tv::tv_uint8 or - tv_uint16 != tv::tv_uint16 or tv_uint32 != tv::tv_uint32 or - tv_uint64 != tv::tv_uint64 or tv_int8 != tv::tv_int8 or - tv_int16 != tv::tv_int16 or tv_int32 != tv::tv_int32) - { - return unitt::put_error(id); - } + if (tv_bool != tv::tv_bool or tv_uint8 != tv::tv_uint8 or tv_uint16 != tv::tv_uint16 or + tv_uint32 != tv::tv_uint32 or tv_uint64 != tv::tv_uint64 or tv_int8 != tv::tv_int8 or + tv_int16 != tv::tv_int16 or tv_int32 != tv::tv_int32) { + return unitt::put_error(id); + } - // These epsilon values were just guessed.. It appears to work though. - if(abs(tv_float - tv::tv_float) > 0.0001 or - abs(tv_double - tv::tv_double) > 0.01 or - abs(tv_sfloat - tv::tv_sfloat) > 0.0001 or - abs(tv_sdouble - tv::tv_sdouble) > 0.01) { - return unitt::put_error(id); - } + // These epsilon values were just guessed.. It appears to work though. + if (abs(tv_float - tv::tv_float) > 0.0001 or abs(tv_double - tv::tv_double) > 0.01 or + abs(tv_sfloat - tv::tv_sfloat) > 0.0001 or abs(tv_sdouble - tv::tv_sdouble) > 0.01) { + return unitt::put_error(id); + } - // Check overflow - return retval::RETURN_OK; + // Check overflow + return retval::RETURN_OK; } // TODO: Also test for constant buffers. ReturnValue_t testserialize::test_serial_buffer_adapter() { - std::string id = "[test_serial_buffer_adapter]"; + std::string id = "[test_serial_buffer_adapter]"; - // I will skip endian swapper testing, its going to be changed anyway.. - // uint8_t tv::tv_uint8_swapped = EndianSwapper::swap(tv::tv_uint8); + // I will skip endian swapper testing, its going to be changed anyway.. + // uint8_t tv::tv_uint8_swapped = EndianSwapper::swap(tv::tv_uint8); - size_t serialized_size = 0; - uint8_t * p_array = test_array.data(); - std::array test_serial_buffer {5, 4, 3, 2, 1}; - SerialBufferAdapter tv_serial_buffer_adapter = - SerialBufferAdapter(test_serial_buffer.data(), - test_serial_buffer.size(), false); - uint16_t testUint16 = 16; + size_t serialized_size = 0; + uint8_t* p_array = test_array.data(); + std::array test_serial_buffer{5, 4, 3, 2, 1}; + SerialBufferAdapter tv_serial_buffer_adapter = + SerialBufferAdapter(test_serial_buffer.data(), test_serial_buffer.size(), false); + uint16_t testUint16 = 16; - SerializeAdapter::serialize(&tv::tv_bool, &p_array,&serialized_size, - test_array.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tv_serial_buffer_adapter, &p_array, - &serialized_size, test_array.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&testUint16, &p_array, &serialized_size, - test_array.size(), SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tv::tv_bool, &p_array, &serialized_size, test_array.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tv_serial_buffer_adapter, &p_array, &serialized_size, + test_array.size(), SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&testUint16, &p_array, &serialized_size, test_array.size(), + SerializeIF::Endianness::MACHINE); - if(serialized_size != 8 or test_array[0] != true or test_array[1] != 5 - or test_array[2] != 4 or test_array[3] != 3 or test_array[4] != 2 - or test_array[5] != 1) - { - return unitt::put_error(id); - } - memcpy(&testUint16, test_array.data() + 6, sizeof(testUint16)); - if(testUint16 != 16) { - return unitt::put_error(id); - } + if (serialized_size != 8 or test_array[0] != true or test_array[1] != 5 or test_array[2] != 4 or + test_array[3] != 3 or test_array[4] != 2 or test_array[5] != 1) { + return unitt::put_error(id); + } + memcpy(&testUint16, test_array.data() + 6, sizeof(testUint16)); + if (testUint16 != 16) { + return unitt::put_error(id); + } - // Serialize with size field - SerialBufferAdapter tv_serial_buffer_adapter2 = - SerialBufferAdapter(test_serial_buffer.data(), - test_serial_buffer.size(), true); - serialized_size = 0; - p_array = test_array.data(); - SerializeAdapter::serialize(&tv::tv_bool, &p_array,&serialized_size, - test_array.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tv_serial_buffer_adapter2, &p_array, - &serialized_size, test_array.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&testUint16, &p_array, &serialized_size, - test_array.size(), SerializeIF::Endianness::MACHINE); + // Serialize with size field + SerialBufferAdapter tv_serial_buffer_adapter2 = + SerialBufferAdapter(test_serial_buffer.data(), test_serial_buffer.size(), true); + serialized_size = 0; + p_array = test_array.data(); + SerializeAdapter::serialize(&tv::tv_bool, &p_array, &serialized_size, test_array.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tv_serial_buffer_adapter2, &p_array, &serialized_size, + test_array.size(), SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&testUint16, &p_array, &serialized_size, test_array.size(), + SerializeIF::Endianness::MACHINE); - if(serialized_size != 9 or test_array[0] != true or test_array[1] != 5 - or test_array[2] != 5 or test_array[3] != 4 or test_array[4] != 3 - or test_array[5] != 2 or test_array[6] != 1) - { - return unitt::put_error(id); - } - memcpy(&testUint16, test_array.data() + 7, sizeof(testUint16)); - if(testUint16 != 16) { - return unitt::put_error(id); - } - return retval::RETURN_OK; + if (serialized_size != 9 or test_array[0] != true or test_array[1] != 5 or test_array[2] != 5 or + test_array[3] != 4 or test_array[4] != 3 or test_array[5] != 2 or test_array[6] != 1) { + return unitt::put_error(id); + } + memcpy(&testUint16, test_array.data() + 7, sizeof(testUint16)); + if (testUint16 != 16) { + return unitt::put_error(id); + } + return retval::RETURN_OK; } diff --git a/tests/src/fsfw_tests/internal/serialize/IntTestSerialization.h b/tests/src/fsfw_tests/internal/serialize/IntTestSerialization.h index 0767fb44..2f1786d4 100644 --- a/tests/src/fsfw_tests/internal/serialize/IntTestSerialization.h +++ b/tests/src/fsfw_tests/internal/serialize/IntTestSerialization.h @@ -1,9 +1,10 @@ #ifndef FSFW_UNITTEST_INTERNAL_INTTESTSERIALIZATION_H_ #define FSFW_UNITTEST_INTERNAL_INTTESTSERIALIZATION_H_ -#include "fsfw/returnvalues/HasReturnvaluesIF.h" #include +#include "fsfw/returnvalues/HasReturnvaluesIF.h" + namespace testserialize { ReturnValue_t test_serialization(); ReturnValue_t test_endianness_tools(); @@ -11,6 +12,6 @@ ReturnValue_t test_autoserialization(); ReturnValue_t test_serial_buffer_adapter(); extern std::array test_array; -} +} // namespace testserialize #endif /* FSFW_UNITTEST_INTERNAL_INTTESTSERIALIZATION_H_ */ diff --git a/tests/src/fsfw_tests/unit/CatchDefinitions.cpp b/tests/src/fsfw_tests/unit/CatchDefinitions.cpp index c44a561e..85e3aad0 100644 --- a/tests/src/fsfw_tests/unit/CatchDefinitions.cpp +++ b/tests/src/fsfw_tests/unit/CatchDefinitions.cpp @@ -1,16 +1,17 @@ #include "CatchDefinitions.h" -#include + #include +#include StorageManagerIF* tglob::getIpcStoreHandle() { - if(ObjectManager::instance() != nullptr) { - return ObjectManager::instance()->get(objects::IPC_STORE); - } else { + if (ObjectManager::instance() != nullptr) { + return ObjectManager::instance()->get(objects::IPC_STORE); + } else { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "Global object manager uninitialized" << std::endl; + sif::error << "Global object manager uninitialized" << std::endl; #else - sif::printError("Global object manager uninitialized\n\r"); + sif::printError("Global object manager uninitialized\n\r"); #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ - return nullptr; - } + return nullptr; + } } diff --git a/tests/src/fsfw_tests/unit/CatchDefinitions.h b/tests/src/fsfw_tests/unit/CatchDefinitions.h index 366cda7e..f0189602 100644 --- a/tests/src/fsfw_tests/unit/CatchDefinitions.h +++ b/tests/src/fsfw_tests/unit/CatchDefinitions.h @@ -8,14 +8,14 @@ namespace retval { static constexpr int CATCH_OK = static_cast(HasReturnvaluesIF::RETURN_OK); static constexpr int CATCH_FAILED = static_cast(HasReturnvaluesIF::RETURN_FAILED); -} +} // namespace retval namespace tconst { - static constexpr MessageQueueId_t testQueueId = 42; +static constexpr MessageQueueId_t testQueueId = 42; } namespace tglob { - StorageManagerIF* getIpcStoreHandle(); +StorageManagerIF* getIpcStoreHandle(); } #endif /* FSFW_UNITTEST_CORE_CATCHDEFINITIONS_H_ */ diff --git a/tests/src/fsfw_tests/unit/CatchFactory.cpp b/tests/src/fsfw_tests/unit/CatchFactory.cpp index 42cb927e..01018dfa 100644 --- a/tests/src/fsfw_tests/unit/CatchFactory.cpp +++ b/tests/src/fsfw_tests/unit/CatchFactory.cpp @@ -1,11 +1,7 @@ #include "CatchFactory.h" -#include "tests/TestsConfig.h" -#include "datapoollocal/LocalPoolOwnerBase.h" -#include "mocks/HkReceiverMock.h" #include #include - #include #include #include @@ -15,6 +11,9 @@ #include #include +#include "datapoollocal/LocalPoolOwnerBase.h" +#include "mocks/HkReceiverMock.h" +#include "tests/TestsConfig.h" #if FSFW_ADD_DEFAULT_FACTORY_FUNCTIONS == 1 @@ -32,53 +31,47 @@ * @ingroup init */ void Factory::produceFrameworkObjects(void* args) { - setStaticFrameworkObjectIds(); - new EventManager(objects::EVENT_MANAGER); - new HealthTable(objects::HEALTH_TABLE); - new InternalErrorReporter(objects::INTERNAL_ERROR_REPORTER); + setStaticFrameworkObjectIds(); + new EventManager(objects::EVENT_MANAGER); + new HealthTable(objects::HEALTH_TABLE); + new InternalErrorReporter(objects::INTERNAL_ERROR_REPORTER); - new LocalPoolOwnerBase (objects::TEST_LOCAL_POOL_OWNER_BASE); - new HkReceiverMock(objects::HK_RECEIVER_MOCK); + new LocalPoolOwnerBase(objects::TEST_LOCAL_POOL_OWNER_BASE); + new HkReceiverMock(objects::HK_RECEIVER_MOCK); - { - PoolManager::LocalPoolConfig poolCfg = { - {100, 16}, {50, 32}, {25, 64} , {15, 128}, {5, 1024} - }; - new PoolManager(objects::TC_STORE, poolCfg); - } + { + PoolManager::LocalPoolConfig poolCfg = {{100, 16}, {50, 32}, {25, 64}, {15, 128}, {5, 1024}}; + new PoolManager(objects::TC_STORE, poolCfg); + } - { - PoolManager::LocalPoolConfig poolCfg = { - {100, 16}, {50, 32}, {25, 64} , {15, 128}, {5, 1024} - }; - new PoolManager(objects::TM_STORE, poolCfg); - } + { + PoolManager::LocalPoolConfig poolCfg = {{100, 16}, {50, 32}, {25, 64}, {15, 128}, {5, 1024}}; + new PoolManager(objects::TM_STORE, poolCfg); + } - { - PoolManager::LocalPoolConfig poolCfg = { - {100, 16}, {50, 32}, {25, 64} , {15, 128}, {5, 1024} - }; - new PoolManager(objects::IPC_STORE, poolCfg); - } + { + PoolManager::LocalPoolConfig poolCfg = {{100, 16}, {50, 32}, {25, 64}, {15, 128}, {5, 1024}}; + new PoolManager(objects::IPC_STORE, poolCfg); + } } void Factory::setStaticFrameworkObjectIds() { - PusServiceBase::packetSource = objects::NO_OBJECT; - PusServiceBase::packetDestination = objects::NO_OBJECT; + PusServiceBase::packetSource = objects::NO_OBJECT; + PusServiceBase::packetDestination = objects::NO_OBJECT; - CommandingServiceBase::defaultPacketSource = objects::NO_OBJECT; - CommandingServiceBase::defaultPacketDestination = objects::NO_OBJECT; + CommandingServiceBase::defaultPacketSource = objects::NO_OBJECT; + CommandingServiceBase::defaultPacketDestination = objects::NO_OBJECT; - VerificationReporter::messageReceiver = objects::PUS_SERVICE_1_VERIFICATION; + VerificationReporter::messageReceiver = objects::PUS_SERVICE_1_VERIFICATION; - DeviceHandlerBase::powerSwitcherId = objects::NO_OBJECT; - DeviceHandlerBase::rawDataReceiverId = objects::PUS_SERVICE_2_DEVICE_ACCESS; + DeviceHandlerBase::powerSwitcherId = objects::NO_OBJECT; + DeviceHandlerBase::rawDataReceiverId = objects::PUS_SERVICE_2_DEVICE_ACCESS; - LocalDataPoolManager::defaultHkDestination = objects::HK_RECEIVER_MOCK; + LocalDataPoolManager::defaultHkDestination = objects::HK_RECEIVER_MOCK; - DeviceHandlerFailureIsolation::powerConfirmationId = objects::NO_OBJECT; + DeviceHandlerFailureIsolation::powerConfirmationId = objects::NO_OBJECT; - TmPacketBase::timeStamperId = objects::NO_OBJECT; + TmPacketBase::timeStamperId = objects::NO_OBJECT; } #endif diff --git a/tests/src/fsfw_tests/unit/CatchFactory.h b/tests/src/fsfw_tests/unit/CatchFactory.h index cc14e3d9..26de653e 100644 --- a/tests/src/fsfw_tests/unit/CatchFactory.h +++ b/tests/src/fsfw_tests/unit/CatchFactory.h @@ -1,23 +1,23 @@ #ifndef FSFW_CATCHFACTORY_H_ #define FSFW_CATCHFACTORY_H_ -#include "tests/TestsConfig.h" -#include "fsfw/objectmanager/SystemObjectIF.h" #include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/objectmanager/SystemObjectIF.h" +#include "tests/TestsConfig.h" // TODO: It is possible to solve this more cleanly using a special class which // is allowed to set the object IDs and has virtual functions. #if FSFW_ADD_DEFAULT_FACTORY_FUNCTIONS == 1 namespace Factory { - /** - * @brief Creates all SystemObject elements which are persistent - * during execution. - */ - void produceFrameworkObjects(void* args); - void setStaticFrameworkObjectIds(); +/** + * @brief Creates all SystemObject elements which are persistent + * during execution. + */ +void produceFrameworkObjects(void* args); +void setStaticFrameworkObjectIds(); -} +} // namespace Factory #endif /* FSFW_ADD_DEFAULT_FSFW_FACTORY == 1 */ diff --git a/tests/src/fsfw_tests/unit/CatchRunner.cpp b/tests/src/fsfw_tests/unit/CatchRunner.cpp index 1ea3ab35..1377049c 100644 --- a/tests/src/fsfw_tests/unit/CatchRunner.cpp +++ b/tests/src/fsfw_tests/unit/CatchRunner.cpp @@ -15,12 +15,11 @@ extern int customSetup(); int main(int argc, char* argv[]) { - customSetup(); + customSetup(); - // Catch internal function call - int result = Catch::Session().run(argc, argv); + // Catch internal function call + int result = Catch::Session().run(argc, argv); - // global clean-up - return result; + // global clean-up + return result; } - diff --git a/tests/src/fsfw_tests/unit/CatchRunner.h b/tests/src/fsfw_tests/unit/CatchRunner.h index 06ff07b6..da654b06 100644 --- a/tests/src/fsfw_tests/unit/CatchRunner.h +++ b/tests/src/fsfw_tests/unit/CatchRunner.h @@ -7,8 +7,8 @@ namespace fsfwtest { * Can be called by upper level main() if default Catch2 main is overriden * @return */ -//int customMain(int argc, char* argv[]); +// int customMain(int argc, char* argv[]); -} +} // namespace fsfwtest #endif /* FSFW_TESTS_USER_UNITTEST_CORE_CATCHRUNNER_H_ */ diff --git a/tests/src/fsfw_tests/unit/CatchSetup.cpp b/tests/src/fsfw_tests/unit/CatchSetup.cpp index a0791bc9..06f5190a 100644 --- a/tests/src/fsfw_tests/unit/CatchSetup.cpp +++ b/tests/src/fsfw_tests/unit/CatchSetup.cpp @@ -1,14 +1,13 @@ -#include "CatchFactory.h" #include "CatchDefinitions.h" +#include "CatchFactory.h" #ifdef GCOV #include #endif #include "fsfw/objectmanager/ObjectManager.h" -#include "fsfw/storagemanager/StorageManagerIF.h" #include "fsfw/serviceinterface/ServiceInterface.h" - +#include "fsfw/storagemanager/StorageManagerIF.h" /* Global instantiations normally done in main.cpp */ /* Initialize Data Pool */ @@ -20,14 +19,13 @@ ServiceInterfaceStream debug("DEBUG"); ServiceInterfaceStream info("INFO"); ServiceInterfaceStream error("ERROR"); ServiceInterfaceStream warning("WARNING"); -} +} // namespace sif #endif int customSetup() { - // global setup - ObjectManager* objMan = ObjectManager::instance(); - objMan->setObjectFactoryFunction(Factory::produceFrameworkObjects, nullptr); - objMan->initialize(); - return 0; + // global setup + ObjectManager* objMan = ObjectManager::instance(); + objMan->setObjectFactoryFunction(Factory::produceFrameworkObjects, nullptr); + objMan->initialize(); + return 0; } - diff --git a/tests/src/fsfw_tests/unit/action/TestActionHelper.cpp b/tests/src/fsfw_tests/unit/action/TestActionHelper.cpp index 3129b001..923b7436 100644 --- a/tests/src/fsfw_tests/unit/action/TestActionHelper.cpp +++ b/tests/src/fsfw_tests/unit/action/TestActionHelper.cpp @@ -1,110 +1,114 @@ #include "TestActionHelper.h" -#include "fsfw_tests/unit/mocks/MessageQueueMockBase.h" #include #include -#include #include +#include +#include "fsfw_tests/unit/mocks/MessageQueueMockBase.h" -TEST_CASE( "Action Helper" , "[ActionHelper]") { - ActionHelperOwnerMockBase testDhMock; - MessageQueueMockBase testMqMock; - ActionHelper actionHelper = ActionHelper( - &testDhMock, dynamic_cast(&testMqMock)); - CommandMessage actionMessage; - ActionId_t testActionId = 777; - std::array testParams {1, 2, 3}; - store_address_t paramAddress; - StorageManagerIF *ipcStore = tglob::getIpcStoreHandle(); - REQUIRE(ipcStore != nullptr); - ipcStore->addData(¶mAddress, testParams.data(), 3); - REQUIRE(actionHelper.initialize() == retval::CATCH_OK); +TEST_CASE("Action Helper", "[ActionHelper]") { + ActionHelperOwnerMockBase testDhMock; + MessageQueueMockBase testMqMock; + ActionHelper actionHelper = ActionHelper(&testDhMock, dynamic_cast(&testMqMock)); + CommandMessage actionMessage; + ActionId_t testActionId = 777; + std::array testParams{1, 2, 3}; + store_address_t paramAddress; + StorageManagerIF* ipcStore = tglob::getIpcStoreHandle(); + REQUIRE(ipcStore != nullptr); + ipcStore->addData(¶mAddress, testParams.data(), 3); + REQUIRE(actionHelper.initialize() == retval::CATCH_OK); - SECTION ("Simple tests") { - ActionMessage::setCommand(&actionMessage, testActionId, paramAddress); - CHECK(not testDhMock.executeActionCalled); - REQUIRE(actionHelper.handleActionMessage(&actionMessage) == retval::CATCH_OK); - CHECK(testDhMock.executeActionCalled); - // No message is sent if everything is alright. - CHECK(not testMqMock.wasMessageSent()); - store_address_t invalidAddress; - ActionMessage::setCommand(&actionMessage, testActionId, invalidAddress); - actionHelper.handleActionMessage(&actionMessage); - CHECK(testMqMock.wasMessageSent()); - const uint8_t* ptr = nullptr; - size_t size = 0; - REQUIRE(ipcStore->getData(paramAddress, &ptr, &size) == static_cast(StorageManagerIF::DATA_DOES_NOT_EXIST)); - REQUIRE(ptr == nullptr); - REQUIRE(size == 0); - testDhMock.getBuffer(&ptr, &size); - REQUIRE(size == 3); - for(uint8_t i = 0; i<3;i++){ - REQUIRE(ptr[i] == (i+1)); - } - testDhMock.clearBuffer(); - } + SECTION("Simple tests") { + ActionMessage::setCommand(&actionMessage, testActionId, paramAddress); + CHECK(not testDhMock.executeActionCalled); + REQUIRE(actionHelper.handleActionMessage(&actionMessage) == retval::CATCH_OK); + CHECK(testDhMock.executeActionCalled); + // No message is sent if everything is alright. + CHECK(not testMqMock.wasMessageSent()); + store_address_t invalidAddress; + ActionMessage::setCommand(&actionMessage, testActionId, invalidAddress); + actionHelper.handleActionMessage(&actionMessage); + CHECK(testMqMock.wasMessageSent()); + const uint8_t* ptr = nullptr; + size_t size = 0; + REQUIRE(ipcStore->getData(paramAddress, &ptr, &size) == + static_cast(StorageManagerIF::DATA_DOES_NOT_EXIST)); + REQUIRE(ptr == nullptr); + REQUIRE(size == 0); + testDhMock.getBuffer(&ptr, &size); + REQUIRE(size == 3); + for (uint8_t i = 0; i < 3; i++) { + REQUIRE(ptr[i] == (i + 1)); + } + testDhMock.clearBuffer(); + } - SECTION("Handle failures"){ - actionMessage.setCommand(1234); - REQUIRE(actionHelper.handleActionMessage(&actionMessage) == static_cast(CommandMessage::UNKNOWN_COMMAND)); - CHECK(not testMqMock.wasMessageSent()); - uint16_t step = 5; - ReturnValue_t status = 0x1234; - actionHelper.step(step, testMqMock.getId(), testActionId, status); - step += 1; - CHECK(testMqMock.wasMessageSent()); - CommandMessage testMessage; - REQUIRE(testMqMock.receiveMessage(&testMessage) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(testMessage.getCommand() == static_cast(ActionMessage::STEP_FAILED)); - REQUIRE(testMessage.getParameter() == static_cast(testActionId)); - uint32_t parameter2 = ((uint32_t)step << 16) | (uint32_t)status; - REQUIRE(testMessage.getParameter2() == parameter2); - REQUIRE(ActionMessage::getStep(&testMessage) == step); - } + SECTION("Handle failures") { + actionMessage.setCommand(1234); + REQUIRE(actionHelper.handleActionMessage(&actionMessage) == + static_cast(CommandMessage::UNKNOWN_COMMAND)); + CHECK(not testMqMock.wasMessageSent()); + uint16_t step = 5; + ReturnValue_t status = 0x1234; + actionHelper.step(step, testMqMock.getId(), testActionId, status); + step += 1; + CHECK(testMqMock.wasMessageSent()); + CommandMessage testMessage; + REQUIRE(testMqMock.receiveMessage(&testMessage) == + static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(testMessage.getCommand() == static_cast(ActionMessage::STEP_FAILED)); + REQUIRE(testMessage.getParameter() == static_cast(testActionId)); + uint32_t parameter2 = ((uint32_t)step << 16) | (uint32_t)status; + REQUIRE(testMessage.getParameter2() == parameter2); + REQUIRE(ActionMessage::getStep(&testMessage) == step); + } - SECTION("Handle finish"){ - CHECK(not testMqMock.wasMessageSent()); - ReturnValue_t status = 0x9876; - actionHelper.finish(false, testMqMock.getId(), testActionId, status); - CHECK(testMqMock.wasMessageSent()); - CommandMessage testMessage; - REQUIRE(testMqMock.receiveMessage(&testMessage) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(testMessage.getCommand() == static_cast(ActionMessage::COMPLETION_FAILED)); - REQUIRE(ActionMessage::getActionId(&testMessage) == testActionId); - REQUIRE(ActionMessage::getReturnCode(&testMessage) == static_cast(status)); - } + SECTION("Handle finish") { + CHECK(not testMqMock.wasMessageSent()); + ReturnValue_t status = 0x9876; + actionHelper.finish(false, testMqMock.getId(), testActionId, status); + CHECK(testMqMock.wasMessageSent()); + CommandMessage testMessage; + REQUIRE(testMqMock.receiveMessage(&testMessage) == + static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(testMessage.getCommand() == static_cast(ActionMessage::COMPLETION_FAILED)); + REQUIRE(ActionMessage::getActionId(&testMessage) == testActionId); + REQUIRE(ActionMessage::getReturnCode(&testMessage) == static_cast(status)); + } - SECTION("Handle failed"){ - store_address_t toLongParamAddress = StorageManagerIF::INVALID_ADDRESS; - std::array toLongData = {5, 4, 3, 2, 1}; - REQUIRE(ipcStore->addData(&toLongParamAddress, toLongData.data(), 5) == retval::CATCH_OK); - ActionMessage::setCommand(&actionMessage, testActionId, toLongParamAddress); - CHECK(not testDhMock.executeActionCalled); - REQUIRE(actionHelper.handleActionMessage(&actionMessage) == retval::CATCH_OK); - REQUIRE(ipcStore->getData(toLongParamAddress).first == static_cast(StorageManagerIF::DATA_DOES_NOT_EXIST)); - CommandMessage testMessage; - REQUIRE(testMqMock.receiveMessage(&testMessage) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(testMessage.getCommand() == static_cast(ActionMessage::STEP_FAILED)); - REQUIRE(ActionMessage::getReturnCode(&testMessage) == 0xAFFE); - REQUIRE(ActionMessage::getStep(&testMessage) == 0); - REQUIRE(ActionMessage::getActionId(&testMessage) == testActionId); - } + SECTION("Handle failed") { + store_address_t toLongParamAddress = StorageManagerIF::INVALID_ADDRESS; + std::array toLongData = {5, 4, 3, 2, 1}; + REQUIRE(ipcStore->addData(&toLongParamAddress, toLongData.data(), 5) == retval::CATCH_OK); + ActionMessage::setCommand(&actionMessage, testActionId, toLongParamAddress); + CHECK(not testDhMock.executeActionCalled); + REQUIRE(actionHelper.handleActionMessage(&actionMessage) == retval::CATCH_OK); + REQUIRE(ipcStore->getData(toLongParamAddress).first == + static_cast(StorageManagerIF::DATA_DOES_NOT_EXIST)); + CommandMessage testMessage; + REQUIRE(testMqMock.receiveMessage(&testMessage) == + static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(testMessage.getCommand() == static_cast(ActionMessage::STEP_FAILED)); + REQUIRE(ActionMessage::getReturnCode(&testMessage) == 0xAFFE); + REQUIRE(ActionMessage::getStep(&testMessage) == 0); + REQUIRE(ActionMessage::getActionId(&testMessage) == testActionId); + } - SECTION("Missing IPC Data"){ - ActionMessage::setCommand(&actionMessage, testActionId, StorageManagerIF::INVALID_ADDRESS); - CHECK(not testDhMock.executeActionCalled); - REQUIRE(actionHelper.handleActionMessage(&actionMessage) == retval::CATCH_OK); - CommandMessage testMessage; - REQUIRE(testMqMock.receiveMessage(&testMessage) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(testMessage.getCommand() == static_cast(ActionMessage::STEP_FAILED)); - REQUIRE(ActionMessage::getReturnCode(&testMessage) == static_cast(StorageManagerIF::ILLEGAL_STORAGE_ID)); - REQUIRE(ActionMessage::getStep(&testMessage) == 0); - } + SECTION("Missing IPC Data") { + ActionMessage::setCommand(&actionMessage, testActionId, StorageManagerIF::INVALID_ADDRESS); + CHECK(not testDhMock.executeActionCalled); + REQUIRE(actionHelper.handleActionMessage(&actionMessage) == retval::CATCH_OK); + CommandMessage testMessage; + REQUIRE(testMqMock.receiveMessage(&testMessage) == + static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(testMessage.getCommand() == static_cast(ActionMessage::STEP_FAILED)); + REQUIRE(ActionMessage::getReturnCode(&testMessage) == + static_cast(StorageManagerIF::ILLEGAL_STORAGE_ID)); + REQUIRE(ActionMessage::getStep(&testMessage) == 0); + } - - SECTION("Data Reply"){ - - } + SECTION("Data Reply") {} } diff --git a/tests/src/fsfw_tests/unit/action/TestActionHelper.h b/tests/src/fsfw_tests/unit/action/TestActionHelper.h index 34b228c0..243f030a 100644 --- a/tests/src/fsfw_tests/unit/action/TestActionHelper.h +++ b/tests/src/fsfw_tests/unit/action/TestActionHelper.h @@ -1,50 +1,49 @@ #ifndef UNITTEST_HOSTED_TESTACTIONHELPER_H_ #define UNITTEST_HOSTED_TESTACTIONHELPER_H_ -#include "fsfw_tests/unit/CatchDefinitions.h" #include #include + #include -class ActionHelperOwnerMockBase: public HasActionsIF { -public: - bool getCommandQueueCalled = false; - bool executeActionCalled = false; - static const size_t MAX_SIZE = 3; - uint8_t buffer[MAX_SIZE] = {0, 0, 0}; - size_t size = 0; +#include "fsfw_tests/unit/CatchDefinitions.h" - MessageQueueId_t getCommandQueue() const override { - return tconst::testQueueId; - } +class ActionHelperOwnerMockBase : public HasActionsIF { + public: + bool getCommandQueueCalled = false; + bool executeActionCalled = false; + static const size_t MAX_SIZE = 3; + uint8_t buffer[MAX_SIZE] = {0, 0, 0}; + size_t size = 0; - ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, - const uint8_t* data, size_t size) override { - executeActionCalled = true; - if(size > MAX_SIZE){ - return 0xAFFE; - } - this->size = size; - memcpy(buffer, data, size); - return HasReturnvaluesIF::RETURN_OK; - } + MessageQueueId_t getCommandQueue() const override { return tconst::testQueueId; } - void clearBuffer(){ - this->size = 0; - for(size_t i = 0; i MAX_SIZE) { + return 0xAFFE; + } + this->size = size; + memcpy(buffer, data, size); + return HasReturnvaluesIF::RETURN_OK; + } - void getBuffer(const uint8_t** ptr, size_t* size){ - if(size != nullptr){ - *size = this->size; - } - if(ptr != nullptr){ - *ptr = buffer; - } - } + void clearBuffer() { + this->size = 0; + for (size_t i = 0; i < MAX_SIZE; i++) { + buffer[i] = 0; + } + } + + void getBuffer(const uint8_t** ptr, size_t* size) { + if (size != nullptr) { + *size = this->size; + } + if (ptr != nullptr) { + *ptr = buffer; + } + } }; - #endif /* UNITTEST_TESTFW_NEWTESTS_TESTACTIONHELPER_H_ */ diff --git a/tests/src/fsfw_tests/unit/cfdp/testAckPdu.cpp b/tests/src/fsfw_tests/unit/cfdp/testAckPdu.cpp index 70576543..e5668799 100644 --- a/tests/src/fsfw_tests/unit/cfdp/testAckPdu.cpp +++ b/tests/src/fsfw_tests/unit/cfdp/testAckPdu.cpp @@ -1,101 +1,100 @@ +#include #include #include "fsfw/cfdp/pdu/AckPduDeserializer.h" #include "fsfw/cfdp/pdu/AckPduSerializer.h" #include "fsfw/globalfunctions/arrayprinter.h" -#include +TEST_CASE("ACK PDU", "[AckPdu]") { + using namespace cfdp; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + std::array buf = {}; + uint8_t* bufptr = buf.data(); + size_t maxsz = buf.size(); + size_t sz = 0; + auto seqNum = TransactionSeqNum(WidthInBytes::TWO_BYTES, 15); + auto sourceId = EntityId(WidthInBytes::TWO_BYTES, 1); + auto destId = EntityId(WidthInBytes::TWO_BYTES, 2); + auto pduConf = PduConfig(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); + AckInfo ackInfo(FileDirectives::EOF_DIRECTIVE, ConditionCode::NO_ERROR, + AckTransactionStatus::ACTIVE); + auto ackSerializer = AckPduSerializer(ackInfo, pduConf); + result = ackSerializer.serialize(&bufptr, &sz, maxsz, SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); -TEST_CASE( "ACK PDU" , "[AckPdu]") { + SECTION("Serialize") { + REQUIRE(buf.data()[sz - 3] == cfdp::FileDirectives::ACK); + REQUIRE((buf.data()[sz - 2] >> 4) == FileDirectives::EOF_DIRECTIVE); + REQUIRE((buf.data()[sz - 2] & 0x0f) == 0); + REQUIRE(buf.data()[sz - 1] == AckTransactionStatus::ACTIVE); + ackInfo.setAckedDirective(FileDirectives::FINISH); + ackInfo.setAckedConditionCode(ConditionCode::FILESTORE_REJECTION); + ackInfo.setTransactionStatus(AckTransactionStatus::TERMINATED); + auto ackSerializer2 = AckPduSerializer(ackInfo, pduConf); + bufptr = buf.data(); + sz = 0; + result = ackSerializer2.serialize(&bufptr, &sz, maxsz, SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(buf.data()[sz - 3] == cfdp::FileDirectives::ACK); + REQUIRE((buf.data()[sz - 2] >> 4) == FileDirectives::FINISH); + REQUIRE((buf.data()[sz - 2] & 0x0f) == 0b0001); + REQUIRE((buf.data()[sz - 1] >> 4) == ConditionCode::FILESTORE_REJECTION); + REQUIRE((buf.data()[sz - 1] & 0b11) == AckTransactionStatus::TERMINATED); - using namespace cfdp; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - std::array buf = {}; - uint8_t* bufptr = buf.data(); - size_t maxsz = buf.size(); - size_t sz = 0; - auto seqNum = TransactionSeqNum(WidthInBytes::TWO_BYTES, 15); - auto sourceId = EntityId(WidthInBytes::TWO_BYTES, 1); - auto destId = EntityId(WidthInBytes::TWO_BYTES, 2); - auto pduConf = PduConfig(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); - AckInfo ackInfo(FileDirectives::EOF_DIRECTIVE, ConditionCode::NO_ERROR, AckTransactionStatus::ACTIVE); - auto ackSerializer = AckPduSerializer(ackInfo, pduConf); - result = ackSerializer.serialize(&bufptr, &sz, maxsz, SerializeIF::Endianness::NETWORK); + bufptr = buf.data(); + sz = 0; + ackInfo.setAckedDirective(FileDirectives::KEEP_ALIVE); + auto ackSerializer3 = AckPduSerializer(ackInfo, pduConf); + result = ackSerializer3.serialize(&bufptr, &sz, maxsz, SerializeIF::Endianness::NETWORK); + // Invalid file directive + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + + ackInfo.setAckedDirective(FileDirectives::FINISH); + // buffer too small + result = ackSerializer.serialize(&bufptr, &sz, 8, SerializeIF::Endianness::NETWORK); + REQUIRE(result == SerializeIF::BUFFER_TOO_SHORT); + } + + SECTION("Deserialize") { + AckInfo ackInfo; + auto reader = AckPduDeserializer(buf.data(), sz, ackInfo); + result = reader.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(ackInfo.getAckedDirective() == FileDirectives::EOF_DIRECTIVE); + REQUIRE(ackInfo.getAckedConditionCode() == ConditionCode::NO_ERROR); + REQUIRE(ackInfo.getDirectiveSubtypeCode() == 0); + REQUIRE(ackInfo.getTransactionStatus() == AckTransactionStatus::ACTIVE); + + AckInfo newInfo = AckInfo(FileDirectives::FINISH, ConditionCode::FILESTORE_REJECTION, + AckTransactionStatus::TERMINATED); + auto ackSerializer2 = AckPduSerializer(newInfo, pduConf); + bufptr = buf.data(); + sz = 0; + result = ackSerializer2.serialize(&bufptr, &sz, maxsz, SerializeIF::Endianness::NETWORK); REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - SECTION("Serialize") { - REQUIRE(buf.data()[sz - 3] == cfdp::FileDirectives::ACK); - REQUIRE((buf.data()[sz - 2] >> 4) == FileDirectives::EOF_DIRECTIVE); - REQUIRE((buf.data()[sz - 2] & 0x0f) == 0); - REQUIRE(buf.data()[sz - 1] == AckTransactionStatus::ACTIVE); - ackInfo.setAckedDirective(FileDirectives::FINISH); - ackInfo.setAckedConditionCode(ConditionCode::FILESTORE_REJECTION); - ackInfo.setTransactionStatus(AckTransactionStatus::TERMINATED); - auto ackSerializer2 = AckPduSerializer(ackInfo, pduConf); - bufptr = buf.data(); - sz = 0; - result = ackSerializer2.serialize(&bufptr, &sz, maxsz, SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(buf.data()[sz - 3] == cfdp::FileDirectives::ACK); - REQUIRE((buf.data()[sz - 2] >> 4) == FileDirectives::FINISH); - REQUIRE((buf.data()[sz - 2] & 0x0f) == 0b0001); - REQUIRE((buf.data()[sz - 1] >> 4) == ConditionCode::FILESTORE_REJECTION); - REQUIRE((buf.data()[sz - 1] & 0b11) == AckTransactionStatus::TERMINATED); + auto reader2 = AckPduDeserializer(buf.data(), sz, ackInfo); + result = reader2.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(ackInfo.getAckedDirective() == FileDirectives::FINISH); + REQUIRE(ackInfo.getAckedConditionCode() == ConditionCode::FILESTORE_REJECTION); + REQUIRE(ackInfo.getDirectiveSubtypeCode() == 0b0001); + REQUIRE(ackInfo.getTransactionStatus() == AckTransactionStatus::TERMINATED); - bufptr = buf.data(); - sz = 0; - ackInfo.setAckedDirective(FileDirectives::KEEP_ALIVE); - auto ackSerializer3 = AckPduSerializer(ackInfo, pduConf); - result = ackSerializer3.serialize(&bufptr, &sz, maxsz, SerializeIF::Endianness::NETWORK); - // Invalid file directive - REQUIRE(result != HasReturnvaluesIF::RETURN_OK); - - ackInfo.setAckedDirective(FileDirectives::FINISH); - // buffer too small - result = ackSerializer.serialize(&bufptr, &sz, 8, SerializeIF::Endianness::NETWORK); - REQUIRE(result == SerializeIF::BUFFER_TOO_SHORT); - } - - SECTION("Deserialize") { - AckInfo ackInfo; - auto reader = AckPduDeserializer(buf.data(), sz, ackInfo); - result = reader.parseData(); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(ackInfo.getAckedDirective() == FileDirectives::EOF_DIRECTIVE); - REQUIRE(ackInfo.getAckedConditionCode() == ConditionCode::NO_ERROR); - REQUIRE(ackInfo.getDirectiveSubtypeCode() == 0); - REQUIRE(ackInfo.getTransactionStatus() == AckTransactionStatus::ACTIVE); - - AckInfo newInfo = AckInfo(FileDirectives::FINISH, - ConditionCode::FILESTORE_REJECTION, AckTransactionStatus::TERMINATED); - auto ackSerializer2 = AckPduSerializer(newInfo, pduConf); - bufptr = buf.data(); - sz = 0; - result = ackSerializer2.serialize(&bufptr, &sz, maxsz, SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - - auto reader2 = AckPduDeserializer(buf.data(), sz, ackInfo); - result = reader2.parseData(); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(ackInfo.getAckedDirective() == FileDirectives::FINISH); - REQUIRE(ackInfo.getAckedConditionCode() == ConditionCode::FILESTORE_REJECTION); - REQUIRE(ackInfo.getDirectiveSubtypeCode() == 0b0001); - REQUIRE(ackInfo.getTransactionStatus() == AckTransactionStatus::TERMINATED); - - uint8_t prevVal = buf[sz - 2]; - buf[sz - 2] = FileDirectives::INVALID_DIRECTIVE << 4; - result = reader2.parseData(); - REQUIRE(result == cfdp::INVALID_ACK_DIRECTIVE_FIELDS); - buf[sz - 2] = FileDirectives::FINISH << 4 | 0b1111; - result = reader2.parseData(); - REQUIRE(result == cfdp::INVALID_ACK_DIRECTIVE_FIELDS); - buf[sz - 2] = prevVal; - buf[sz - 3] = cfdp::FileDirectives::INVALID_DIRECTIVE; - result = reader2.parseData(); - REQUIRE(result == cfdp::INVALID_DIRECTIVE_FIELDS); - buf[sz - 3] = cfdp::FileDirectives::ACK; - auto maxSizeTooSmall = AckPduDeserializer(buf.data(), sz - 2, ackInfo); - result = maxSizeTooSmall.parseData(); - REQUIRE(result == SerializeIF::STREAM_TOO_SHORT); - } + uint8_t prevVal = buf[sz - 2]; + buf[sz - 2] = FileDirectives::INVALID_DIRECTIVE << 4; + result = reader2.parseData(); + REQUIRE(result == cfdp::INVALID_ACK_DIRECTIVE_FIELDS); + buf[sz - 2] = FileDirectives::FINISH << 4 | 0b1111; + result = reader2.parseData(); + REQUIRE(result == cfdp::INVALID_ACK_DIRECTIVE_FIELDS); + buf[sz - 2] = prevVal; + buf[sz - 3] = cfdp::FileDirectives::INVALID_DIRECTIVE; + result = reader2.parseData(); + REQUIRE(result == cfdp::INVALID_DIRECTIVE_FIELDS); + buf[sz - 3] = cfdp::FileDirectives::ACK; + auto maxSizeTooSmall = AckPduDeserializer(buf.data(), sz - 2, ackInfo); + result = maxSizeTooSmall.parseData(); + REQUIRE(result == SerializeIF::STREAM_TOO_SHORT); + } } diff --git a/tests/src/fsfw_tests/unit/cfdp/testCfdp.cpp b/tests/src/fsfw_tests/unit/cfdp/testCfdp.cpp index 7db3800d..19b1ec7f 100644 --- a/tests/src/fsfw_tests/unit/cfdp/testCfdp.cpp +++ b/tests/src/fsfw_tests/unit/cfdp/testCfdp.cpp @@ -1,372 +1,368 @@ +#include #include +#include + +#include "fsfw/cfdp/FileSize.h" #include "fsfw/cfdp/pdu/FileDirectiveDeserializer.h" #include "fsfw/cfdp/pdu/FileDirectiveSerializer.h" #include "fsfw/cfdp/pdu/HeaderDeserializer.h" -#include "fsfw_tests/unit/CatchDefinitions.h" -#include "fsfw/cfdp/FileSize.h" -#include "fsfw/globalfunctions/arrayprinter.h" #include "fsfw/cfdp/pdu/HeaderSerializer.h" +#include "fsfw/globalfunctions/arrayprinter.h" #include "fsfw/serialize/SerializeAdapter.h" +#include "fsfw_tests/unit/CatchDefinitions.h" -#include -#include +TEST_CASE("CFDP Base", "[CfdpBase]") { + using namespace cfdp; + std::array serBuf; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + cfdp::TransactionSeqNum seqNum = TransactionSeqNum(cfdp::WidthInBytes::ONE_BYTE, 2); + cfdp::EntityId sourceId = EntityId(cfdp::WidthInBytes::ONE_BYTE, 0); + cfdp::EntityId destId = EntityId(cfdp::WidthInBytes::ONE_BYTE, 1); + PduConfig pduConf = + PduConfig(cfdp::TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId, false); + uint8_t* serTarget = serBuf.data(); + const uint8_t* deserTarget = serTarget; + size_t serSize = 0; -TEST_CASE( "CFDP Base" , "[CfdpBase]") { - using namespace cfdp; - std::array serBuf; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - cfdp::TransactionSeqNum seqNum = TransactionSeqNum(cfdp::WidthInBytes::ONE_BYTE, 2); - cfdp::EntityId sourceId = EntityId(cfdp::WidthInBytes::ONE_BYTE, 0); - cfdp::EntityId destId = EntityId(cfdp::WidthInBytes::ONE_BYTE, 1); - PduConfig pduConf = PduConfig(cfdp::TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, - destId, false); - uint8_t* serTarget = serBuf.data(); - const uint8_t* deserTarget = serTarget; - size_t serSize = 0; + SECTION("Header Serialization") { + auto headerSerializer = HeaderSerializer(pduConf, cfdp::PduType::FILE_DIRECTIVE, 0); + const uint8_t** dummyPtr = nullptr; + ReturnValue_t deserResult = + headerSerializer.deSerialize(dummyPtr, &serSize, SerializeIF::Endianness::NETWORK); + REQUIRE(deserResult == retval::CATCH_FAILED); + deserResult = headerSerializer.serialize(nullptr, &serSize, serBuf.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(deserResult == retval::CATCH_FAILED); + REQUIRE(seqNum.getSerializedSize() == 1); - SECTION("Header Serialization") { - auto headerSerializer = HeaderSerializer(pduConf, cfdp::PduType::FILE_DIRECTIVE, 0); - const uint8_t** dummyPtr = nullptr; - ReturnValue_t deserResult = headerSerializer.deSerialize(dummyPtr, &serSize, - SerializeIF::Endianness::NETWORK); - REQUIRE(deserResult == retval::CATCH_FAILED); - deserResult = headerSerializer.serialize(nullptr, &serSize, serBuf.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(deserResult == retval::CATCH_FAILED); - REQUIRE(seqNum.getSerializedSize() == 1); + REQUIRE(headerSerializer.getPduDataFieldLen() == 0); + REQUIRE(headerSerializer.getSerializedSize() == 7); + REQUIRE(headerSerializer.getWholePduSize() == 7); + REQUIRE(headerSerializer.getCrcFlag() == false); + REQUIRE(headerSerializer.getDirection() == cfdp::Direction::TOWARDS_RECEIVER); + REQUIRE(headerSerializer.getLargeFileFlag() == false); + REQUIRE(headerSerializer.getLenEntityIds() == 1); + REQUIRE(headerSerializer.getLenSeqNum() == 1); + REQUIRE(headerSerializer.getPduType() == cfdp::PduType::FILE_DIRECTIVE); + REQUIRE(headerSerializer.getSegmentMetadataFlag() == cfdp::SegmentMetadataFlag::NOT_PRESENT); + REQUIRE(headerSerializer.getSegmentationControl() == false); + REQUIRE(headerSerializer.getTransmissionMode() == cfdp::TransmissionModes::ACKNOWLEDGED); - REQUIRE(headerSerializer.getPduDataFieldLen() == 0); - REQUIRE(headerSerializer.getSerializedSize() == 7); - REQUIRE(headerSerializer.getWholePduSize() == 7); - REQUIRE(headerSerializer.getCrcFlag() == false); - REQUIRE(headerSerializer.getDirection() == cfdp::Direction::TOWARDS_RECEIVER); - REQUIRE(headerSerializer.getLargeFileFlag() == false); - REQUIRE(headerSerializer.getLenEntityIds() == 1); - REQUIRE(headerSerializer.getLenSeqNum() == 1); - REQUIRE(headerSerializer.getPduType() == cfdp::PduType::FILE_DIRECTIVE); - REQUIRE(headerSerializer.getSegmentMetadataFlag() == cfdp::SegmentMetadataFlag::NOT_PRESENT); - REQUIRE(headerSerializer.getSegmentationControl() == false); - REQUIRE(headerSerializer.getTransmissionMode() == cfdp::TransmissionModes::ACKNOWLEDGED); + cfdp::TransactionSeqNum seqNumLocal; + headerSerializer.getTransactionSeqNum(seqNumLocal); + REQUIRE(seqNumLocal.getWidth() == cfdp::WidthInBytes::ONE_BYTE); + REQUIRE(seqNumLocal.getValue() == 2); + cfdp::EntityId sourceDestId; + headerSerializer.getSourceId(sourceDestId); + REQUIRE(sourceDestId.getWidth() == cfdp::WidthInBytes::ONE_BYTE); + REQUIRE(sourceDestId.getValue() == 0); + headerSerializer.getDestId(sourceDestId); + REQUIRE(sourceDestId.getWidth() == cfdp::WidthInBytes::ONE_BYTE); + REQUIRE(sourceDestId.getValue() == 1); - cfdp::TransactionSeqNum seqNumLocal; - headerSerializer.getTransactionSeqNum(seqNumLocal); - REQUIRE(seqNumLocal.getWidth() == cfdp::WidthInBytes::ONE_BYTE); - REQUIRE(seqNumLocal.getValue() == 2); - cfdp::EntityId sourceDestId; - headerSerializer.getSourceId(sourceDestId); - REQUIRE(sourceDestId.getWidth() == cfdp::WidthInBytes::ONE_BYTE); - REQUIRE(sourceDestId.getValue() == 0); - headerSerializer.getDestId(sourceDestId); - REQUIRE(sourceDestId.getWidth() == cfdp::WidthInBytes::ONE_BYTE); - REQUIRE(sourceDestId.getValue() == 1); + result = headerSerializer.serialize(&serTarget, &serSize, serBuf.size(), + SerializeIF::Endianness::BIG); + REQUIRE(result == retval::CATCH_OK); + REQUIRE(serSize == 7); + // Only version bits are set + REQUIRE(serBuf[0] == 0b00100000); + // PDU data field length is 0 + REQUIRE(serBuf[1] == 0); + REQUIRE(serBuf[2] == 0); + // Entity and Transaction Sequence number are 1 byte large + REQUIRE(serBuf[3] == 0b00010001); + // Source ID + REQUIRE(serBuf[4] == 0); + // Transaction Seq Number + REQUIRE(serBuf[5] == 2); + // Dest ID + REQUIRE(serBuf[6] == 1); - result = headerSerializer.serialize(&serTarget, &serSize, - serBuf.size(), SerializeIF::Endianness::BIG); - REQUIRE(result == retval::CATCH_OK); - REQUIRE(serSize == 7); - // Only version bits are set - REQUIRE(serBuf[0] == 0b00100000); - // PDU data field length is 0 - REQUIRE(serBuf[1] == 0); - REQUIRE(serBuf[2] == 0); - // Entity and Transaction Sequence number are 1 byte large - REQUIRE(serBuf[3] == 0b00010001); - // Source ID - REQUIRE(serBuf[4] == 0); - // Transaction Seq Number - REQUIRE(serBuf[5] == 2); - // Dest ID - REQUIRE(serBuf[6] == 1); - - for(uint8_t idx = 0; idx < 7; idx++) { - ReturnValue_t result = headerSerializer.serialize(&serTarget, &serSize, - idx, SerializeIF::Endianness::BIG); - REQUIRE(result == static_cast(SerializeIF::BUFFER_TOO_SHORT)); - } - - // Set PDU data field len - headerSerializer.setPduDataFieldLen(0x0ff0); - REQUIRE(headerSerializer.getPduDataFieldLen() == 0x0ff0); - REQUIRE(headerSerializer.getSerializedSize() == 7); - REQUIRE(headerSerializer.getWholePduSize() == 7 + 0x0ff0); - serTarget = serBuf.data(); - serSize = 0; - result = headerSerializer.serialize(&serTarget, &serSize, - serBuf.size(), SerializeIF::Endianness::BIG); - REQUIRE(serBuf[1] == 0x0f); - REQUIRE(serBuf[2] == 0xf0); - - pduConf.crcFlag = true; - pduConf.largeFile = true; - pduConf.direction = cfdp::Direction::TOWARDS_SENDER; - pduConf.mode = cfdp::TransmissionModes::UNACKNOWLEDGED; - headerSerializer.setSegmentationControl( - cfdp::SegmentationControl::RECORD_BOUNDARIES_PRESERVATION); - headerSerializer.setPduType(cfdp::PduType::FILE_DATA); - headerSerializer.setSegmentMetadataFlag(cfdp::SegmentMetadataFlag::PRESENT); - serTarget = serBuf.data(); - serSize = 0; - result = headerSerializer.serialize(&serTarget, &serSize, - serBuf.size(), SerializeIF::Endianness::BIG); - - // Everything except version bit flipped to one now - REQUIRE(serBuf[0] == 0x3f); - REQUIRE(serBuf[3] == 0x99); - pduConf.seqNum.setValue(cfdp::WidthInBytes::TWO_BYTES, 0x0fff); - pduConf.sourceId.setValue(cfdp::WidthInBytes::FOUR_BYTES, 0xff00ff00); - pduConf.destId.setValue(cfdp::WidthInBytes::FOUR_BYTES, 0x00ff00ff); - REQUIRE(pduConf.sourceId.getSerializedSize() == 4); - REQUIRE(headerSerializer.getSerializedSize() == 14); - serTarget = serBuf.data(); - serSize = 0; - result = headerSerializer.serialize(&serTarget, &serSize, - serBuf.size(), SerializeIF::Endianness::BIG); - - for(uint8_t idx = 0; idx < 14; idx++) { - ReturnValue_t result = headerSerializer.serialize(&serTarget, &serSize, - idx, SerializeIF::Endianness::BIG); - REQUIRE(result == static_cast(SerializeIF::BUFFER_TOO_SHORT)); - } - REQUIRE(headerSerializer.getCrcFlag() == true); - REQUIRE(headerSerializer.getDirection() == cfdp::Direction::TOWARDS_SENDER); - REQUIRE(headerSerializer.getLargeFileFlag() == true); - REQUIRE(headerSerializer.getLenEntityIds() == 4); - REQUIRE(headerSerializer.getLenSeqNum() == 2); - REQUIRE(headerSerializer.getPduType() == cfdp::PduType::FILE_DATA); - REQUIRE(headerSerializer.getSegmentMetadataFlag() == cfdp::SegmentMetadataFlag::PRESENT); - REQUIRE(headerSerializer.getTransmissionMode() == cfdp::TransmissionModes::UNACKNOWLEDGED); - REQUIRE(headerSerializer.getSegmentationControl() == true); - // Last three bits are 2 now (length of seq number) and bit 1 to bit 3 is 4 (len entity IDs) - REQUIRE(serBuf[3] == 0b11001010); - uint32_t entityId = 0; - size_t deSerSize = 0; - SerializeAdapter::deSerialize(&entityId, serBuf.data() + 4, &deSerSize, - SerializeIF::Endianness::NETWORK); - REQUIRE(deSerSize == 4); - REQUIRE(entityId == 0xff00ff00); - uint16_t seqNum = 0; - SerializeAdapter::deSerialize(&seqNum, serBuf.data() + 8, &deSerSize, - SerializeIF::Endianness::NETWORK); - REQUIRE(deSerSize == 2); - REQUIRE(seqNum == 0x0fff); - SerializeAdapter::deSerialize(&entityId, serBuf.data() + 10, &deSerSize, - SerializeIF::Endianness::NETWORK); - REQUIRE(deSerSize == 4); - REQUIRE(entityId == 0x00ff00ff); - - result = pduConf.sourceId.setValue(cfdp::WidthInBytes::ONE_BYTE, 0xfff); - REQUIRE(result == retval::CATCH_FAILED); - result = pduConf.sourceId.setValue(cfdp::WidthInBytes::TWO_BYTES, 0xfffff); - REQUIRE(result == retval::CATCH_FAILED); - result = pduConf.sourceId.setValue(cfdp::WidthInBytes::FOUR_BYTES, 0xfffffffff); - REQUIRE(result == retval::CATCH_FAILED); - uint8_t oneByteSourceId = 32; - serTarget = &oneByteSourceId; - size_t deserLen = 1; - pduConf.sourceId.deSerialize(cfdp::WidthInBytes::ONE_BYTE, - const_cast(&serTarget), &deserLen, - SerializeIF::Endianness::MACHINE); - REQUIRE(pduConf.sourceId.getValue() == 32); - - uint16_t twoByteSourceId = 0xf0f0; - serTarget = reinterpret_cast(&twoByteSourceId); - deserLen = 2; - pduConf.sourceId.deSerialize(cfdp::WidthInBytes::TWO_BYTES, - const_cast(&serTarget), &deserLen, - SerializeIF::Endianness::MACHINE); - REQUIRE(pduConf.sourceId.getValue() == 0xf0f0); - - uint32_t fourByteSourceId = 0xf0f0f0f0; - serTarget = reinterpret_cast(&fourByteSourceId); - deserLen = 4; - pduConf.sourceId.deSerialize(cfdp::WidthInBytes::FOUR_BYTES, - const_cast(&serTarget), &deserLen, - SerializeIF::Endianness::MACHINE); - REQUIRE(pduConf.sourceId.getValue() == 0xf0f0f0f0); - - pduConf.sourceId.setValue(cfdp::WidthInBytes::ONE_BYTE, 1); - serTarget = serBuf.data(); - serSize = 1; - result = pduConf.sourceId.serialize(&serTarget, &serSize, 1, - SerializeIF::Endianness::MACHINE); - REQUIRE(result == static_cast(SerializeIF::BUFFER_TOO_SHORT)); + for (uint8_t idx = 0; idx < 7; idx++) { + ReturnValue_t result = + headerSerializer.serialize(&serTarget, &serSize, idx, SerializeIF::Endianness::BIG); + REQUIRE(result == static_cast(SerializeIF::BUFFER_TOO_SHORT)); } - SECTION( "Header Deserialization" ) { - // We unittested the serializer before, so we can use it now to generate valid raw CFDP - // data - auto headerSerializer = HeaderSerializer(pduConf, cfdp::PduType::FILE_DIRECTIVE, 0); - ReturnValue_t result = headerSerializer.serialize(&serTarget, &serSize, - serBuf.size(), SerializeIF::Endianness::BIG); - REQUIRE(result == retval::CATCH_OK); - REQUIRE(serBuf[1] == 0); - REQUIRE(serBuf[2] == 0); - // Entity and Transaction Sequence number are 1 byte large - REQUIRE(serBuf[3] == 0b00010001); - REQUIRE(serSize == 7); - // Deser call not strictly necessary - auto headerDeser = HeaderDeserializer(serBuf.data(), serBuf.size()); + // Set PDU data field len + headerSerializer.setPduDataFieldLen(0x0ff0); + REQUIRE(headerSerializer.getPduDataFieldLen() == 0x0ff0); + REQUIRE(headerSerializer.getSerializedSize() == 7); + REQUIRE(headerSerializer.getWholePduSize() == 7 + 0x0ff0); + serTarget = serBuf.data(); + serSize = 0; + result = headerSerializer.serialize(&serTarget, &serSize, serBuf.size(), + SerializeIF::Endianness::BIG); + REQUIRE(serBuf[1] == 0x0f); + REQUIRE(serBuf[2] == 0xf0); - ReturnValue_t serResult = headerDeser.parseData(); - REQUIRE(serResult == retval::CATCH_OK); - REQUIRE(headerDeser.getPduDataFieldLen() == 0); - REQUIRE(headerDeser.getHeaderSize() == 7); - REQUIRE(headerDeser.getWholePduSize() == 7); - REQUIRE(headerDeser.getCrcFlag() == false); - REQUIRE(headerDeser.getDirection() == cfdp::Direction::TOWARDS_RECEIVER); - REQUIRE(headerDeser.getLargeFileFlag() == false); - REQUIRE(headerDeser.getLenEntityIds() == 1); - REQUIRE(headerDeser.getLenSeqNum() == 1); - REQUIRE(headerDeser.getPduType() == cfdp::PduType::FILE_DIRECTIVE); - REQUIRE(headerDeser.getSegmentMetadataFlag() == cfdp::SegmentMetadataFlag::NOT_PRESENT); - REQUIRE(headerDeser.getSegmentationControl() == false); - REQUIRE(headerDeser.getTransmissionMode() == cfdp::TransmissionModes::ACKNOWLEDGED); + pduConf.crcFlag = true; + pduConf.largeFile = true; + pduConf.direction = cfdp::Direction::TOWARDS_SENDER; + pduConf.mode = cfdp::TransmissionModes::UNACKNOWLEDGED; + headerSerializer.setSegmentationControl( + cfdp::SegmentationControl::RECORD_BOUNDARIES_PRESERVATION); + headerSerializer.setPduType(cfdp::PduType::FILE_DATA); + headerSerializer.setSegmentMetadataFlag(cfdp::SegmentMetadataFlag::PRESENT); + serTarget = serBuf.data(); + serSize = 0; + result = headerSerializer.serialize(&serTarget, &serSize, serBuf.size(), + SerializeIF::Endianness::BIG); - pduConf.crcFlag = true; - pduConf.largeFile = true; - pduConf.direction = cfdp::Direction::TOWARDS_SENDER; - pduConf.mode = cfdp::TransmissionModes::UNACKNOWLEDGED; - headerSerializer.setSegmentationControl( - cfdp::SegmentationControl::RECORD_BOUNDARIES_PRESERVATION); - headerSerializer.setPduType(cfdp::PduType::FILE_DATA); - headerSerializer.setSegmentMetadataFlag(cfdp::SegmentMetadataFlag::PRESENT); - result = pduConf.seqNum.setValue(cfdp::WidthInBytes::TWO_BYTES, 0x0fff); - REQUIRE(result == retval::CATCH_OK); - result = pduConf.sourceId.setValue(cfdp::WidthInBytes::FOUR_BYTES, 0xff00ff00); - REQUIRE(result == retval::CATCH_OK); - result = pduConf.destId.setValue(cfdp::WidthInBytes::FOUR_BYTES, 0x00ff00ff); - REQUIRE(result == retval::CATCH_OK); - serTarget = serBuf.data(); - serSize = 0; - result = headerSerializer.serialize(&serTarget, &serSize, - serBuf.size(), SerializeIF::Endianness::BIG); - headerDeser = HeaderDeserializer(serBuf.data(), serBuf.size()); + // Everything except version bit flipped to one now + REQUIRE(serBuf[0] == 0x3f); + REQUIRE(serBuf[3] == 0x99); + pduConf.seqNum.setValue(cfdp::WidthInBytes::TWO_BYTES, 0x0fff); + pduConf.sourceId.setValue(cfdp::WidthInBytes::FOUR_BYTES, 0xff00ff00); + pduConf.destId.setValue(cfdp::WidthInBytes::FOUR_BYTES, 0x00ff00ff); + REQUIRE(pduConf.sourceId.getSerializedSize() == 4); + REQUIRE(headerSerializer.getSerializedSize() == 14); + serTarget = serBuf.data(); + serSize = 0; + result = headerSerializer.serialize(&serTarget, &serSize, serBuf.size(), + SerializeIF::Endianness::BIG); - result = headerDeser.parseData(); - REQUIRE(result == retval::CATCH_OK); - // Everything except version bit flipped to one now - REQUIRE(serBuf[0] == 0x3f); - REQUIRE(serBuf[3] == 0b11001010); - REQUIRE(headerDeser.getWholePduSize() == 14); + for (uint8_t idx = 0; idx < 14; idx++) { + ReturnValue_t result = + headerSerializer.serialize(&serTarget, &serSize, idx, SerializeIF::Endianness::BIG); + REQUIRE(result == static_cast(SerializeIF::BUFFER_TOO_SHORT)); + } + REQUIRE(headerSerializer.getCrcFlag() == true); + REQUIRE(headerSerializer.getDirection() == cfdp::Direction::TOWARDS_SENDER); + REQUIRE(headerSerializer.getLargeFileFlag() == true); + REQUIRE(headerSerializer.getLenEntityIds() == 4); + REQUIRE(headerSerializer.getLenSeqNum() == 2); + REQUIRE(headerSerializer.getPduType() == cfdp::PduType::FILE_DATA); + REQUIRE(headerSerializer.getSegmentMetadataFlag() == cfdp::SegmentMetadataFlag::PRESENT); + REQUIRE(headerSerializer.getTransmissionMode() == cfdp::TransmissionModes::UNACKNOWLEDGED); + REQUIRE(headerSerializer.getSegmentationControl() == true); + // Last three bits are 2 now (length of seq number) and bit 1 to bit 3 is 4 (len entity IDs) + REQUIRE(serBuf[3] == 0b11001010); + uint32_t entityId = 0; + size_t deSerSize = 0; + SerializeAdapter::deSerialize(&entityId, serBuf.data() + 4, &deSerSize, + SerializeIF::Endianness::NETWORK); + REQUIRE(deSerSize == 4); + REQUIRE(entityId == 0xff00ff00); + uint16_t seqNum = 0; + SerializeAdapter::deSerialize(&seqNum, serBuf.data() + 8, &deSerSize, + SerializeIF::Endianness::NETWORK); + REQUIRE(deSerSize == 2); + REQUIRE(seqNum == 0x0fff); + SerializeAdapter::deSerialize(&entityId, serBuf.data() + 10, &deSerSize, + SerializeIF::Endianness::NETWORK); + REQUIRE(deSerSize == 4); + REQUIRE(entityId == 0x00ff00ff); - REQUIRE(headerDeser.getCrcFlag() == true); - REQUIRE(headerDeser.getDirection() == cfdp::Direction::TOWARDS_SENDER); - REQUIRE(headerDeser.getLargeFileFlag() == true); - REQUIRE(headerDeser.getLenEntityIds() == 4); - REQUIRE(headerDeser.getLenSeqNum() == 2); - REQUIRE(headerDeser.getPduType() == cfdp::PduType::FILE_DATA); - REQUIRE(headerDeser.getSegmentMetadataFlag() == cfdp::SegmentMetadataFlag::PRESENT); - REQUIRE(headerDeser.getSegmentationControl() == true); - REQUIRE(headerDeser.getTransmissionMode() == cfdp::TransmissionModes::UNACKNOWLEDGED); + result = pduConf.sourceId.setValue(cfdp::WidthInBytes::ONE_BYTE, 0xfff); + REQUIRE(result == retval::CATCH_FAILED); + result = pduConf.sourceId.setValue(cfdp::WidthInBytes::TWO_BYTES, 0xfffff); + REQUIRE(result == retval::CATCH_FAILED); + result = pduConf.sourceId.setValue(cfdp::WidthInBytes::FOUR_BYTES, 0xfffffffff); + REQUIRE(result == retval::CATCH_FAILED); + uint8_t oneByteSourceId = 32; + serTarget = &oneByteSourceId; + size_t deserLen = 1; + pduConf.sourceId.deSerialize(cfdp::WidthInBytes::ONE_BYTE, + const_cast(&serTarget), &deserLen, + SerializeIF::Endianness::MACHINE); + REQUIRE(pduConf.sourceId.getValue() == 32); - cfdp::TransactionSeqNum seqNumLocal; - headerDeser.getTransactionSeqNum(seqNumLocal); - REQUIRE(seqNumLocal.getWidth() == cfdp::WidthInBytes::TWO_BYTES); - REQUIRE(seqNumLocal.getValue() == 0x0fff); - cfdp::EntityId sourceDestId; - headerDeser.getSourceId(sourceDestId); - REQUIRE(sourceDestId.getWidth() == cfdp::WidthInBytes::FOUR_BYTES); - REQUIRE(sourceDestId.getValue() == 0xff00ff00); - headerDeser.getDestId(sourceDestId); - REQUIRE(sourceDestId.getWidth() == cfdp::WidthInBytes::FOUR_BYTES); - REQUIRE(sourceDestId.getValue() == 0x00ff00ff); + uint16_t twoByteSourceId = 0xf0f0; + serTarget = reinterpret_cast(&twoByteSourceId); + deserLen = 2; + pduConf.sourceId.deSerialize(cfdp::WidthInBytes::TWO_BYTES, + const_cast(&serTarget), &deserLen, + SerializeIF::Endianness::MACHINE); + REQUIRE(pduConf.sourceId.getValue() == 0xf0f0); - size_t deSerSize = headerDeser.getWholePduSize(); - serTarget = serBuf.data(); - const uint8_t** serTargetConst = const_cast(&serTarget); - result = headerDeser.parseData(); - REQUIRE(result == retval::CATCH_OK); + uint32_t fourByteSourceId = 0xf0f0f0f0; + serTarget = reinterpret_cast(&fourByteSourceId); + deserLen = 4; + pduConf.sourceId.deSerialize(cfdp::WidthInBytes::FOUR_BYTES, + const_cast(&serTarget), &deserLen, + SerializeIF::Endianness::MACHINE); + REQUIRE(pduConf.sourceId.getValue() == 0xf0f0f0f0); - headerDeser.setData(nullptr, -1); - REQUIRE(headerDeser.getHeaderSize() == 0); - headerDeser.setData(serBuf.data(), serBuf.size()); + pduConf.sourceId.setValue(cfdp::WidthInBytes::ONE_BYTE, 1); + serTarget = serBuf.data(); + serSize = 1; + result = pduConf.sourceId.serialize(&serTarget, &serSize, 1, SerializeIF::Endianness::MACHINE); + REQUIRE(result == static_cast(SerializeIF::BUFFER_TOO_SHORT)); + } - serTarget = serBuf.data(); - serSize = 0; - pduConf.sourceId.setValue(cfdp::WidthInBytes::ONE_BYTE, 22); - pduConf.destId.setValue(cfdp::WidthInBytes::ONE_BYTE, 48); - result = headerSerializer.serialize(&serTarget, &serSize, - serBuf.size(), SerializeIF::Endianness::BIG); - REQUIRE(result == retval::CATCH_OK); - REQUIRE(headerDeser.getWholePduSize() == 8); - headerDeser.setData(serBuf.data(), serBuf.size()); + SECTION("Header Deserialization") { + // We unittested the serializer before, so we can use it now to generate valid raw CFDP + // data + auto headerSerializer = HeaderSerializer(pduConf, cfdp::PduType::FILE_DIRECTIVE, 0); + ReturnValue_t result = headerSerializer.serialize(&serTarget, &serSize, serBuf.size(), + SerializeIF::Endianness::BIG); + REQUIRE(result == retval::CATCH_OK); + REQUIRE(serBuf[1] == 0); + REQUIRE(serBuf[2] == 0); + // Entity and Transaction Sequence number are 1 byte large + REQUIRE(serBuf[3] == 0b00010001); + REQUIRE(serSize == 7); + // Deser call not strictly necessary + auto headerDeser = HeaderDeserializer(serBuf.data(), serBuf.size()); - headerDeser.getSourceId(sourceDestId); - REQUIRE(sourceDestId.getWidth() == cfdp::WidthInBytes::ONE_BYTE); - REQUIRE(sourceDestId.getValue() == 22); + ReturnValue_t serResult = headerDeser.parseData(); + REQUIRE(serResult == retval::CATCH_OK); + REQUIRE(headerDeser.getPduDataFieldLen() == 0); + REQUIRE(headerDeser.getHeaderSize() == 7); + REQUIRE(headerDeser.getWholePduSize() == 7); + REQUIRE(headerDeser.getCrcFlag() == false); + REQUIRE(headerDeser.getDirection() == cfdp::Direction::TOWARDS_RECEIVER); + REQUIRE(headerDeser.getLargeFileFlag() == false); + REQUIRE(headerDeser.getLenEntityIds() == 1); + REQUIRE(headerDeser.getLenSeqNum() == 1); + REQUIRE(headerDeser.getPduType() == cfdp::PduType::FILE_DIRECTIVE); + REQUIRE(headerDeser.getSegmentMetadataFlag() == cfdp::SegmentMetadataFlag::NOT_PRESENT); + REQUIRE(headerDeser.getSegmentationControl() == false); + REQUIRE(headerDeser.getTransmissionMode() == cfdp::TransmissionModes::ACKNOWLEDGED); + + pduConf.crcFlag = true; + pduConf.largeFile = true; + pduConf.direction = cfdp::Direction::TOWARDS_SENDER; + pduConf.mode = cfdp::TransmissionModes::UNACKNOWLEDGED; + headerSerializer.setSegmentationControl( + cfdp::SegmentationControl::RECORD_BOUNDARIES_PRESERVATION); + headerSerializer.setPduType(cfdp::PduType::FILE_DATA); + headerSerializer.setSegmentMetadataFlag(cfdp::SegmentMetadataFlag::PRESENT); + result = pduConf.seqNum.setValue(cfdp::WidthInBytes::TWO_BYTES, 0x0fff); + REQUIRE(result == retval::CATCH_OK); + result = pduConf.sourceId.setValue(cfdp::WidthInBytes::FOUR_BYTES, 0xff00ff00); + REQUIRE(result == retval::CATCH_OK); + result = pduConf.destId.setValue(cfdp::WidthInBytes::FOUR_BYTES, 0x00ff00ff); + REQUIRE(result == retval::CATCH_OK); + serTarget = serBuf.data(); + serSize = 0; + result = headerSerializer.serialize(&serTarget, &serSize, serBuf.size(), + SerializeIF::Endianness::BIG); + headerDeser = HeaderDeserializer(serBuf.data(), serBuf.size()); + + result = headerDeser.parseData(); + REQUIRE(result == retval::CATCH_OK); + // Everything except version bit flipped to one now + REQUIRE(serBuf[0] == 0x3f); + REQUIRE(serBuf[3] == 0b11001010); + REQUIRE(headerDeser.getWholePduSize() == 14); + + REQUIRE(headerDeser.getCrcFlag() == true); + REQUIRE(headerDeser.getDirection() == cfdp::Direction::TOWARDS_SENDER); + REQUIRE(headerDeser.getLargeFileFlag() == true); + REQUIRE(headerDeser.getLenEntityIds() == 4); + REQUIRE(headerDeser.getLenSeqNum() == 2); + REQUIRE(headerDeser.getPduType() == cfdp::PduType::FILE_DATA); + REQUIRE(headerDeser.getSegmentMetadataFlag() == cfdp::SegmentMetadataFlag::PRESENT); + REQUIRE(headerDeser.getSegmentationControl() == true); + REQUIRE(headerDeser.getTransmissionMode() == cfdp::TransmissionModes::UNACKNOWLEDGED); + + cfdp::TransactionSeqNum seqNumLocal; + headerDeser.getTransactionSeqNum(seqNumLocal); + REQUIRE(seqNumLocal.getWidth() == cfdp::WidthInBytes::TWO_BYTES); + REQUIRE(seqNumLocal.getValue() == 0x0fff); + cfdp::EntityId sourceDestId; + headerDeser.getSourceId(sourceDestId); + REQUIRE(sourceDestId.getWidth() == cfdp::WidthInBytes::FOUR_BYTES); + REQUIRE(sourceDestId.getValue() == 0xff00ff00); + headerDeser.getDestId(sourceDestId); + REQUIRE(sourceDestId.getWidth() == cfdp::WidthInBytes::FOUR_BYTES); + REQUIRE(sourceDestId.getValue() == 0x00ff00ff); + + size_t deSerSize = headerDeser.getWholePduSize(); + serTarget = serBuf.data(); + const uint8_t** serTargetConst = const_cast(&serTarget); + result = headerDeser.parseData(); + REQUIRE(result == retval::CATCH_OK); + + headerDeser.setData(nullptr, -1); + REQUIRE(headerDeser.getHeaderSize() == 0); + headerDeser.setData(serBuf.data(), serBuf.size()); + + serTarget = serBuf.data(); + serSize = 0; + pduConf.sourceId.setValue(cfdp::WidthInBytes::ONE_BYTE, 22); + pduConf.destId.setValue(cfdp::WidthInBytes::ONE_BYTE, 48); + result = headerSerializer.serialize(&serTarget, &serSize, serBuf.size(), + SerializeIF::Endianness::BIG); + REQUIRE(result == retval::CATCH_OK); + REQUIRE(headerDeser.getWholePduSize() == 8); + headerDeser.setData(serBuf.data(), serBuf.size()); + + headerDeser.getSourceId(sourceDestId); + REQUIRE(sourceDestId.getWidth() == cfdp::WidthInBytes::ONE_BYTE); + REQUIRE(sourceDestId.getValue() == 22); + } + + SECTION("File Directive") { + auto fdSer = FileDirectiveSerializer(pduConf, FileDirectives::ACK, 4); + REQUIRE(fdSer.getSerializedSize() == 8); + serTarget = serBuf.data(); + serSize = 0; + result = fdSer.serialize(&serTarget, &serSize, serBuf.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + // Only version bits are set + REQUIRE(serBuf[0] == 0b00100000); + // PDU data field length is 5 (4 + Directive code octet) + REQUIRE(serBuf[1] == 0); + REQUIRE(serBuf[2] == 5); + // Entity and Transaction Sequence number are 1 byte large + REQUIRE(serBuf[3] == 0b00010001); + // Source ID + REQUIRE(serBuf[4] == 0); + // Transaction Seq Number + REQUIRE(serBuf[5] == 2); + // Dest ID + REQUIRE(serBuf[6] == 1); + REQUIRE(serBuf[7] == FileDirectives::ACK); + + serTarget = serBuf.data(); + size_t deserSize = 20; + serSize = 0; + REQUIRE(fdSer.deSerialize(&deserTarget, &deserSize, SerializeIF::Endianness::NETWORK) == + HasReturnvaluesIF::RETURN_FAILED); + REQUIRE(fdSer.serialize(nullptr, nullptr, 85, SerializeIF::Endianness::NETWORK) == + HasReturnvaluesIF::RETURN_FAILED); + for (uint8_t idx = 0; idx < 8; idx++) { + serTarget = serBuf.data(); + serSize = 0; + REQUIRE(fdSer.serialize(&serTarget, &serSize, idx, SerializeIF::Endianness::NETWORK) == + SerializeIF::BUFFER_TOO_SHORT); } - SECTION("File Directive") { - auto fdSer = FileDirectiveSerializer(pduConf, FileDirectives::ACK, 4); - REQUIRE(fdSer.getSerializedSize() == 8); - serTarget = serBuf.data(); - serSize = 0; - result = fdSer.serialize(&serTarget, &serSize, serBuf.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - // Only version bits are set - REQUIRE(serBuf[0] == 0b00100000); - // PDU data field length is 5 (4 + Directive code octet) - REQUIRE(serBuf[1] == 0); - REQUIRE(serBuf[2] == 5); - // Entity and Transaction Sequence number are 1 byte large - REQUIRE(serBuf[3] == 0b00010001); - // Source ID - REQUIRE(serBuf[4] == 0); - // Transaction Seq Number - REQUIRE(serBuf[5] == 2); - // Dest ID - REQUIRE(serBuf[6] == 1); - REQUIRE(serBuf[7] == FileDirectives::ACK); + deserTarget = serBuf.data(); + deserSize = 0; + auto fdDeser = FileDirectiveDeserializer(deserTarget, serBuf.size()); + REQUIRE(fdDeser.getEndianness() == SerializeIF::Endianness::NETWORK); + fdDeser.setEndianness(SerializeIF::Endianness::MACHINE); + REQUIRE(fdDeser.getEndianness() == SerializeIF::Endianness::MACHINE); + fdDeser.setEndianness(SerializeIF::Endianness::NETWORK); + REQUIRE(fdDeser.parseData() == HasReturnvaluesIF::RETURN_OK); + REQUIRE(fdDeser.getFileDirective() == FileDirectives::ACK); + REQUIRE(fdDeser.getPduDataFieldLen() == 5); + REQUIRE(fdDeser.getHeaderSize() == 8); + REQUIRE(fdDeser.getPduType() == cfdp::PduType::FILE_DIRECTIVE); - serTarget = serBuf.data(); - size_t deserSize = 20; - serSize = 0; - REQUIRE(fdSer.deSerialize(&deserTarget, &deserSize, SerializeIF::Endianness::NETWORK) == - HasReturnvaluesIF::RETURN_FAILED); - REQUIRE(fdSer.serialize(nullptr, nullptr, 85, SerializeIF::Endianness::NETWORK) == - HasReturnvaluesIF::RETURN_FAILED); - for(uint8_t idx = 0; idx < 8; idx++) { - serTarget = serBuf.data(); - serSize = 0; - REQUIRE(fdSer.serialize(&serTarget, &serSize, idx, SerializeIF::Endianness::NETWORK) == - SerializeIF::BUFFER_TOO_SHORT); - } + serBuf[7] = 0xff; + // Invalid file directive + REQUIRE(fdDeser.parseData() == cfdp::INVALID_DIRECTIVE_FIELDS); + } - deserTarget = serBuf.data(); - deserSize = 0; - auto fdDeser = FileDirectiveDeserializer(deserTarget, serBuf.size()); - REQUIRE(fdDeser.getEndianness() == SerializeIF::Endianness::NETWORK); - fdDeser.setEndianness(SerializeIF::Endianness::MACHINE); - REQUIRE(fdDeser.getEndianness() == SerializeIF::Endianness::MACHINE); - fdDeser.setEndianness(SerializeIF::Endianness::NETWORK); - REQUIRE(fdDeser.parseData() == HasReturnvaluesIF::RETURN_OK); - REQUIRE(fdDeser.getFileDirective() == FileDirectives::ACK); - REQUIRE(fdDeser.getPduDataFieldLen() == 5); - REQUIRE(fdDeser.getHeaderSize() == 8); - REQUIRE(fdDeser.getPduType() == cfdp::PduType::FILE_DIRECTIVE); - - serBuf[7] = 0xff; - // Invalid file directive - REQUIRE(fdDeser.parseData() == cfdp::INVALID_DIRECTIVE_FIELDS); - } - - SECTION("FileSize") { - std::array fssBuf = {}; - uint8_t* buffer = fssBuf.data(); - size_t size = 0; - cfdp::FileSize fss; - REQUIRE(fss.getSize() == 0); - fss.setFileSize(0x20, false); - ReturnValue_t result = fss.serialize(&buffer, &size, fssBuf.size(), - SerializeIF::Endianness::MACHINE); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - uint32_t fileSize = 0; - result = SerializeAdapter::deSerialize(&fileSize, fssBuf.data(), nullptr, - SerializeIF::Endianness::MACHINE); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(fileSize == 0x20); - - } + SECTION("FileSize") { + std::array fssBuf = {}; + uint8_t* buffer = fssBuf.data(); + size_t size = 0; + cfdp::FileSize fss; + REQUIRE(fss.getSize() == 0); + fss.setFileSize(0x20, false); + ReturnValue_t result = + fss.serialize(&buffer, &size, fssBuf.size(), SerializeIF::Endianness::MACHINE); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + uint32_t fileSize = 0; + result = SerializeAdapter::deSerialize(&fileSize, fssBuf.data(), nullptr, + SerializeIF::Endianness::MACHINE); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(fileSize == 0x20); + } } - diff --git a/tests/src/fsfw_tests/unit/cfdp/testEofPdu.cpp b/tests/src/fsfw_tests/unit/cfdp/testEofPdu.cpp index 9edaf572..d400af5a 100644 --- a/tests/src/fsfw_tests/unit/cfdp/testEofPdu.cpp +++ b/tests/src/fsfw_tests/unit/cfdp/testEofPdu.cpp @@ -1,124 +1,118 @@ +#include #include #include "fsfw/cfdp/pdu/EofPduDeserializer.h" #include "fsfw/cfdp/pdu/EofPduSerializer.h" #include "fsfw/globalfunctions/arrayprinter.h" -#include +TEST_CASE("EOF PDU", "[EofPdu]") { + using namespace cfdp; -TEST_CASE( "EOF PDU" , "[EofPdu]") { - using namespace cfdp; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + std::array buf = {}; + uint8_t* bufPtr = buf.data(); + size_t sz = 0; + EntityId destId(WidthInBytes::TWO_BYTES, 2); + EntityIdTlv faultLoc(destId); + FileSize fileSize(12); + // We can already set the fault location, it will be ignored + EofInfo eofInfo(cfdp::ConditionCode::NO_ERROR, 5, fileSize, &faultLoc); + TransactionSeqNum seqNum(WidthInBytes::TWO_BYTES, 15); + EntityId sourceId(WidthInBytes::TWO_BYTES, 1); - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - std::array buf = {}; - uint8_t* bufPtr = buf.data(); - size_t sz = 0; - EntityId destId(WidthInBytes::TWO_BYTES, 2); - EntityIdTlv faultLoc(destId); - FileSize fileSize(12); - // We can already set the fault location, it will be ignored - EofInfo eofInfo(cfdp::ConditionCode::NO_ERROR, 5, fileSize, &faultLoc); - TransactionSeqNum seqNum(WidthInBytes::TWO_BYTES, 15); - EntityId sourceId(WidthInBytes::TWO_BYTES, 1); + PduConfig pduConf(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); - PduConfig pduConf(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); + auto eofSerializer = EofPduSerializer(pduConf, eofInfo); + SECTION("Serialize") { + result = eofSerializer.serialize(&bufPtr, &sz, buf.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(((buf[1] << 8) | buf[2]) == 10); + uint32_t checksum = 0; + result = SerializeAdapter::deSerialize(&checksum, buf.data() + sz - 8, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(checksum == 5); + uint32_t fileSizeVal = 0; + result = SerializeAdapter::deSerialize(&fileSizeVal, buf.data() + sz - 4, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(fileSizeVal == 12); + REQUIRE(buf[sz - 10] == cfdp::FileDirectives::EOF_DIRECTIVE); + REQUIRE(buf[sz - 9] == 0x00); + REQUIRE(sz == 20); - auto eofSerializer = EofPduSerializer(pduConf, eofInfo); - SECTION("Serialize") { - result = eofSerializer.serialize(&bufPtr, &sz, buf.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(((buf[1] << 8) | buf[2]) == 10); - uint32_t checksum = 0; - result = SerializeAdapter::deSerialize(&checksum, buf.data() + sz - 8, nullptr, - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(checksum == 5); - uint32_t fileSizeVal = 0; - result = SerializeAdapter::deSerialize(&fileSizeVal, buf.data() + sz - 4, nullptr, - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(fileSizeVal == 12); - REQUIRE(buf[sz - 10] == cfdp::FileDirectives::EOF_DIRECTIVE); - REQUIRE(buf[sz - 9] == 0x00); - REQUIRE(sz == 20); - - eofInfo.setConditionCode(cfdp::ConditionCode::FILESTORE_REJECTION); - eofInfo.setFileSize(0x10ffffff10, true); - pduConf.largeFile = true; - // Should serialize with fault location now - auto serializeWithFaultLocation = EofPduSerializer(pduConf, eofInfo); - bufPtr = buf.data(); - sz = 0; - result = serializeWithFaultLocation.serialize(&bufPtr, &sz, buf.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(sz == 28); - REQUIRE(buf[10] == cfdp::FileDirectives::EOF_DIRECTIVE); - REQUIRE(buf[11] >> 4 == cfdp::ConditionCode::FILESTORE_REJECTION); - uint64_t fileSizeLarge = 0; - result = SerializeAdapter::deSerialize(&fileSizeLarge, buf.data() + 16, nullptr, - SerializeIF::Endianness::NETWORK); - REQUIRE(fileSizeLarge == 0x10ffffff10); - REQUIRE(buf[sz - 4] == cfdp::TlvTypes::ENTITY_ID); - // width of entity ID is 2 - REQUIRE(buf[sz - 3] == 2); - uint16_t entityIdRaw = 0; - result = SerializeAdapter::deSerialize(&entityIdRaw, buf.data() + sz - 2, nullptr, - SerializeIF::Endianness::NETWORK); - REQUIRE(entityIdRaw == 2); - bufPtr = buf.data(); - sz = 0; - for(size_t idx = 0; idx < 27; idx++) { - result = serializeWithFaultLocation.serialize(&bufPtr, &sz, idx, - SerializeIF::Endianness::NETWORK); - REQUIRE(result == SerializeIF::BUFFER_TOO_SHORT); - bufPtr = buf.data(); - sz = 0; - } - eofInfo.setChecksum(16); - eofInfo.setFaultLoc(nullptr); + eofInfo.setConditionCode(cfdp::ConditionCode::FILESTORE_REJECTION); + eofInfo.setFileSize(0x10ffffff10, true); + pduConf.largeFile = true; + // Should serialize with fault location now + auto serializeWithFaultLocation = EofPduSerializer(pduConf, eofInfo); + bufPtr = buf.data(); + sz = 0; + result = serializeWithFaultLocation.serialize(&bufPtr, &sz, buf.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(sz == 28); + REQUIRE(buf[10] == cfdp::FileDirectives::EOF_DIRECTIVE); + REQUIRE(buf[11] >> 4 == cfdp::ConditionCode::FILESTORE_REJECTION); + uint64_t fileSizeLarge = 0; + result = SerializeAdapter::deSerialize(&fileSizeLarge, buf.data() + 16, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(fileSizeLarge == 0x10ffffff10); + REQUIRE(buf[sz - 4] == cfdp::TlvTypes::ENTITY_ID); + // width of entity ID is 2 + REQUIRE(buf[sz - 3] == 2); + uint16_t entityIdRaw = 0; + result = SerializeAdapter::deSerialize(&entityIdRaw, buf.data() + sz - 2, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(entityIdRaw == 2); + bufPtr = buf.data(); + sz = 0; + for (size_t idx = 0; idx < 27; idx++) { + result = + serializeWithFaultLocation.serialize(&bufPtr, &sz, idx, SerializeIF::Endianness::NETWORK); + REQUIRE(result == SerializeIF::BUFFER_TOO_SHORT); + bufPtr = buf.data(); + sz = 0; } + eofInfo.setChecksum(16); + eofInfo.setFaultLoc(nullptr); + } - SECTION("Deserialize") { - result = eofSerializer.serialize(&bufPtr, &sz, buf.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - EntityIdTlv tlv(destId); - EofInfo emptyInfo(&tlv); - auto deserializer = EofPduDeserializer(buf.data(), buf.size(), emptyInfo); - result = deserializer.parseData(); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(emptyInfo.getConditionCode() == cfdp::ConditionCode::NO_ERROR); - REQUIRE(emptyInfo.getChecksum() == 5); - REQUIRE(emptyInfo.getFileSize().getSize() == 12); + SECTION("Deserialize") { + result = eofSerializer.serialize(&bufPtr, &sz, buf.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + EntityIdTlv tlv(destId); + EofInfo emptyInfo(&tlv); + auto deserializer = EofPduDeserializer(buf.data(), buf.size(), emptyInfo); + result = deserializer.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(emptyInfo.getConditionCode() == cfdp::ConditionCode::NO_ERROR); + REQUIRE(emptyInfo.getChecksum() == 5); + REQUIRE(emptyInfo.getFileSize().getSize() == 12); - eofInfo.setConditionCode(cfdp::ConditionCode::FILESTORE_REJECTION); - eofInfo.setFileSize(0x10ffffff10, true); - pduConf.largeFile = true; - // Should serialize with fault location now - auto serializeWithFaultLocation = EofPduSerializer(pduConf, eofInfo); - bufPtr = buf.data(); - sz = 0; - result = serializeWithFaultLocation.serialize(&bufPtr, &sz, buf.size(), - SerializeIF::Endianness::NETWORK); - auto deserializer2 = EofPduDeserializer(buf.data(), buf.size(), emptyInfo); - result = deserializer2.parseData(); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(emptyInfo.getConditionCode() == cfdp::ConditionCode::FILESTORE_REJECTION); - REQUIRE(emptyInfo.getChecksum() == 5); - REQUIRE(emptyInfo.getFileSize().getSize() == 0x10ffffff10); - REQUIRE(emptyInfo.getFaultLoc()->getType() == cfdp::TlvTypes::ENTITY_ID); - REQUIRE(emptyInfo.getFaultLoc()->getSerializedSize() == 4); - uint16_t destId = emptyInfo.getFaultLoc()->getEntityId().getValue(); - REQUIRE(destId == 2); - for(size_t maxSz = 0; maxSz < deserializer2.getWholePduSize() - 1; maxSz++) { - auto invalidDeser = EofPduDeserializer(buf.data(), maxSz, emptyInfo); - result = invalidDeser.parseData(); - REQUIRE(result != HasReturnvaluesIF::RETURN_OK); - } + eofInfo.setConditionCode(cfdp::ConditionCode::FILESTORE_REJECTION); + eofInfo.setFileSize(0x10ffffff10, true); + pduConf.largeFile = true; + // Should serialize with fault location now + auto serializeWithFaultLocation = EofPduSerializer(pduConf, eofInfo); + bufPtr = buf.data(); + sz = 0; + result = serializeWithFaultLocation.serialize(&bufPtr, &sz, buf.size(), + SerializeIF::Endianness::NETWORK); + auto deserializer2 = EofPduDeserializer(buf.data(), buf.size(), emptyInfo); + result = deserializer2.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(emptyInfo.getConditionCode() == cfdp::ConditionCode::FILESTORE_REJECTION); + REQUIRE(emptyInfo.getChecksum() == 5); + REQUIRE(emptyInfo.getFileSize().getSize() == 0x10ffffff10); + REQUIRE(emptyInfo.getFaultLoc()->getType() == cfdp::TlvTypes::ENTITY_ID); + REQUIRE(emptyInfo.getFaultLoc()->getSerializedSize() == 4); + uint16_t destId = emptyInfo.getFaultLoc()->getEntityId().getValue(); + REQUIRE(destId == 2); + for (size_t maxSz = 0; maxSz < deserializer2.getWholePduSize() - 1; maxSz++) { + auto invalidDeser = EofPduDeserializer(buf.data(), maxSz, emptyInfo); + result = invalidDeser.parseData(); + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); } - + } } - - diff --git a/tests/src/fsfw_tests/unit/cfdp/testFileData.cpp b/tests/src/fsfw_tests/unit/cfdp/testFileData.cpp index 8a84a2a3..1f6a09e9 100644 --- a/tests/src/fsfw_tests/unit/cfdp/testFileData.cpp +++ b/tests/src/fsfw_tests/unit/cfdp/testFileData.cpp @@ -1,3 +1,4 @@ +#include #include #include "fsfw/cfdp/pdu/FileDataDeserializer.h" @@ -5,171 +6,166 @@ #include "fsfw/globalfunctions/arrayprinter.h" #include "fsfw/serviceinterface.h" -#include +TEST_CASE("File Data PDU", "[FileDataPdu]") { + using namespace cfdp; -TEST_CASE( "File Data PDU" , "[FileDataPdu]") { - using namespace cfdp; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + std::array fileBuffer = {}; + std::array fileDataBuffer = {}; + uint8_t* buffer = fileDataBuffer.data(); + size_t sz = 0; + EntityId destId(WidthInBytes::TWO_BYTES, 2); + TransactionSeqNum seqNum(WidthInBytes::TWO_BYTES, 15); + EntityId sourceId(WidthInBytes::TWO_BYTES, 1); + PduConfig pduConf(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - std::array fileBuffer = {}; - std::array fileDataBuffer = {}; - uint8_t* buffer = fileDataBuffer.data(); - size_t sz = 0; - EntityId destId(WidthInBytes::TWO_BYTES, 2); - TransactionSeqNum seqNum(WidthInBytes::TWO_BYTES, 15); - EntityId sourceId(WidthInBytes::TWO_BYTES, 1); - PduConfig pduConf(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); + for (uint8_t idx = 0; idx < 10; idx++) { + fileBuffer[idx] = idx; + } + FileSize offset(50); + FileDataInfo info(offset, fileBuffer.data(), 10); - for(uint8_t idx = 0; idx < 10; idx++) { - fileBuffer[idx] = idx; - } - FileSize offset(50); - FileDataInfo info(offset, fileBuffer.data(), 10); - - SECTION("Serialization") { - FileDataSerializer serializer(pduConf, info); - result = serializer.serialize(&buffer, &sz, fileDataBuffer.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(sz == 24); - // 10 file bytes plus 4 byte offset - REQUIRE(((fileDataBuffer[1] << 8) | fileDataBuffer[2]) == 14); - // File Data -> Fourth bit is one - REQUIRE(fileDataBuffer[0] == 0b00110000); - uint32_t offsetRaw = 0; - buffer = fileDataBuffer.data(); - result = SerializeAdapter::deSerialize(&offsetRaw, buffer + 10, nullptr, - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(offsetRaw == 50); - buffer = fileDataBuffer.data() + 14; - for(size_t idx = 0; idx < 10; idx++) { - REQUIRE(buffer[idx] == idx); - } - - REQUIRE(info.hasSegmentMetadata() == false); - info.addSegmentMetadataInfo(cfdp::RecordContinuationState::CONTAINS_START_AND_END, - fileBuffer.data(), 10); - REQUIRE(info.hasSegmentMetadata() == true); - REQUIRE(info.getSegmentationControl() == - cfdp::SegmentationControl::NO_RECORD_BOUNDARIES_PRESERVATION); - info.setSegmentationControl(cfdp::SegmentationControl::RECORD_BOUNDARIES_PRESERVATION); - serializer.update(); - REQUIRE(serializer.getSegmentationControl() == - cfdp::SegmentationControl::RECORD_BOUNDARIES_PRESERVATION); - buffer = fileDataBuffer.data(); - sz = 0; - serializer.setSegmentationControl(cfdp::SegmentationControl::RECORD_BOUNDARIES_PRESERVATION); - - result = serializer.serialize(&buffer, &sz, fileDataBuffer.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(((fileDataBuffer[1] << 8) | fileDataBuffer[2]) == 25); - // First bit: Seg Ctrl is set - // Bits 1 to 3 length of enitity IDs is 2 - // Bit 4: Segment metadata flag is set - // Bit 5 to seven: length of transaction seq num is 2 - REQUIRE(fileDataBuffer[3] == 0b10101010); - REQUIRE((fileDataBuffer[10] >> 6) & 0b11 == - cfdp::RecordContinuationState::CONTAINS_START_AND_END); - // Segment metadata length - REQUIRE((fileDataBuffer[10] & 0x3f) == 10); - buffer = fileDataBuffer.data() + 11; - // Check segment metadata - for(size_t idx = 0; idx < 10; idx++) { - REQUIRE(buffer[idx] == idx); - } - // Check filedata - buffer = fileDataBuffer.data() + 25; - for(size_t idx = 0; idx < 10; idx++) { - REQUIRE(buffer[idx] == idx); - } - - for(size_t invalidStartSz = 1; invalidStartSz < sz; invalidStartSz ++) { - buffer = fileDataBuffer.data(); - sz = 0; - result = serializer.serialize(&buffer, &invalidStartSz, sz, - SerializeIF::Endianness::NETWORK); - REQUIRE(result != HasReturnvaluesIF::RETURN_OK); - } - - info.setSegmentMetadataFlag(true); - REQUIRE(info.getSegmentMetadataFlag() == cfdp::SegmentMetadataFlag::PRESENT); - info.setSegmentMetadataFlag(false); - REQUIRE(info.getSegmentMetadataFlag() == cfdp::SegmentMetadataFlag::NOT_PRESENT); - info.setRecordContinuationState(cfdp::RecordContinuationState::CONTAINS_END_NO_START); - info.setSegmentMetadataLen(10); - info.setSegmentMetadata(nullptr); - info.setFileData(nullptr, 0); + SECTION("Serialization") { + FileDataSerializer serializer(pduConf, info); + result = + serializer.serialize(&buffer, &sz, fileDataBuffer.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(sz == 24); + // 10 file bytes plus 4 byte offset + REQUIRE(((fileDataBuffer[1] << 8) | fileDataBuffer[2]) == 14); + // File Data -> Fourth bit is one + REQUIRE(fileDataBuffer[0] == 0b00110000); + uint32_t offsetRaw = 0; + buffer = fileDataBuffer.data(); + result = SerializeAdapter::deSerialize(&offsetRaw, buffer + 10, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(offsetRaw == 50); + buffer = fileDataBuffer.data() + 14; + for (size_t idx = 0; idx < 10; idx++) { + REQUIRE(buffer[idx] == idx); } - SECTION("Deserialization") { - FileDataSerializer serializer(pduConf, info); - result = serializer.serialize(&buffer, &sz, fileDataBuffer.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - - FileSize emptyOffset; - FileDataInfo emptyInfo(emptyOffset); - FileDataDeserializer deserializer(fileDataBuffer.data(), fileDataBuffer.size(), emptyInfo); - result = deserializer.parseData(); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(deserializer.getWholePduSize() == 24); - REQUIRE(deserializer.getPduDataFieldLen() == 14); - REQUIRE(deserializer.getSegmentationControl() == - cfdp::SegmentationControl::NO_RECORD_BOUNDARIES_PRESERVATION); - REQUIRE(deserializer.getSegmentMetadataFlag() == - cfdp::SegmentMetadataFlag::NOT_PRESENT); - - REQUIRE(emptyInfo.getOffset().getSize() == 50); - REQUIRE(emptyInfo.hasSegmentMetadata() == false); - size_t emptyFileSize = 0; - const uint8_t* fileData = emptyInfo.getFileData(&emptyFileSize); - REQUIRE(emptyFileSize == 10); - for(size_t idx = 0; idx < 10; idx++) { - REQUIRE(fileData[idx] == idx); - } - - deserializer.setEndianness(SerializeIF::Endianness::NETWORK); - - info.addSegmentMetadataInfo(cfdp::RecordContinuationState::CONTAINS_START_AND_END, - fileBuffer.data(), 10); - serializer.update(); - buffer = fileDataBuffer.data(); - sz = 0; - result = serializer.serialize(&buffer, &sz, fileDataBuffer.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - - result = deserializer.parseData(); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - - REQUIRE(emptyInfo.getOffset().getSize() == 50); - REQUIRE(emptyInfo.hasSegmentMetadata() == true); - REQUIRE(emptyInfo.getRecordContinuationState() == - cfdp::RecordContinuationState::CONTAINS_START_AND_END); - emptyFileSize = 0; - fileData = emptyInfo.getFileData(&emptyFileSize); - REQUIRE(emptyFileSize == 10); - for(size_t idx = 0; idx < 10; idx++) { - REQUIRE(fileData[idx] == idx); - } - size_t segmentMetadataLen = 0; - fileData = emptyInfo.getSegmentMetadata(&segmentMetadataLen); - REQUIRE(segmentMetadataLen == 10); - for(size_t idx = 0; idx < 10; idx++) { - REQUIRE(fileData[idx] == idx); - } - for(size_t invalidPduField = 0; invalidPduField < 24; invalidPduField++) { - fileDataBuffer[1] = (invalidPduField >> 8) & 0xff; - fileDataBuffer[2] = invalidPduField & 0xff; - result = deserializer.parseData(); - // Starting at 15, the file data is parsed. There is not leading file data length - // field to the parser can't check whether the remaining length is valid - if(invalidPduField < 15) { - REQUIRE(result != HasReturnvaluesIF::RETURN_OK); - } - } + REQUIRE(info.hasSegmentMetadata() == false); + info.addSegmentMetadataInfo(cfdp::RecordContinuationState::CONTAINS_START_AND_END, + fileBuffer.data(), 10); + REQUIRE(info.hasSegmentMetadata() == true); + REQUIRE(info.getSegmentationControl() == + cfdp::SegmentationControl::NO_RECORD_BOUNDARIES_PRESERVATION); + info.setSegmentationControl(cfdp::SegmentationControl::RECORD_BOUNDARIES_PRESERVATION); + serializer.update(); + REQUIRE(serializer.getSegmentationControl() == + cfdp::SegmentationControl::RECORD_BOUNDARIES_PRESERVATION); + buffer = fileDataBuffer.data(); + sz = 0; + serializer.setSegmentationControl(cfdp::SegmentationControl::RECORD_BOUNDARIES_PRESERVATION); + result = + serializer.serialize(&buffer, &sz, fileDataBuffer.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(((fileDataBuffer[1] << 8) | fileDataBuffer[2]) == 25); + // First bit: Seg Ctrl is set + // Bits 1 to 3 length of enitity IDs is 2 + // Bit 4: Segment metadata flag is set + // Bit 5 to seven: length of transaction seq num is 2 + REQUIRE(fileDataBuffer[3] == 0b10101010); + REQUIRE((fileDataBuffer[10] >> 6) & + 0b11 == cfdp::RecordContinuationState::CONTAINS_START_AND_END); + // Segment metadata length + REQUIRE((fileDataBuffer[10] & 0x3f) == 10); + buffer = fileDataBuffer.data() + 11; + // Check segment metadata + for (size_t idx = 0; idx < 10; idx++) { + REQUIRE(buffer[idx] == idx); } + // Check filedata + buffer = fileDataBuffer.data() + 25; + for (size_t idx = 0; idx < 10; idx++) { + REQUIRE(buffer[idx] == idx); + } + + for (size_t invalidStartSz = 1; invalidStartSz < sz; invalidStartSz++) { + buffer = fileDataBuffer.data(); + sz = 0; + result = serializer.serialize(&buffer, &invalidStartSz, sz, SerializeIF::Endianness::NETWORK); + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + } + + info.setSegmentMetadataFlag(true); + REQUIRE(info.getSegmentMetadataFlag() == cfdp::SegmentMetadataFlag::PRESENT); + info.setSegmentMetadataFlag(false); + REQUIRE(info.getSegmentMetadataFlag() == cfdp::SegmentMetadataFlag::NOT_PRESENT); + info.setRecordContinuationState(cfdp::RecordContinuationState::CONTAINS_END_NO_START); + info.setSegmentMetadataLen(10); + info.setSegmentMetadata(nullptr); + info.setFileData(nullptr, 0); + } + + SECTION("Deserialization") { + FileDataSerializer serializer(pduConf, info); + result = + serializer.serialize(&buffer, &sz, fileDataBuffer.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + FileSize emptyOffset; + FileDataInfo emptyInfo(emptyOffset); + FileDataDeserializer deserializer(fileDataBuffer.data(), fileDataBuffer.size(), emptyInfo); + result = deserializer.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(deserializer.getWholePduSize() == 24); + REQUIRE(deserializer.getPduDataFieldLen() == 14); + REQUIRE(deserializer.getSegmentationControl() == + cfdp::SegmentationControl::NO_RECORD_BOUNDARIES_PRESERVATION); + REQUIRE(deserializer.getSegmentMetadataFlag() == cfdp::SegmentMetadataFlag::NOT_PRESENT); + + REQUIRE(emptyInfo.getOffset().getSize() == 50); + REQUIRE(emptyInfo.hasSegmentMetadata() == false); + size_t emptyFileSize = 0; + const uint8_t* fileData = emptyInfo.getFileData(&emptyFileSize); + REQUIRE(emptyFileSize == 10); + for (size_t idx = 0; idx < 10; idx++) { + REQUIRE(fileData[idx] == idx); + } + + deserializer.setEndianness(SerializeIF::Endianness::NETWORK); + + info.addSegmentMetadataInfo(cfdp::RecordContinuationState::CONTAINS_START_AND_END, + fileBuffer.data(), 10); + serializer.update(); + buffer = fileDataBuffer.data(); + sz = 0; + result = + serializer.serialize(&buffer, &sz, fileDataBuffer.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + result = deserializer.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + REQUIRE(emptyInfo.getOffset().getSize() == 50); + REQUIRE(emptyInfo.hasSegmentMetadata() == true); + REQUIRE(emptyInfo.getRecordContinuationState() == + cfdp::RecordContinuationState::CONTAINS_START_AND_END); + emptyFileSize = 0; + fileData = emptyInfo.getFileData(&emptyFileSize); + REQUIRE(emptyFileSize == 10); + for (size_t idx = 0; idx < 10; idx++) { + REQUIRE(fileData[idx] == idx); + } + size_t segmentMetadataLen = 0; + fileData = emptyInfo.getSegmentMetadata(&segmentMetadataLen); + REQUIRE(segmentMetadataLen == 10); + for (size_t idx = 0; idx < 10; idx++) { + REQUIRE(fileData[idx] == idx); + } + for (size_t invalidPduField = 0; invalidPduField < 24; invalidPduField++) { + fileDataBuffer[1] = (invalidPduField >> 8) & 0xff; + fileDataBuffer[2] = invalidPduField & 0xff; + result = deserializer.parseData(); + // Starting at 15, the file data is parsed. There is not leading file data length + // field to the parser can't check whether the remaining length is valid + if (invalidPduField < 15) { + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + } + } + } } diff --git a/tests/src/fsfw_tests/unit/cfdp/testFinishedPdu.cpp b/tests/src/fsfw_tests/unit/cfdp/testFinishedPdu.cpp index 72c3f932..143eaf2a 100644 --- a/tests/src/fsfw_tests/unit/cfdp/testFinishedPdu.cpp +++ b/tests/src/fsfw_tests/unit/cfdp/testFinishedPdu.cpp @@ -1,196 +1,189 @@ +#include #include -#include "fsfw/globalfunctions/arrayprinter.h" #include "fsfw/cfdp/pdu/FinishedPduDeserializer.h" #include "fsfw/cfdp/pdu/FinishedPduSerializer.h" +#include "fsfw/globalfunctions/arrayprinter.h" -#include +TEST_CASE("Finished PDU", "[FinishedPdu]") { + using namespace cfdp; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + std::array fnBuffer = {}; + uint8_t* buffer = fnBuffer.data(); + size_t sz = 0; + EntityId destId(WidthInBytes::TWO_BYTES, 2); + TransactionSeqNum seqNum(WidthInBytes::TWO_BYTES, 15); + EntityId sourceId(WidthInBytes::TWO_BYTES, 1); + PduConfig pduConf(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); -TEST_CASE( "Finished PDU" , "[FinishedPdu]") { - using namespace cfdp; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - std::array fnBuffer = {}; - uint8_t* buffer = fnBuffer.data(); - size_t sz = 0; - EntityId destId(WidthInBytes::TWO_BYTES, 2); - TransactionSeqNum seqNum(WidthInBytes::TWO_BYTES, 15); - EntityId sourceId(WidthInBytes::TWO_BYTES, 1); - PduConfig pduConf(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); + cfdp::Lv emptyFsMsg; + FinishedInfo info(cfdp::ConditionCode::INACTIVITY_DETECTED, + cfdp::FinishedDeliveryCode::DATA_INCOMPLETE, + cfdp::FinishedFileStatus::DISCARDED_DELIBERATELY); - cfdp::Lv emptyFsMsg; - FinishedInfo info(cfdp::ConditionCode::INACTIVITY_DETECTED, - cfdp::FinishedDeliveryCode::DATA_INCOMPLETE, - cfdp::FinishedFileStatus::DISCARDED_DELIBERATELY); + SECTION("Serialize") { + FinishPduSerializer serializer(pduConf, info); + result = serializer.serialize(&buffer, &sz, fnBuffer.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(serializer.getSerializedSize() == 12); + REQUIRE(((fnBuffer[1] << 8) | fnBuffer[2]) == 2); + REQUIRE(fnBuffer[10] == cfdp::FileDirectives::FINISH); + REQUIRE(((fnBuffer[sz - 1] >> 4) & 0x0f) == cfdp::ConditionCode::INACTIVITY_DETECTED); + REQUIRE(((fnBuffer[sz - 1] >> 2) & 0x01) == cfdp::FinishedDeliveryCode::DATA_INCOMPLETE); + REQUIRE((fnBuffer[sz - 1] & 0b11) == cfdp::FinishedFileStatus::DISCARDED_DELIBERATELY); + REQUIRE(sz == 12); - SECTION("Serialize") { - FinishPduSerializer serializer(pduConf, info); - result = serializer.serialize(&buffer, &sz, fnBuffer.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(serializer.getSerializedSize() == 12); - REQUIRE(((fnBuffer[1] << 8) | fnBuffer[2]) == 2); - REQUIRE(fnBuffer[10] == cfdp::FileDirectives::FINISH); - REQUIRE(((fnBuffer[sz - 1] >> 4) & 0x0f) == cfdp::ConditionCode::INACTIVITY_DETECTED); - REQUIRE(((fnBuffer[sz - 1] >> 2) & 0x01) == cfdp::FinishedDeliveryCode::DATA_INCOMPLETE); - REQUIRE((fnBuffer[sz - 1] & 0b11) == cfdp::FinishedFileStatus::DISCARDED_DELIBERATELY); - REQUIRE(sz == 12); + // Add a filestore response + std::string firstName = "hello.txt"; + cfdp::Lv firstNameLv(reinterpret_cast(firstName.data()), firstName.size()); + FilestoreResponseTlv response(cfdp::FilestoreActionCode::DELETE_FILE, + cfdp::FSR_APPEND_FILE_1_NOT_EXISTS, firstNameLv, nullptr); + FilestoreResponseTlv* responsePtr = &response; + REQUIRE(response.getSerializedSize() == 14); + size_t len = 1; + info.setFilestoreResponsesArray(&responsePtr, &len, &len); + serializer.updateDirectiveFieldLen(); + REQUIRE(serializer.getSerializedSize() == 12 + 14); + sz = 0; + buffer = fnBuffer.data(); + result = serializer.serialize(&buffer, &sz, fnBuffer.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(serializer.getSerializedSize() == 12 + 14); + REQUIRE(serializer.getPduDataFieldLen() == 16); - // Add a filestore response - std::string firstName = "hello.txt"; - cfdp::Lv firstNameLv(reinterpret_cast(firstName.data()), firstName.size()); - FilestoreResponseTlv response(cfdp::FilestoreActionCode::DELETE_FILE, - cfdp::FSR_APPEND_FILE_1_NOT_EXISTS, firstNameLv, nullptr); - FilestoreResponseTlv* responsePtr = &response; - REQUIRE(response.getSerializedSize() == 14); - size_t len = 1; - info.setFilestoreResponsesArray(&responsePtr, &len, &len); - serializer.updateDirectiveFieldLen(); - REQUIRE(serializer.getSerializedSize() == 12 + 14); - sz = 0; - buffer = fnBuffer.data(); - result = serializer.serialize(&buffer, &sz, fnBuffer.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(serializer.getSerializedSize() == 12 + 14); - REQUIRE(serializer.getPduDataFieldLen() == 16); + // Add two filestore responses and a fault location parameter + std::string secondName = "hello2.txt"; + cfdp::Lv secondNameLv(reinterpret_cast(secondName.data()), secondName.size()); + FilestoreResponseTlv response2(cfdp::FilestoreActionCode::DENY_FILE, cfdp::FSR_SUCCESS, + secondNameLv, nullptr); + REQUIRE(response2.getSerializedSize() == 15); + len = 2; + std::array responses{&response, &response2}; + info.setFilestoreResponsesArray(responses.data(), &len, &len); + serializer.updateDirectiveFieldLen(); - // Add two filestore responses and a fault location parameter - std::string secondName = "hello2.txt"; - cfdp::Lv secondNameLv(reinterpret_cast(secondName.data()), secondName.size()); - FilestoreResponseTlv response2(cfdp::FilestoreActionCode::DENY_FILE , - cfdp::FSR_SUCCESS, secondNameLv, nullptr); - REQUIRE(response2.getSerializedSize() == 15); - len = 2; - std::array responses {&response, &response2}; - info.setFilestoreResponsesArray(responses.data(), &len, &len); - serializer.updateDirectiveFieldLen(); - - EntityIdTlv faultLoc(destId); - REQUIRE(faultLoc.getSerializedSize() == 4); - info.setFaultLocation(&faultLoc); - serializer.updateDirectiveFieldLen(); - sz = 0; - buffer = fnBuffer.data(); - result = serializer.serialize(&buffer, &sz, fnBuffer.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - info.setConditionCode(cfdp::ConditionCode::FILESTORE_REJECTION); - REQUIRE(serializer.getSerializedSize() == 12 + 14 + 15 + 4); - REQUIRE(sz == 12 + 14 + 15 + 4); - info.setFileStatus(cfdp::FinishedFileStatus::DISCARDED_FILESTORE_REJECTION); - REQUIRE(info.getFileStatus() == cfdp::FinishedFileStatus::DISCARDED_FILESTORE_REJECTION); - info.setDeliveryCode(cfdp::FinishedDeliveryCode::DATA_INCOMPLETE); - REQUIRE(info.getDeliveryCode() == cfdp::FinishedDeliveryCode::DATA_INCOMPLETE); - for(size_t maxSz = 0; maxSz < 45; maxSz++) { - sz = 0; - buffer = fnBuffer.data(); - result = serializer.serialize(&buffer, &sz, maxSz, SerializeIF::Endianness::NETWORK); - REQUIRE(result != HasReturnvaluesIF::RETURN_OK); - } + EntityIdTlv faultLoc(destId); + REQUIRE(faultLoc.getSerializedSize() == 4); + info.setFaultLocation(&faultLoc); + serializer.updateDirectiveFieldLen(); + sz = 0; + buffer = fnBuffer.data(); + result = serializer.serialize(&buffer, &sz, fnBuffer.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + info.setConditionCode(cfdp::ConditionCode::FILESTORE_REJECTION); + REQUIRE(serializer.getSerializedSize() == 12 + 14 + 15 + 4); + REQUIRE(sz == 12 + 14 + 15 + 4); + info.setFileStatus(cfdp::FinishedFileStatus::DISCARDED_FILESTORE_REJECTION); + REQUIRE(info.getFileStatus() == cfdp::FinishedFileStatus::DISCARDED_FILESTORE_REJECTION); + info.setDeliveryCode(cfdp::FinishedDeliveryCode::DATA_INCOMPLETE); + REQUIRE(info.getDeliveryCode() == cfdp::FinishedDeliveryCode::DATA_INCOMPLETE); + for (size_t maxSz = 0; maxSz < 45; maxSz++) { + sz = 0; + buffer = fnBuffer.data(); + result = serializer.serialize(&buffer, &sz, maxSz, SerializeIF::Endianness::NETWORK); + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); } + } - SECTION("Deserialize") { - FinishedInfo emptyInfo; - FinishPduSerializer serializer(pduConf, info); - result = serializer.serialize(&buffer, &sz, fnBuffer.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - FinishPduDeserializer deserializer(fnBuffer.data(), fnBuffer.size(), emptyInfo); - result = deserializer.parseData(); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(emptyInfo.getFileStatus() == cfdp::FinishedFileStatus::DISCARDED_DELIBERATELY); - REQUIRE(emptyInfo.getConditionCode() == cfdp::ConditionCode::INACTIVITY_DETECTED); - REQUIRE(emptyInfo.getDeliveryCode() == cfdp::FinishedDeliveryCode::DATA_INCOMPLETE); + SECTION("Deserialize") { + FinishedInfo emptyInfo; + FinishPduSerializer serializer(pduConf, info); + result = serializer.serialize(&buffer, &sz, fnBuffer.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + FinishPduDeserializer deserializer(fnBuffer.data(), fnBuffer.size(), emptyInfo); + result = deserializer.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(emptyInfo.getFileStatus() == cfdp::FinishedFileStatus::DISCARDED_DELIBERATELY); + REQUIRE(emptyInfo.getConditionCode() == cfdp::ConditionCode::INACTIVITY_DETECTED); + REQUIRE(emptyInfo.getDeliveryCode() == cfdp::FinishedDeliveryCode::DATA_INCOMPLETE); - // Add a filestore response - sz = 0; - buffer = fnBuffer.data(); - std::string firstName = "hello.txt"; - cfdp::Lv firstNameLv(reinterpret_cast(firstName.data()), firstName.size()); - FilestoreResponseTlv response(cfdp::FilestoreActionCode::DELETE_FILE, - cfdp::FSR_NOT_PERFORMED, firstNameLv, nullptr); - FilestoreResponseTlv* responsePtr = &response; - size_t len = 1; - info.setFilestoreResponsesArray(&responsePtr, &len, &len); - serializer.updateDirectiveFieldLen(); - REQUIRE(serializer.getPduDataFieldLen() == 16); - result = serializer.serialize(&buffer, &sz, fnBuffer.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - FilestoreResponseTlv emptyResponse(firstNameLv, nullptr); - responsePtr = &emptyResponse; - emptyInfo.setFilestoreResponsesArray(&responsePtr, nullptr, &len); - FinishPduDeserializer deserializer2(fnBuffer.data(), fnBuffer.size(), emptyInfo); - result = deserializer2.parseData(); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(emptyInfo.getFsResponsesLen() == 1); - FilestoreResponseTlv** responseArray = nullptr; - emptyInfo.getFilestoreResonses(&responseArray, nullptr, nullptr); - REQUIRE(responseArray[0]->getActionCode() == cfdp::FilestoreActionCode::DELETE_FILE); - REQUIRE(responseArray[0]->getStatusCode() == cfdp::FSR_NOT_PERFORMED); - auto& fileNameRef = responseArray[0]->getFirstFileName(); - size_t stringSize = 0; - const char* string = reinterpret_cast(fileNameRef.getValue(&stringSize)); - std::string firstFileName(string, stringSize); - REQUIRE(firstFileName == "hello.txt"); + // Add a filestore response + sz = 0; + buffer = fnBuffer.data(); + std::string firstName = "hello.txt"; + cfdp::Lv firstNameLv(reinterpret_cast(firstName.data()), firstName.size()); + FilestoreResponseTlv response(cfdp::FilestoreActionCode::DELETE_FILE, cfdp::FSR_NOT_PERFORMED, + firstNameLv, nullptr); + FilestoreResponseTlv* responsePtr = &response; + size_t len = 1; + info.setFilestoreResponsesArray(&responsePtr, &len, &len); + serializer.updateDirectiveFieldLen(); + REQUIRE(serializer.getPduDataFieldLen() == 16); + result = serializer.serialize(&buffer, &sz, fnBuffer.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + FilestoreResponseTlv emptyResponse(firstNameLv, nullptr); + responsePtr = &emptyResponse; + emptyInfo.setFilestoreResponsesArray(&responsePtr, nullptr, &len); + FinishPduDeserializer deserializer2(fnBuffer.data(), fnBuffer.size(), emptyInfo); + result = deserializer2.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(emptyInfo.getFsResponsesLen() == 1); + FilestoreResponseTlv** responseArray = nullptr; + emptyInfo.getFilestoreResonses(&responseArray, nullptr, nullptr); + REQUIRE(responseArray[0]->getActionCode() == cfdp::FilestoreActionCode::DELETE_FILE); + REQUIRE(responseArray[0]->getStatusCode() == cfdp::FSR_NOT_PERFORMED); + auto& fileNameRef = responseArray[0]->getFirstFileName(); + size_t stringSize = 0; + const char* string = reinterpret_cast(fileNameRef.getValue(&stringSize)); + std::string firstFileName(string, stringSize); + REQUIRE(firstFileName == "hello.txt"); - // Add two filestore responses and a fault location parameter - std::string secondName = "hello2.txt"; - cfdp::Lv secondNameLv(reinterpret_cast(secondName.data()), secondName.size()); - FilestoreResponseTlv response2(cfdp::FilestoreActionCode::DENY_FILE , - cfdp::FSR_SUCCESS, secondNameLv, nullptr); - REQUIRE(response2.getSerializedSize() == 15); - len = 2; - std::array responses {&response, &response2}; - info.setFilestoreResponsesArray(responses.data(), &len, &len); - serializer.updateDirectiveFieldLen(); + // Add two filestore responses and a fault location parameter + std::string secondName = "hello2.txt"; + cfdp::Lv secondNameLv(reinterpret_cast(secondName.data()), secondName.size()); + FilestoreResponseTlv response2(cfdp::FilestoreActionCode::DENY_FILE, cfdp::FSR_SUCCESS, + secondNameLv, nullptr); + REQUIRE(response2.getSerializedSize() == 15); + len = 2; + std::array responses{&response, &response2}; + info.setFilestoreResponsesArray(responses.data(), &len, &len); + serializer.updateDirectiveFieldLen(); - EntityIdTlv faultLoc(destId); - info.setFaultLocation(&faultLoc); - serializer.updateDirectiveFieldLen(); - sz = 0; - buffer = fnBuffer.data(); - result = serializer.serialize(&buffer, &sz, fnBuffer.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - EntityId emptyId; - EntityIdTlv emptyFaultLoc(emptyId); - emptyInfo.setFaultLocation(&emptyFaultLoc); - response.setFilestoreMessage(&emptyFsMsg); - emptyInfo.setFilestoreResponsesArray(responses.data(), &len, &len); - response2.setFilestoreMessage(&emptyFsMsg); - FinishPduDeserializer deserializer3(fnBuffer.data(), fnBuffer.size(), emptyInfo); - result = deserializer3.parseData(); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - auto& infoRef = deserializer3.getInfo(); - REQUIRE(deserializer3.getWholePduSize() == 45); + EntityIdTlv faultLoc(destId); + info.setFaultLocation(&faultLoc); + serializer.updateDirectiveFieldLen(); + sz = 0; + buffer = fnBuffer.data(); + result = serializer.serialize(&buffer, &sz, fnBuffer.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + EntityId emptyId; + EntityIdTlv emptyFaultLoc(emptyId); + emptyInfo.setFaultLocation(&emptyFaultLoc); + response.setFilestoreMessage(&emptyFsMsg); + emptyInfo.setFilestoreResponsesArray(responses.data(), &len, &len); + response2.setFilestoreMessage(&emptyFsMsg); + FinishPduDeserializer deserializer3(fnBuffer.data(), fnBuffer.size(), emptyInfo); + result = deserializer3.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + auto& infoRef = deserializer3.getInfo(); + REQUIRE(deserializer3.getWholePduSize() == 45); - size_t invalidMaxLen = 1; - emptyInfo.setFilestoreResponsesArray(responses.data(), &len, &invalidMaxLen); - result = deserializer3.parseData(); - REQUIRE(result == cfdp::FINISHED_CANT_PARSE_FS_RESPONSES); - emptyInfo.setFilestoreResponsesArray(nullptr, nullptr, nullptr); - result = deserializer3.parseData(); - REQUIRE(result == cfdp::FINISHED_CANT_PARSE_FS_RESPONSES); + size_t invalidMaxLen = 1; + emptyInfo.setFilestoreResponsesArray(responses.data(), &len, &invalidMaxLen); + result = deserializer3.parseData(); + REQUIRE(result == cfdp::FINISHED_CANT_PARSE_FS_RESPONSES); + emptyInfo.setFilestoreResponsesArray(nullptr, nullptr, nullptr); + result = deserializer3.parseData(); + REQUIRE(result == cfdp::FINISHED_CANT_PARSE_FS_RESPONSES); - // Clear condition code - auto tmp = fnBuffer[11]; - fnBuffer[11] = fnBuffer[11] & ~0xf0; - fnBuffer[11] = fnBuffer[11] | (cfdp::ConditionCode::NO_ERROR << 4); - emptyInfo.setFilestoreResponsesArray(responses.data(), &len, &len); - result = deserializer3.parseData(); - REQUIRE(result == cfdp::INVALID_TLV_TYPE); + // Clear condition code + auto tmp = fnBuffer[11]; + fnBuffer[11] = fnBuffer[11] & ~0xf0; + fnBuffer[11] = fnBuffer[11] | (cfdp::ConditionCode::NO_ERROR << 4); + emptyInfo.setFilestoreResponsesArray(responses.data(), &len, &len); + result = deserializer3.parseData(); + REQUIRE(result == cfdp::INVALID_TLV_TYPE); - fnBuffer[11] = tmp; - // Invalid TLV type, should be entity ID - fnBuffer[sz - 4] = cfdp::TlvTypes::FILESTORE_REQUEST; - result = deserializer3.parseData(); - REQUIRE(result == cfdp::INVALID_TLV_TYPE); + fnBuffer[11] = tmp; + // Invalid TLV type, should be entity ID + fnBuffer[sz - 4] = cfdp::TlvTypes::FILESTORE_REQUEST; + result = deserializer3.parseData(); + REQUIRE(result == cfdp::INVALID_TLV_TYPE); - for(size_t maxSz = 0; maxSz < 45; maxSz++) { - FinishPduDeserializer faultyDeser(fnBuffer.data(), maxSz, emptyInfo); - result = faultyDeser.parseData(); - REQUIRE(result != HasReturnvaluesIF::RETURN_OK); - } + for (size_t maxSz = 0; maxSz < 45; maxSz++) { + FinishPduDeserializer faultyDeser(fnBuffer.data(), maxSz, emptyInfo); + result = faultyDeser.parseData(); + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); } + } } diff --git a/tests/src/fsfw_tests/unit/cfdp/testKeepAlivePdu.cpp b/tests/src/fsfw_tests/unit/cfdp/testKeepAlivePdu.cpp index 09008650..8ec8c66c 100644 --- a/tests/src/fsfw_tests/unit/cfdp/testKeepAlivePdu.cpp +++ b/tests/src/fsfw_tests/unit/cfdp/testKeepAlivePdu.cpp @@ -1,84 +1,79 @@ +#include #include #include "fsfw/cfdp/pdu/KeepAlivePduDeserializer.h" #include "fsfw/cfdp/pdu/KeepAlivePduSerializer.h" #include "fsfw/globalfunctions/arrayprinter.h" -#include +TEST_CASE("Keep Alive PDU", "[KeepAlivePdu]") { + using namespace cfdp; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + std::array kaBuffer = {}; + uint8_t* buffer = kaBuffer.data(); + size_t sz = 0; + EntityId destId(WidthInBytes::TWO_BYTES, 2); + TransactionSeqNum seqNum(WidthInBytes::TWO_BYTES, 15); + EntityId sourceId(WidthInBytes::TWO_BYTES, 1); + PduConfig pduConf(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); -TEST_CASE( "Keep Alive PDU" , "[KeepAlivePdu]") { - using namespace cfdp; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - std::array kaBuffer = {}; - uint8_t* buffer = kaBuffer.data(); - size_t sz = 0; - EntityId destId(WidthInBytes::TWO_BYTES, 2); - TransactionSeqNum seqNum(WidthInBytes::TWO_BYTES, 15); - EntityId sourceId(WidthInBytes::TWO_BYTES, 1); - PduConfig pduConf(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); + FileSize progress(0x50); - FileSize progress(0x50); + SECTION("Serialize") { + KeepAlivePduSerializer serializer(pduConf, progress); + result = serializer.serialize(&buffer, &sz, kaBuffer.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(kaBuffer[10] == cfdp::FileDirectives::KEEP_ALIVE); + uint32_t fsRaw = 0; + result = SerializeAdapter::deSerialize(&fsRaw, kaBuffer.data() + 11, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(fsRaw == 0x50); + REQUIRE(sz == 15); + REQUIRE(serializer.getWholePduSize() == 15); + REQUIRE(serializer.getPduDataFieldLen() == 5); - SECTION("Serialize") { - KeepAlivePduSerializer serializer(pduConf, progress); - result = serializer.serialize(&buffer, &sz, kaBuffer.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(kaBuffer[10] == cfdp::FileDirectives::KEEP_ALIVE); - uint32_t fsRaw = 0; - result = SerializeAdapter::deSerialize(&fsRaw, kaBuffer.data() + 11, nullptr, - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(fsRaw == 0x50); - REQUIRE(sz == 15); - REQUIRE(serializer.getWholePduSize() == 15); - REQUIRE(serializer.getPduDataFieldLen() == 5); + pduConf.largeFile = true; + serializer.updateDirectiveFieldLen(); + buffer = kaBuffer.data(); + sz = 0; + result = serializer.serialize(&buffer, &sz, kaBuffer.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(serializer.getWholePduSize() == 19); + REQUIRE(serializer.getPduDataFieldLen() == 9); + uint64_t fsRawLarge = 0; + result = SerializeAdapter::deSerialize(&fsRawLarge, kaBuffer.data() + 11, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(fsRawLarge == 0x50); - pduConf.largeFile = true; - serializer.updateDirectiveFieldLen(); - buffer = kaBuffer.data(); - sz = 0; - result = serializer.serialize(&buffer, &sz, kaBuffer.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(serializer.getWholePduSize() == 19); - REQUIRE(serializer.getPduDataFieldLen() == 9); - uint64_t fsRawLarge = 0; - result = SerializeAdapter::deSerialize(&fsRawLarge, kaBuffer.data() + 11, nullptr, - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(fsRawLarge == 0x50); - - for(size_t invalidMaxSz = 0; invalidMaxSz < sz; invalidMaxSz++) { - buffer = kaBuffer.data(); - sz = 0; - result = serializer.serialize(&buffer, &sz, invalidMaxSz, - SerializeIF::Endianness::NETWORK); - REQUIRE(result != HasReturnvaluesIF::RETURN_OK); - } + for (size_t invalidMaxSz = 0; invalidMaxSz < sz; invalidMaxSz++) { + buffer = kaBuffer.data(); + sz = 0; + result = serializer.serialize(&buffer, &sz, invalidMaxSz, SerializeIF::Endianness::NETWORK); + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); } + } - SECTION("Deserialize") { - KeepAlivePduSerializer serializer(pduConf, progress); - result = serializer.serialize(&buffer, &sz, kaBuffer.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + SECTION("Deserialize") { + KeepAlivePduSerializer serializer(pduConf, progress); + result = serializer.serialize(&buffer, &sz, kaBuffer.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - // Set another file size - progress.setFileSize(200, false); - KeepAlivePduDeserializer deserializer(kaBuffer.data(), kaBuffer.size(), progress); - result = deserializer.parseData(); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - auto& progRef = deserializer.getProgress(); - // Should have been overwritten - REQUIRE(progRef.getSize() == 0x50); - sz = deserializer.getWholePduSize(); + // Set another file size + progress.setFileSize(200, false); + KeepAlivePduDeserializer deserializer(kaBuffer.data(), kaBuffer.size(), progress); + result = deserializer.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + auto& progRef = deserializer.getProgress(); + // Should have been overwritten + REQUIRE(progRef.getSize() == 0x50); + sz = deserializer.getWholePduSize(); - // invalid max size - for(size_t invalidMaxSz = 0; invalidMaxSz < sz; invalidMaxSz++) { - deserializer.setData(kaBuffer.data(), invalidMaxSz); - result = deserializer.parseData(); - REQUIRE(result != HasReturnvaluesIF::RETURN_OK); - } + // invalid max size + for (size_t invalidMaxSz = 0; invalidMaxSz < sz; invalidMaxSz++) { + deserializer.setData(kaBuffer.data(), invalidMaxSz); + result = deserializer.parseData(); + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); } + } } diff --git a/tests/src/fsfw_tests/unit/cfdp/testMetadataPdu.cpp b/tests/src/fsfw_tests/unit/cfdp/testMetadataPdu.cpp index 50dae9e9..331d64a9 100644 --- a/tests/src/fsfw_tests/unit/cfdp/testMetadataPdu.cpp +++ b/tests/src/fsfw_tests/unit/cfdp/testMetadataPdu.cpp @@ -1,185 +1,179 @@ -#include #include -#include "fsfw/cfdp/tlv/FilestoreResponseTlv.h" +#include +#include + #include "fsfw/cfdp/pdu/MetadataPduDeserializer.h" #include "fsfw/cfdp/pdu/MetadataPduSerializer.h" +#include "fsfw/cfdp/tlv/FilestoreResponseTlv.h" #include "fsfw/globalfunctions/arrayprinter.h" -#include +TEST_CASE("Metadata PDU", "[MetadataPdu]") { + using namespace cfdp; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + std::array mdBuffer = {}; + uint8_t* buffer = mdBuffer.data(); + size_t sz = 0; + EntityId destId(WidthInBytes::TWO_BYTES, 2); + TransactionSeqNum seqNum(WidthInBytes::TWO_BYTES, 15); + EntityId sourceId(WidthInBytes::TWO_BYTES, 1); + PduConfig pduConf(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); -TEST_CASE( "Metadata PDU" , "[MetadataPdu]") { - using namespace cfdp; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - std::array mdBuffer = {}; + std::string firstFileName = "hello.txt"; + cfdp::Lv sourceFileName(reinterpret_cast(firstFileName.data()), + firstFileName.size()); + cfdp::Lv destFileName(nullptr, 0); + FileSize fileSize(35); + MetadataInfo info(false, ChecksumType::MODULAR, fileSize, sourceFileName, destFileName); + + FilestoreResponseTlv response(FilestoreActionCode::CREATE_DIRECTORY, FSR_CREATE_NOT_ALLOWED, + sourceFileName, nullptr); + std::array msg = {0x41, 0x42, 0x43}; + cfdp::Tlv responseTlv; + std::array responseBuf = {}; + uint8_t* responseBufPtr = responseBuf.data(); + response.convertToTlv(responseTlv, buffer, responseBuf.size(), SerializeIF::Endianness::MACHINE); + MessageToUserTlv msgToUser(msg.data(), msg.size()); + std::array options{&responseTlv, &msgToUser}; + REQUIRE(options[0]->getSerializedSize() == 2 + 1 + 10 + 1); + REQUIRE(options[1]->getSerializedSize() == 5); + + SECTION("Serialize") { + MetadataPduSerializer serializer(pduConf, info); + result = serializer.serialize(&buffer, &sz, mdBuffer.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(serializer.getWholePduSize() == 27); + REQUIRE(info.getSourceFileName().getSerializedSize() == 10); + REQUIRE(info.getDestFileName().getSerializedSize() == 1); + REQUIRE(info.getSerializedSize() == 16); + REQUIRE((mdBuffer[1] << 8 | mdBuffer[2]) == 17); + REQUIRE(mdBuffer[10] == FileDirectives::METADATA); + // no closure requested and checksum type is modular => 0x00 + REQUIRE(mdBuffer[11] == 0x00); + uint32_t fileSizeRaw = 0; + result = SerializeAdapter::deSerialize(&fileSizeRaw, mdBuffer.data() + 12, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(fileSizeRaw == 35); + REQUIRE(mdBuffer[16] == 9); + REQUIRE(mdBuffer[17] == 'h'); + REQUIRE(mdBuffer[18] == 'e'); + REQUIRE(mdBuffer[19] == 'l'); + REQUIRE(mdBuffer[20] == 'l'); + REQUIRE(mdBuffer[21] == 'o'); + REQUIRE(mdBuffer[22] == '.'); + REQUIRE(mdBuffer[23] == 't'); + REQUIRE(mdBuffer[24] == 'x'); + REQUIRE(mdBuffer[25] == 't'); + REQUIRE(mdBuffer[26] == 0); + + std::string otherFileName = "hello2.txt"; + cfdp::Lv otherFileNameLv(reinterpret_cast(otherFileName.data()), + otherFileName.size()); + info.setSourceFileName(otherFileNameLv); + size_t sizeOfOptions = options.size(); + info.setOptionsArray(options.data(), &sizeOfOptions, &sizeOfOptions); + REQUIRE(info.getMaxOptionsLen() == 2); + info.setMaxOptionsLen(3); + REQUIRE(info.getMaxOptionsLen() == 3); + info.setChecksumType(cfdp::ChecksumType::CRC_32C); + info.setClosureRequested(true); uint8_t* buffer = mdBuffer.data(); size_t sz = 0; - EntityId destId(WidthInBytes::TWO_BYTES, 2); - TransactionSeqNum seqNum(WidthInBytes::TWO_BYTES, 15); - EntityId sourceId(WidthInBytes::TWO_BYTES, 1); - PduConfig pduConf(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); + serializer.updateDirectiveFieldLen(); - std::string firstFileName = "hello.txt"; - cfdp::Lv sourceFileName(reinterpret_cast(firstFileName.data()), - firstFileName.size()); - cfdp::Lv destFileName(nullptr, 0); - FileSize fileSize(35); - MetadataInfo info(false, ChecksumType::MODULAR, fileSize, sourceFileName, destFileName); + result = serializer.serialize(&buffer, &sz, mdBuffer.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE((mdBuffer[1] << 8 | mdBuffer[2]) == 37); + auto checksumType = static_cast(mdBuffer[11] & 0x0f); + REQUIRE(checksumType == cfdp::ChecksumType::CRC_32C); + bool closureRequested = mdBuffer[11] >> 6 & 0x01; + REQUIRE(closureRequested == true); + // The size of the two options is 19. Summing up: + // - 11 bytes of source file name + // - 1 byte for dest file name + // - 4 for FSS + // - 1 leading byte. + // - 1 byte for PDU type + // PDU header has 10 bytes. + // I am not going to check the options raw content, those are part of the dedicated + // TLV unittests + REQUIRE(sz == 10 + 37); + for (size_t maxSz = 0; maxSz < sz; maxSz++) { + uint8_t* buffer = mdBuffer.data(); + size_t sz = 0; + result = serializer.serialize(&buffer, &sz, maxSz, SerializeIF::Endianness::NETWORK); + REQUIRE(result == SerializeIF::BUFFER_TOO_SHORT); + } + for (size_t initSz = 1; initSz < 47; initSz++) { + uint8_t* buffer = mdBuffer.data(); + size_t sz = initSz; + result = serializer.serialize(&buffer, &sz, 46, SerializeIF::Endianness::NETWORK); + REQUIRE(result == SerializeIF::BUFFER_TOO_SHORT); + } + info.setDestFileName(destFileName); + } - FilestoreResponseTlv response(FilestoreActionCode::CREATE_DIRECTORY, FSR_CREATE_NOT_ALLOWED, - sourceFileName, nullptr); - std::array msg = {0x41, 0x42, 0x43}; - cfdp::Tlv responseTlv; - std::array responseBuf = {}; - uint8_t* responseBufPtr = responseBuf.data(); - response.convertToTlv(responseTlv, buffer, responseBuf.size(), - SerializeIF::Endianness::MACHINE); - MessageToUserTlv msgToUser(msg.data(), msg.size()); - std::array options {&responseTlv, &msgToUser}; - REQUIRE(options[0]->getSerializedSize() == 2 + 1 + 10 + 1); + SECTION("Deserialize") { + MetadataPduSerializer serializer(pduConf, info); + result = serializer.serialize(&buffer, &sz, mdBuffer.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + MetadataPduDeserializer deserializer(mdBuffer.data(), mdBuffer.size(), info); + result = deserializer.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + size_t fullSize = deserializer.getWholePduSize(); + for (size_t maxSz = 0; maxSz < fullSize; maxSz++) { + MetadataPduDeserializer invalidSzDeser(mdBuffer.data(), maxSz, info); + result = invalidSzDeser.parseData(); + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + } + size_t sizeOfOptions = options.size(); + size_t maxSize = 4; + info.setOptionsArray(options.data(), &sizeOfOptions, &maxSize); + REQUIRE(info.getOptionsLen() == 2); + info.setChecksumType(cfdp::ChecksumType::CRC_32C); + info.setClosureRequested(true); + uint8_t* buffer = mdBuffer.data(); + size_t sz = 0; + serializer.updateDirectiveFieldLen(); + + info.setSourceFileName(sourceFileName); + result = serializer.serialize(&buffer, &sz, mdBuffer.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + MetadataPduDeserializer deserializer2(mdBuffer.data(), mdBuffer.size(), info); + result = deserializer2.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(options[0]->getType() == cfdp::TlvTypes::FILESTORE_RESPONSE); + REQUIRE(options[0]->getSerializedSize() == 14); + REQUIRE(options[1]->getType() == cfdp::TlvTypes::MSG_TO_USER); REQUIRE(options[1]->getSerializedSize() == 5); - SECTION("Serialize") { - MetadataPduSerializer serializer(pduConf, info); - result = serializer.serialize(&buffer, &sz, mdBuffer.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(serializer.getWholePduSize() == 27); - REQUIRE(info.getSourceFileName().getSerializedSize() == 10); - REQUIRE(info.getDestFileName().getSerializedSize() == 1); - REQUIRE(info.getSerializedSize() == 16); - REQUIRE((mdBuffer[1] << 8 | mdBuffer[2]) == 17); - REQUIRE(mdBuffer[10] == FileDirectives::METADATA); - // no closure requested and checksum type is modular => 0x00 - REQUIRE(mdBuffer[11] == 0x00); - uint32_t fileSizeRaw = 0; - result = SerializeAdapter::deSerialize(&fileSizeRaw, mdBuffer.data() + 12, nullptr, - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(fileSizeRaw == 35); - REQUIRE(mdBuffer[16] == 9); - REQUIRE(mdBuffer[17] == 'h'); - REQUIRE(mdBuffer[18] == 'e'); - REQUIRE(mdBuffer[19] == 'l'); - REQUIRE(mdBuffer[20] == 'l'); - REQUIRE(mdBuffer[21] == 'o'); - REQUIRE(mdBuffer[22] == '.'); - REQUIRE(mdBuffer[23] == 't'); - REQUIRE(mdBuffer[24] == 'x'); - REQUIRE(mdBuffer[25] == 't'); - REQUIRE(mdBuffer[26] == 0); - - std::string otherFileName = "hello2.txt"; - cfdp::Lv otherFileNameLv(reinterpret_cast(otherFileName.data()), - otherFileName.size()); - info.setSourceFileName(otherFileNameLv); - size_t sizeOfOptions = options.size(); - info.setOptionsArray(options.data(), &sizeOfOptions, &sizeOfOptions); - REQUIRE(info.getMaxOptionsLen() == 2); - info.setMaxOptionsLen(3); - REQUIRE(info.getMaxOptionsLen() == 3); - info.setChecksumType(cfdp::ChecksumType::CRC_32C); - info.setClosureRequested(true); - uint8_t* buffer = mdBuffer.data(); - size_t sz = 0; - serializer.updateDirectiveFieldLen(); - - result = serializer.serialize(&buffer, &sz, mdBuffer.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE((mdBuffer[1] << 8 | mdBuffer[2]) == 37); - auto checksumType = static_cast(mdBuffer[11] & 0x0f); - REQUIRE(checksumType == cfdp::ChecksumType::CRC_32C); - bool closureRequested = mdBuffer[11] >> 6 & 0x01; - REQUIRE(closureRequested == true); - // The size of the two options is 19. Summing up: - // - 11 bytes of source file name - // - 1 byte for dest file name - // - 4 for FSS - // - 1 leading byte. - // - 1 byte for PDU type - // PDU header has 10 bytes. - // I am not going to check the options raw content, those are part of the dedicated - // TLV unittests - REQUIRE(sz == 10 + 37); - for(size_t maxSz = 0; maxSz < sz; maxSz++) { - uint8_t* buffer = mdBuffer.data(); - size_t sz = 0; - result = serializer.serialize(&buffer, &sz, maxSz, - SerializeIF::Endianness::NETWORK); - REQUIRE(result == SerializeIF::BUFFER_TOO_SHORT); - } - for(size_t initSz = 1; initSz < 47; initSz++) { - uint8_t* buffer = mdBuffer.data(); - size_t sz = initSz; - result = serializer.serialize(&buffer, &sz, 46, SerializeIF::Endianness::NETWORK); - REQUIRE(result == SerializeIF::BUFFER_TOO_SHORT); - } - info.setDestFileName(destFileName); + for (size_t invalidFieldLen = 0; invalidFieldLen < 36; invalidFieldLen++) { + mdBuffer[1] = (invalidFieldLen >> 8) & 0xff; + mdBuffer[2] = invalidFieldLen & 0xff; + result = deserializer2.parseData(); + if (invalidFieldLen == 17) { + REQUIRE(info.getOptionsLen() == 0); + } + if (invalidFieldLen == 31) { + REQUIRE(info.getOptionsLen() == 1); + } + // This is the precise length where there are no options or one option + if (invalidFieldLen != 17 and invalidFieldLen != 31) { + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + } } - - SECTION("Deserialize") { - MetadataPduSerializer serializer(pduConf, info); - result = serializer.serialize(&buffer, &sz, mdBuffer.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - - MetadataPduDeserializer deserializer(mdBuffer.data(), mdBuffer.size(), info); - result = deserializer.parseData(); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - size_t fullSize = deserializer.getWholePduSize(); - for(size_t maxSz = 0; maxSz < fullSize; maxSz++) { - MetadataPduDeserializer invalidSzDeser(mdBuffer.data(), maxSz, info); - result = invalidSzDeser.parseData(); - REQUIRE(result != HasReturnvaluesIF::RETURN_OK); - } - size_t sizeOfOptions = options.size(); - size_t maxSize = 4; - info.setOptionsArray(options.data(), &sizeOfOptions, &maxSize); - REQUIRE(info.getOptionsLen() == 2); - info.setChecksumType(cfdp::ChecksumType::CRC_32C); - info.setClosureRequested(true); - uint8_t* buffer = mdBuffer.data(); - size_t sz = 0; - serializer.updateDirectiveFieldLen(); - - info.setSourceFileName(sourceFileName); - result = serializer.serialize(&buffer, &sz, mdBuffer.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - - MetadataPduDeserializer deserializer2(mdBuffer.data(), mdBuffer.size(), info); - result = deserializer2.parseData(); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(options[0]->getType() == cfdp::TlvTypes::FILESTORE_RESPONSE); - REQUIRE(options[0]->getSerializedSize() == 14); - REQUIRE(options[1]->getType() == cfdp::TlvTypes::MSG_TO_USER); - REQUIRE(options[1]->getSerializedSize() == 5); - - for(size_t invalidFieldLen = 0; invalidFieldLen < 36; invalidFieldLen++) { - mdBuffer[1] = (invalidFieldLen >> 8) & 0xff; - mdBuffer[2] = invalidFieldLen & 0xff; - result = deserializer2.parseData(); - if(invalidFieldLen == 17) { - REQUIRE(info.getOptionsLen() == 0); - } - if(invalidFieldLen == 31) { - REQUIRE(info.getOptionsLen() == 1); - } - // This is the precise length where there are no options or one option - if(invalidFieldLen != 17 and invalidFieldLen != 31) { - REQUIRE(result != HasReturnvaluesIF::RETURN_OK); - } - } - mdBuffer[1] = (36 >> 8) & 0xff; - mdBuffer[2] = 36 & 0xff; - info.setOptionsArray(nullptr, nullptr, nullptr); - REQUIRE(deserializer2.parseData() == cfdp::METADATA_CANT_PARSE_OPTIONS); - info.setOptionsArray(options.data(), &sizeOfOptions, nullptr); - for(size_t maxSz = 0; maxSz < 46; maxSz++) { - MetadataPduDeserializer invalidSzDeser(mdBuffer.data(), maxSz, info); - result = invalidSzDeser.parseData(); - REQUIRE(result == SerializeIF::STREAM_TOO_SHORT); - } + mdBuffer[1] = (36 >> 8) & 0xff; + mdBuffer[2] = 36 & 0xff; + info.setOptionsArray(nullptr, nullptr, nullptr); + REQUIRE(deserializer2.parseData() == cfdp::METADATA_CANT_PARSE_OPTIONS); + info.setOptionsArray(options.data(), &sizeOfOptions, nullptr); + for (size_t maxSz = 0; maxSz < 46; maxSz++) { + MetadataPduDeserializer invalidSzDeser(mdBuffer.data(), maxSz, info); + result = invalidSzDeser.parseData(); + REQUIRE(result == SerializeIF::STREAM_TOO_SHORT); } + } } diff --git a/tests/src/fsfw_tests/unit/cfdp/testNakPdu.cpp b/tests/src/fsfw_tests/unit/cfdp/testNakPdu.cpp index 57ec5140..38b45300 100644 --- a/tests/src/fsfw_tests/unit/cfdp/testNakPdu.cpp +++ b/tests/src/fsfw_tests/unit/cfdp/testNakPdu.cpp @@ -1,160 +1,152 @@ +#include #include -#include "fsfw/cfdp/pdu/PduConfig.h" #include "fsfw/cfdp/pdu/NakPduDeserializer.h" #include "fsfw/cfdp/pdu/NakPduSerializer.h" +#include "fsfw/cfdp/pdu/PduConfig.h" #include "fsfw/globalfunctions/arrayprinter.h" -#include +TEST_CASE("NAK PDU", "[NakPdu]") { + using namespace cfdp; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + std::array nakBuffer = {}; + uint8_t* buffer = nakBuffer.data(); + size_t sz = 0; + EntityId destId(WidthInBytes::TWO_BYTES, 2); + TransactionSeqNum seqNum(WidthInBytes::TWO_BYTES, 15); + EntityId sourceId(WidthInBytes::TWO_BYTES, 1); + PduConfig pduConf(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); -TEST_CASE( "NAK PDU" , "[NakPdu]") { - using namespace cfdp; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - std::array nakBuffer = {}; + FileSize startOfScope(50); + FileSize endOfScope(1050); + NakInfo info(startOfScope, endOfScope); + SECTION("Serializer") { + NakPduSerializer serializer(pduConf, info); + result = serializer.serialize(&buffer, &sz, nakBuffer.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(serializer.getSerializedSize() == 19); + REQUIRE(serializer.FileDirectiveSerializer::getSerializedSize() == 11); + REQUIRE(sz == 19); + REQUIRE(serializer.getPduDataFieldLen() == 9); + REQUIRE(((nakBuffer[1] << 8) | nakBuffer[2]) == 0x09); + REQUIRE(nakBuffer[10] == cfdp::FileDirectives::NAK); + uint32_t scope = 0; + result = SerializeAdapter::deSerialize(&scope, nakBuffer.data() + 11, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(scope == 50); + result = SerializeAdapter::deSerialize(&scope, nakBuffer.data() + 15, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(scope == 1050); + + NakInfo::SegmentRequest segReq0(cfdp::FileSize(2020), cfdp::FileSize(2520)); + NakInfo::SegmentRequest segReq1(cfdp::FileSize(2932), cfdp::FileSize(3021)); + // Now add 2 segment requests to NAK info and serialize them as well + std::array segReqs = {segReq0, segReq1}; + size_t segReqsLen = segReqs.size(); + info.setSegmentRequests(segReqs.data(), &segReqsLen, &segReqsLen); uint8_t* buffer = nakBuffer.data(); size_t sz = 0; - EntityId destId(WidthInBytes::TWO_BYTES, 2); - TransactionSeqNum seqNum(WidthInBytes::TWO_BYTES, 15); - EntityId sourceId(WidthInBytes::TWO_BYTES, 1); - PduConfig pduConf(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); + serializer.updateDirectiveFieldLen(); + result = serializer.serialize(&buffer, &sz, nakBuffer.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(serializer.getSerializedSize() == 35); + REQUIRE(serializer.getPduDataFieldLen() == 25); + REQUIRE(((nakBuffer[1] << 8) | nakBuffer[2]) == 25); + uint32_t segReqScopes = 0; + result = SerializeAdapter::deSerialize(&segReqScopes, nakBuffer.data() + 19, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(segReqScopes == 2020); + result = SerializeAdapter::deSerialize(&segReqScopes, nakBuffer.data() + 23, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(segReqScopes == 2520); + result = SerializeAdapter::deSerialize(&segReqScopes, nakBuffer.data() + 27, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(segReqScopes == 2932); + result = SerializeAdapter::deSerialize(&segReqScopes, nakBuffer.data() + 31, nullptr, + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(segReqScopes == 3021); - FileSize startOfScope(50); - FileSize endOfScope(1050); - NakInfo info(startOfScope, endOfScope); - SECTION("Serializer") { - NakPduSerializer serializer(pduConf, info); - result = serializer.serialize(&buffer, &sz, nakBuffer.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(serializer.getSerializedSize() == 19); - REQUIRE(serializer.FileDirectiveSerializer::getSerializedSize() == 11); - REQUIRE(sz == 19); - REQUIRE(serializer.getPduDataFieldLen() == 9); - REQUIRE(((nakBuffer[1] << 8) | nakBuffer[2]) == 0x09); - REQUIRE(nakBuffer[10] == cfdp::FileDirectives::NAK); - uint32_t scope = 0; - result = SerializeAdapter::deSerialize(&scope, nakBuffer.data() + 11, nullptr, - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(scope == 50); - result = SerializeAdapter::deSerialize(&scope, nakBuffer.data() + 15, nullptr, - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(scope == 1050); - - NakInfo::SegmentRequest segReq0(cfdp::FileSize(2020), cfdp::FileSize(2520)); - NakInfo::SegmentRequest segReq1(cfdp::FileSize(2932), cfdp::FileSize(3021)); - // Now add 2 segment requests to NAK info and serialize them as well - std::array segReqs = { segReq0, segReq1 }; - size_t segReqsLen = segReqs.size(); - info.setSegmentRequests(segReqs.data(), &segReqsLen , &segReqsLen); - uint8_t* buffer = nakBuffer.data(); - size_t sz = 0; - serializer.updateDirectiveFieldLen(); - result = serializer.serialize(&buffer, &sz, nakBuffer.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(serializer.getSerializedSize() == 35); - REQUIRE(serializer.getPduDataFieldLen() == 25); - REQUIRE(((nakBuffer[1] << 8) | nakBuffer[2]) == 25); - uint32_t segReqScopes = 0; - result = SerializeAdapter::deSerialize(&segReqScopes, nakBuffer.data() + 19, nullptr, - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(segReqScopes == 2020); - result = SerializeAdapter::deSerialize(&segReqScopes, nakBuffer.data() + 23, nullptr, - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(segReqScopes == 2520); - result = SerializeAdapter::deSerialize(&segReqScopes, nakBuffer.data() + 27, nullptr, - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(segReqScopes == 2932); - result = SerializeAdapter::deSerialize(&segReqScopes, nakBuffer.data() + 31, nullptr, - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(segReqScopes == 3021); - - for(size_t maxSz = 0; maxSz < 35; maxSz++) { - uint8_t* buffer = nakBuffer.data(); - size_t sz = 0; - result = serializer.serialize(&buffer, &sz, maxSz, - SerializeIF::Endianness::NETWORK); - REQUIRE(result == SerializeIF::BUFFER_TOO_SHORT); - } - for(size_t sz = 35; sz > 0; sz--) { - uint8_t* buffer = nakBuffer.data(); - size_t locSize = sz; - result = serializer.serialize(&buffer, &locSize, 35, - SerializeIF::Endianness::NETWORK); - REQUIRE(result == SerializeIF::BUFFER_TOO_SHORT); - } + for (size_t maxSz = 0; maxSz < 35; maxSz++) { + uint8_t* buffer = nakBuffer.data(); + size_t sz = 0; + result = serializer.serialize(&buffer, &sz, maxSz, SerializeIF::Endianness::NETWORK); + REQUIRE(result == SerializeIF::BUFFER_TOO_SHORT); } + for (size_t sz = 35; sz > 0; sz--) { + uint8_t* buffer = nakBuffer.data(); + size_t locSize = sz; + result = serializer.serialize(&buffer, &locSize, 35, SerializeIF::Endianness::NETWORK); + REQUIRE(result == SerializeIF::BUFFER_TOO_SHORT); + } + } - SECTION("Deserializer") { - NakPduSerializer serializer(pduConf, info); - result = serializer.serialize(&buffer, &sz, nakBuffer.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + SECTION("Deserializer") { + NakPduSerializer serializer(pduConf, info); + result = serializer.serialize(&buffer, &sz, nakBuffer.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - info.getStartOfScope().setFileSize(0, false); - info.getEndOfScope().setFileSize(0, false); - NakPduDeserializer deserializer(nakBuffer.data(), nakBuffer.size(), info); - result = deserializer.parseData(); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(deserializer.getWholePduSize() == 19); - REQUIRE(info.getStartOfScope().getSize() == 50); - REQUIRE(info.getEndOfScope().getSize() == 1050); + info.getStartOfScope().setFileSize(0, false); + info.getEndOfScope().setFileSize(0, false); + NakPduDeserializer deserializer(nakBuffer.data(), nakBuffer.size(), info); + result = deserializer.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(deserializer.getWholePduSize() == 19); + REQUIRE(info.getStartOfScope().getSize() == 50); + REQUIRE(info.getEndOfScope().getSize() == 1050); - NakInfo::SegmentRequest segReq0(cfdp::FileSize(2020), cfdp::FileSize(2520)); - NakInfo::SegmentRequest segReq1(cfdp::FileSize(2932), cfdp::FileSize(3021)); - // Now add 2 segment requests to NAK info and serialize them as well - std::array segReqs = { segReq0, segReq1 }; - size_t segReqsLen = segReqs.size(); - info.setSegmentRequests(segReqs.data(), &segReqsLen, &segReqsLen); - uint8_t* buffer = nakBuffer.data(); - size_t sz = 0; - serializer.updateDirectiveFieldLen(); - result = serializer.serialize(&buffer, &sz, nakBuffer.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + NakInfo::SegmentRequest segReq0(cfdp::FileSize(2020), cfdp::FileSize(2520)); + NakInfo::SegmentRequest segReq1(cfdp::FileSize(2932), cfdp::FileSize(3021)); + // Now add 2 segment requests to NAK info and serialize them as well + std::array segReqs = {segReq0, segReq1}; + size_t segReqsLen = segReqs.size(); + info.setSegmentRequests(segReqs.data(), &segReqsLen, &segReqsLen); + uint8_t* buffer = nakBuffer.data(); + size_t sz = 0; + serializer.updateDirectiveFieldLen(); + result = serializer.serialize(&buffer, &sz, nakBuffer.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - NakPduDeserializer deserializeWithSegReqs(nakBuffer.data(), nakBuffer.size(), info); - result = deserializeWithSegReqs.parseData(); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - NakInfo::SegmentRequest* segReqsPtr = nullptr; - size_t readSegReqs = 0; - info.getSegmentRequests(&segReqsPtr, &readSegReqs, nullptr); - REQUIRE(readSegReqs == 2); - REQUIRE(segReqsPtr[0].first.getSize() == 2020); - REQUIRE(segReqsPtr[0].second.getSize() == 2520); - REQUIRE(segReqsPtr[1].first.getSize() == 2932); - REQUIRE(segReqsPtr[1].second.getSize() == 3021); - REQUIRE(deserializeWithSegReqs.getPduDataFieldLen() == 25); + NakPduDeserializer deserializeWithSegReqs(nakBuffer.data(), nakBuffer.size(), info); + result = deserializeWithSegReqs.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + NakInfo::SegmentRequest* segReqsPtr = nullptr; + size_t readSegReqs = 0; + info.getSegmentRequests(&segReqsPtr, &readSegReqs, nullptr); + REQUIRE(readSegReqs == 2); + REQUIRE(segReqsPtr[0].first.getSize() == 2020); + REQUIRE(segReqsPtr[0].second.getSize() == 2520); + REQUIRE(segReqsPtr[1].first.getSize() == 2932); + REQUIRE(segReqsPtr[1].second.getSize() == 3021); + REQUIRE(deserializeWithSegReqs.getPduDataFieldLen() == 25); + REQUIRE(info.getSegmentRequestsLen() == 2); + for (size_t idx = 0; idx < 34; idx++) { + NakPduDeserializer faultyDeserializer(nakBuffer.data(), idx, info); + result = faultyDeserializer.parseData(); + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + } + for (size_t pduFieldLen = 0; pduFieldLen < 25; pduFieldLen++) { + nakBuffer[1] = (pduFieldLen >> 8) & 0xff; + nakBuffer[2] = pduFieldLen & 0xff; + NakPduDeserializer faultyDeserializer(nakBuffer.data(), nakBuffer.size(), info); + result = faultyDeserializer.parseData(); + if (pduFieldLen == 9) { + REQUIRE(info.getSegmentRequestsLen() == 0); + } else if (pduFieldLen == 17) { + REQUIRE(info.getSegmentRequestsLen() == 1); + } else if (pduFieldLen == 25) { REQUIRE(info.getSegmentRequestsLen() == 2); - for(size_t idx = 0; idx < 34; idx ++) { - NakPduDeserializer faultyDeserializer(nakBuffer.data(), idx, info); - result = faultyDeserializer.parseData(); - REQUIRE(result != HasReturnvaluesIF::RETURN_OK); - } - for(size_t pduFieldLen = 0; pduFieldLen < 25; pduFieldLen++) { - nakBuffer[1] = (pduFieldLen >> 8) & 0xff; - nakBuffer[2] = pduFieldLen & 0xff; - NakPduDeserializer faultyDeserializer(nakBuffer.data(), nakBuffer.size(), info); - result = faultyDeserializer.parseData(); - if(pduFieldLen == 9) { - REQUIRE(info.getSegmentRequestsLen() == 0); - } else if(pduFieldLen == 17) { - REQUIRE(info.getSegmentRequestsLen() == 1); - } else if(pduFieldLen == 25) { - REQUIRE(info.getSegmentRequestsLen() == 2); - } - if(pduFieldLen != 9 and pduFieldLen != 17 and pduFieldLen != 25) { - REQUIRE(result != HasReturnvaluesIF::RETURN_OK); - } - } - info.setMaxSegmentRequestLen(5); - REQUIRE(info.getSegmentRequestsMaxLen() == 5); + } + if (pduFieldLen != 9 and pduFieldLen != 17 and pduFieldLen != 25) { + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + } } + info.setMaxSegmentRequestLen(5); + REQUIRE(info.getSegmentRequestsMaxLen() == 5); + } } - diff --git a/tests/src/fsfw_tests/unit/cfdp/testPromptPdu.cpp b/tests/src/fsfw_tests/unit/cfdp/testPromptPdu.cpp index 64589e46..9f406aec 100644 --- a/tests/src/fsfw_tests/unit/cfdp/testPromptPdu.cpp +++ b/tests/src/fsfw_tests/unit/cfdp/testPromptPdu.cpp @@ -1,71 +1,65 @@ +#include #include #include "fsfw/cfdp/pdu/PromptPduDeserializer.h" #include "fsfw/cfdp/pdu/PromptPduSerializer.h" #include "fsfw/globalfunctions/arrayprinter.h" -#include +TEST_CASE("Prompt PDU", "[PromptPdu]") { + using namespace cfdp; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + std::array rawBuf = {}; + uint8_t* buffer = rawBuf.data(); + size_t sz = 0; + EntityId destId(WidthInBytes::TWO_BYTES, 2); + TransactionSeqNum seqNum(WidthInBytes::TWO_BYTES, 15); + EntityId sourceId(WidthInBytes::TWO_BYTES, 1); + PduConfig pduConf(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); -TEST_CASE( "Prompt PDU" , "[PromptPdu]") { - using namespace cfdp; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - std::array rawBuf = {}; - uint8_t* buffer = rawBuf.data(); - size_t sz = 0; - EntityId destId(WidthInBytes::TWO_BYTES, 2); - TransactionSeqNum seqNum(WidthInBytes::TWO_BYTES, 15); - EntityId sourceId(WidthInBytes::TWO_BYTES, 1); - PduConfig pduConf(TransmissionModes::ACKNOWLEDGED, seqNum, sourceId, destId); + SECTION("Serialize") { + PromptPduSerializer serializer(pduConf, cfdp::PromptResponseRequired::PROMPT_KEEP_ALIVE); + result = serializer.serialize(&buffer, &sz, rawBuf.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(serializer.getWholePduSize() == 12); + REQUIRE(sz == 12); + REQUIRE(serializer.getPduDataFieldLen() == 2); + REQUIRE(rawBuf[10] == FileDirectives::PROMPT); + REQUIRE((rawBuf[sz - 1] >> 7) & 0x01 == cfdp::PromptResponseRequired::PROMPT_KEEP_ALIVE); - SECTION("Serialize") { - PromptPduSerializer serializer(pduConf, cfdp::PromptResponseRequired::PROMPT_KEEP_ALIVE); - result = serializer.serialize(&buffer, &sz, rawBuf.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(serializer.getWholePduSize() == 12); - REQUIRE(sz == 12); - REQUIRE(serializer.getPduDataFieldLen() == 2); - REQUIRE(rawBuf[10] == FileDirectives::PROMPT); - REQUIRE((rawBuf[sz - 1] >> 7) & 0x01 == cfdp::PromptResponseRequired::PROMPT_KEEP_ALIVE); - - for(size_t invalidMaxSz = 0; invalidMaxSz < sz; invalidMaxSz++) { - uint8_t* buffer = rawBuf.data(); - size_t sz = 0; - result = serializer.serialize(&buffer, &sz, invalidMaxSz, - SerializeIF::Endianness::NETWORK); - REQUIRE(result != HasReturnvaluesIF::RETURN_OK); - } - for(size_t invalidSz = 1; invalidSz < sz; invalidSz++) { - size_t locSz = invalidSz; - uint8_t* buffer = rawBuf.data(); - result = serializer.serialize(&buffer, &locSz, sz, - SerializeIF::Endianness::NETWORK); - REQUIRE(result != HasReturnvaluesIF::RETURN_OK); - } + for (size_t invalidMaxSz = 0; invalidMaxSz < sz; invalidMaxSz++) { + uint8_t* buffer = rawBuf.data(); + size_t sz = 0; + result = serializer.serialize(&buffer, &sz, invalidMaxSz, SerializeIF::Endianness::NETWORK); + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); } - - SECTION("Deserialize") { - PromptPduSerializer serializer(pduConf, cfdp::PromptResponseRequired::PROMPT_KEEP_ALIVE); - result = serializer.serialize(&buffer, &sz, rawBuf.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - - PromptPduDeserializer deserializer(rawBuf.data(), rawBuf.size()); - result = deserializer.parseData(); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(deserializer.getPromptResponseRequired() == - cfdp::PromptResponseRequired::PROMPT_KEEP_ALIVE); - sz = deserializer.getWholePduSize(); - rawBuf[2] = 1; - result = deserializer.parseData(); - REQUIRE(result == SerializeIF::STREAM_TOO_SHORT); - rawBuf[2] = 2; - - for(size_t invalidMaxSz = 0; invalidMaxSz < sz; invalidMaxSz++) { - deserializer.setData(rawBuf.data(), invalidMaxSz); - result = deserializer.parseData(); - REQUIRE(result != HasReturnvaluesIF::RETURN_OK); - } + for (size_t invalidSz = 1; invalidSz < sz; invalidSz++) { + size_t locSz = invalidSz; + uint8_t* buffer = rawBuf.data(); + result = serializer.serialize(&buffer, &locSz, sz, SerializeIF::Endianness::NETWORK); + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); } + } + + SECTION("Deserialize") { + PromptPduSerializer serializer(pduConf, cfdp::PromptResponseRequired::PROMPT_KEEP_ALIVE); + result = serializer.serialize(&buffer, &sz, rawBuf.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + PromptPduDeserializer deserializer(rawBuf.data(), rawBuf.size()); + result = deserializer.parseData(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(deserializer.getPromptResponseRequired() == + cfdp::PromptResponseRequired::PROMPT_KEEP_ALIVE); + sz = deserializer.getWholePduSize(); + rawBuf[2] = 1; + result = deserializer.parseData(); + REQUIRE(result == SerializeIF::STREAM_TOO_SHORT); + rawBuf[2] = 2; + + for (size_t invalidMaxSz = 0; invalidMaxSz < sz; invalidMaxSz++) { + deserializer.setData(rawBuf.data(), invalidMaxSz); + result = deserializer.parseData(); + REQUIRE(result != HasReturnvaluesIF::RETURN_OK); + } + } } - diff --git a/tests/src/fsfw_tests/unit/cfdp/testTlvsLvs.cpp b/tests/src/fsfw_tests/unit/cfdp/testTlvsLvs.cpp index 15e94ebb..c251fd15 100644 --- a/tests/src/fsfw_tests/unit/cfdp/testTlvsLvs.cpp +++ b/tests/src/fsfw_tests/unit/cfdp/testTlvsLvs.cpp @@ -1,334 +1,330 @@ -#include "fsfw/cfdp/pdu/PduConfig.h" -#include "fsfw/cfdp/tlv/Tlv.h" -#include "fsfw/cfdp/tlv/Lv.h" - -#include #include #include #include - -#include "fsfw/globalfunctions/arrayprinter.h" #include #include #include #include +#include #include -TEST_CASE( "CFDP TLV LV" , "[CfdpTlvLv]") { - using namespace cfdp; - int result = HasReturnvaluesIF::RETURN_OK; - std::array rawBuf; - uint8_t* serPtr = rawBuf.data(); - const uint8_t* deserPtr = rawBuf.data(); - size_t deserSize = 0; - cfdp::EntityId sourceId = EntityId(cfdp::WidthInBytes::TWO_BYTES, 0x0ff0); +#include "fsfw/cfdp/pdu/PduConfig.h" +#include "fsfw/cfdp/tlv/Lv.h" +#include "fsfw/cfdp/tlv/Tlv.h" +#include "fsfw/globalfunctions/arrayprinter.h" - SECTION("TLV Serialization") { - std::array tlvRawBuf; - serPtr = tlvRawBuf.data(); - result = sourceId.serialize(&serPtr, &deserSize, tlvRawBuf.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(deserSize == 2); - auto tlv = Tlv(TlvTypes::ENTITY_ID, tlvRawBuf.data(), deserSize); - REQUIRE(tlv.getSerializedSize() == 4); - REQUIRE(tlv.getLengthField() == 2); - serPtr = rawBuf.data(); - deserSize = 0; - result = tlv.serialize(&serPtr, &deserSize, rawBuf.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(deserSize == 4); - REQUIRE(rawBuf[0] == TlvTypes::ENTITY_ID); - REQUIRE(rawBuf[1] == 2); - uint16_t entityId = 0; - SerializeAdapter::deSerialize(&entityId, rawBuf.data() + 2, &deserSize, - SerializeIF::Endianness::NETWORK); - REQUIRE(entityId == 0x0ff0); +TEST_CASE("CFDP TLV LV", "[CfdpTlvLv]") { + using namespace cfdp; + int result = HasReturnvaluesIF::RETURN_OK; + std::array rawBuf; + uint8_t* serPtr = rawBuf.data(); + const uint8_t* deserPtr = rawBuf.data(); + size_t deserSize = 0; + cfdp::EntityId sourceId = EntityId(cfdp::WidthInBytes::TWO_BYTES, 0x0ff0); - // Set new value - sourceId.setValue(cfdp::WidthInBytes::FOUR_BYTES, 12); - serPtr = tlvRawBuf.data(); - deserSize = 0; - result = sourceId.serialize(&serPtr, &deserSize, tlvRawBuf.size(), - SerializeIF::Endianness::NETWORK); - tlv.setValue(tlvRawBuf.data(), cfdp::WidthInBytes::FOUR_BYTES); - serPtr = rawBuf.data(); - deserSize = 0; - result = tlv.serialize(&serPtr, &deserSize, rawBuf.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(rawBuf[0] == TlvTypes::ENTITY_ID); - REQUIRE(rawBuf[1] == 4); + SECTION("TLV Serialization") { + std::array tlvRawBuf; + serPtr = tlvRawBuf.data(); + result = + sourceId.serialize(&serPtr, &deserSize, tlvRawBuf.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(deserSize == 2); + auto tlv = Tlv(TlvTypes::ENTITY_ID, tlvRawBuf.data(), deserSize); + REQUIRE(tlv.getSerializedSize() == 4); + REQUIRE(tlv.getLengthField() == 2); + serPtr = rawBuf.data(); + deserSize = 0; + result = tlv.serialize(&serPtr, &deserSize, rawBuf.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(deserSize == 4); + REQUIRE(rawBuf[0] == TlvTypes::ENTITY_ID); + REQUIRE(rawBuf[1] == 2); + uint16_t entityId = 0; + SerializeAdapter::deSerialize(&entityId, rawBuf.data() + 2, &deserSize, + SerializeIF::Endianness::NETWORK); + REQUIRE(entityId == 0x0ff0); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + // Set new value + sourceId.setValue(cfdp::WidthInBytes::FOUR_BYTES, 12); + serPtr = tlvRawBuf.data(); + deserSize = 0; + result = + sourceId.serialize(&serPtr, &deserSize, tlvRawBuf.size(), SerializeIF::Endianness::NETWORK); + tlv.setValue(tlvRawBuf.data(), cfdp::WidthInBytes::FOUR_BYTES); + serPtr = rawBuf.data(); + deserSize = 0; + result = tlv.serialize(&serPtr, &deserSize, rawBuf.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(rawBuf[0] == TlvTypes::ENTITY_ID); + REQUIRE(rawBuf[1] == 4); - serPtr = rawBuf.data(); - deserSize = 0; - auto tlvInvalid = Tlv(cfdp::TlvTypes::INVALID_TLV, tlvRawBuf.data(), 0); - REQUIRE(tlvInvalid.serialize(&serPtr, &deserSize, rawBuf.size(), - SerializeIF::Endianness::NETWORK) != HasReturnvaluesIF::RETURN_OK); - tlvInvalid = Tlv(cfdp::TlvTypes::ENTITY_ID, nullptr, 3); - REQUIRE(tlvInvalid.serialize(&serPtr, &deserSize, rawBuf.size(), - SerializeIF::Endianness::NETWORK) != HasReturnvaluesIF::RETURN_OK); - REQUIRE(tlvInvalid.serialize(&serPtr, &deserSize, 0, - SerializeIF::Endianness::NETWORK) != HasReturnvaluesIF::RETURN_OK); - REQUIRE(tlvInvalid.getSerializedSize() == 0); - REQUIRE(tlvInvalid.serialize(nullptr, nullptr, 0, - SerializeIF::Endianness::NETWORK) != HasReturnvaluesIF::RETURN_OK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - Tlv zeroLenField(TlvTypes::FAULT_HANDLER, nullptr, 0); - REQUIRE(zeroLenField.getSerializedSize() == 2); - serPtr = rawBuf.data(); - deserSize = 0; - REQUIRE(zeroLenField.serialize(&serPtr, &deserSize, rawBuf.size(), - SerializeIF::Endianness::NETWORK) == HasReturnvaluesIF::RETURN_OK); - REQUIRE(rawBuf[0] == TlvTypes::FAULT_HANDLER); - REQUIRE(rawBuf[1] == 0); - } + serPtr = rawBuf.data(); + deserSize = 0; + auto tlvInvalid = Tlv(cfdp::TlvTypes::INVALID_TLV, tlvRawBuf.data(), 0); + REQUIRE(tlvInvalid.serialize(&serPtr, &deserSize, rawBuf.size(), + SerializeIF::Endianness::NETWORK) != HasReturnvaluesIF::RETURN_OK); + tlvInvalid = Tlv(cfdp::TlvTypes::ENTITY_ID, nullptr, 3); + REQUIRE(tlvInvalid.serialize(&serPtr, &deserSize, rawBuf.size(), + SerializeIF::Endianness::NETWORK) != HasReturnvaluesIF::RETURN_OK); + REQUIRE(tlvInvalid.serialize(&serPtr, &deserSize, 0, SerializeIF::Endianness::NETWORK) != + HasReturnvaluesIF::RETURN_OK); + REQUIRE(tlvInvalid.getSerializedSize() == 0); + REQUIRE(tlvInvalid.serialize(nullptr, nullptr, 0, SerializeIF::Endianness::NETWORK) != + HasReturnvaluesIF::RETURN_OK); - SECTION("TLV Deserialization") { - // Serialization was tested before, generate raw data now - std::array tlvRawBuf; - serPtr = tlvRawBuf.data(); - result = sourceId.serialize(&serPtr, &deserSize, tlvRawBuf.size(), - SerializeIF::Endianness::NETWORK); - auto tlvSerialization = Tlv(TlvTypes::ENTITY_ID, tlvRawBuf.data(), deserSize); - serPtr = rawBuf.data(); - deserSize = 0; - result = tlvSerialization.serialize(&serPtr, &deserSize, rawBuf.size(), - SerializeIF::Endianness::NETWORK); - Tlv tlv; - deserPtr = rawBuf.data(); - result = tlv.deSerialize(&deserPtr, &deserSize, SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(tlv.getSerializedSize() == 4); - REQUIRE(tlv.getType() == TlvTypes::ENTITY_ID); - deserPtr = tlv.getValue(); - uint16_t entityId = 0; - deserSize = 0; - SerializeAdapter::deSerialize(&entityId, deserPtr, &deserSize, - SerializeIF::Endianness::NETWORK); - REQUIRE(entityId == 0x0ff0); + Tlv zeroLenField(TlvTypes::FAULT_HANDLER, nullptr, 0); + REQUIRE(zeroLenField.getSerializedSize() == 2); + serPtr = rawBuf.data(); + deserSize = 0; + REQUIRE(zeroLenField.serialize(&serPtr, &deserSize, rawBuf.size(), + SerializeIF::Endianness::NETWORK) == + HasReturnvaluesIF::RETURN_OK); + REQUIRE(rawBuf[0] == TlvTypes::FAULT_HANDLER); + REQUIRE(rawBuf[1] == 0); + } - REQUIRE(tlv.deSerialize(nullptr, nullptr, SerializeIF::Endianness::NETWORK) != - HasReturnvaluesIF::RETURN_OK); - deserPtr = rawBuf.data(); - deserSize = 0; - REQUIRE(tlv.deSerialize(&deserPtr, &deserSize, SerializeIF::Endianness::NETWORK) == - SerializeIF::STREAM_TOO_SHORT); - // Set invalid TLV - rawBuf[0] = TlvTypes::INVALID_TLV; - deserSize = 4; - REQUIRE(tlv.deSerialize(&deserPtr, &deserSize, SerializeIF::Endianness::NETWORK) != - HasReturnvaluesIF::RETURN_OK); + SECTION("TLV Deserialization") { + // Serialization was tested before, generate raw data now + std::array tlvRawBuf; + serPtr = tlvRawBuf.data(); + result = + sourceId.serialize(&serPtr, &deserSize, tlvRawBuf.size(), SerializeIF::Endianness::NETWORK); + auto tlvSerialization = Tlv(TlvTypes::ENTITY_ID, tlvRawBuf.data(), deserSize); + serPtr = rawBuf.data(); + deserSize = 0; + result = tlvSerialization.serialize(&serPtr, &deserSize, rawBuf.size(), + SerializeIF::Endianness::NETWORK); + Tlv tlv; + deserPtr = rawBuf.data(); + result = tlv.deSerialize(&deserPtr, &deserSize, SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(tlv.getSerializedSize() == 4); + REQUIRE(tlv.getType() == TlvTypes::ENTITY_ID); + deserPtr = tlv.getValue(); + uint16_t entityId = 0; + deserSize = 0; + SerializeAdapter::deSerialize(&entityId, deserPtr, &deserSize, + SerializeIF::Endianness::NETWORK); + REQUIRE(entityId == 0x0ff0); - Tlv zeroLenField(TlvTypes::FAULT_HANDLER, nullptr, 0); - serPtr = rawBuf.data(); - deserSize = 0; - REQUIRE(zeroLenField.serialize(&serPtr, &deserSize, rawBuf.size(), - SerializeIF::Endianness::NETWORK) == HasReturnvaluesIF::RETURN_OK); - deserPtr = rawBuf.data(); - result = zeroLenField.deSerialize(&deserPtr, &deserSize, SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(zeroLenField.getSerializedSize() == 2); - REQUIRE(deserSize == 0); - } + REQUIRE(tlv.deSerialize(nullptr, nullptr, SerializeIF::Endianness::NETWORK) != + HasReturnvaluesIF::RETURN_OK); + deserPtr = rawBuf.data(); + deserSize = 0; + REQUIRE(tlv.deSerialize(&deserPtr, &deserSize, SerializeIF::Endianness::NETWORK) == + SerializeIF::STREAM_TOO_SHORT); + // Set invalid TLV + rawBuf[0] = TlvTypes::INVALID_TLV; + deserSize = 4; + REQUIRE(tlv.deSerialize(&deserPtr, &deserSize, SerializeIF::Endianness::NETWORK) != + HasReturnvaluesIF::RETURN_OK); - SECTION("LV Serialization") { - std::array lvRawBuf; - serPtr = lvRawBuf.data(); - result = sourceId.serialize(&serPtr, &deserSize, lvRawBuf.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(deserSize == 2); - auto lv = cfdp::Lv(lvRawBuf.data(), 2); - auto lvCopy = cfdp::Lv(lv); - REQUIRE(lv.getSerializedSize() == 3); - REQUIRE(lvCopy.getSerializedSize() == 3); - REQUIRE(lv.getValue(nullptr) == lvCopy.getValue(nullptr)); - serPtr = rawBuf.data(); - deserSize = 0; - result = lv.serialize(&serPtr, &deserSize, rawBuf.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(deserSize == 3); - REQUIRE(rawBuf[0] == 2); - uint16_t sourceId = 0; - result = SerializeAdapter::deSerialize(&sourceId, rawBuf.data() + 1, &deserSize, - SerializeIF::Endianness::BIG); - REQUIRE(sourceId == 0x0ff0); + Tlv zeroLenField(TlvTypes::FAULT_HANDLER, nullptr, 0); + serPtr = rawBuf.data(); + deserSize = 0; + REQUIRE(zeroLenField.serialize(&serPtr, &deserSize, rawBuf.size(), + SerializeIF::Endianness::NETWORK) == + HasReturnvaluesIF::RETURN_OK); + deserPtr = rawBuf.data(); + result = zeroLenField.deSerialize(&deserPtr, &deserSize, SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(zeroLenField.getSerializedSize() == 2); + REQUIRE(deserSize == 0); + } - auto lvEmpty = Lv(nullptr, 0); - REQUIRE(lvEmpty.getSerializedSize() == 1); - serPtr = rawBuf.data(); - deserSize = 0; - result = lvEmpty.serialize(&serPtr, &deserSize, rawBuf.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(deserSize == 1); - } + SECTION("LV Serialization") { + std::array lvRawBuf; + serPtr = lvRawBuf.data(); + result = + sourceId.serialize(&serPtr, &deserSize, lvRawBuf.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(deserSize == 2); + auto lv = cfdp::Lv(lvRawBuf.data(), 2); + auto lvCopy = cfdp::Lv(lv); + REQUIRE(lv.getSerializedSize() == 3); + REQUIRE(lvCopy.getSerializedSize() == 3); + REQUIRE(lv.getValue(nullptr) == lvCopy.getValue(nullptr)); + serPtr = rawBuf.data(); + deserSize = 0; + result = lv.serialize(&serPtr, &deserSize, rawBuf.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(deserSize == 3); + REQUIRE(rawBuf[0] == 2); + uint16_t sourceId = 0; + result = SerializeAdapter::deSerialize(&sourceId, rawBuf.data() + 1, &deserSize, + SerializeIF::Endianness::BIG); + REQUIRE(sourceId == 0x0ff0); - SECTION("LV Deserialization") { - std::array lvRawBuf; - serPtr = lvRawBuf.data(); - result = sourceId.serialize(&serPtr, &deserSize, lvRawBuf.size(), - SerializeIF::Endianness::NETWORK); - auto lv = cfdp::Lv(lvRawBuf.data(), 2); - serPtr = rawBuf.data(); - deserSize = 0; - result = lv.serialize(&serPtr, &deserSize, rawBuf.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + auto lvEmpty = Lv(nullptr, 0); + REQUIRE(lvEmpty.getSerializedSize() == 1); + serPtr = rawBuf.data(); + deserSize = 0; + result = + lvEmpty.serialize(&serPtr, &deserSize, rawBuf.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(deserSize == 1); + } - Lv uninitLv; - deserPtr = rawBuf.data(); - deserSize = 3; - result = uninitLv.deSerialize(&deserPtr, &deserSize, SerializeIF::Endianness::BIG); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(uninitLv.getSerializedSize() == 3); - const uint8_t* storedValue = uninitLv.getValue(nullptr); - uint16_t sourceId = 0; - result = SerializeAdapter::deSerialize(&sourceId, storedValue, &deserSize, - SerializeIF::Endianness::BIG); - REQUIRE(sourceId == 0x0ff0); + SECTION("LV Deserialization") { + std::array lvRawBuf; + serPtr = lvRawBuf.data(); + result = + sourceId.serialize(&serPtr, &deserSize, lvRawBuf.size(), SerializeIF::Endianness::NETWORK); + auto lv = cfdp::Lv(lvRawBuf.data(), 2); + serPtr = rawBuf.data(); + deserSize = 0; + result = lv.serialize(&serPtr, &deserSize, rawBuf.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - auto lvEmpty = Lv(nullptr, 0); - REQUIRE(lvEmpty.getSerializedSize() == 1); - serPtr = rawBuf.data(); - deserSize = 0; - result = lvEmpty.serialize(&serPtr, &deserSize, rawBuf.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(deserSize == 1); - deserPtr = rawBuf.data(); - result = uninitLv.deSerialize(&deserPtr, &deserSize, SerializeIF::Endianness::BIG); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(uninitLv.getSerializedSize() == 1); + Lv uninitLv; + deserPtr = rawBuf.data(); + deserSize = 3; + result = uninitLv.deSerialize(&deserPtr, &deserSize, SerializeIF::Endianness::BIG); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(uninitLv.getSerializedSize() == 3); + const uint8_t* storedValue = uninitLv.getValue(nullptr); + uint16_t sourceId = 0; + result = SerializeAdapter::deSerialize(&sourceId, storedValue, &deserSize, + SerializeIF::Endianness::BIG); + REQUIRE(sourceId == 0x0ff0); - REQUIRE(uninitLv.deSerialize(nullptr, nullptr, SerializeIF::Endianness::BIG) == - HasReturnvaluesIF::RETURN_FAILED); - serPtr = rawBuf.data(); - deserSize = 0; - REQUIRE(uninitLv.serialize(&serPtr, &deserSize, 0, SerializeIF::Endianness::BIG) == - SerializeIF::BUFFER_TOO_SHORT); - REQUIRE(uninitLv.serialize(nullptr, nullptr, 12, SerializeIF::Endianness::BIG)); - deserSize = 0; - REQUIRE(uninitLv.deSerialize(&deserPtr, &deserSize, SerializeIF::Endianness::BIG) == - SerializeIF::STREAM_TOO_SHORT); - } + auto lvEmpty = Lv(nullptr, 0); + REQUIRE(lvEmpty.getSerializedSize() == 1); + serPtr = rawBuf.data(); + deserSize = 0; + result = + lvEmpty.serialize(&serPtr, &deserSize, rawBuf.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(deserSize == 1); + deserPtr = rawBuf.data(); + result = uninitLv.deSerialize(&deserPtr, &deserSize, SerializeIF::Endianness::BIG); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(uninitLv.getSerializedSize() == 1); - SECTION("Filestore Response TLV") { - std::string name = "hello.txt"; - cfdp::Lv firstName(reinterpret_cast(name.data()), name.size()); - std::string name2 = "hello2.txt"; - cfdp::Lv secondName(reinterpret_cast(name2.data()), name2.size()); - std::string msg = "12345"; - cfdp::Lv fsMsg(reinterpret_cast(msg.data()), msg.size()); - FilestoreResponseTlv response(cfdp::FilestoreActionCode::APPEND_FILE, cfdp::FSR_SUCCESS, - firstName, &fsMsg); - response.setSecondFileName(&secondName); - REQUIRE(response.getLengthField() == 10 + 11 + 6 + 1); - REQUIRE(response.getSerializedSize() == response.getLengthField() + 2); + REQUIRE(uninitLv.deSerialize(nullptr, nullptr, SerializeIF::Endianness::BIG) == + HasReturnvaluesIF::RETURN_FAILED); + serPtr = rawBuf.data(); + deserSize = 0; + REQUIRE(uninitLv.serialize(&serPtr, &deserSize, 0, SerializeIF::Endianness::BIG) == + SerializeIF::BUFFER_TOO_SHORT); + REQUIRE(uninitLv.serialize(nullptr, nullptr, 12, SerializeIF::Endianness::BIG)); + deserSize = 0; + REQUIRE(uninitLv.deSerialize(&deserPtr, &deserSize, SerializeIF::Endianness::BIG) == + SerializeIF::STREAM_TOO_SHORT); + } - cfdp::Tlv rawResponse; - std::array serBuf = {}; - result = response.convertToTlv(rawResponse, serBuf.data(), serBuf.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(rawResponse.getType() == cfdp::TlvTypes::FILESTORE_RESPONSE); - cfdp::Lv emptyMsg; - cfdp::Lv emptySecondName; - FilestoreResponseTlv emptyTlv(firstName, &emptyMsg); - emptyTlv.setSecondFileName(&emptySecondName); - result = emptyTlv.deSerialize(rawResponse, SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(emptyTlv.getActionCode() == cfdp::FilestoreActionCode::APPEND_FILE); - REQUIRE(emptyTlv.getStatusCode() == cfdp::FSR_SUCCESS); - size_t firstNameLen = 0; - const char* firstNamePtr = reinterpret_cast( - emptyTlv.getFirstFileName().getValue(&firstNameLen)); - auto helloString = std::string(firstNamePtr, firstNameLen); - REQUIRE(helloString == "hello.txt"); - } + SECTION("Filestore Response TLV") { + std::string name = "hello.txt"; + cfdp::Lv firstName(reinterpret_cast(name.data()), name.size()); + std::string name2 = "hello2.txt"; + cfdp::Lv secondName(reinterpret_cast(name2.data()), name2.size()); + std::string msg = "12345"; + cfdp::Lv fsMsg(reinterpret_cast(msg.data()), msg.size()); + FilestoreResponseTlv response(cfdp::FilestoreActionCode::APPEND_FILE, cfdp::FSR_SUCCESS, + firstName, &fsMsg); + response.setSecondFileName(&secondName); + REQUIRE(response.getLengthField() == 10 + 11 + 6 + 1); + REQUIRE(response.getSerializedSize() == response.getLengthField() + 2); - SECTION("Filestore Request TLV") { - std::string name = "hello.txt"; - cfdp::Lv firstName(reinterpret_cast(name.data()), name.size()); - std::string name2 = "hello2.txt"; - cfdp::Lv secondName(reinterpret_cast(name2.data()), name2.size()); - FilestoreRequestTlv request(cfdp::FilestoreActionCode::APPEND_FILE, firstName); + cfdp::Tlv rawResponse; + std::array serBuf = {}; + result = response.convertToTlv(rawResponse, serBuf.data(), serBuf.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(rawResponse.getType() == cfdp::TlvTypes::FILESTORE_RESPONSE); + cfdp::Lv emptyMsg; + cfdp::Lv emptySecondName; + FilestoreResponseTlv emptyTlv(firstName, &emptyMsg); + emptyTlv.setSecondFileName(&emptySecondName); + result = emptyTlv.deSerialize(rawResponse, SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(emptyTlv.getActionCode() == cfdp::FilestoreActionCode::APPEND_FILE); + REQUIRE(emptyTlv.getStatusCode() == cfdp::FSR_SUCCESS); + size_t firstNameLen = 0; + const char* firstNamePtr = + reinterpret_cast(emptyTlv.getFirstFileName().getValue(&firstNameLen)); + auto helloString = std::string(firstNamePtr, firstNameLen); + REQUIRE(helloString == "hello.txt"); + } - // second name not set yet - REQUIRE(request.getLengthField() == 10 + 1); - REQUIRE(request.getSerializedSize() == request.getLengthField() + 2); + SECTION("Filestore Request TLV") { + std::string name = "hello.txt"; + cfdp::Lv firstName(reinterpret_cast(name.data()), name.size()); + std::string name2 = "hello2.txt"; + cfdp::Lv secondName(reinterpret_cast(name2.data()), name2.size()); + FilestoreRequestTlv request(cfdp::FilestoreActionCode::APPEND_FILE, firstName); - std::array serBuf = {}; - uint8_t* ptr = serBuf.data(); - size_t sz = 0; - result = request.serialize(&ptr, &sz, serBuf.size(), SerializeIF::Endianness::NETWORK); - REQUIRE(result == cfdp::FILESTORE_REQUIRES_SECOND_FILE); + // second name not set yet + REQUIRE(request.getLengthField() == 10 + 1); + REQUIRE(request.getSerializedSize() == request.getLengthField() + 2); - ptr = serBuf.data(); - sz = 0; - request.setSecondFileName(&secondName); - size_t expectedSz = request.getLengthField(); - REQUIRE(expectedSz == 10 + 11 + 1); - REQUIRE(request.getSerializedSize() == expectedSz + 2); - result = request.serialize(&ptr, &sz, serBuf.size(), SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(sz == expectedSz + 2); + std::array serBuf = {}; + uint8_t* ptr = serBuf.data(); + size_t sz = 0; + result = request.serialize(&ptr, &sz, serBuf.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == cfdp::FILESTORE_REQUIRES_SECOND_FILE); - FilestoreRequestTlv emptyRequest(firstName); - emptyRequest.setSecondFileName(&secondName); - const uint8_t* constptr = serBuf.data(); - result = emptyRequest.deSerialize(&constptr, &sz, SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + ptr = serBuf.data(); + sz = 0; + request.setSecondFileName(&secondName); + size_t expectedSz = request.getLengthField(); + REQUIRE(expectedSz == 10 + 11 + 1); + REQUIRE(request.getSerializedSize() == expectedSz + 2); + result = request.serialize(&ptr, &sz, serBuf.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(sz == expectedSz + 2); - cfdp::Tlv rawRequest; - ptr = serBuf.data(); - sz = 0; - result = request.convertToTlv(rawRequest, serBuf.data(), serBuf.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(rawRequest.getType() == cfdp::TlvTypes::FILESTORE_REQUEST); + FilestoreRequestTlv emptyRequest(firstName); + emptyRequest.setSecondFileName(&secondName); + const uint8_t* constptr = serBuf.data(); + result = emptyRequest.deSerialize(&constptr, &sz, SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - emptyRequest.setActionCode(cfdp::FilestoreActionCode::DELETE_FILE); - result = emptyRequest.deSerialize(rawRequest, SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(emptyRequest.getType() == cfdp::TlvTypes::FILESTORE_REQUEST); - REQUIRE(emptyRequest.getActionCode() == cfdp::FilestoreActionCode::APPEND_FILE); - } + cfdp::Tlv rawRequest; + ptr = serBuf.data(); + sz = 0; + result = request.convertToTlv(rawRequest, serBuf.data(), serBuf.size(), + SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(rawRequest.getType() == cfdp::TlvTypes::FILESTORE_REQUEST); - SECTION("Other") { - MessageToUserTlv emptyTlv; - uint8_t flowLabel = 1; - FlowLabelTlv flowLabelTlv(&flowLabel, 1); + emptyRequest.setActionCode(cfdp::FilestoreActionCode::DELETE_FILE); + result = emptyRequest.deSerialize(rawRequest, SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(emptyRequest.getType() == cfdp::TlvTypes::FILESTORE_REQUEST); + REQUIRE(emptyRequest.getActionCode() == cfdp::FilestoreActionCode::APPEND_FILE); + } - FaultHandlerOverrideTlv faultOverrideTlv(cfdp::ConditionCode::FILESTORE_REJECTION, - cfdp::FaultHandlerCode::NOTICE_OF_CANCELLATION); - size_t sz = 0; - ReturnValue_t result = faultOverrideTlv.serialize(&serPtr, &sz, rawBuf.size(), - SerializeIF::Endianness::NETWORK); - REQUIRE(faultOverrideTlv.getSerializedSize() == 3); - REQUIRE(sz == 3); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + SECTION("Other") { + MessageToUserTlv emptyTlv; + uint8_t flowLabel = 1; + FlowLabelTlv flowLabelTlv(&flowLabel, 1); - FaultHandlerOverrideTlv emptyOverrideTlv; - result = emptyOverrideTlv.deSerialize(&deserPtr, &sz, SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + FaultHandlerOverrideTlv faultOverrideTlv(cfdp::ConditionCode::FILESTORE_REJECTION, + cfdp::FaultHandlerCode::NOTICE_OF_CANCELLATION); + size_t sz = 0; + ReturnValue_t result = + faultOverrideTlv.serialize(&serPtr, &sz, rawBuf.size(), SerializeIF::Endianness::NETWORK); + REQUIRE(faultOverrideTlv.getSerializedSize() == 3); + REQUIRE(sz == 3); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - EntityId entId(cfdp::WidthInBytes::TWO_BYTES, 0x42); - EntityId emptyId; - EntityIdTlv idTlv(emptyId); - serPtr = rawBuf.data(); - result = idTlv.serialize(&serPtr, &deserSize, rawBuf.size(), - SerializeIF::Endianness::NETWORK); - cfdp::Tlv rawTlv(cfdp::TlvTypes::ENTITY_ID, rawBuf.data() + 2, 2); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - deserPtr = rawBuf.data(); - result = idTlv.deSerialize(rawTlv, SerializeIF::Endianness::NETWORK); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - } + FaultHandlerOverrideTlv emptyOverrideTlv; + result = emptyOverrideTlv.deSerialize(&deserPtr, &sz, SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + + EntityId entId(cfdp::WidthInBytes::TWO_BYTES, 0x42); + EntityId emptyId; + EntityIdTlv idTlv(emptyId); + serPtr = rawBuf.data(); + result = idTlv.serialize(&serPtr, &deserSize, rawBuf.size(), SerializeIF::Endianness::NETWORK); + cfdp::Tlv rawTlv(cfdp::TlvTypes::ENTITY_ID, rawBuf.data() + 2, 2); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + deserPtr = rawBuf.data(); + result = idTlv.deSerialize(rawTlv, SerializeIF::Endianness::NETWORK); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + } } diff --git a/tests/src/fsfw_tests/unit/container/RingBufferTest.cpp b/tests/src/fsfw_tests/unit/container/RingBufferTest.cpp index 0be8b2a7..a83fa2ac 100644 --- a/tests/src/fsfw_tests/unit/container/RingBufferTest.cpp +++ b/tests/src/fsfw_tests/unit/container/RingBufferTest.cpp @@ -1,327 +1,321 @@ -#include "fsfw_tests/unit/CatchDefinitions.h" #include #include #include -TEST_CASE("Ring Buffer Test" , "[RingBufferTest]") { - uint8_t testData[13]= {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12}; - uint8_t readBuffer[10] = {13, 13, 13, 13, 13, 13, 13, 13, 13, 13}; - SimpleRingBuffer ringBuffer(10, false, 5); +#include "fsfw_tests/unit/CatchDefinitions.h" - SECTION("Simple Test") { - REQUIRE(ringBuffer.availableWriteSpace() == 9); - REQUIRE(ringBuffer.writeData(testData, 9) == retval::CATCH_OK); - REQUIRE(ringBuffer.writeData(testData, 3) == retval::CATCH_FAILED); - REQUIRE(ringBuffer.readData(readBuffer, 5, true) == retval::CATCH_OK); - for(uint8_t i = 0; i< 5; i++) { - CHECK(readBuffer[i] == i); - } - REQUIRE(ringBuffer.availableWriteSpace() == 5); - ringBuffer.clear(); - REQUIRE(ringBuffer.availableWriteSpace() == 9); - REQUIRE(ringBuffer.writeData(testData, 4) == retval::CATCH_OK); - REQUIRE(ringBuffer.readData(readBuffer, 4, true) == retval::CATCH_OK); - for(uint8_t i = 0; i< 4; i++) { - CHECK(readBuffer[i] == i); - } - REQUIRE(ringBuffer.writeData(testData, 9) == retval::CATCH_OK); - REQUIRE(ringBuffer.readData(readBuffer, 9, true) == retval::CATCH_OK); - for(uint8_t i = 0; i< 9; i++) { - CHECK(readBuffer[i] == i); - } +TEST_CASE("Ring Buffer Test", "[RingBufferTest]") { + uint8_t testData[13] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12}; + uint8_t readBuffer[10] = {13, 13, 13, 13, 13, 13, 13, 13, 13, 13}; + SimpleRingBuffer ringBuffer(10, false, 5); - } + SECTION("Simple Test") { + REQUIRE(ringBuffer.availableWriteSpace() == 9); + REQUIRE(ringBuffer.writeData(testData, 9) == retval::CATCH_OK); + REQUIRE(ringBuffer.writeData(testData, 3) == retval::CATCH_FAILED); + REQUIRE(ringBuffer.readData(readBuffer, 5, true) == retval::CATCH_OK); + for (uint8_t i = 0; i < 5; i++) { + CHECK(readBuffer[i] == i); + } + REQUIRE(ringBuffer.availableWriteSpace() == 5); + ringBuffer.clear(); + REQUIRE(ringBuffer.availableWriteSpace() == 9); + REQUIRE(ringBuffer.writeData(testData, 4) == retval::CATCH_OK); + REQUIRE(ringBuffer.readData(readBuffer, 4, true) == retval::CATCH_OK); + for (uint8_t i = 0; i < 4; i++) { + CHECK(readBuffer[i] == i); + } + REQUIRE(ringBuffer.writeData(testData, 9) == retval::CATCH_OK); + REQUIRE(ringBuffer.readData(readBuffer, 9, true) == retval::CATCH_OK); + for (uint8_t i = 0; i < 9; i++) { + CHECK(readBuffer[i] == i); + } + } - SECTION("Get Free Element Test") { - REQUIRE(ringBuffer.availableWriteSpace() == 9); - REQUIRE(ringBuffer.writeData(testData, 8) == retval::CATCH_OK); - REQUIRE(ringBuffer.availableWriteSpace() == 1); - REQUIRE(ringBuffer.readData(readBuffer, 8, true) == retval::CATCH_OK); - REQUIRE(ringBuffer.availableWriteSpace() == 9); - uint8_t *testPtr = nullptr; - REQUIRE(ringBuffer.getFreeElement(&testPtr, 10) == retval::CATCH_FAILED); + SECTION("Get Free Element Test") { + REQUIRE(ringBuffer.availableWriteSpace() == 9); + REQUIRE(ringBuffer.writeData(testData, 8) == retval::CATCH_OK); + REQUIRE(ringBuffer.availableWriteSpace() == 1); + REQUIRE(ringBuffer.readData(readBuffer, 8, true) == retval::CATCH_OK); + REQUIRE(ringBuffer.availableWriteSpace() == 9); + uint8_t *testPtr = nullptr; + REQUIRE(ringBuffer.getFreeElement(&testPtr, 10) == retval::CATCH_FAILED); + REQUIRE(ringBuffer.writeTillWrap() == 2); + // too many excess bytes. + REQUIRE(ringBuffer.getFreeElement(&testPtr, 8) == retval::CATCH_FAILED); + REQUIRE(ringBuffer.getFreeElement(&testPtr, 5) == retval::CATCH_OK); + REQUIRE(ringBuffer.getExcessBytes() == 3); + std::memcpy(testPtr, testData, 5); + ringBuffer.confirmBytesWritten(5); + REQUIRE(ringBuffer.getAvailableReadData() == 5); + ringBuffer.readData(readBuffer, 5, true); + for (uint8_t i = 0; i < 5; i++) { + CHECK(readBuffer[i] == i); + } + } - REQUIRE(ringBuffer.writeTillWrap() == 2); - // too many excess bytes. - REQUIRE(ringBuffer.getFreeElement(&testPtr, 8) == retval::CATCH_FAILED); - REQUIRE(ringBuffer.getFreeElement(&testPtr, 5) == retval::CATCH_OK); - REQUIRE(ringBuffer.getExcessBytes() == 3); - std::memcpy(testPtr, testData, 5); - ringBuffer.confirmBytesWritten(5); - REQUIRE(ringBuffer.getAvailableReadData() == 5); - ringBuffer.readData(readBuffer, 5, true); - for(uint8_t i = 0; i< 5; i++) { - CHECK(readBuffer[i] == i); - } - } - - SECTION("Read Remaining Test") { - REQUIRE(ringBuffer.writeData(testData, 3) == retval::CATCH_OK); - REQUIRE(ringBuffer.getAvailableReadData() == 3); - REQUIRE(ringBuffer.readData(readBuffer, 5, false, false, nullptr) == retval::CATCH_FAILED); - size_t trueSize = 0; - REQUIRE(ringBuffer.readData(readBuffer, 5, false, true, &trueSize) == retval::CATCH_OK); - REQUIRE(trueSize == 3); - for(uint8_t i = 0; i< 3; i++) { - CHECK(readBuffer[i] == i); - } - trueSize = 0; - REQUIRE(ringBuffer.deleteData(5, false, &trueSize) == retval::CATCH_FAILED); - REQUIRE(trueSize == 0); - REQUIRE(ringBuffer.deleteData(5, true, &trueSize) == retval::CATCH_OK); - REQUIRE(trueSize == 3); - } + SECTION("Read Remaining Test") { + REQUIRE(ringBuffer.writeData(testData, 3) == retval::CATCH_OK); + REQUIRE(ringBuffer.getAvailableReadData() == 3); + REQUIRE(ringBuffer.readData(readBuffer, 5, false, false, nullptr) == retval::CATCH_FAILED); + size_t trueSize = 0; + REQUIRE(ringBuffer.readData(readBuffer, 5, false, true, &trueSize) == retval::CATCH_OK); + REQUIRE(trueSize == 3); + for (uint8_t i = 0; i < 3; i++) { + CHECK(readBuffer[i] == i); + } + trueSize = 0; + REQUIRE(ringBuffer.deleteData(5, false, &trueSize) == retval::CATCH_FAILED); + REQUIRE(trueSize == 0); + REQUIRE(ringBuffer.deleteData(5, true, &trueSize) == retval::CATCH_OK); + REQUIRE(trueSize == 3); + } } -TEST_CASE("Ring Buffer Test2" , "[RingBufferTest2]") { - uint8_t testData[13]= {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12}; - uint8_t readBuffer[10] = {13, 13, 13, 13, 13, 13, 13, 13, 13, 13}; - uint8_t* newBuffer = new uint8_t[15]; - SimpleRingBuffer ringBuffer(newBuffer, 10, true, 5); +TEST_CASE("Ring Buffer Test2", "[RingBufferTest2]") { + uint8_t testData[13] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12}; + uint8_t readBuffer[10] = {13, 13, 13, 13, 13, 13, 13, 13, 13, 13}; + uint8_t *newBuffer = new uint8_t[15]; + SimpleRingBuffer ringBuffer(newBuffer, 10, true, 5); - SECTION("Simple Test") { - REQUIRE(ringBuffer.availableWriteSpace() == 9); - REQUIRE(ringBuffer.writeData(testData, 9) == retval::CATCH_OK); - REQUIRE(ringBuffer.readData(readBuffer, 5, true) == retval::CATCH_OK); - for(uint8_t i = 0; i< 5; i++) { - CHECK(readBuffer[i] == i); - } - REQUIRE(ringBuffer.availableWriteSpace() == 5); - ringBuffer.clear(); - REQUIRE(ringBuffer.availableWriteSpace() == 9); - REQUIRE(ringBuffer.writeData(testData, 4) == retval::CATCH_OK); - REQUIRE(ringBuffer.readData(readBuffer, 4, true) == retval::CATCH_OK); - for(uint8_t i = 0; i< 4; i++) { - CHECK(readBuffer[i] == i); - } - REQUIRE(ringBuffer.writeData(testData, 9) == retval::CATCH_OK); - REQUIRE(ringBuffer.readData(readBuffer, 9, true) == retval::CATCH_OK); - for(uint8_t i = 0; i< 9; i++) { - CHECK(readBuffer[i] == i); - } + SECTION("Simple Test") { + REQUIRE(ringBuffer.availableWriteSpace() == 9); + REQUIRE(ringBuffer.writeData(testData, 9) == retval::CATCH_OK); + REQUIRE(ringBuffer.readData(readBuffer, 5, true) == retval::CATCH_OK); + for (uint8_t i = 0; i < 5; i++) { + CHECK(readBuffer[i] == i); + } + REQUIRE(ringBuffer.availableWriteSpace() == 5); + ringBuffer.clear(); + REQUIRE(ringBuffer.availableWriteSpace() == 9); + REQUIRE(ringBuffer.writeData(testData, 4) == retval::CATCH_OK); + REQUIRE(ringBuffer.readData(readBuffer, 4, true) == retval::CATCH_OK); + for (uint8_t i = 0; i < 4; i++) { + CHECK(readBuffer[i] == i); + } + REQUIRE(ringBuffer.writeData(testData, 9) == retval::CATCH_OK); + REQUIRE(ringBuffer.readData(readBuffer, 9, true) == retval::CATCH_OK); + for (uint8_t i = 0; i < 9; i++) { + CHECK(readBuffer[i] == i); + } + } - } + SECTION("Get Free Element Test") { + REQUIRE(ringBuffer.availableWriteSpace() == 9); + REQUIRE(ringBuffer.writeData(testData, 8) == retval::CATCH_OK); + REQUIRE(ringBuffer.availableWriteSpace() == 1); + REQUIRE(ringBuffer.readData(readBuffer, 8, true) == retval::CATCH_OK); + REQUIRE(ringBuffer.availableWriteSpace() == 9); + uint8_t *testPtr = nullptr; + REQUIRE(ringBuffer.getFreeElement(&testPtr, 10) == retval::CATCH_FAILED); - SECTION("Get Free Element Test") { - REQUIRE(ringBuffer.availableWriteSpace() == 9); - REQUIRE(ringBuffer.writeData(testData, 8) == retval::CATCH_OK); - REQUIRE(ringBuffer.availableWriteSpace() == 1); - REQUIRE(ringBuffer.readData(readBuffer, 8, true) == retval::CATCH_OK); - REQUIRE(ringBuffer.availableWriteSpace() == 9); - uint8_t *testPtr = nullptr; - REQUIRE(ringBuffer.getFreeElement(&testPtr, 10) == retval::CATCH_FAILED); + REQUIRE(ringBuffer.writeTillWrap() == 2); + // too many excess bytes. + REQUIRE(ringBuffer.getFreeElement(&testPtr, 8) == retval::CATCH_FAILED); + REQUIRE(ringBuffer.getFreeElement(&testPtr, 5) == retval::CATCH_OK); + REQUIRE(ringBuffer.getExcessBytes() == 3); + std::memcpy(testPtr, testData, 5); + ringBuffer.confirmBytesWritten(5); + REQUIRE(ringBuffer.getAvailableReadData() == 5); + ringBuffer.readData(readBuffer, 5, true); + for (uint8_t i = 0; i < 5; i++) { + CHECK(readBuffer[i] == i); + } + } + SECTION("Read Remaining Test") { + REQUIRE(ringBuffer.writeData(testData, 3) == retval::CATCH_OK); + REQUIRE(ringBuffer.getAvailableReadData() == 3); + REQUIRE(ringBuffer.readData(readBuffer, 5, false, false, nullptr) == retval::CATCH_FAILED); + size_t trueSize = 0; + REQUIRE(ringBuffer.readData(readBuffer, 5, false, true, &trueSize) == retval::CATCH_OK); + REQUIRE(trueSize == 3); + for (uint8_t i = 0; i < 3; i++) { + CHECK(readBuffer[i] == i); + } + trueSize = 0; + REQUIRE(ringBuffer.deleteData(5, false, &trueSize) == retval::CATCH_FAILED); + REQUIRE(trueSize == 0); + REQUIRE(ringBuffer.deleteData(5, true, &trueSize) == retval::CATCH_OK); + REQUIRE(trueSize == 3); + } - REQUIRE(ringBuffer.writeTillWrap() == 2); - // too many excess bytes. - REQUIRE(ringBuffer.getFreeElement(&testPtr, 8) == retval::CATCH_FAILED); - REQUIRE(ringBuffer.getFreeElement(&testPtr, 5) == retval::CATCH_OK); - REQUIRE(ringBuffer.getExcessBytes() == 3); - std::memcpy(testPtr, testData, 5); - ringBuffer.confirmBytesWritten(5); - REQUIRE(ringBuffer.getAvailableReadData() == 5); - ringBuffer.readData(readBuffer, 5, true); - for(uint8_t i = 0; i< 5; i++) { - CHECK(readBuffer[i] == i); - } - } - - SECTION("Read Remaining Test") { - REQUIRE(ringBuffer.writeData(testData, 3) == retval::CATCH_OK); - REQUIRE(ringBuffer.getAvailableReadData() == 3); - REQUIRE(ringBuffer.readData(readBuffer, 5, false, false, nullptr) == retval::CATCH_FAILED); - size_t trueSize = 0; - REQUIRE(ringBuffer.readData(readBuffer, 5, false, true, &trueSize) == retval::CATCH_OK); - REQUIRE(trueSize == 3); - for(uint8_t i = 0; i< 3; i++) { - CHECK(readBuffer[i] == i); - } - trueSize = 0; - REQUIRE(ringBuffer.deleteData(5, false, &trueSize) == retval::CATCH_FAILED); - REQUIRE(trueSize == 0); - REQUIRE(ringBuffer.deleteData(5, true, &trueSize) == retval::CATCH_OK); - REQUIRE(trueSize == 3); - } - - SECTION("Overflow"){ - REQUIRE(ringBuffer.availableWriteSpace()==9); - //Writing more than the buffer is large, technically thats allowed - //But it is senseless and has undesired impact on read call - REQUIRE(ringBuffer.writeData(testData, 13) == retval::CATCH_OK); - REQUIRE(ringBuffer.getAvailableReadData()==3); - ringBuffer.clear(); - uint8_t * ptr = nullptr; - REQUIRE(ringBuffer.getFreeElement(&ptr, 13) == retval::CATCH_OK); - REQUIRE(ptr != nullptr); - memcpy(ptr, testData, 13); - ringBuffer.confirmBytesWritten(13); - REQUIRE(ringBuffer.getAvailableReadData()==3); - REQUIRE(ringBuffer.readData(readBuffer, 3, true)== retval::CATCH_OK); - for(auto i =0;i<3;i++){ - REQUIRE(readBuffer[i] == testData[i+10]); - } - } + SECTION("Overflow") { + REQUIRE(ringBuffer.availableWriteSpace() == 9); + // Writing more than the buffer is large, technically thats allowed + // But it is senseless and has undesired impact on read call + REQUIRE(ringBuffer.writeData(testData, 13) == retval::CATCH_OK); + REQUIRE(ringBuffer.getAvailableReadData() == 3); + ringBuffer.clear(); + uint8_t *ptr = nullptr; + REQUIRE(ringBuffer.getFreeElement(&ptr, 13) == retval::CATCH_OK); + REQUIRE(ptr != nullptr); + memcpy(ptr, testData, 13); + ringBuffer.confirmBytesWritten(13); + REQUIRE(ringBuffer.getAvailableReadData() == 3); + REQUIRE(ringBuffer.readData(readBuffer, 3, true) == retval::CATCH_OK); + for (auto i = 0; i < 3; i++) { + REQUIRE(readBuffer[i] == testData[i + 10]); + } + } } -TEST_CASE("Ring Buffer Test3" , "[RingBufferTest3]") { - uint8_t testData[13]= {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12}; - uint8_t readBuffer[10] = {13, 13, 13, 13, 13, 13, 13, 13, 13, 13}; - uint8_t* newBuffer = new uint8_t[25]; - SimpleRingBuffer ringBuffer(newBuffer, 10, true, 15); +TEST_CASE("Ring Buffer Test3", "[RingBufferTest3]") { + uint8_t testData[13] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12}; + uint8_t readBuffer[10] = {13, 13, 13, 13, 13, 13, 13, 13, 13, 13}; + uint8_t *newBuffer = new uint8_t[25]; + SimpleRingBuffer ringBuffer(newBuffer, 10, true, 15); - SECTION("Simple Test") { - REQUIRE(ringBuffer.availableWriteSpace() == 9); - REQUIRE(ringBuffer.writeData(testData, 9) == retval::CATCH_OK); - REQUIRE(ringBuffer.readData(readBuffer, 5, true) == retval::CATCH_OK); - for(uint8_t i = 0; i< 5; i++) { - CHECK(readBuffer[i] == i); - } - REQUIRE(ringBuffer.availableWriteSpace() == 5); - ringBuffer.clear(); - REQUIRE(ringBuffer.availableWriteSpace() == 9); - REQUIRE(ringBuffer.writeData(testData, 4) == retval::CATCH_OK); - REQUIRE(ringBuffer.readData(readBuffer, 4, true) == retval::CATCH_OK); - for(uint8_t i = 0; i< 4; i++) { - CHECK(readBuffer[i] == i); - } - REQUIRE(ringBuffer.writeData(testData, 9) == retval::CATCH_OK); - REQUIRE(ringBuffer.readData(readBuffer, 9, true) == retval::CATCH_OK); - for(uint8_t i = 0; i< 9; i++) { - CHECK(readBuffer[i] == i); - } + SECTION("Simple Test") { + REQUIRE(ringBuffer.availableWriteSpace() == 9); + REQUIRE(ringBuffer.writeData(testData, 9) == retval::CATCH_OK); + REQUIRE(ringBuffer.readData(readBuffer, 5, true) == retval::CATCH_OK); + for (uint8_t i = 0; i < 5; i++) { + CHECK(readBuffer[i] == i); + } + REQUIRE(ringBuffer.availableWriteSpace() == 5); + ringBuffer.clear(); + REQUIRE(ringBuffer.availableWriteSpace() == 9); + REQUIRE(ringBuffer.writeData(testData, 4) == retval::CATCH_OK); + REQUIRE(ringBuffer.readData(readBuffer, 4, true) == retval::CATCH_OK); + for (uint8_t i = 0; i < 4; i++) { + CHECK(readBuffer[i] == i); + } + REQUIRE(ringBuffer.writeData(testData, 9) == retval::CATCH_OK); + REQUIRE(ringBuffer.readData(readBuffer, 9, true) == retval::CATCH_OK); + for (uint8_t i = 0; i < 9; i++) { + CHECK(readBuffer[i] == i); + } + } - } + SECTION("Get Free Element Test") { + REQUIRE(ringBuffer.availableWriteSpace() == 9); + REQUIRE(ringBuffer.writeData(testData, 8) == retval::CATCH_OK); + REQUIRE(ringBuffer.availableWriteSpace() == 1); + REQUIRE(ringBuffer.readData(readBuffer, 8, true) == retval::CATCH_OK); + REQUIRE(ringBuffer.availableWriteSpace() == 9); + uint8_t *testPtr = nullptr; + REQUIRE(ringBuffer.getFreeElement(&testPtr, 10) == retval::CATCH_OK); + REQUIRE(ringBuffer.getExcessBytes() == 8); - SECTION("Get Free Element Test") { - REQUIRE(ringBuffer.availableWriteSpace() == 9); - REQUIRE(ringBuffer.writeData(testData, 8) == retval::CATCH_OK); - REQUIRE(ringBuffer.availableWriteSpace() == 1); - REQUIRE(ringBuffer.readData(readBuffer, 8, true) == retval::CATCH_OK); - REQUIRE(ringBuffer.availableWriteSpace() == 9); - uint8_t *testPtr = nullptr; - REQUIRE(ringBuffer.getFreeElement(&testPtr, 10) == retval::CATCH_OK); - REQUIRE(ringBuffer.getExcessBytes() == 8); + REQUIRE(ringBuffer.writeTillWrap() == 2); + // too many excess bytes. + REQUIRE(ringBuffer.getFreeElement(&testPtr, 8) == retval::CATCH_FAILED); + // Less Execss bytes overwrites before + REQUIRE(ringBuffer.getFreeElement(&testPtr, 3) == retval::CATCH_OK); + REQUIRE(ringBuffer.getExcessBytes() == 1); + std::memcpy(testPtr, testData, 3); + ringBuffer.confirmBytesWritten(3); + REQUIRE(ringBuffer.getAvailableReadData() == 3); + ringBuffer.readData(readBuffer, 3, true); + for (uint8_t i = 0; i < 3; i++) { + CHECK(readBuffer[i] == i); + } + } - REQUIRE(ringBuffer.writeTillWrap() == 2); - // too many excess bytes. - REQUIRE(ringBuffer.getFreeElement(&testPtr, 8) == retval::CATCH_FAILED); - // Less Execss bytes overwrites before - REQUIRE(ringBuffer.getFreeElement(&testPtr, 3) == retval::CATCH_OK); - REQUIRE(ringBuffer.getExcessBytes() == 1); - std::memcpy(testPtr, testData, 3); - ringBuffer.confirmBytesWritten(3); - REQUIRE(ringBuffer.getAvailableReadData() == 3); - ringBuffer.readData(readBuffer, 3, true); - for(uint8_t i = 0; i< 3; i++) { - CHECK(readBuffer[i] == i); - } - } + SECTION("Read Remaining Test") { + REQUIRE(ringBuffer.writeData(testData, 3) == retval::CATCH_OK); + REQUIRE(ringBuffer.getAvailableReadData() == 3); + REQUIRE(ringBuffer.readData(readBuffer, 5, false, false, nullptr) == retval::CATCH_FAILED); + size_t trueSize = 0; + REQUIRE(ringBuffer.readData(readBuffer, 5, false, true, &trueSize) == retval::CATCH_OK); + REQUIRE(trueSize == 3); + for (uint8_t i = 0; i < 3; i++) { + CHECK(readBuffer[i] == i); + } + trueSize = 0; + REQUIRE(ringBuffer.deleteData(5, false, &trueSize) == retval::CATCH_FAILED); + REQUIRE(trueSize == 0); + REQUIRE(ringBuffer.deleteData(5, true, &trueSize) == retval::CATCH_OK); + REQUIRE(trueSize == 3); + } - SECTION("Read Remaining Test") { - REQUIRE(ringBuffer.writeData(testData, 3) == retval::CATCH_OK); - REQUIRE(ringBuffer.getAvailableReadData() == 3); - REQUIRE(ringBuffer.readData(readBuffer, 5, false, false, nullptr) == retval::CATCH_FAILED); - size_t trueSize = 0; - REQUIRE(ringBuffer.readData(readBuffer, 5, false, true, &trueSize) == retval::CATCH_OK); - REQUIRE(trueSize == 3); - for(uint8_t i = 0; i< 3; i++) { - CHECK(readBuffer[i] == i); - } - trueSize = 0; - REQUIRE(ringBuffer.deleteData(5, false, &trueSize) == retval::CATCH_FAILED); - REQUIRE(trueSize == 0); - REQUIRE(ringBuffer.deleteData(5, true, &trueSize) == retval::CATCH_OK); - REQUIRE(trueSize == 3); - } - - SECTION("Overflow"){ - REQUIRE(ringBuffer.availableWriteSpace()==9); - //Writing more than the buffer is large, technically thats allowed - //But it is senseless and has undesired impact on read call - REQUIRE(ringBuffer.writeData(testData, 13) == retval::CATCH_OK); - REQUIRE(ringBuffer.getAvailableReadData()==3); - ringBuffer.clear(); - uint8_t * ptr = nullptr; - REQUIRE(ringBuffer.getFreeElement(&ptr, 13) == retval::CATCH_OK); - REQUIRE(ptr != nullptr); - memcpy(ptr, testData, 13); - ringBuffer.confirmBytesWritten(13); - REQUIRE(ringBuffer.getAvailableReadData()==3); - REQUIRE(ringBuffer.readData(readBuffer, 3, true)== retval::CATCH_OK); - for(auto i =0;i<3;i++){ - REQUIRE(readBuffer[i] == testData[i+10]); - } - } + SECTION("Overflow") { + REQUIRE(ringBuffer.availableWriteSpace() == 9); + // Writing more than the buffer is large, technically thats allowed + // But it is senseless and has undesired impact on read call + REQUIRE(ringBuffer.writeData(testData, 13) == retval::CATCH_OK); + REQUIRE(ringBuffer.getAvailableReadData() == 3); + ringBuffer.clear(); + uint8_t *ptr = nullptr; + REQUIRE(ringBuffer.getFreeElement(&ptr, 13) == retval::CATCH_OK); + REQUIRE(ptr != nullptr); + memcpy(ptr, testData, 13); + ringBuffer.confirmBytesWritten(13); + REQUIRE(ringBuffer.getAvailableReadData() == 3); + REQUIRE(ringBuffer.readData(readBuffer, 3, true) == retval::CATCH_OK); + for (auto i = 0; i < 3; i++) { + REQUIRE(readBuffer[i] == testData[i + 10]); + } + } } -TEST_CASE("Ring Buffer Test4" , "[RingBufferTest4]") { - uint8_t testData[13]= {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12}; - uint8_t readBuffer[10] = {13, 13, 13, 13, 13, 13, 13, 13, 13, 13}; - SimpleRingBuffer ringBuffer(10, false, 15); +TEST_CASE("Ring Buffer Test4", "[RingBufferTest4]") { + uint8_t testData[13] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12}; + uint8_t readBuffer[10] = {13, 13, 13, 13, 13, 13, 13, 13, 13, 13}; + SimpleRingBuffer ringBuffer(10, false, 15); - SECTION("Simple Test") { - REQUIRE(ringBuffer.availableWriteSpace() == 9); - REQUIRE(ringBuffer.writeData(testData, 9) == retval::CATCH_OK); - REQUIRE(ringBuffer.writeData(testData, 3) == retval::CATCH_FAILED); - REQUIRE(ringBuffer.readData(readBuffer, 5, true) == retval::CATCH_OK); - for(uint8_t i = 0; i< 5; i++) { - CHECK(readBuffer[i] == i); - } - REQUIRE(ringBuffer.availableWriteSpace() == 5); - ringBuffer.clear(); - REQUIRE(ringBuffer.availableWriteSpace() == 9); - REQUIRE(ringBuffer.writeData(testData, 4) == retval::CATCH_OK); - REQUIRE(ringBuffer.readData(readBuffer, 4, true) == retval::CATCH_OK); - for(uint8_t i = 0; i< 4; i++) { - CHECK(readBuffer[i] == i); - } - REQUIRE(ringBuffer.writeData(testData, 9) == retval::CATCH_OK); - REQUIRE(ringBuffer.readData(readBuffer, 9, true) == retval::CATCH_OK); - for(uint8_t i = 0; i< 9; i++) { - CHECK(readBuffer[i] == i); - } + SECTION("Simple Test") { + REQUIRE(ringBuffer.availableWriteSpace() == 9); + REQUIRE(ringBuffer.writeData(testData, 9) == retval::CATCH_OK); + REQUIRE(ringBuffer.writeData(testData, 3) == retval::CATCH_FAILED); + REQUIRE(ringBuffer.readData(readBuffer, 5, true) == retval::CATCH_OK); + for (uint8_t i = 0; i < 5; i++) { + CHECK(readBuffer[i] == i); + } + REQUIRE(ringBuffer.availableWriteSpace() == 5); + ringBuffer.clear(); + REQUIRE(ringBuffer.availableWriteSpace() == 9); + REQUIRE(ringBuffer.writeData(testData, 4) == retval::CATCH_OK); + REQUIRE(ringBuffer.readData(readBuffer, 4, true) == retval::CATCH_OK); + for (uint8_t i = 0; i < 4; i++) { + CHECK(readBuffer[i] == i); + } + REQUIRE(ringBuffer.writeData(testData, 9) == retval::CATCH_OK); + REQUIRE(ringBuffer.readData(readBuffer, 9, true) == retval::CATCH_OK); + for (uint8_t i = 0; i < 9; i++) { + CHECK(readBuffer[i] == i); + } + } - } + SECTION("Get Free Element Test") { + REQUIRE(ringBuffer.availableWriteSpace() == 9); + REQUIRE(ringBuffer.writeData(testData, 8) == retval::CATCH_OK); + REQUIRE(ringBuffer.availableWriteSpace() == 1); + REQUIRE(ringBuffer.readData(readBuffer, 8, true) == retval::CATCH_OK); + REQUIRE(ringBuffer.availableWriteSpace() == 9); + uint8_t *testPtr = nullptr; + REQUIRE(ringBuffer.getFreeElement(&testPtr, 10) == retval::CATCH_FAILED); - SECTION("Get Free Element Test") { - REQUIRE(ringBuffer.availableWriteSpace() == 9); - REQUIRE(ringBuffer.writeData(testData, 8) == retval::CATCH_OK); - REQUIRE(ringBuffer.availableWriteSpace() == 1); - REQUIRE(ringBuffer.readData(readBuffer, 8, true) == retval::CATCH_OK); - REQUIRE(ringBuffer.availableWriteSpace() == 9); - uint8_t *testPtr = nullptr; - REQUIRE(ringBuffer.getFreeElement(&testPtr, 10) == retval::CATCH_FAILED); + REQUIRE(ringBuffer.writeTillWrap() == 2); + REQUIRE(ringBuffer.getFreeElement(&testPtr, 8) == retval::CATCH_OK); + REQUIRE(ringBuffer.getFreeElement(&testPtr, 5) == retval::CATCH_OK); + REQUIRE(ringBuffer.getExcessBytes() == 3); + std::memcpy(testPtr, testData, 5); + ringBuffer.confirmBytesWritten(5); + REQUIRE(ringBuffer.getAvailableReadData() == 5); + ringBuffer.readData(readBuffer, 5, true); + for (uint8_t i = 0; i < 5; i++) { + CHECK(readBuffer[i] == i); + } + } - - REQUIRE(ringBuffer.writeTillWrap() == 2); - REQUIRE(ringBuffer.getFreeElement(&testPtr, 8) == retval::CATCH_OK); - REQUIRE(ringBuffer.getFreeElement(&testPtr, 5) == retval::CATCH_OK); - REQUIRE(ringBuffer.getExcessBytes() == 3); - std::memcpy(testPtr, testData, 5); - ringBuffer.confirmBytesWritten(5); - REQUIRE(ringBuffer.getAvailableReadData() == 5); - ringBuffer.readData(readBuffer, 5, true); - for(uint8_t i = 0; i< 5; i++) { - CHECK(readBuffer[i] == i); - } - } - - SECTION("Read Remaining Test") { - REQUIRE(ringBuffer.writeData(testData, 3) == retval::CATCH_OK); - REQUIRE(ringBuffer.getAvailableReadData() == 3); - REQUIRE(ringBuffer.readData(readBuffer, 5, false, false, nullptr) == retval::CATCH_FAILED); - size_t trueSize = 0; - REQUIRE(ringBuffer.readData(readBuffer, 5, false, true, &trueSize) == retval::CATCH_OK); - REQUIRE(trueSize == 3); - for(uint8_t i = 0; i< 3; i++) { - CHECK(readBuffer[i] == i); - } - trueSize = 0; - REQUIRE(ringBuffer.deleteData(5, false, &trueSize) == retval::CATCH_FAILED); - REQUIRE(trueSize == 0); - REQUIRE(ringBuffer.deleteData(5, true, &trueSize) == retval::CATCH_OK); - REQUIRE(trueSize == 3); - } + SECTION("Read Remaining Test") { + REQUIRE(ringBuffer.writeData(testData, 3) == retval::CATCH_OK); + REQUIRE(ringBuffer.getAvailableReadData() == 3); + REQUIRE(ringBuffer.readData(readBuffer, 5, false, false, nullptr) == retval::CATCH_FAILED); + size_t trueSize = 0; + REQUIRE(ringBuffer.readData(readBuffer, 5, false, true, &trueSize) == retval::CATCH_OK); + REQUIRE(trueSize == 3); + for (uint8_t i = 0; i < 3; i++) { + CHECK(readBuffer[i] == i); + } + trueSize = 0; + REQUIRE(ringBuffer.deleteData(5, false, &trueSize) == retval::CATCH_FAILED); + REQUIRE(trueSize == 0); + REQUIRE(ringBuffer.deleteData(5, true, &trueSize) == retval::CATCH_OK); + REQUIRE(trueSize == 3); + } } diff --git a/tests/src/fsfw_tests/unit/container/TestArrayList.cpp b/tests/src/fsfw_tests/unit/container/TestArrayList.cpp index 9417144c..2c5a37d9 100644 --- a/tests/src/fsfw_tests/unit/container/TestArrayList.cpp +++ b/tests/src/fsfw_tests/unit/container/TestArrayList.cpp @@ -1,92 +1,92 @@ -#include "fsfw_tests/unit/CatchDefinitions.h" - #include #include #include +#include "fsfw_tests/unit/CatchDefinitions.h" + /** * @brief Array List test */ -TEST_CASE("Array List" , "[ArrayListTest]") { - //perform set-up here - ArrayList list(20); - struct TestClass{ - public: - TestClass(){}; - TestClass(uint32_t number1, uint64_t number2): - number1(number1), number2(number2){}; - uint32_t number1 = -1; - uint64_t number2 = -1; - bool operator==(const TestClass& other){ - return ((this->number1 == other.number1) and (this->number2 == other.number2)); - }; - }; - ArrayList complexList(20); - SECTION("SimpleTest") { - REQUIRE(list.maxSize()==20); - REQUIRE(list.size == 0); - REQUIRE(list.insert(10) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(list[0] == 10); - REQUIRE(list.front() != nullptr); - REQUIRE((*list.front()) == 10); - REQUIRE(list.back() != nullptr); - REQUIRE((*list.back()) == 10); - // Need to test the const version of back as well - const uint16_t* number = const_cast*>(&list)->back(); - REQUIRE(*number == 10); - list.clear(); - REQUIRE(list.size == 0); - } - SECTION("Fill and check"){ - //This is an invalid element but its not a nullptr - REQUIRE(list.back() != nullptr); - for (auto i =0; i < 20; i++){ - REQUIRE(list.insert(i) == static_cast(HasReturnvaluesIF::RETURN_OK)); - } - REQUIRE(list.insert(20) == static_cast(ArrayList::FULL)); - ArrayList::Iterator it = list.begin(); - REQUIRE((*it) == 0); - it++; - REQUIRE((*it) == 1); - it--; - REQUIRE((*it) == 0); - it++; - for(auto it2 = list.begin(); it2!=list.end(); it2++){ - if (it == it2){ - REQUIRE((*it) == (*it2)); - break; - }else{ - REQUIRE((*it2) == 0); - REQUIRE(it2 != it); - } - } - } - SECTION("Const Iterator"){ - ArrayList::Iterator it = list.begin(); - for (auto i =0; i < 10; i++){ - REQUIRE(list.insert(i) == static_cast(HasReturnvaluesIF::RETURN_OK)); - } - it++; - const uint16_t* number = it.value; - REQUIRE(*number == 1); - } +TEST_CASE("Array List", "[ArrayListTest]") { + // perform set-up here + ArrayList list(20); + struct TestClass { + public: + TestClass(){}; + TestClass(uint32_t number1, uint64_t number2) : number1(number1), number2(number2){}; + uint32_t number1 = -1; + uint64_t number2 = -1; + bool operator==(const TestClass& other) { + return ((this->number1 == other.number1) and (this->number2 == other.number2)); + }; + }; + ArrayList complexList(20); + SECTION("SimpleTest") { + REQUIRE(list.maxSize() == 20); + REQUIRE(list.size == 0); + REQUIRE(list.insert(10) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(list[0] == 10); + REQUIRE(list.front() != nullptr); + REQUIRE((*list.front()) == 10); + REQUIRE(list.back() != nullptr); + REQUIRE((*list.back()) == 10); + // Need to test the const version of back as well + const uint16_t* number = const_cast*>(&list)->back(); + REQUIRE(*number == 10); + list.clear(); + REQUIRE(list.size == 0); + } + SECTION("Fill and check") { + // This is an invalid element but its not a nullptr + REQUIRE(list.back() != nullptr); + for (auto i = 0; i < 20; i++) { + REQUIRE(list.insert(i) == static_cast(HasReturnvaluesIF::RETURN_OK)); + } + REQUIRE(list.insert(20) == static_cast(ArrayList::FULL)); + ArrayList::Iterator it = list.begin(); + REQUIRE((*it) == 0); + it++; + REQUIRE((*it) == 1); + it--; + REQUIRE((*it) == 0); + it++; + for (auto it2 = list.begin(); it2 != list.end(); it2++) { + if (it == it2) { + REQUIRE((*it) == (*it2)); + break; + } else { + REQUIRE((*it2) == 0); + REQUIRE(it2 != it); + } + } + } + SECTION("Const Iterator") { + ArrayList::Iterator it = list.begin(); + for (auto i = 0; i < 10; i++) { + REQUIRE(list.insert(i) == static_cast(HasReturnvaluesIF::RETURN_OK)); + } + it++; + const uint16_t* number = it.value; + REQUIRE(*number == 1); + } - SECTION("Const Iterator"){ - ArrayList::Iterator it = complexList.begin(); - for (auto i =0; i < 10; i++){ - REQUIRE(complexList.insert(TestClass(i, i+1)) == static_cast(HasReturnvaluesIF::RETURN_OK)); - } - it++; - const TestClass* secondTest = it.value; - bool compare = TestClass(1, 2) == *secondTest; - REQUIRE(compare); - it++; - REQUIRE(it->number1 == 2); - REQUIRE(it->number2 == 3); - const ArrayList::Iterator it4(&(complexList[2])); - REQUIRE(it4->number1 == 2); - REQUIRE((*it4).number2 == 3); - REQUIRE(complexList.remaining()==10); - } + SECTION("Const Iterator") { + ArrayList::Iterator it = complexList.begin(); + for (auto i = 0; i < 10; i++) { + REQUIRE(complexList.insert(TestClass(i, i + 1)) == + static_cast(HasReturnvaluesIF::RETURN_OK)); + } + it++; + const TestClass* secondTest = it.value; + bool compare = TestClass(1, 2) == *secondTest; + REQUIRE(compare); + it++; + REQUIRE(it->number1 == 2); + REQUIRE(it->number2 == 3); + const ArrayList::Iterator it4(&(complexList[2])); + REQUIRE(it4->number1 == 2); + REQUIRE((*it4).number2 == 3); + REQUIRE(complexList.remaining() == 10); + } } diff --git a/tests/src/fsfw_tests/unit/container/TestDynamicFifo.cpp b/tests/src/fsfw_tests/unit/container/TestDynamicFifo.cpp index a1bab3ba..540ea31e 100644 --- a/tests/src/fsfw_tests/unit/container/TestDynamicFifo.cpp +++ b/tests/src/fsfw_tests/unit/container/TestDynamicFifo.cpp @@ -1,149 +1,145 @@ -#include "fsfw_tests/unit/CatchDefinitions.h" - #include #include #include #include -TEST_CASE( "Dynamic Fifo Tests", "[TestDynamicFifo]") { - INFO("Dynamic Fifo Tests"); - struct Test{ - uint64_t number1; - uint32_t number2; - uint8_t number3; - bool operator==(struct Test& other){ - if ((other.number1 == this->number1) and - (other.number1 == this->number1) and - (other.number1 == this->number1)){ - return true; - } - return false; - } - }; - DynamicFIFO fifo(3); - std::vector list; +#include "fsfw_tests/unit/CatchDefinitions.h" - struct Test structOne({UINT64_MAX, UINT32_MAX, UINT8_MAX}); - struct Test structTwo({0, 1, 2}); - struct Test structThree({42, 43, 44}); - list.push_back(structThree); - list.push_back(structTwo); - list.push_back(structOne); - SECTION("Insert, retrieval test"){ - REQUIRE(fifo.getMaxCapacity()==3); - REQUIRE(fifo.size()==0); - REQUIRE(fifo.empty()); - REQUIRE(not fifo.full()); +TEST_CASE("Dynamic Fifo Tests", "[TestDynamicFifo]") { + INFO("Dynamic Fifo Tests"); + struct Test { + uint64_t number1; + uint32_t number2; + uint8_t number3; + bool operator==(struct Test& other) { + if ((other.number1 == this->number1) and (other.number1 == this->number1) and + (other.number1 == this->number1)) { + return true; + } + return false; + } + }; + DynamicFIFO fifo(3); + std::vector list; - REQUIRE(fifo.insert(structOne)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.insert(structTwo)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.insert(structThree)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.insert(structTwo)==static_cast(FIFOBase::FULL)); + struct Test structOne({UINT64_MAX, UINT32_MAX, UINT8_MAX}); + struct Test structTwo({0, 1, 2}); + struct Test structThree({42, 43, 44}); + list.push_back(structThree); + list.push_back(structTwo); + list.push_back(structOne); + SECTION("Insert, retrieval test") { + REQUIRE(fifo.getMaxCapacity() == 3); + REQUIRE(fifo.size() == 0); + REQUIRE(fifo.empty()); + REQUIRE(not fifo.full()); - struct Test testptr; - REQUIRE(fifo.peek(&testptr)==static_cast(HasReturnvaluesIF::RETURN_OK)); - bool equal = testptr == structOne; - REQUIRE(equal); - REQUIRE(fifo.size()==3); - REQUIRE(fifo.full()); - REQUIRE(not fifo.empty()); + REQUIRE(fifo.insert(structOne) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.insert(structTwo) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.insert(structThree) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.insert(structTwo) == static_cast(FIFOBase::FULL)); - for(size_t i=2;i<3;i--){ - testptr.number1 = 0; - testptr.number2 = 0; - testptr.number3 = 0; - REQUIRE(fifo.retrieve(&testptr)==static_cast(HasReturnvaluesIF::RETURN_OK)); - equal = testptr == list[i]; - REQUIRE(equal); - REQUIRE(fifo.size()==i); - } - testptr.number1 = 0; - testptr.number2 = 0; - testptr.number3 = 0; - REQUIRE(fifo.retrieve(&testptr)==static_cast(FIFOBase::EMPTY)); - REQUIRE(fifo.peek(&testptr)==static_cast(FIFOBase::EMPTY)); - REQUIRE(not fifo.full()); - REQUIRE(fifo.empty()); - REQUIRE(fifo.pop()==static_cast(FIFOBase::EMPTY)); + struct Test testptr; + REQUIRE(fifo.peek(&testptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); + bool equal = testptr == structOne; + REQUIRE(equal); + REQUIRE(fifo.size() == 3); + REQUIRE(fifo.full()); + REQUIRE(not fifo.empty()); - REQUIRE(fifo.insert(structOne)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.size()==1); - REQUIRE(fifo.insert(structTwo)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.size()==2); - REQUIRE(fifo.pop()==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.size()==1); - testptr.number1 = 0; - testptr.number2 = 0; - testptr.number3 = 0; - REQUIRE(fifo.peek(&testptr)==static_cast(HasReturnvaluesIF::RETURN_OK)); - equal = testptr == structTwo; - REQUIRE(equal); - REQUIRE(fifo.pop()==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.size()==0); - REQUIRE(fifo.empty()); - //struct Test* ptr = nullptr; - //REQUIRE(fifo.retrieve(ptr) == static_cast(HasReturnvaluesIF::RETURN_FAILED)); - //REQUIRE(fifo.peek(ptr) == static_cast(HasReturnvaluesIF::RETURN_FAILED)); - }; - SECTION("Copy Test"){ - REQUIRE(fifo.insert(structOne)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.insert(structTwo)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.insert(structThree)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.size()==3); - REQUIRE(fifo.full()); - REQUIRE(not fifo.empty()); + for (size_t i = 2; i < 3; i--) { + testptr.number1 = 0; + testptr.number2 = 0; + testptr.number3 = 0; + REQUIRE(fifo.retrieve(&testptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); + equal = testptr == list[i]; + REQUIRE(equal); + REQUIRE(fifo.size() == i); + } + testptr.number1 = 0; + testptr.number2 = 0; + testptr.number3 = 0; + REQUIRE(fifo.retrieve(&testptr) == static_cast(FIFOBase::EMPTY)); + REQUIRE(fifo.peek(&testptr) == static_cast(FIFOBase::EMPTY)); + REQUIRE(not fifo.full()); + REQUIRE(fifo.empty()); + REQUIRE(fifo.pop() == static_cast(FIFOBase::EMPTY)); - DynamicFIFO fifo2(fifo); - REQUIRE(fifo2.size()==3); - REQUIRE(fifo2.full()); - REQUIRE(not fifo2.empty()); + REQUIRE(fifo.insert(structOne) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.size() == 1); + REQUIRE(fifo.insert(structTwo) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.size() == 2); + REQUIRE(fifo.pop() == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.size() == 1); + testptr.number1 = 0; + testptr.number2 = 0; + testptr.number3 = 0; + REQUIRE(fifo.peek(&testptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); + equal = testptr == structTwo; + REQUIRE(equal); + REQUIRE(fifo.pop() == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.size() == 0); + REQUIRE(fifo.empty()); + // struct Test* ptr = nullptr; + // REQUIRE(fifo.retrieve(ptr) == static_cast(HasReturnvaluesIF::RETURN_FAILED)); + // REQUIRE(fifo.peek(ptr) == static_cast(HasReturnvaluesIF::RETURN_FAILED)); + }; + SECTION("Copy Test") { + REQUIRE(fifo.insert(structOne) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.insert(structTwo) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.insert(structThree) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.size() == 3); + REQUIRE(fifo.full()); + REQUIRE(not fifo.empty()); - }; + DynamicFIFO fifo2(fifo); + REQUIRE(fifo2.size() == 3); + REQUIRE(fifo2.full()); + REQUIRE(not fifo2.empty()); + }; - SECTION("Assignment Test"){ - REQUIRE(fifo.insert(structOne)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.insert(structTwo)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.insert(structThree)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.size()==3); - REQUIRE(fifo.full()); - REQUIRE(not fifo.empty()); + SECTION("Assignment Test") { + REQUIRE(fifo.insert(structOne) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.insert(structTwo) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.insert(structThree) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.size() == 3); + REQUIRE(fifo.full()); + REQUIRE(not fifo.empty()); - DynamicFIFO fifo2(6); - fifo2 = fifo; - REQUIRE(fifo2.size()==3); - REQUIRE(fifo2.full()); - REQUIRE(not fifo2.empty()); - for(size_t i=2;i<3;i--){ - struct Test testptr = {0, 0, 0}; - REQUIRE(fifo2.retrieve(&testptr)==static_cast(HasReturnvaluesIF::RETURN_OK)); - bool equal = testptr == list[i]; - REQUIRE(equal); - REQUIRE(fifo2.size()==i); - } + DynamicFIFO fifo2(6); + fifo2 = fifo; + REQUIRE(fifo2.size() == 3); + REQUIRE(fifo2.full()); + REQUIRE(not fifo2.empty()); + for (size_t i = 2; i < 3; i--) { + struct Test testptr = {0, 0, 0}; + REQUIRE(fifo2.retrieve(&testptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); + bool equal = testptr == list[i]; + REQUIRE(equal); + REQUIRE(fifo2.size() == i); + } + }; - }; - - SECTION("Assignment Test Smaller"){ - REQUIRE(fifo.insert(structOne)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.insert(structTwo)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.insert(structThree)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.size()==3); - REQUIRE(fifo.full()); - REQUIRE(not fifo.empty()); - - DynamicFIFO fifo2(2); - fifo2 = fifo; - REQUIRE(fifo2.size()==3); - REQUIRE(fifo2.full()); - REQUIRE(not fifo2.empty()); - for(size_t i=2;i<3;i--){ - struct Test testptr = {0, 0, 0}; - REQUIRE(fifo2.retrieve(&testptr)==static_cast(HasReturnvaluesIF::RETURN_OK)); - bool equal = testptr == list[i]; - REQUIRE(equal); - REQUIRE(fifo2.size()==i); - } - }; + SECTION("Assignment Test Smaller") { + REQUIRE(fifo.insert(structOne) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.insert(structTwo) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.insert(structThree) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.size() == 3); + REQUIRE(fifo.full()); + REQUIRE(not fifo.empty()); + DynamicFIFO fifo2(2); + fifo2 = fifo; + REQUIRE(fifo2.size() == 3); + REQUIRE(fifo2.full()); + REQUIRE(not fifo2.empty()); + for (size_t i = 2; i < 3; i--) { + struct Test testptr = {0, 0, 0}; + REQUIRE(fifo2.retrieve(&testptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); + bool equal = testptr == list[i]; + REQUIRE(equal); + REQUIRE(fifo2.size() == i); + } + }; }; diff --git a/tests/src/fsfw_tests/unit/container/TestFifo.cpp b/tests/src/fsfw_tests/unit/container/TestFifo.cpp index 311dd8fd..a9eb7956 100644 --- a/tests/src/fsfw_tests/unit/container/TestFifo.cpp +++ b/tests/src/fsfw_tests/unit/container/TestFifo.cpp @@ -1,138 +1,133 @@ -#include "fsfw_tests/unit/CatchDefinitions.h" - #include #include #include #include -TEST_CASE( "Static Fifo Tests", "[TestFifo]") { - INFO("Fifo Tests"); - struct Test{ - uint64_t number1; - uint32_t number2; - uint8_t number3; - bool operator==(struct Test& other){ - if ((other.number1 == this->number1) and - (other.number1 == this->number1) and - (other.number1 == this->number1)){ - return true; - } - return false; - } - }; - FIFO fifo; - std::vector list; +#include "fsfw_tests/unit/CatchDefinitions.h" - struct Test structOne({UINT64_MAX, UINT32_MAX, UINT8_MAX}); - struct Test structTwo({0, 1, 2}); - struct Test structThree({42, 43, 44}); - list.push_back(structThree); - list.push_back(structTwo); - list.push_back(structOne); - SECTION("Insert, retrieval test"){ - REQUIRE(fifo.getMaxCapacity()==3); - REQUIRE(fifo.size()==0); - REQUIRE(fifo.empty()); - REQUIRE(not fifo.full()); +TEST_CASE("Static Fifo Tests", "[TestFifo]") { + INFO("Fifo Tests"); + struct Test { + uint64_t number1; + uint32_t number2; + uint8_t number3; + bool operator==(struct Test& other) { + if ((other.number1 == this->number1) and (other.number1 == this->number1) and + (other.number1 == this->number1)) { + return true; + } + return false; + } + }; + FIFO fifo; + std::vector list; - REQUIRE(fifo.insert(structOne)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.insert(structTwo)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.insert(structThree)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.insert(structTwo)==static_cast(FIFOBase::FULL)); + struct Test structOne({UINT64_MAX, UINT32_MAX, UINT8_MAX}); + struct Test structTwo({0, 1, 2}); + struct Test structThree({42, 43, 44}); + list.push_back(structThree); + list.push_back(structTwo); + list.push_back(structOne); + SECTION("Insert, retrieval test") { + REQUIRE(fifo.getMaxCapacity() == 3); + REQUIRE(fifo.size() == 0); + REQUIRE(fifo.empty()); + REQUIRE(not fifo.full()); - struct Test testptr; - REQUIRE(fifo.peek(&testptr)==static_cast(HasReturnvaluesIF::RETURN_OK)); - bool equal = testptr == structOne; - REQUIRE(equal); - REQUIRE(fifo.size()==3); - REQUIRE(fifo.full()); - REQUIRE(not fifo.empty()); + REQUIRE(fifo.insert(structOne) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.insert(structTwo) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.insert(structThree) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.insert(structTwo) == static_cast(FIFOBase::FULL)); - for(size_t i=2;i<3;i--){ - testptr.number1 = 0; - testptr.number2 = 0; - testptr.number3 = 0; - REQUIRE(fifo.retrieve(&testptr)==static_cast(HasReturnvaluesIF::RETURN_OK)); - equal = testptr == list[i]; - REQUIRE(equal); - REQUIRE(fifo.size()==i); - } - testptr.number1 = 0; - testptr.number2 = 0; - testptr.number3 = 0; - REQUIRE(fifo.retrieve(&testptr)==static_cast(FIFOBase::EMPTY)); - REQUIRE(fifo.peek(&testptr)==static_cast(FIFOBase::EMPTY)); - REQUIRE(not fifo.full()); - REQUIRE(fifo.empty()); - REQUIRE(fifo.pop()==static_cast(FIFOBase::EMPTY)); + struct Test testptr; + REQUIRE(fifo.peek(&testptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); + bool equal = testptr == structOne; + REQUIRE(equal); + REQUIRE(fifo.size() == 3); + REQUIRE(fifo.full()); + REQUIRE(not fifo.empty()); - REQUIRE(fifo.insert(structOne)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.size()==1); - REQUIRE(fifo.insert(structTwo)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.size()==2); - REQUIRE(fifo.pop()==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.size()==1); - testptr.number1 = 0; - testptr.number2 = 0; - testptr.number3 = 0; + for (size_t i = 2; i < 3; i--) { + testptr.number1 = 0; + testptr.number2 = 0; + testptr.number3 = 0; + REQUIRE(fifo.retrieve(&testptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); + equal = testptr == list[i]; + REQUIRE(equal); + REQUIRE(fifo.size() == i); + } + testptr.number1 = 0; + testptr.number2 = 0; + testptr.number3 = 0; + REQUIRE(fifo.retrieve(&testptr) == static_cast(FIFOBase::EMPTY)); + REQUIRE(fifo.peek(&testptr) == static_cast(FIFOBase::EMPTY)); + REQUIRE(not fifo.full()); + REQUIRE(fifo.empty()); + REQUIRE(fifo.pop() == static_cast(FIFOBase::EMPTY)); - // Test that retrieve and peek will not cause a nullptr dereference - struct Test* ptr = nullptr; - REQUIRE(fifo.retrieve(ptr) == static_cast(HasReturnvaluesIF::RETURN_FAILED)); - REQUIRE(fifo.peek(ptr) == static_cast(HasReturnvaluesIF::RETURN_FAILED)); + REQUIRE(fifo.insert(structOne) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.size() == 1); + REQUIRE(fifo.insert(structTwo) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.size() == 2); + REQUIRE(fifo.pop() == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.size() == 1); + testptr.number1 = 0; + testptr.number2 = 0; + testptr.number3 = 0; + // Test that retrieve and peek will not cause a nullptr dereference + struct Test* ptr = nullptr; + REQUIRE(fifo.retrieve(ptr) == static_cast(HasReturnvaluesIF::RETURN_FAILED)); + REQUIRE(fifo.peek(ptr) == static_cast(HasReturnvaluesIF::RETURN_FAILED)); - REQUIRE(fifo.peek(&testptr)==static_cast(HasReturnvaluesIF::RETURN_OK)); - equal = testptr == structTwo; - REQUIRE(equal); - REQUIRE(fifo.pop()==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.size()==0); - REQUIRE(fifo.empty()); + REQUIRE(fifo.peek(&testptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); + equal = testptr == structTwo; + REQUIRE(equal); + REQUIRE(fifo.pop() == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.size() == 0); + REQUIRE(fifo.empty()); + }; + SECTION("Copy Test") { + REQUIRE(fifo.insert(structOne) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.insert(structTwo) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.insert(structThree) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.size() == 3); + REQUIRE(fifo.full()); + REQUIRE(not fifo.empty()); + FIFO fifo2(fifo); + REQUIRE(fifo2.size() == 3); + REQUIRE(fifo2.full()); + REQUIRE(not fifo2.empty()); + for (size_t i = 2; i < 3; i--) { + struct Test testptr = {0, 0, 0}; + REQUIRE(fifo2.retrieve(&testptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); + bool equal = testptr == list[i]; + REQUIRE(equal); + REQUIRE(fifo2.size() == i); + } + }; - }; - SECTION("Copy Test"){ - REQUIRE(fifo.insert(structOne)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.insert(structTwo)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.insert(structThree)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.size()==3); - REQUIRE(fifo.full()); - REQUIRE(not fifo.empty()); + SECTION("Assignment Test") { + REQUIRE(fifo.insert(structOne) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.insert(structTwo) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.insert(structThree) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(fifo.size() == 3); + REQUIRE(fifo.full()); + REQUIRE(not fifo.empty()); - FIFO fifo2(fifo); - REQUIRE(fifo2.size()==3); - REQUIRE(fifo2.full()); - REQUIRE(not fifo2.empty()); - for(size_t i=2;i<3;i--){ - struct Test testptr = {0, 0, 0}; - REQUIRE(fifo2.retrieve(&testptr)==static_cast(HasReturnvaluesIF::RETURN_OK)); - bool equal = testptr == list[i]; - REQUIRE(equal); - REQUIRE(fifo2.size()==i); - } - - }; - - SECTION("Assignment Test"){ - REQUIRE(fifo.insert(structOne)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.insert(structTwo)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.insert(structThree)==static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(fifo.size()==3); - REQUIRE(fifo.full()); - REQUIRE(not fifo.empty()); - - FIFO fifo2; - fifo2 = fifo; - REQUIRE(fifo2.size()==3); - REQUIRE(fifo2.full()); - REQUIRE(not fifo2.empty()); - for(size_t i=2;i<3;i--){ - struct Test testptr = {0, 0, 0}; - REQUIRE(fifo2.retrieve(&testptr)==static_cast(HasReturnvaluesIF::RETURN_OK)); - bool equal = testptr == list[i]; - REQUIRE(equal); - REQUIRE(fifo2.size()==i); - } - }; + FIFO fifo2; + fifo2 = fifo; + REQUIRE(fifo2.size() == 3); + REQUIRE(fifo2.full()); + REQUIRE(not fifo2.empty()); + for (size_t i = 2; i < 3; i--) { + struct Test testptr = {0, 0, 0}; + REQUIRE(fifo2.retrieve(&testptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); + bool equal = testptr == list[i]; + REQUIRE(equal); + REQUIRE(fifo2.size() == i); + } + }; }; diff --git a/tests/src/fsfw_tests/unit/container/TestFixedArrayList.cpp b/tests/src/fsfw_tests/unit/container/TestFixedArrayList.cpp index ed597f73..42ae01d5 100644 --- a/tests/src/fsfw_tests/unit/container/TestFixedArrayList.cpp +++ b/tests/src/fsfw_tests/unit/container/TestFixedArrayList.cpp @@ -1,42 +1,38 @@ -#include "fsfw_tests/unit/CatchDefinitions.h" - #include #include #include +#include "fsfw_tests/unit/CatchDefinitions.h" -TEST_CASE( "FixedArrayList Tests", "[TestFixedArrayList]") { - INFO("FixedArrayList Tests"); - using testList = FixedArrayList; - testList list; - REQUIRE(list.size==0); - REQUIRE(list.insert(10) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(list.size==1); - REQUIRE(list.maxSize()==260); - SECTION("Copy Constructor"){ - testList list2(list); - REQUIRE(list2.size==1); - REQUIRE(list2[0] == 10); - REQUIRE(list.maxSize()==260); - }; - SECTION("Assignment copy"){ - testList list2; - REQUIRE(list2.size==0); - list2 = list; - REQUIRE(list2.size==1); - REQUIRE(list2[0] == 10); - REQUIRE(list.maxSize()==260); - }; - SECTION("Fill"){ - for(auto i=1;i<260;i++){ - REQUIRE(list.insert(i) == static_cast(HasReturnvaluesIF::RETURN_OK)); - } - REQUIRE(list.insert(260) == static_cast(ArrayList::FULL)); - list.clear(); - REQUIRE(list.size == 0); - } +TEST_CASE("FixedArrayList Tests", "[TestFixedArrayList]") { + INFO("FixedArrayList Tests"); + using testList = FixedArrayList; + testList list; + REQUIRE(list.size == 0); + REQUIRE(list.insert(10) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(list.size == 1); + REQUIRE(list.maxSize() == 260); + SECTION("Copy Constructor") { + testList list2(list); + REQUIRE(list2.size == 1); + REQUIRE(list2[0] == 10); + REQUIRE(list.maxSize() == 260); + }; + SECTION("Assignment copy") { + testList list2; + REQUIRE(list2.size == 0); + list2 = list; + REQUIRE(list2.size == 1); + REQUIRE(list2[0] == 10); + REQUIRE(list.maxSize() == 260); + }; + SECTION("Fill") { + for (auto i = 1; i < 260; i++) { + REQUIRE(list.insert(i) == static_cast(HasReturnvaluesIF::RETURN_OK)); + } + REQUIRE(list.insert(260) == static_cast(ArrayList::FULL)); + list.clear(); + REQUIRE(list.size == 0); + } } - - - diff --git a/tests/src/fsfw_tests/unit/container/TestFixedMap.cpp b/tests/src/fsfw_tests/unit/container/TestFixedMap.cpp index 488418b9..4c3cad1e 100644 --- a/tests/src/fsfw_tests/unit/container/TestFixedMap.cpp +++ b/tests/src/fsfw_tests/unit/container/TestFixedMap.cpp @@ -1,173 +1,166 @@ -#include "fsfw_tests/unit/CatchDefinitions.h" - #include #include #include +#include "fsfw_tests/unit/CatchDefinitions.h" + template class FixedMap; -TEST_CASE( "FixedMap Tests", "[TestFixedMap]") { - INFO("FixedMap Tests"); +TEST_CASE("FixedMap Tests", "[TestFixedMap]") { + INFO("FixedMap Tests"); - FixedMap map(30); - REQUIRE(map.size() == 0); - REQUIRE(map.maxSize() == 30); - REQUIRE(map.getSerializedSize() == sizeof(uint32_t)); - REQUIRE(map.empty()); - REQUIRE(not map.full()); + FixedMap map(30); + REQUIRE(map.size() == 0); + REQUIRE(map.maxSize() == 30); + REQUIRE(map.getSerializedSize() == sizeof(uint32_t)); + REQUIRE(map.empty()); + REQUIRE(not map.full()); - SECTION("Fill and erase"){ - for (uint16_t i=0;i<30;i++){ - REQUIRE(map.insert(std::make_pair(i, i+1))== static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(map.exists(i) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(map.find(i)->second==i+1); - REQUIRE(not map.empty()); - } - REQUIRE(map.insert(0, 0) == static_cast(FixedMap::KEY_ALREADY_EXISTS)); - REQUIRE(map.insert(31, 0) == static_cast(FixedMap::MAP_FULL)); - REQUIRE(map.exists(31) == static_cast(FixedMap::KEY_DOES_NOT_EXIST)); - REQUIRE(map.size() == 30); - REQUIRE(map.full()); - { - uint16_t* ptr; - REQUIRE(map.find(5,&ptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(*ptr == 6); - REQUIRE(*(map.findValue(6)) == 7); - REQUIRE(map.find(31,&ptr) == static_cast(FixedMap::KEY_DOES_NOT_EXIST)); - } + SECTION("Fill and erase") { + for (uint16_t i = 0; i < 30; i++) { + REQUIRE(map.insert(std::make_pair(i, i + 1)) == + static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(map.exists(i) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(map.find(i)->second == i + 1); + REQUIRE(not map.empty()); + } + REQUIRE(map.insert(0, 0) == static_cast(FixedMap::KEY_ALREADY_EXISTS)); + REQUIRE(map.insert(31, 0) == static_cast(FixedMap::MAP_FULL)); + REQUIRE(map.exists(31) == static_cast(FixedMap::KEY_DOES_NOT_EXIST)); + REQUIRE(map.size() == 30); + REQUIRE(map.full()); + { + uint16_t* ptr; + REQUIRE(map.find(5, &ptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(*ptr == 6); + REQUIRE(*(map.findValue(6)) == 7); + REQUIRE(map.find(31, &ptr) == + static_cast(FixedMap::KEY_DOES_NOT_EXIST)); + } - REQUIRE(map.getSerializedSize() == (sizeof(uint32_t)+ 30*(sizeof(uint32_t) + sizeof(uint16_t)))); - REQUIRE(map.erase(2) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(map.erase(31) == static_cast(FixedMap::KEY_DOES_NOT_EXIST)); - REQUIRE(map.exists(2) == static_cast(FixedMap::KEY_DOES_NOT_EXIST)); - REQUIRE(map.size() == 29); + REQUIRE(map.getSerializedSize() == + (sizeof(uint32_t) + 30 * (sizeof(uint32_t) + sizeof(uint16_t)))); + REQUIRE(map.erase(2) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(map.erase(31) == static_cast(FixedMap::KEY_DOES_NOT_EXIST)); + REQUIRE(map.exists(2) == static_cast(FixedMap::KEY_DOES_NOT_EXIST)); + REQUIRE(map.size() == 29); - for (auto element: map){ - if (element.first == 5){ - REQUIRE(element.second == 6); - } - } + for (auto element : map) { + if (element.first == 5) { + REQUIRE(element.second == 6); + } + } - for (FixedMap::Iterator it = map.begin(); it != map.end(); it++){ - REQUIRE(it->second == it->first + 1); - REQUIRE((*it).second == (*it).first + 1); - it->second = it->second + 1; - REQUIRE(it->second == it->first + 2); - } + for (FixedMap::Iterator it = map.begin(); it != map.end(); it++) { + REQUIRE(it->second == it->first + 1); + REQUIRE((*it).second == (*it).first + 1); + it->second = it->second + 1; + REQUIRE(it->second == it->first + 2); + } - for (FixedMap::Iterator it = map.begin(); it != map.end(); it++){ - REQUIRE(map.erase(&it) == static_cast(HasReturnvaluesIF::RETURN_OK)); - } + for (FixedMap::Iterator it = map.begin(); it != map.end(); it++) { + REQUIRE(map.erase(&it) == static_cast(HasReturnvaluesIF::RETURN_OK)); + } - REQUIRE(map.size() == 0); + REQUIRE(map.size() == 0); - for (FixedMap::Iterator it = map.begin(); it != map.end(); it++){ - // This line should never executed if begin and end is correct - FAIL("Should never be reached, Iterators invalid"); - } - }; + for (FixedMap::Iterator it = map.begin(); it != map.end(); it++) { + // This line should never executed if begin and end is correct + FAIL("Should never be reached, Iterators invalid"); + } + }; - SECTION("Insert variants"){ - FixedMap::Iterator it = map.end(); - REQUIRE(map.insert(36, 37, &it) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(it->first == 36); - REQUIRE(it->second == 37); - REQUIRE(map.size() == 1); - REQUIRE(map.insert(37, 38, nullptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(map.find(37)->second == 38); - REQUIRE(map.size() == 2); - REQUIRE(map.insert(37, 24, nullptr) == static_cast(FixedMap::KEY_ALREADY_EXISTS)); - REQUIRE(map.find(37)->second != 24); - REQUIRE(map.size() == 2); - }; - SECTION("Serialize and DeSerialize") { - REQUIRE(map.insert(36, 37, nullptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(map.insert(37, 38, nullptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); - uint8_t buffer[sizeof(uint32_t) - + 2 * (sizeof(uint32_t) + sizeof(uint16_t))]; - REQUIRE( - map.getSerializedSize() - == (sizeof(uint32_t) - + 2 * (sizeof(uint32_t) + sizeof(uint16_t)))); - uint8_t *loc_ptr = buffer; - size_t size = 0; - REQUIRE( - map.serialize(&loc_ptr, &size, 10, SerializeIF::Endianness::BIG) - == static_cast(SerializeIF::BUFFER_TOO_SHORT)); - loc_ptr = buffer; - size = 0; - REQUIRE( - map.serialize(&loc_ptr, &size, - sizeof(uint32_t) - + 2 * (sizeof(uint32_t) + sizeof(uint16_t)), - SerializeIF::Endianness::BIG) - == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(size == 16); + SECTION("Insert variants") { + FixedMap::Iterator it = map.end(); + REQUIRE(map.insert(36, 37, &it) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(it->first == 36); + REQUIRE(it->second == 37); + REQUIRE(map.size() == 1); + REQUIRE(map.insert(37, 38, nullptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(map.find(37)->second == 38); + REQUIRE(map.size() == 2); + REQUIRE(map.insert(37, 24, nullptr) == + static_cast(FixedMap::KEY_ALREADY_EXISTS)); + REQUIRE(map.find(37)->second != 24); + REQUIRE(map.size() == 2); + }; + SECTION("Serialize and DeSerialize") { + REQUIRE(map.insert(36, 37, nullptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(map.insert(37, 38, nullptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); + uint8_t buffer[sizeof(uint32_t) + 2 * (sizeof(uint32_t) + sizeof(uint16_t))]; + REQUIRE(map.getSerializedSize() == + (sizeof(uint32_t) + 2 * (sizeof(uint32_t) + sizeof(uint16_t)))); + uint8_t* loc_ptr = buffer; + size_t size = 0; + REQUIRE(map.serialize(&loc_ptr, &size, 10, SerializeIF::Endianness::BIG) == + static_cast(SerializeIF::BUFFER_TOO_SHORT)); + loc_ptr = buffer; + size = 0; + REQUIRE(map.serialize( + &loc_ptr, &size, sizeof(uint32_t) + 2 * (sizeof(uint32_t) + sizeof(uint16_t)), + SerializeIF::Endianness::BIG) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(size == 16); - uint32_t internal_size = 0; - const uint8_t *ptr2 = buffer; - REQUIRE( - SerializeAdapter::deSerialize(&internal_size, &ptr2, &size, - SerializeIF::Endianness::BIG) - == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(internal_size == 2); - for (uint8_t i = 36; i < 38; i++) { - uint32_t first_element = 0; - REQUIRE( - SerializeAdapter::deSerialize(&first_element, &ptr2, &size, - SerializeIF::Endianness::BIG) - == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(first_element == i); - uint16_t second_element = 0; - REQUIRE( - SerializeAdapter::deSerialize(&second_element, &ptr2, &size, - SerializeIF::Endianness::BIG) - == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(second_element == i + 1); - } - REQUIRE(size == 0); - map.clear(); - const uint8_t* constPtr = buffer; - size = 16; - REQUIRE(map.size() == 0); - REQUIRE(map.deSerialize(&constPtr, &size, - SerializeIF::Endianness::BIG) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(map.size() == 2); - REQUIRE(map.find(36)->second == 37); - for(auto& element: map){ - REQUIRE((element.first+1) == element.second); - } - }; + uint32_t internal_size = 0; + const uint8_t* ptr2 = buffer; + REQUIRE( + SerializeAdapter::deSerialize(&internal_size, &ptr2, &size, SerializeIF::Endianness::BIG) == + static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(internal_size == 2); + for (uint8_t i = 36; i < 38; i++) { + uint32_t first_element = 0; + REQUIRE(SerializeAdapter::deSerialize(&first_element, &ptr2, &size, + SerializeIF::Endianness::BIG) == + static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(first_element == i); + uint16_t second_element = 0; + REQUIRE(SerializeAdapter::deSerialize(&second_element, &ptr2, &size, + SerializeIF::Endianness::BIG) == + static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(second_element == i + 1); + } + REQUIRE(size == 0); + map.clear(); + const uint8_t* constPtr = buffer; + size = 16; + REQUIRE(map.size() == 0); + REQUIRE(map.deSerialize(&constPtr, &size, SerializeIF::Endianness::BIG) == + static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(map.size() == 2); + REQUIRE(map.find(36)->second == 37); + for (auto& element : map) { + REQUIRE((element.first + 1) == element.second); + } + }; - - SECTION("Failed erase and deSerialize"){ - FixedMap::Iterator it; - std::pair pair = std::make_pair(44, 43); - it = FixedMap::Iterator(&pair); - REQUIRE(map.erase(&it) == static_cast(FixedMap::KEY_DOES_NOT_EXIST)); - REQUIRE(map.find(45) == map.end()); - size_t toLargeMap = 100; - const uint8_t* ptr = reinterpret_cast(&toLargeMap); - size_t size = sizeof(size_t); - REQUIRE(map.deSerialize(&ptr, &size, SerializeIF::Endianness::BIG) == - static_cast(SerializeIF::TOO_MANY_ELEMENTS)); - }; - SECTION("Little Endianess"){ - map.clear(); - map.insert(10,20, nullptr); - uint8_t newBuffer[sizeof(uint32_t)+ 1*(sizeof(uint32_t) + sizeof(uint16_t))]; - uint8_t* ptr = newBuffer; - size_t size = 0; - size_t max_size = sizeof(uint32_t)+ 1*(sizeof(uint32_t) + sizeof(uint16_t)); - REQUIRE(map.serialize(&ptr, &size, max_size, - SerializeIF::Endianness::LITTLE) == static_cast(HasReturnvaluesIF::RETURN_OK)); - map.clear(); - REQUIRE(map.size()==0); - const uint8_t* ptr2 = newBuffer; - REQUIRE(map.deSerialize(&ptr2, &size, - SerializeIF::Endianness::LITTLE) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(map.size()==1); - REQUIRE(map.find(10)->second == 20); - }; + SECTION("Failed erase and deSerialize") { + FixedMap::Iterator it; + std::pair pair = std::make_pair(44, 43); + it = FixedMap::Iterator(&pair); + REQUIRE(map.erase(&it) == static_cast(FixedMap::KEY_DOES_NOT_EXIST)); + REQUIRE(map.find(45) == map.end()); + size_t toLargeMap = 100; + const uint8_t* ptr = reinterpret_cast(&toLargeMap); + size_t size = sizeof(size_t); + REQUIRE(map.deSerialize(&ptr, &size, SerializeIF::Endianness::BIG) == + static_cast(SerializeIF::TOO_MANY_ELEMENTS)); + }; + SECTION("Little Endianess") { + map.clear(); + map.insert(10, 20, nullptr); + uint8_t newBuffer[sizeof(uint32_t) + 1 * (sizeof(uint32_t) + sizeof(uint16_t))]; + uint8_t* ptr = newBuffer; + size_t size = 0; + size_t max_size = sizeof(uint32_t) + 1 * (sizeof(uint32_t) + sizeof(uint16_t)); + REQUIRE(map.serialize(&ptr, &size, max_size, SerializeIF::Endianness::LITTLE) == + static_cast(HasReturnvaluesIF::RETURN_OK)); + map.clear(); + REQUIRE(map.size() == 0); + const uint8_t* ptr2 = newBuffer; + REQUIRE(map.deSerialize(&ptr2, &size, SerializeIF::Endianness::LITTLE) == + static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(map.size() == 1); + REQUIRE(map.find(10)->second == 20); + }; } diff --git a/tests/src/fsfw_tests/unit/container/TestFixedOrderedMultimap.cpp b/tests/src/fsfw_tests/unit/container/TestFixedOrderedMultimap.cpp index 23d91744..7dd63b34 100644 --- a/tests/src/fsfw_tests/unit/container/TestFixedOrderedMultimap.cpp +++ b/tests/src/fsfw_tests/unit/container/TestFixedOrderedMultimap.cpp @@ -1,204 +1,221 @@ -#include "fsfw_tests/unit/CatchDefinitions.h" - #include #include #include -TEST_CASE( "FixedOrderedMultimap Tests", "[TestFixedOrderedMultimap]") { - INFO("FixedOrderedMultimap Tests"); +#include "fsfw_tests/unit/CatchDefinitions.h" - FixedOrderedMultimap map(30); - REQUIRE(map.size() == 0); - REQUIRE(map.maxSize() == 30); +TEST_CASE("FixedOrderedMultimap Tests", "[TestFixedOrderedMultimap]") { + INFO("FixedOrderedMultimap Tests"); - SECTION("Test insert, find, exists"){ - for (uint16_t i=0;i<30;i++){ - REQUIRE(map.insert(std::make_pair(i, i+1))== static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(map.exists(i) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(map.find(i)->second==i+1); - } - REQUIRE(map.insert(0, 0) == static_cast(FixedOrderedMultimap::MAP_FULL)); - REQUIRE(map.exists(31) == static_cast(FixedOrderedMultimap::KEY_DOES_NOT_EXIST)); - REQUIRE(map.size() == 30); - { - uint16_t* ptr; - REQUIRE(map.find(5,&ptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(*ptr == 6); - REQUIRE(map.find(31,&ptr) == static_cast(FixedOrderedMultimap::KEY_DOES_NOT_EXIST)); - } - REQUIRE(map.erase(2) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(map.erase(31) == static_cast(FixedOrderedMultimap::KEY_DOES_NOT_EXIST)); - REQUIRE(map.exists(2) == static_cast(FixedOrderedMultimap::KEY_DOES_NOT_EXIST)); - REQUIRE(map.size() == 29); + FixedOrderedMultimap map(30); + REQUIRE(map.size() == 0); + REQUIRE(map.maxSize() == 30); - for (auto element: map){ - if (element.first == 5){ - REQUIRE(element.second == 6); - } - } + SECTION("Test insert, find, exists") { + for (uint16_t i = 0; i < 30; i++) { + REQUIRE(map.insert(std::make_pair(i, i + 1)) == + static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(map.exists(i) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(map.find(i)->second == i + 1); + } + REQUIRE(map.insert(0, 0) == + static_cast(FixedOrderedMultimap::MAP_FULL)); + REQUIRE(map.exists(31) == + static_cast(FixedOrderedMultimap::KEY_DOES_NOT_EXIST)); + REQUIRE(map.size() == 30); + { + uint16_t* ptr; + REQUIRE(map.find(5, &ptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(*ptr == 6); + REQUIRE(map.find(31, &ptr) == + static_cast(FixedOrderedMultimap::KEY_DOES_NOT_EXIST)); + } + REQUIRE(map.erase(2) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(map.erase(31) == + static_cast(FixedOrderedMultimap::KEY_DOES_NOT_EXIST)); + REQUIRE(map.exists(2) == + static_cast(FixedOrderedMultimap::KEY_DOES_NOT_EXIST)); + REQUIRE(map.size() == 29); - for (FixedOrderedMultimap::Iterator it = map.begin(); it != map.end(); it++){ - REQUIRE(it->second == it->first + 1); - REQUIRE((*it).second == (*it).first + 1); - it->second = it->second + 1; - REQUIRE(it->second == it->first + 2); - } + for (auto element : map) { + if (element.first == 5) { + REQUIRE(element.second == 6); + } + } - { - FixedOrderedMultimap::Iterator it = map.begin(); - while(it != map.end()){ - REQUIRE(map.erase(&it) == static_cast(HasReturnvaluesIF::RETURN_OK)); - } - REQUIRE(map.size() == 0); - } + for (FixedOrderedMultimap::Iterator it = map.begin(); it != map.end(); + it++) { + REQUIRE(it->second == it->first + 1); + REQUIRE((*it).second == (*it).first + 1); + it->second = it->second + 1; + REQUIRE(it->second == it->first + 2); + } - for (FixedOrderedMultimap::Iterator it = map.begin(); it != map.end(); it++){ - // This line should never executed if begin and end is correct - FAIL("Should never be reached, Iterators invalid"); - } - }; + { + FixedOrderedMultimap::Iterator it = map.begin(); + while (it != map.end()) { + REQUIRE(map.erase(&it) == static_cast(HasReturnvaluesIF::RETURN_OK)); + } + REQUIRE(map.size() == 0); + } - SECTION("Test different insert variants") - { - FixedOrderedMultimap::Iterator it = map.end(); - REQUIRE(map.insert(36, 37, &it) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(it->first == 36); - REQUIRE(it->second == 37); - REQUIRE(map.size() == 1); - REQUIRE(map.insert(37, 38, nullptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(map.find(37)->second == 38); - REQUIRE(map.size() == 2); - REQUIRE(map.insert(37, 24, nullptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(map.find(37)->second == 38); - REQUIRE(map.insert(0, 1, nullptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(map.find(0)->second == 1); - REQUIRE(map.size() == 4); - map.clear(); - REQUIRE(map.size() == 0); - } - SECTION("Test different erase and find with no entries"){ - FixedOrderedMultimap::Iterator it; - it = map.end(); - REQUIRE(map.erase(&it) == static_cast(FixedOrderedMultimap::KEY_DOES_NOT_EXIST)); - REQUIRE(map.find(1)== map.end()); - } + for (FixedOrderedMultimap::Iterator it = map.begin(); it != map.end(); + it++) { + // This line should never executed if begin and end is correct + FAIL("Should never be reached, Iterators invalid"); + } + }; + + SECTION("Test different insert variants") { + FixedOrderedMultimap::Iterator it = map.end(); + REQUIRE(map.insert(36, 37, &it) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(it->first == 36); + REQUIRE(it->second == 37); + REQUIRE(map.size() == 1); + REQUIRE(map.insert(37, 38, nullptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(map.find(37)->second == 38); + REQUIRE(map.size() == 2); + REQUIRE(map.insert(37, 24, nullptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(map.find(37)->second == 38); + REQUIRE(map.insert(0, 1, nullptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(map.find(0)->second == 1); + REQUIRE(map.size() == 4); + map.clear(); + REQUIRE(map.size() == 0); + } + SECTION("Test different erase and find with no entries") { + FixedOrderedMultimap::Iterator it; + it = map.end(); + REQUIRE(map.erase(&it) == + static_cast(FixedOrderedMultimap::KEY_DOES_NOT_EXIST)); + REQUIRE(map.find(1) == map.end()); + } } -TEST_CASE( "FixedOrderedMultimap Non Trivial Type", "[TestFixedOrderedMultimapNonTrivial]") { - INFO("FixedOrderedMultimap Non Trivial Type"); +TEST_CASE("FixedOrderedMultimap Non Trivial Type", "[TestFixedOrderedMultimapNonTrivial]") { + INFO("FixedOrderedMultimap Non Trivial Type"); - class TestClass{ - public: - TestClass(){}; - TestClass(uint32_t number1, uint64_t number2): - number1(number1),number2(number2){}; - ~TestClass(){}; + class TestClass { + public: + TestClass(){}; + TestClass(uint32_t number1, uint64_t number2) : number1(number1), number2(number2){}; + ~TestClass(){}; - bool operator==(const TestClass& lhs){ - return ((this->number1 == lhs.number1) and (this->number2 == lhs.number2)); - } - bool operator!=(const TestClass& lhs){ - return not(this->operator ==(lhs)); - } + bool operator==(const TestClass& lhs) { + return ((this->number1 == lhs.number1) and (this->number2 == lhs.number2)); + } + bool operator!=(const TestClass& lhs) { return not(this->operator==(lhs)); } - TestClass(const TestClass& other){ - this->number1 = other.number1; - this->number2 = other.number2; - }; - TestClass& operator=(const TestClass& other){ - this->number1 = other.number1; - this->number2 = other.number2; - return *this; - }; + TestClass(const TestClass& other) { + this->number1 = other.number1; + this->number2 = other.number2; + }; + TestClass& operator=(const TestClass& other) { + this->number1 = other.number1; + this->number2 = other.number2; + return *this; + }; - private: - uint32_t number1 = 0; - uint64_t number2 = 5; - }; - FixedOrderedMultimap map(30); - REQUIRE(map.size() == 0); - REQUIRE(map.maxSize() == 30); + private: + uint32_t number1 = 0; + uint64_t number2 = 5; + }; + FixedOrderedMultimap map(30); + REQUIRE(map.size() == 0); + REQUIRE(map.maxSize() == 30); - SECTION("Test insert, find, exists"){ - for (uint16_t i=0;i<30;i++){ - REQUIRE(map.insert(std::make_pair(i, TestClass(i+1,i)))== static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(map.exists(i) == static_cast(HasReturnvaluesIF::RETURN_OK)); - bool compare = map.find(i)->second == TestClass(i+1,i); - REQUIRE(compare); - } - REQUIRE(map.insert(0, TestClass()) == static_cast(FixedOrderedMultimap::MAP_FULL)); - REQUIRE(map.exists(31) == static_cast(FixedOrderedMultimap::KEY_DOES_NOT_EXIST)); - REQUIRE(map.size() == 30); - { - TestClass* ptr = nullptr; - REQUIRE(map.find(5,&ptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); - bool compare = *ptr == TestClass(6, 5); - REQUIRE(compare); - REQUIRE(map.find(31,&ptr) == static_cast(FixedOrderedMultimap::KEY_DOES_NOT_EXIST)); - } - REQUIRE(map.erase(2) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(map.erase(31) == static_cast(FixedOrderedMultimap::KEY_DOES_NOT_EXIST)); - REQUIRE(map.exists(2) == static_cast(FixedOrderedMultimap::KEY_DOES_NOT_EXIST)); - REQUIRE(map.size() == 29); + SECTION("Test insert, find, exists") { + for (uint16_t i = 0; i < 30; i++) { + REQUIRE(map.insert(std::make_pair(i, TestClass(i + 1, i))) == + static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(map.exists(i) == static_cast(HasReturnvaluesIF::RETURN_OK)); + bool compare = map.find(i)->second == TestClass(i + 1, i); + REQUIRE(compare); + } + REQUIRE(map.insert(0, TestClass()) == + static_cast(FixedOrderedMultimap::MAP_FULL)); + REQUIRE(map.exists(31) == + static_cast(FixedOrderedMultimap::KEY_DOES_NOT_EXIST)); + REQUIRE(map.size() == 30); + { + TestClass* ptr = nullptr; + REQUIRE(map.find(5, &ptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); + bool compare = *ptr == TestClass(6, 5); + REQUIRE(compare); + REQUIRE(map.find(31, &ptr) == + static_cast(FixedOrderedMultimap::KEY_DOES_NOT_EXIST)); + } + REQUIRE(map.erase(2) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(map.erase(31) == + static_cast(FixedOrderedMultimap::KEY_DOES_NOT_EXIST)); + REQUIRE(map.exists(2) == + static_cast(FixedOrderedMultimap::KEY_DOES_NOT_EXIST)); + REQUIRE(map.size() == 29); - for (auto element: map){ - if (element.first == 5){ - bool compare = element.second == TestClass(6, 5); - REQUIRE(compare); - } - } + for (auto element : map) { + if (element.first == 5) { + bool compare = element.second == TestClass(6, 5); + REQUIRE(compare); + } + } - for (FixedOrderedMultimap::Iterator it = map.begin(); it != map.end(); it++){ - bool compare = it->second == TestClass(it->first + 1, it->first); - REQUIRE(compare); - compare = (*it).second == TestClass((*it).first + 1, (*it).first); - REQUIRE(compare); - it->second = TestClass(it->first + 2, it->first); - compare = it->second == TestClass(it->first + 2, it->first); - REQUIRE(compare); - } + for (FixedOrderedMultimap::Iterator it = map.begin(); it != map.end(); + it++) { + bool compare = it->second == TestClass(it->first + 1, it->first); + REQUIRE(compare); + compare = (*it).second == TestClass((*it).first + 1, (*it).first); + REQUIRE(compare); + it->second = TestClass(it->first + 2, it->first); + compare = it->second == TestClass(it->first + 2, it->first); + REQUIRE(compare); + } - { - FixedOrderedMultimap::Iterator it = map.begin(); - while(it != map.end()){ - REQUIRE(map.erase(&it) == static_cast(HasReturnvaluesIF::RETURN_OK)); - } - REQUIRE(map.size() == 0); - } + { + FixedOrderedMultimap::Iterator it = map.begin(); + while (it != map.end()) { + REQUIRE(map.erase(&it) == static_cast(HasReturnvaluesIF::RETURN_OK)); + } + REQUIRE(map.size() == 0); + } - for (FixedOrderedMultimap::Iterator it = map.begin(); it != map.end(); it++){ - // This line should never executed if begin and end is correct - FAIL("Should never be reached, Iterators invalid"); - } - }; + for (FixedOrderedMultimap::Iterator it = map.begin(); it != map.end(); + it++) { + // This line should never executed if begin and end is correct + FAIL("Should never be reached, Iterators invalid"); + } + }; - SECTION("Test different insert variants") - { - FixedOrderedMultimap::Iterator it = map.end(); - REQUIRE(map.insert(36, TestClass(37, 36), &it) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(it->first == 36); - bool compare = it->second == TestClass(37, 36); - REQUIRE(compare); - REQUIRE(map.size() == 1); - REQUIRE(map.insert(37, TestClass(38, 37), nullptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); - compare = map.find(37)->second == TestClass(38, 37); - REQUIRE(compare); - REQUIRE(map.size() == 2); - REQUIRE(map.insert(37, TestClass(24, 37), nullptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); - compare = map.find(37)->second == TestClass(38, 37); - REQUIRE(compare); - REQUIRE(map.insert(0, TestClass(1, 0), nullptr) == static_cast(HasReturnvaluesIF::RETURN_OK)); - compare = map.find(0)->second == TestClass(1, 0); - REQUIRE(compare); - REQUIRE(map.size() == 4); - map.clear(); - REQUIRE(map.size() == 0); - } - SECTION("Test different erase and find with no entries"){ - FixedOrderedMultimap::Iterator it; - it = map.end(); - REQUIRE(map.erase(&it) == static_cast(FixedOrderedMultimap::KEY_DOES_NOT_EXIST)); - REQUIRE(map.find(1)== map.end()); - } + SECTION("Test different insert variants") { + FixedOrderedMultimap::Iterator it = map.end(); + REQUIRE(map.insert(36, TestClass(37, 36), &it) == + static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(it->first == 36); + bool compare = it->second == TestClass(37, 36); + REQUIRE(compare); + REQUIRE(map.size() == 1); + REQUIRE(map.insert(37, TestClass(38, 37), nullptr) == + static_cast(HasReturnvaluesIF::RETURN_OK)); + compare = map.find(37)->second == TestClass(38, 37); + REQUIRE(compare); + REQUIRE(map.size() == 2); + REQUIRE(map.insert(37, TestClass(24, 37), nullptr) == + static_cast(HasReturnvaluesIF::RETURN_OK)); + compare = map.find(37)->second == TestClass(38, 37); + REQUIRE(compare); + REQUIRE(map.insert(0, TestClass(1, 0), nullptr) == + static_cast(HasReturnvaluesIF::RETURN_OK)); + compare = map.find(0)->second == TestClass(1, 0); + REQUIRE(compare); + REQUIRE(map.size() == 4); + map.clear(); + REQUIRE(map.size() == 0); + } + SECTION("Test different erase and find with no entries") { + FixedOrderedMultimap::Iterator it; + it = map.end(); + REQUIRE(map.erase(&it) == + static_cast(FixedOrderedMultimap::KEY_DOES_NOT_EXIST)); + REQUIRE(map.find(1) == map.end()); + } } diff --git a/tests/src/fsfw_tests/unit/container/TestPlacementFactory.cpp b/tests/src/fsfw_tests/unit/container/TestPlacementFactory.cpp index 1e328fc7..0140ce05 100644 --- a/tests/src/fsfw_tests/unit/container/TestPlacementFactory.cpp +++ b/tests/src/fsfw_tests/unit/container/TestPlacementFactory.cpp @@ -1,49 +1,48 @@ -#include "fsfw_tests/unit/CatchDefinitions.h" - -#include -#include -#include #include +#include +#include +#include #include -TEST_CASE( "PlacementFactory Tests", "[TestPlacementFactory]") { - INFO("PlacementFactory Tests"); +#include "fsfw_tests/unit/CatchDefinitions.h" - LocalPool::LocalPoolConfig poolCfg= {{1, sizeof(uint16_t)}, - {1, sizeof(uint32_t)}, {1, sizeof(uint64_t)} - }; - //const uint16_t element_sizes[3] = {sizeof(uint16_t), sizeof(uint32_t), sizeof(uint64_t)}; - //const uint16_t n_elements[3] = {1, 1, 1}; - LocalPool storagePool(0x1, poolCfg, false, true); - PlacementFactory factory(&storagePool); +TEST_CASE("PlacementFactory Tests", "[TestPlacementFactory]") { + INFO("PlacementFactory Tests"); - SECTION("Pool overload"){ - store_address_t address; - uint8_t* ptr = nullptr; - REQUIRE(storagePool.getFreeElement(&address, sizeof(ArrayList), &ptr) - == static_cast(StorageManagerIF::DATA_TOO_LARGE)); - ArrayList* list2 = factory.generate >(80); - REQUIRE(list2 == nullptr); - } + LocalPool::LocalPoolConfig poolCfg = { + {1, sizeof(uint16_t)}, {1, sizeof(uint32_t)}, {1, sizeof(uint64_t)}}; + // const uint16_t element_sizes[3] = {sizeof(uint16_t), sizeof(uint32_t), sizeof(uint64_t)}; + // const uint16_t n_elements[3] = {1, 1, 1}; + LocalPool storagePool(0x1, poolCfg, false, true); + PlacementFactory factory(&storagePool); - SECTION("Test generate and destroy"){ - uint64_t* number = factory.generate(32000); - REQUIRE(number != nullptr); - REQUIRE(*number == 32000); - store_address_t address; - uint8_t* ptr = nullptr; - REQUIRE(storagePool.getFreeElement(&address, sizeof(uint64_t), &ptr) - == static_cast(StorageManagerIF::DATA_TOO_LARGE)); - uint64_t* number2 = factory.generate(12345); - REQUIRE(number2 == nullptr); - REQUIRE(factory.destroy(number) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(storagePool.getFreeElement(&address, sizeof(uint64_t), &ptr) - == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(storagePool.deleteData(address) == static_cast(HasReturnvaluesIF::RETURN_OK)); + SECTION("Pool overload") { + store_address_t address; + uint8_t* ptr = nullptr; + REQUIRE(storagePool.getFreeElement(&address, sizeof(ArrayList), &ptr) == + static_cast(StorageManagerIF::DATA_TOO_LARGE)); + ArrayList* list2 = factory.generate >(80); + REQUIRE(list2 == nullptr); + } - //Check that PlacementFactory checks for nullptr - ptr = nullptr; - REQUIRE(factory.destroy(ptr) == static_cast(HasReturnvaluesIF::RETURN_FAILED)); - } + SECTION("Test generate and destroy") { + uint64_t* number = factory.generate(32000); + REQUIRE(number != nullptr); + REQUIRE(*number == 32000); + store_address_t address; + uint8_t* ptr = nullptr; + REQUIRE(storagePool.getFreeElement(&address, sizeof(uint64_t), &ptr) == + static_cast(StorageManagerIF::DATA_TOO_LARGE)); + uint64_t* number2 = factory.generate(12345); + REQUIRE(number2 == nullptr); + REQUIRE(factory.destroy(number) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(storagePool.getFreeElement(&address, sizeof(uint64_t), &ptr) == + static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(storagePool.deleteData(address) == static_cast(HasReturnvaluesIF::RETURN_OK)); + + // Check that PlacementFactory checks for nullptr + ptr = nullptr; + REQUIRE(factory.destroy(ptr) == static_cast(HasReturnvaluesIF::RETURN_FAILED)); + } } diff --git a/tests/src/fsfw_tests/unit/datapoollocal/DataSetTest.cpp b/tests/src/fsfw_tests/unit/datapoollocal/DataSetTest.cpp index e84f07b6..902d59ef 100644 --- a/tests/src/fsfw_tests/unit/datapoollocal/DataSetTest.cpp +++ b/tests/src/fsfw_tests/unit/datapoollocal/DataSetTest.cpp @@ -1,295 +1,286 @@ -#include "LocalPoolOwnerBase.h" -#include "tests/TestsConfig.h" -#include "fsfw_tests/unit/CatchDefinitions.h" - -#include +#include #include #include #include -#include #include +#include -#include #include +#include -TEST_CASE("DataSetTest" , "[DataSetTest]") { - LocalPoolOwnerBase* poolOwner = ObjectManager::instance()-> - get(objects::TEST_LOCAL_POOL_OWNER_BASE); - REQUIRE(poolOwner != nullptr); - REQUIRE(poolOwner->initializeHkManager() == retval::CATCH_OK); - REQUIRE(poolOwner->initializeHkManagerAfterTaskCreation() - == retval::CATCH_OK); - LocalPoolStaticTestDataSet localSet; +#include "LocalPoolOwnerBase.h" +#include "fsfw_tests/unit/CatchDefinitions.h" +#include "tests/TestsConfig.h" - SECTION("BasicTest") { - /* Test some basic functions */ - CHECK(localSet.getReportingEnabled() == false); - CHECK(localSet.getLocalPoolIdsSerializedSize(false) == 3 * sizeof(lp_id_t)); - CHECK(localSet.getLocalPoolIdsSerializedSize(true) == - 3 * sizeof(lp_id_t) + sizeof(uint8_t)); - CHECK(localSet.getSid() == lpool::testSid); - CHECK(localSet.getCreatorObjectId() == objects::TEST_LOCAL_POOL_OWNER_BASE); - size_t maxSize = localSet.getLocalPoolIdsSerializedSize(true); - uint8_t localPoolIdBuff[maxSize]; - /* Skip size field */ - lp_id_t* lpIds = reinterpret_cast(localPoolIdBuff + 1); - size_t serSize = 0; - uint8_t *localPoolIdBuffPtr = reinterpret_cast(localPoolIdBuff); +TEST_CASE("DataSetTest", "[DataSetTest]") { + LocalPoolOwnerBase* poolOwner = + ObjectManager::instance()->get(objects::TEST_LOCAL_POOL_OWNER_BASE); + REQUIRE(poolOwner != nullptr); + REQUIRE(poolOwner->initializeHkManager() == retval::CATCH_OK); + REQUIRE(poolOwner->initializeHkManagerAfterTaskCreation() == retval::CATCH_OK); + LocalPoolStaticTestDataSet localSet; - /* Test local pool ID serialization */ - CHECK(localSet.serializeLocalPoolIds(&localPoolIdBuffPtr, &serSize, - maxSize, SerializeIF::Endianness::MACHINE) == retval::CATCH_OK); - CHECK(serSize == maxSize); - CHECK(localPoolIdBuff[0] == 3); - CHECK(lpIds[0] == localSet.localPoolVarUint8.getDataPoolId()); - CHECK(lpIds[1] == localSet.localPoolVarFloat.getDataPoolId()); - CHECK(lpIds[2] == localSet.localPoolUint16Vec.getDataPoolId()); - /* Now serialize without fill count */ - lpIds = reinterpret_cast(localPoolIdBuff); - localPoolIdBuffPtr = localPoolIdBuff; - serSize = 0; - CHECK(localSet.serializeLocalPoolIds(&localPoolIdBuffPtr, &serSize, - maxSize, SerializeIF::Endianness::MACHINE, false) == retval::CATCH_OK); - CHECK(serSize == maxSize - sizeof(uint8_t)); - CHECK(lpIds[0] == localSet.localPoolVarUint8.getDataPoolId()); - CHECK(lpIds[1] == localSet.localPoolVarFloat.getDataPoolId()); - CHECK(lpIds[2] == localSet.localPoolUint16Vec.getDataPoolId()); + SECTION("BasicTest") { + /* Test some basic functions */ + CHECK(localSet.getReportingEnabled() == false); + CHECK(localSet.getLocalPoolIdsSerializedSize(false) == 3 * sizeof(lp_id_t)); + CHECK(localSet.getLocalPoolIdsSerializedSize(true) == 3 * sizeof(lp_id_t) + sizeof(uint8_t)); + CHECK(localSet.getSid() == lpool::testSid); + CHECK(localSet.getCreatorObjectId() == objects::TEST_LOCAL_POOL_OWNER_BASE); + size_t maxSize = localSet.getLocalPoolIdsSerializedSize(true); + uint8_t localPoolIdBuff[maxSize]; + /* Skip size field */ + lp_id_t* lpIds = reinterpret_cast(localPoolIdBuff + 1); + size_t serSize = 0; + uint8_t* localPoolIdBuffPtr = reinterpret_cast(localPoolIdBuff); - { - /* Test read operation. Values should be all zeros */ - PoolReadGuard readHelper(&localSet); - REQUIRE(readHelper.getReadResult() == retval::CATCH_OK); - CHECK(not localSet.isValid()); - CHECK(localSet.localPoolVarUint8.value == 0); - CHECK(not localSet.localPoolVarUint8.isValid()); - CHECK(localSet.localPoolVarFloat.value == Catch::Approx(0.0)); - CHECK(not localSet.localPoolVarUint8.isValid()); - CHECK(localSet.localPoolUint16Vec.value[0] == 0); - CHECK(localSet.localPoolUint16Vec.value[1] == 0); - CHECK(localSet.localPoolUint16Vec.value[2] == 0); - CHECK(not localSet.localPoolVarUint8.isValid()); + /* Test local pool ID serialization */ + CHECK(localSet.serializeLocalPoolIds(&localPoolIdBuffPtr, &serSize, maxSize, + SerializeIF::Endianness::MACHINE) == retval::CATCH_OK); + CHECK(serSize == maxSize); + CHECK(localPoolIdBuff[0] == 3); + CHECK(lpIds[0] == localSet.localPoolVarUint8.getDataPoolId()); + CHECK(lpIds[1] == localSet.localPoolVarFloat.getDataPoolId()); + CHECK(lpIds[2] == localSet.localPoolUint16Vec.getDataPoolId()); + /* Now serialize without fill count */ + lpIds = reinterpret_cast(localPoolIdBuff); + localPoolIdBuffPtr = localPoolIdBuff; + serSize = 0; + CHECK(localSet.serializeLocalPoolIds(&localPoolIdBuffPtr, &serSize, maxSize, + SerializeIF::Endianness::MACHINE, + false) == retval::CATCH_OK); + CHECK(serSize == maxSize - sizeof(uint8_t)); + CHECK(lpIds[0] == localSet.localPoolVarUint8.getDataPoolId()); + CHECK(lpIds[1] == localSet.localPoolVarFloat.getDataPoolId()); + CHECK(lpIds[2] == localSet.localPoolUint16Vec.getDataPoolId()); - /* Now set new values, commit should be done by read helper automatically */ - localSet.localPoolVarUint8 = 232; - localSet.localPoolVarFloat = -2324.322; - localSet.localPoolUint16Vec.value[0] = 232; - localSet.localPoolUint16Vec.value[1] = 23923; - localSet.localPoolUint16Vec.value[2] = 1; - localSet.setValidity(true, true); - } - - /* Zero out some values for next test */ - localSet.localPoolVarUint8 = 0; - localSet.localPoolVarFloat = 0; - - localSet.setAllVariablesReadOnly(); - CHECK(localSet.localPoolUint16Vec.getReadWriteMode() == pool_rwm_t::VAR_READ); - CHECK(localSet.localPoolVarUint8.getReadWriteMode() == pool_rwm_t::VAR_READ); - CHECK(localSet.localPoolVarFloat.getReadWriteMode() == pool_rwm_t::VAR_READ); - - { - /* Now we read again and check whether our zeroed values were overwritten with - the values in the pool */ - PoolReadGuard readHelper(&localSet); - REQUIRE(readHelper.getReadResult() == retval::CATCH_OK); - CHECK(localSet.isValid()); - CHECK(localSet.localPoolVarUint8.value == 232); - CHECK(localSet.localPoolVarUint8.isValid()); - CHECK(localSet.localPoolVarFloat.value == Catch::Approx(-2324.322)); - CHECK(localSet.localPoolVarFloat.isValid()); - CHECK(localSet.localPoolUint16Vec.value[0] == 232); - CHECK(localSet.localPoolUint16Vec.value[1] == 23923); - CHECK(localSet.localPoolUint16Vec.value[2] == 1); - CHECK(localSet.localPoolUint16Vec.isValid()); - - /* Now we serialize these values into a buffer without the validity buffer */ - localSet.setValidityBufferGeneration(false); - maxSize = localSet.getSerializedSize(); - CHECK(maxSize == sizeof(uint8_t) + sizeof(uint16_t) * 3 + sizeof(float)); - serSize = 0; - /* Already reserve additional space for validity buffer, will be needed later */ - uint8_t buffer[maxSize + 1]; - uint8_t* buffPtr = buffer; - CHECK(localSet.serialize(&buffPtr, &serSize, maxSize, - SerializeIF::Endianness::MACHINE) == retval::CATCH_OK); - uint8_t rawUint8 = buffer[0]; - CHECK(rawUint8 == 232); - float rawFloat = 0.0; - std::memcpy(&rawFloat, buffer + sizeof(uint8_t), sizeof(float)); - CHECK(rawFloat == Catch::Approx(-2324.322)); - - uint16_t rawUint16Vec[3]; - std::memcpy(&rawUint16Vec, buffer + sizeof(uint8_t) + sizeof(float), - 3 * sizeof(uint16_t)); - CHECK(rawUint16Vec[0] == 232); - CHECK(rawUint16Vec[1] == 23923); - CHECK(rawUint16Vec[2] == 1); - - size_t sizeToDeserialize = maxSize; - /* Now we zeros out the raw entries and deserialize back into the dataset */ - std::memset(buffer, 0, sizeof(buffer)); - const uint8_t* constBuffPtr = buffer; - CHECK(localSet.deSerialize(&constBuffPtr, &sizeToDeserialize, - SerializeIF::Endianness::MACHINE) == retval::CATCH_OK); - /* Check whether deserialization was successfull */ - CHECK(localSet.localPoolVarUint8.value == 0); - CHECK(localSet.localPoolVarFloat.value == Catch::Approx(0.0)); - CHECK(localSet.localPoolVarUint8.value == 0); - CHECK(localSet.localPoolUint16Vec.value[0] == 0); - CHECK(localSet.localPoolUint16Vec.value[1] == 0); - CHECK(localSet.localPoolUint16Vec.value[2] == 0); - /* Validity should be unchanged */ - CHECK(localSet.localPoolVarUint8.isValid()); - CHECK(localSet.localPoolVarFloat.isValid()); - CHECK(localSet.localPoolUint16Vec.isValid()); - - /* Now we do the same process but with the validity buffer */ - localSet.localPoolVarUint8 = 232; - localSet.localPoolVarFloat = -2324.322; - localSet.localPoolUint16Vec.value[0] = 232; - localSet.localPoolUint16Vec.value[1] = 23923; - localSet.localPoolUint16Vec.value[2] = 1; - localSet.localPoolVarUint8.setValid(true); - localSet.localPoolVarFloat.setValid(false); - localSet.localPoolUint16Vec.setValid(true); - localSet.setValidityBufferGeneration(true); - maxSize = localSet.getSerializedSize(); - CHECK(maxSize == sizeof(uint8_t) + sizeof(uint16_t) * 3 + sizeof(float) + 1); - serSize = 0; - buffPtr = buffer; - CHECK(localSet.serialize(&buffPtr, &serSize, maxSize, - SerializeIF::Endianness::MACHINE) == retval::CATCH_OK); - CHECK(rawUint8 == 232); - std::memcpy(&rawFloat, buffer + sizeof(uint8_t), sizeof(float)); - CHECK(rawFloat == Catch::Approx(-2324.322)); - - std::memcpy(&rawUint16Vec, buffer + sizeof(uint8_t) + sizeof(float), - 3 * sizeof(uint16_t)); - CHECK(rawUint16Vec[0] == 232); - CHECK(rawUint16Vec[1] == 23923); - CHECK(rawUint16Vec[2] == 1); - /* We can do it like this because the buffer only has one byte for - less than 8 variables */ - uint8_t* validityByte = buffer + sizeof(buffer) - 1; - bool bitSet = false; - bitutil::get(validityByte, 0, bitSet); - - CHECK(bitSet == true); - bitutil::get(validityByte, 1, bitSet); - CHECK(bitSet == false); - bitutil::get(validityByte, 2, bitSet); - CHECK(bitSet == true); - - /* Now we manipulate the validity buffer for the deserialization */ - bitutil::clear(validityByte, 0); - bitutil::set(validityByte, 1); - bitutil::clear(validityByte, 2); - /* Zero out everything except validity buffer */ - std::memset(buffer, 0, sizeof(buffer) - 1); - sizeToDeserialize = maxSize; - constBuffPtr = buffer; - CHECK(localSet.deSerialize(&constBuffPtr, &sizeToDeserialize, - SerializeIF::Endianness::MACHINE) == retval::CATCH_OK); - /* Check whether deserialization was successfull */ - CHECK(localSet.localPoolVarUint8.value == 0); - CHECK(localSet.localPoolVarFloat.value == Catch::Approx(0.0)); - CHECK(localSet.localPoolVarUint8.value == 0); - CHECK(localSet.localPoolUint16Vec.value[0] == 0); - CHECK(localSet.localPoolUint16Vec.value[1] == 0); - CHECK(localSet.localPoolUint16Vec.value[2] == 0); - CHECK(not localSet.localPoolVarUint8.isValid()); - CHECK(localSet.localPoolVarFloat.isValid()); - CHECK(not localSet.localPoolUint16Vec.isValid()); - - } - - /* Common fault test cases */ - LocalPoolObjectBase* variableHandle = poolOwner->getPoolObjectHandle(lpool::uint32VarId); - CHECK(variableHandle != nullptr); - CHECK(localSet.registerVariable(variableHandle) == - static_cast(DataSetIF::DATA_SET_FULL)); - variableHandle = nullptr; - REQUIRE(localSet.registerVariable(variableHandle) == - static_cast(DataSetIF::POOL_VAR_NULL)); + { + /* Test read operation. Values should be all zeros */ + PoolReadGuard readHelper(&localSet); + REQUIRE(readHelper.getReadResult() == retval::CATCH_OK); + CHECK(not localSet.isValid()); + CHECK(localSet.localPoolVarUint8.value == 0); + CHECK(not localSet.localPoolVarUint8.isValid()); + CHECK(localSet.localPoolVarFloat.value == Catch::Approx(0.0)); + CHECK(not localSet.localPoolVarUint8.isValid()); + CHECK(localSet.localPoolUint16Vec.value[0] == 0); + CHECK(localSet.localPoolUint16Vec.value[1] == 0); + CHECK(localSet.localPoolUint16Vec.value[2] == 0); + CHECK(not localSet.localPoolVarUint8.isValid()); + /* Now set new values, commit should be done by read helper automatically */ + localSet.localPoolVarUint8 = 232; + localSet.localPoolVarFloat = -2324.322; + localSet.localPoolUint16Vec.value[0] = 232; + localSet.localPoolUint16Vec.value[1] = 23923; + localSet.localPoolUint16Vec.value[2] = 1; + localSet.setValidity(true, true); } - SECTION("MorePoolVariables") { - LocalDataSet set(poolOwner, 2, 10); + /* Zero out some values for next test */ + localSet.localPoolVarUint8 = 0; + localSet.localPoolVarFloat = 0; - /* Register same variables again to get more than 8 registered variables */ - for(uint8_t idx = 0; idx < 8; idx ++) { - REQUIRE(set.registerVariable(&localSet.localPoolVarUint8) == retval::CATCH_OK); - } - REQUIRE(set.registerVariable(&localSet.localPoolVarUint8) == retval::CATCH_OK); - REQUIRE(set.registerVariable(&localSet.localPoolUint16Vec) == retval::CATCH_OK); + localSet.setAllVariablesReadOnly(); + CHECK(localSet.localPoolUint16Vec.getReadWriteMode() == pool_rwm_t::VAR_READ); + CHECK(localSet.localPoolVarUint8.getReadWriteMode() == pool_rwm_t::VAR_READ); + CHECK(localSet.localPoolVarFloat.getReadWriteMode() == pool_rwm_t::VAR_READ); - set.setValidityBufferGeneration(true); - { - PoolReadGuard readHelper(&localSet); - localSet.localPoolVarUint8.value = 42; - localSet.localPoolVarUint8.setValid(true); - localSet.localPoolUint16Vec.setValid(false); - } + { + /* Now we read again and check whether our zeroed values were overwritten with + the values in the pool */ + PoolReadGuard readHelper(&localSet); + REQUIRE(readHelper.getReadResult() == retval::CATCH_OK); + CHECK(localSet.isValid()); + CHECK(localSet.localPoolVarUint8.value == 232); + CHECK(localSet.localPoolVarUint8.isValid()); + CHECK(localSet.localPoolVarFloat.value == Catch::Approx(-2324.322)); + CHECK(localSet.localPoolVarFloat.isValid()); + CHECK(localSet.localPoolUint16Vec.value[0] == 232); + CHECK(localSet.localPoolUint16Vec.value[1] == 23923); + CHECK(localSet.localPoolUint16Vec.value[2] == 1); + CHECK(localSet.localPoolUint16Vec.isValid()); - size_t maxSize = set.getSerializedSize(); - CHECK(maxSize == 9 + sizeof(uint16_t) * 3 + 2); - size_t serSize = 0; - /* Already reserve additional space for validity buffer, will be needed later */ - uint8_t buffer[maxSize + 1]; - uint8_t* buffPtr = buffer; - CHECK(set.serialize(&buffPtr, &serSize, maxSize, - SerializeIF::Endianness::MACHINE) == retval::CATCH_OK); - std::array validityBuffer; - std::memcpy(validityBuffer.data(), buffer + 9 + sizeof(uint16_t) * 3, 2); - /* The first 9 variables should be valid */ - CHECK(validityBuffer[0] == 0xff); - bool bitSet = false; - bitutil::get(validityBuffer.data() + 1, 0, bitSet); - CHECK(bitSet == true); - bitutil::get(validityBuffer.data() + 1, 1, bitSet); - CHECK(bitSet == false); + /* Now we serialize these values into a buffer without the validity buffer */ + localSet.setValidityBufferGeneration(false); + maxSize = localSet.getSerializedSize(); + CHECK(maxSize == sizeof(uint8_t) + sizeof(uint16_t) * 3 + sizeof(float)); + serSize = 0; + /* Already reserve additional space for validity buffer, will be needed later */ + uint8_t buffer[maxSize + 1]; + uint8_t* buffPtr = buffer; + CHECK(localSet.serialize(&buffPtr, &serSize, maxSize, SerializeIF::Endianness::MACHINE) == + retval::CATCH_OK); + uint8_t rawUint8 = buffer[0]; + CHECK(rawUint8 == 232); + float rawFloat = 0.0; + std::memcpy(&rawFloat, buffer + sizeof(uint8_t), sizeof(float)); + CHECK(rawFloat == Catch::Approx(-2324.322)); - /* Now we invert the validity */ - validityBuffer[0] = 0; - validityBuffer[1] = 0b0100'0000; - std::memcpy(buffer + 9 + sizeof(uint16_t) * 3, validityBuffer.data(), 2); - const uint8_t* constBuffPtr = buffer; - size_t sizeToDeSerialize = serSize; - CHECK(set.deSerialize(&constBuffPtr, &sizeToDeSerialize, SerializeIF::Endianness::MACHINE) - == retval::CATCH_OK); - CHECK(localSet.localPoolVarUint8.isValid() == false); - CHECK(localSet.localPoolUint16Vec.isValid() == true); + uint16_t rawUint16Vec[3]; + std::memcpy(&rawUint16Vec, buffer + sizeof(uint8_t) + sizeof(float), 3 * sizeof(uint16_t)); + CHECK(rawUint16Vec[0] == 232); + CHECK(rawUint16Vec[1] == 23923); + CHECK(rawUint16Vec[2] == 1); + + size_t sizeToDeserialize = maxSize; + /* Now we zeros out the raw entries and deserialize back into the dataset */ + std::memset(buffer, 0, sizeof(buffer)); + const uint8_t* constBuffPtr = buffer; + CHECK(localSet.deSerialize(&constBuffPtr, &sizeToDeserialize, + SerializeIF::Endianness::MACHINE) == retval::CATCH_OK); + /* Check whether deserialization was successfull */ + CHECK(localSet.localPoolVarUint8.value == 0); + CHECK(localSet.localPoolVarFloat.value == Catch::Approx(0.0)); + CHECK(localSet.localPoolVarUint8.value == 0); + CHECK(localSet.localPoolUint16Vec.value[0] == 0); + CHECK(localSet.localPoolUint16Vec.value[1] == 0); + CHECK(localSet.localPoolUint16Vec.value[2] == 0); + /* Validity should be unchanged */ + CHECK(localSet.localPoolVarUint8.isValid()); + CHECK(localSet.localPoolVarFloat.isValid()); + CHECK(localSet.localPoolUint16Vec.isValid()); + + /* Now we do the same process but with the validity buffer */ + localSet.localPoolVarUint8 = 232; + localSet.localPoolVarFloat = -2324.322; + localSet.localPoolUint16Vec.value[0] = 232; + localSet.localPoolUint16Vec.value[1] = 23923; + localSet.localPoolUint16Vec.value[2] = 1; + localSet.localPoolVarUint8.setValid(true); + localSet.localPoolVarFloat.setValid(false); + localSet.localPoolUint16Vec.setValid(true); + localSet.setValidityBufferGeneration(true); + maxSize = localSet.getSerializedSize(); + CHECK(maxSize == sizeof(uint8_t) + sizeof(uint16_t) * 3 + sizeof(float) + 1); + serSize = 0; + buffPtr = buffer; + CHECK(localSet.serialize(&buffPtr, &serSize, maxSize, SerializeIF::Endianness::MACHINE) == + retval::CATCH_OK); + CHECK(rawUint8 == 232); + std::memcpy(&rawFloat, buffer + sizeof(uint8_t), sizeof(float)); + CHECK(rawFloat == Catch::Approx(-2324.322)); + + std::memcpy(&rawUint16Vec, buffer + sizeof(uint8_t) + sizeof(float), 3 * sizeof(uint16_t)); + CHECK(rawUint16Vec[0] == 232); + CHECK(rawUint16Vec[1] == 23923); + CHECK(rawUint16Vec[2] == 1); + /* We can do it like this because the buffer only has one byte for + less than 8 variables */ + uint8_t* validityByte = buffer + sizeof(buffer) - 1; + bool bitSet = false; + bitutil::get(validityByte, 0, bitSet); + + CHECK(bitSet == true); + bitutil::get(validityByte, 1, bitSet); + CHECK(bitSet == false); + bitutil::get(validityByte, 2, bitSet); + CHECK(bitSet == true); + + /* Now we manipulate the validity buffer for the deserialization */ + bitutil::clear(validityByte, 0); + bitutil::set(validityByte, 1); + bitutil::clear(validityByte, 2); + /* Zero out everything except validity buffer */ + std::memset(buffer, 0, sizeof(buffer) - 1); + sizeToDeserialize = maxSize; + constBuffPtr = buffer; + CHECK(localSet.deSerialize(&constBuffPtr, &sizeToDeserialize, + SerializeIF::Endianness::MACHINE) == retval::CATCH_OK); + /* Check whether deserialization was successfull */ + CHECK(localSet.localPoolVarUint8.value == 0); + CHECK(localSet.localPoolVarFloat.value == Catch::Approx(0.0)); + CHECK(localSet.localPoolVarUint8.value == 0); + CHECK(localSet.localPoolUint16Vec.value[0] == 0); + CHECK(localSet.localPoolUint16Vec.value[1] == 0); + CHECK(localSet.localPoolUint16Vec.value[2] == 0); + CHECK(not localSet.localPoolVarUint8.isValid()); + CHECK(localSet.localPoolVarFloat.isValid()); + CHECK(not localSet.localPoolUint16Vec.isValid()); } - SECTION("SharedDataSet") { - object_id_t sharedSetId = objects::SHARED_SET_ID; - SharedLocalDataSet sharedSet(sharedSetId, poolOwner, lpool::testSetId, 5); - localSet.localPoolVarUint8.setReadWriteMode(pool_rwm_t::VAR_WRITE); - localSet.localPoolUint16Vec.setReadWriteMode(pool_rwm_t::VAR_WRITE); - CHECK(sharedSet.registerVariable(&localSet.localPoolVarUint8) == retval::CATCH_OK); - CHECK(sharedSet.registerVariable(&localSet.localPoolUint16Vec) == retval::CATCH_OK); - CHECK(sharedSet.initialize() == retval::CATCH_OK); - CHECK(sharedSet.lockDataset() == retval::CATCH_OK); - CHECK(sharedSet.unlockDataset() == retval::CATCH_OK); + /* Common fault test cases */ + LocalPoolObjectBase* variableHandle = poolOwner->getPoolObjectHandle(lpool::uint32VarId); + CHECK(variableHandle != nullptr); + CHECK(localSet.registerVariable(variableHandle) == static_cast(DataSetIF::DATA_SET_FULL)); + variableHandle = nullptr; + REQUIRE(localSet.registerVariable(variableHandle) == + static_cast(DataSetIF::POOL_VAR_NULL)); + } - { - //PoolReadGuard rg(&sharedSet); - //CHECK(rg.getReadResult() == retval::CATCH_OK); - localSet.localPoolVarUint8.value = 5; - localSet.localPoolUint16Vec.value[0] = 1; - localSet.localPoolUint16Vec.value[1] = 2; - localSet.localPoolUint16Vec.value[2] = 3; - CHECK(sharedSet.commit() == retval::CATCH_OK); - } + SECTION("MorePoolVariables") { + LocalDataSet set(poolOwner, 2, 10); - sharedSet.setReadCommitProtectionBehaviour(true); + /* Register same variables again to get more than 8 registered variables */ + for (uint8_t idx = 0; idx < 8; idx++) { + REQUIRE(set.registerVariable(&localSet.localPoolVarUint8) == retval::CATCH_OK); + } + REQUIRE(set.registerVariable(&localSet.localPoolVarUint8) == retval::CATCH_OK); + REQUIRE(set.registerVariable(&localSet.localPoolUint16Vec) == retval::CATCH_OK); + + set.setValidityBufferGeneration(true); + { + PoolReadGuard readHelper(&localSet); + localSet.localPoolVarUint8.value = 42; + localSet.localPoolVarUint8.setValid(true); + localSet.localPoolUint16Vec.setValid(false); } - /* we need to reset the subscription list because the pool owner - is a global object. */ - CHECK(poolOwner->reset() == retval::CATCH_OK); + size_t maxSize = set.getSerializedSize(); + CHECK(maxSize == 9 + sizeof(uint16_t) * 3 + 2); + size_t serSize = 0; + /* Already reserve additional space for validity buffer, will be needed later */ + uint8_t buffer[maxSize + 1]; + uint8_t* buffPtr = buffer; + CHECK(set.serialize(&buffPtr, &serSize, maxSize, SerializeIF::Endianness::MACHINE) == + retval::CATCH_OK); + std::array validityBuffer; + std::memcpy(validityBuffer.data(), buffer + 9 + sizeof(uint16_t) * 3, 2); + /* The first 9 variables should be valid */ + CHECK(validityBuffer[0] == 0xff); + bool bitSet = false; + bitutil::get(validityBuffer.data() + 1, 0, bitSet); + CHECK(bitSet == true); + bitutil::get(validityBuffer.data() + 1, 1, bitSet); + CHECK(bitSet == false); + + /* Now we invert the validity */ + validityBuffer[0] = 0; + validityBuffer[1] = 0b0100'0000; + std::memcpy(buffer + 9 + sizeof(uint16_t) * 3, validityBuffer.data(), 2); + const uint8_t* constBuffPtr = buffer; + size_t sizeToDeSerialize = serSize; + CHECK(set.deSerialize(&constBuffPtr, &sizeToDeSerialize, SerializeIF::Endianness::MACHINE) == + retval::CATCH_OK); + CHECK(localSet.localPoolVarUint8.isValid() == false); + CHECK(localSet.localPoolUint16Vec.isValid() == true); + } + + SECTION("SharedDataSet") { + object_id_t sharedSetId = objects::SHARED_SET_ID; + SharedLocalDataSet sharedSet(sharedSetId, poolOwner, lpool::testSetId, 5); + localSet.localPoolVarUint8.setReadWriteMode(pool_rwm_t::VAR_WRITE); + localSet.localPoolUint16Vec.setReadWriteMode(pool_rwm_t::VAR_WRITE); + CHECK(sharedSet.registerVariable(&localSet.localPoolVarUint8) == retval::CATCH_OK); + CHECK(sharedSet.registerVariable(&localSet.localPoolUint16Vec) == retval::CATCH_OK); + CHECK(sharedSet.initialize() == retval::CATCH_OK); + CHECK(sharedSet.lockDataset() == retval::CATCH_OK); + CHECK(sharedSet.unlockDataset() == retval::CATCH_OK); + + { + // PoolReadGuard rg(&sharedSet); + // CHECK(rg.getReadResult() == retval::CATCH_OK); + localSet.localPoolVarUint8.value = 5; + localSet.localPoolUint16Vec.value[0] = 1; + localSet.localPoolUint16Vec.value[1] = 2; + localSet.localPoolUint16Vec.value[2] = 3; + CHECK(sharedSet.commit() == retval::CATCH_OK); + } + + sharedSet.setReadCommitProtectionBehaviour(true); + } + + /* we need to reset the subscription list because the pool owner + is a global object. */ + CHECK(poolOwner->reset() == retval::CATCH_OK); } - - - diff --git a/tests/src/fsfw_tests/unit/datapoollocal/LocalPoolManagerTest.cpp b/tests/src/fsfw_tests/unit/datapoollocal/LocalPoolManagerTest.cpp index b1160254..fb22972e 100644 --- a/tests/src/fsfw_tests/unit/datapoollocal/LocalPoolManagerTest.cpp +++ b/tests/src/fsfw_tests/unit/datapoollocal/LocalPoolManagerTest.cpp @@ -1,428 +1,419 @@ -#include "LocalPoolOwnerBase.h" -#include "fsfw_tests/unit/CatchDefinitions.h" - -#include #include #include #include #include #include +#include #include -#include #include - +#include #include +#include "LocalPoolOwnerBase.h" +#include "fsfw_tests/unit/CatchDefinitions.h" -TEST_CASE("LocalPoolManagerTest" , "[LocManTest]") { - LocalPoolOwnerBase* poolOwner = ObjectManager::instance()-> - get(objects::TEST_LOCAL_POOL_OWNER_BASE); - REQUIRE(poolOwner != nullptr); - REQUIRE(poolOwner->initializeHkManager() == retval::CATCH_OK); - REQUIRE(poolOwner->initializeHkManagerAfterTaskCreation() - == retval::CATCH_OK); +TEST_CASE("LocalPoolManagerTest", "[LocManTest]") { + LocalPoolOwnerBase* poolOwner = + ObjectManager::instance()->get(objects::TEST_LOCAL_POOL_OWNER_BASE); + REQUIRE(poolOwner != nullptr); + REQUIRE(poolOwner->initializeHkManager() == retval::CATCH_OK); + REQUIRE(poolOwner->initializeHkManagerAfterTaskCreation() == retval::CATCH_OK); - MessageQueueMockBase* mqMock = poolOwner->getMockQueueHandle(); - REQUIRE(mqMock != nullptr); - CommandMessage messageSent; - uint8_t messagesSent = 0; + MessageQueueMockBase* mqMock = poolOwner->getMockQueueHandle(); + REQUIRE(mqMock != nullptr); + CommandMessage messageSent; + uint8_t messagesSent = 0; - SECTION("BasicTest") { - { - /* For code coverage, should not crash */ - LocalDataPoolManager manager(nullptr, nullptr); - } - auto owner = poolOwner->poolManager.getOwner(); - REQUIRE(owner != nullptr); - CHECK(owner->getObjectId() == objects::TEST_LOCAL_POOL_OWNER_BASE); + SECTION("BasicTest") { + { + /* For code coverage, should not crash */ + LocalDataPoolManager manager(nullptr, nullptr); + } + auto owner = poolOwner->poolManager.getOwner(); + REQUIRE(owner != nullptr); + CHECK(owner->getObjectId() == objects::TEST_LOCAL_POOL_OWNER_BASE); - /* Subscribe for message generation on update. */ - REQUIRE(poolOwner->subscribeWrapperSetUpdate() == retval::CATCH_OK); - /* Subscribe for an update message. */ - poolOwner->dataset.setChanged(true); - /* Now the update message should be generated. */ - REQUIRE(poolOwner->poolManager.performHkOperation() == retval::CATCH_OK); - REQUIRE(mqMock->wasMessageSent() == true); + /* Subscribe for message generation on update. */ + REQUIRE(poolOwner->subscribeWrapperSetUpdate() == retval::CATCH_OK); + /* Subscribe for an update message. */ + poolOwner->dataset.setChanged(true); + /* Now the update message should be generated. */ + REQUIRE(poolOwner->poolManager.performHkOperation() == retval::CATCH_OK); + REQUIRE(mqMock->wasMessageSent() == true); - REQUIRE(mqMock->receiveMessage(&messageSent) == retval::CATCH_OK); - CHECK(messageSent.getCommand() == static_cast( - HousekeepingMessage::UPDATE_NOTIFICATION_SET)); + REQUIRE(mqMock->receiveMessage(&messageSent) == retval::CATCH_OK); + CHECK(messageSent.getCommand() == + static_cast(HousekeepingMessage::UPDATE_NOTIFICATION_SET)); - /* Should have been reset. */ - CHECK(poolOwner->dataset.hasChanged() == false); - /* Set changed again, result should be the same. */ - poolOwner->dataset.setChanged(true); - REQUIRE(poolOwner->poolManager.performHkOperation() == retval::CATCH_OK); + /* Should have been reset. */ + CHECK(poolOwner->dataset.hasChanged() == false); + /* Set changed again, result should be the same. */ + poolOwner->dataset.setChanged(true); + REQUIRE(poolOwner->poolManager.performHkOperation() == retval::CATCH_OK); - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(messagesSent == 1); - REQUIRE(mqMock->receiveMessage(&messageSent) == retval::CATCH_OK); - CHECK(messageSent.getCommand() == static_cast( - HousekeepingMessage::UPDATE_NOTIFICATION_SET)); + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(messagesSent == 1); + REQUIRE(mqMock->receiveMessage(&messageSent) == retval::CATCH_OK); + CHECK(messageSent.getCommand() == + static_cast(HousekeepingMessage::UPDATE_NOTIFICATION_SET)); - /* Now subscribe for set update HK as well. */ - REQUIRE(poolOwner->subscribeWrapperSetUpdateHk() == retval::CATCH_OK); - poolOwner->dataset.setChanged(true); - REQUIRE(poolOwner->poolManager.performHkOperation() == retval::CATCH_OK); - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(messagesSent == 2); - /* first message sent should be the update notification, considering - the internal list is a vector checked in insertion order. */ - REQUIRE(mqMock->receiveMessage(&messageSent) == retval::CATCH_OK); - CHECK(messageSent.getCommand() == static_cast( - HousekeepingMessage::UPDATE_NOTIFICATION_SET)); + /* Now subscribe for set update HK as well. */ + REQUIRE(poolOwner->subscribeWrapperSetUpdateHk() == retval::CATCH_OK); + poolOwner->dataset.setChanged(true); + REQUIRE(poolOwner->poolManager.performHkOperation() == retval::CATCH_OK); + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(messagesSent == 2); + /* first message sent should be the update notification, considering + the internal list is a vector checked in insertion order. */ + REQUIRE(mqMock->receiveMessage(&messageSent) == retval::CATCH_OK); + CHECK(messageSent.getCommand() == + static_cast(HousekeepingMessage::UPDATE_NOTIFICATION_SET)); - REQUIRE(mqMock->receiveMessage(&messageSent) == retval::CATCH_OK); - CHECK(messageSent.getCommand() == static_cast( - HousekeepingMessage::HK_REPORT)); - /* Clear message to avoid memory leak, our mock won't do it for us (yet) */ - CommandMessageCleaner::clearCommandMessage(&messageSent); + REQUIRE(mqMock->receiveMessage(&messageSent) == retval::CATCH_OK); + CHECK(messageSent.getCommand() == static_cast(HousekeepingMessage::HK_REPORT)); + /* Clear message to avoid memory leak, our mock won't do it for us (yet) */ + CommandMessageCleaner::clearCommandMessage(&messageSent); + } + SECTION("SetSnapshotUpdateTest") { + /* Set the variables in the set to certain values. These are checked later. */ + { + PoolReadGuard readHelper(&poolOwner->dataset); + REQUIRE(readHelper.getReadResult() == retval::CATCH_OK); + poolOwner->dataset.localPoolVarUint8.value = 5; + poolOwner->dataset.localPoolVarFloat.value = -12.242; + poolOwner->dataset.localPoolUint16Vec.value[0] = 2; + poolOwner->dataset.localPoolUint16Vec.value[1] = 32; + poolOwner->dataset.localPoolUint16Vec.value[2] = 42932; } - SECTION("SetSnapshotUpdateTest") { - /* Set the variables in the set to certain values. These are checked later. */ - { - PoolReadGuard readHelper(&poolOwner->dataset); - REQUIRE(readHelper.getReadResult() == retval::CATCH_OK); - poolOwner->dataset.localPoolVarUint8.value = 5; - poolOwner->dataset.localPoolVarFloat.value = -12.242; - poolOwner->dataset.localPoolUint16Vec.value[0] = 2; - poolOwner->dataset.localPoolUint16Vec.value[1] = 32; - poolOwner->dataset.localPoolUint16Vec.value[2] = 42932; - } + /* Subscribe for snapshot generation on update. */ + REQUIRE(poolOwner->subscribeWrapperSetUpdateSnapshot() == retval::CATCH_OK); + poolOwner->dataset.setChanged(true); - /* Subscribe for snapshot generation on update. */ - REQUIRE(poolOwner->subscribeWrapperSetUpdateSnapshot() == retval::CATCH_OK); - poolOwner->dataset.setChanged(true); + /* Store current time, we are going to check the (approximate) time equality later */ + CCSDSTime::CDS_short timeCdsNow; + timeval now; + Clock::getClock_timeval(&now); + CCSDSTime::convertToCcsds(&timeCdsNow, &now); - /* Store current time, we are going to check the (approximate) time equality later */ - CCSDSTime::CDS_short timeCdsNow; - timeval now; - Clock::getClock_timeval(&now); - CCSDSTime::convertToCcsds(&timeCdsNow, &now); + /* Trigger generation of snapshot */ + REQUIRE(poolOwner->poolManager.performHkOperation() == retval::CATCH_OK); + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(messagesSent == 1); + REQUIRE(mqMock->receiveMessage(&messageSent) == retval::CATCH_OK); + /* Check that snapshot was generated */ + CHECK(messageSent.getCommand() == static_cast(HousekeepingMessage::UPDATE_SNAPSHOT_SET)); + /* Now we deserialize the snapshot into a new dataset instance */ + CCSDSTime::CDS_short cdsShort; + LocalPoolTestDataSet newSet; + HousekeepingSnapshot snapshot(&cdsShort, &newSet); + store_address_t storeId; + HousekeepingMessage::getUpdateSnapshotSetCommand(&messageSent, &storeId); + ConstAccessorPair accessorPair = tglob::getIpcStoreHandle()->getData(storeId); + REQUIRE(accessorPair.first == retval::CATCH_OK); + const uint8_t* readOnlyPtr = accessorPair.second.data(); + size_t sizeToDeserialize = accessorPair.second.size(); + CHECK(newSet.localPoolVarFloat.value == 0); + CHECK(newSet.localPoolVarUint8 == 0); + CHECK(newSet.localPoolUint16Vec.value[0] == 0); + CHECK(newSet.localPoolUint16Vec.value[1] == 0); + CHECK(newSet.localPoolUint16Vec.value[2] == 0); + /* Fill the dataset and timestamp */ + REQUIRE(snapshot.deSerialize(&readOnlyPtr, &sizeToDeserialize, + SerializeIF::Endianness::MACHINE) == retval::CATCH_OK); + /* Now we check that the snapshot is actually correct */ + CHECK(newSet.localPoolVarFloat.value == Catch::Approx(-12.242)); + CHECK(newSet.localPoolVarUint8 == 5); + CHECK(newSet.localPoolUint16Vec.value[0] == 2); + CHECK(newSet.localPoolUint16Vec.value[1] == 32); + CHECK(newSet.localPoolUint16Vec.value[2] == 42932); - /* Trigger generation of snapshot */ - REQUIRE(poolOwner->poolManager.performHkOperation() == retval::CATCH_OK); - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(messagesSent == 1); - REQUIRE(mqMock->receiveMessage(&messageSent) == retval::CATCH_OK); - /* Check that snapshot was generated */ - CHECK(messageSent.getCommand() == static_cast( - HousekeepingMessage::UPDATE_SNAPSHOT_SET)); - /* Now we deserialize the snapshot into a new dataset instance */ - CCSDSTime::CDS_short cdsShort; - LocalPoolTestDataSet newSet; - HousekeepingSnapshot snapshot(&cdsShort, &newSet); - store_address_t storeId; - HousekeepingMessage::getUpdateSnapshotSetCommand(&messageSent, &storeId); - ConstAccessorPair accessorPair = tglob::getIpcStoreHandle()->getData(storeId); - REQUIRE(accessorPair.first == retval::CATCH_OK); - const uint8_t* readOnlyPtr = accessorPair.second.data(); - size_t sizeToDeserialize = accessorPair.second.size(); - CHECK(newSet.localPoolVarFloat.value == 0); - CHECK(newSet.localPoolVarUint8 == 0); - CHECK(newSet.localPoolUint16Vec.value[0] == 0); - CHECK(newSet.localPoolUint16Vec.value[1] == 0); - CHECK(newSet.localPoolUint16Vec.value[2] == 0); - /* Fill the dataset and timestamp */ - REQUIRE(snapshot.deSerialize(&readOnlyPtr, &sizeToDeserialize, - SerializeIF::Endianness::MACHINE) == retval::CATCH_OK); - /* Now we check that the snapshot is actually correct */ - CHECK(newSet.localPoolVarFloat.value == Catch::Approx(-12.242)); - CHECK(newSet.localPoolVarUint8 == 5); - CHECK(newSet.localPoolUint16Vec.value[0] == 2); - CHECK(newSet.localPoolUint16Vec.value[1] == 32); - CHECK(newSet.localPoolUint16Vec.value[2] == 42932); + /* Now we check that both times are equal */ + CHECK(cdsShort.pField == timeCdsNow.pField); + CHECK(cdsShort.dayLSB == Catch::Approx(timeCdsNow.dayLSB).margin(1)); + CHECK(cdsShort.dayMSB == Catch::Approx(timeCdsNow.dayMSB).margin(1)); + CHECK(cdsShort.msDay_h == Catch::Approx(timeCdsNow.msDay_h).margin(1)); + CHECK(cdsShort.msDay_hh == Catch::Approx(timeCdsNow.msDay_hh).margin(1)); + CHECK(cdsShort.msDay_l == Catch::Approx(timeCdsNow.msDay_l).margin(1)); + CHECK(cdsShort.msDay_ll == Catch::Approx(timeCdsNow.msDay_ll).margin(5)); + } - /* Now we check that both times are equal */ - CHECK(cdsShort.pField == timeCdsNow.pField); - CHECK(cdsShort.dayLSB == Catch::Approx(timeCdsNow.dayLSB).margin(1)); - CHECK(cdsShort.dayMSB == Catch::Approx(timeCdsNow.dayMSB).margin(1)); - CHECK(cdsShort.msDay_h == Catch::Approx(timeCdsNow.msDay_h).margin(1)); - CHECK(cdsShort.msDay_hh == Catch::Approx(timeCdsNow.msDay_hh).margin(1)); - CHECK(cdsShort.msDay_l == Catch::Approx(timeCdsNow.msDay_l).margin(1)); - CHECK(cdsShort.msDay_ll == Catch::Approx(timeCdsNow.msDay_ll).margin(5)); + SECTION("VariableSnapshotTest") { + /* Acquire subscription interface */ + ProvidesDataPoolSubscriptionIF* subscriptionIF = poolOwner->getSubscriptionInterface(); + REQUIRE(subscriptionIF != nullptr); + + /* Subscribe for variable snapshot */ + REQUIRE(poolOwner->subscribeWrapperVariableSnapshot(lpool::uint8VarId) == retval::CATCH_OK); + auto poolVar = + dynamic_cast*>(poolOwner->getPoolObjectHandle(lpool::uint8VarId)); + REQUIRE(poolVar != nullptr); + + { + PoolReadGuard rg(poolVar); + CHECK(rg.getReadResult() == retval::CATCH_OK); + poolVar->value = 25; } - SECTION("VariableSnapshotTest") { - /* Acquire subscription interface */ - ProvidesDataPoolSubscriptionIF* subscriptionIF = poolOwner->getSubscriptionInterface(); - REQUIRE(subscriptionIF != nullptr); + poolVar->setChanged(true); - /* Subscribe for variable snapshot */ - REQUIRE(poolOwner->subscribeWrapperVariableSnapshot(lpool::uint8VarId) == retval::CATCH_OK); - auto poolVar = dynamic_cast*>( - poolOwner->getPoolObjectHandle(lpool::uint8VarId)); - REQUIRE(poolVar != nullptr); + /* Store current time, we are going to check the (approximate) time equality later */ + CCSDSTime::CDS_short timeCdsNow; + timeval now; + Clock::getClock_timeval(&now); + CCSDSTime::convertToCcsds(&timeCdsNow, &now); - { - PoolReadGuard rg(poolVar); - CHECK(rg.getReadResult() == retval::CATCH_OK); - poolVar->value = 25; - } + REQUIRE(poolOwner->poolManager.performHkOperation() == retval::CATCH_OK); - poolVar->setChanged(true); + /* Check update snapshot was sent. */ + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(messagesSent == 1); - /* Store current time, we are going to check the (approximate) time equality later */ - CCSDSTime::CDS_short timeCdsNow; - timeval now; - Clock::getClock_timeval(&now); - CCSDSTime::convertToCcsds(&timeCdsNow, &now); + /* Should have been reset. */ + CHECK(poolVar->hasChanged() == false); + REQUIRE(mqMock->receiveMessage(&messageSent) == retval::CATCH_OK); + CHECK(messageSent.getCommand() == + static_cast(HousekeepingMessage::UPDATE_SNAPSHOT_VARIABLE)); + /* Now we deserialize the snapshot into a new dataset instance */ + CCSDSTime::CDS_short cdsShort; + lp_var_t varCopy = lp_var_t(lpool::uint8VarGpid); + HousekeepingSnapshot snapshot(&cdsShort, &varCopy); + store_address_t storeId; + HousekeepingMessage::getUpdateSnapshotVariableCommand(&messageSent, &storeId); + ConstAccessorPair accessorPair = tglob::getIpcStoreHandle()->getData(storeId); + REQUIRE(accessorPair.first == retval::CATCH_OK); + const uint8_t* readOnlyPtr = accessorPair.second.data(); + size_t sizeToDeserialize = accessorPair.second.size(); + CHECK(varCopy.value == 0); + /* Fill the dataset and timestamp */ + REQUIRE(snapshot.deSerialize(&readOnlyPtr, &sizeToDeserialize, + SerializeIF::Endianness::MACHINE) == retval::CATCH_OK); + CHECK(varCopy.value == 25); - REQUIRE(poolOwner->poolManager.performHkOperation() == retval::CATCH_OK); + /* Now we check that both times are equal */ + CHECK(cdsShort.pField == timeCdsNow.pField); + CHECK(cdsShort.dayLSB == Catch::Approx(timeCdsNow.dayLSB).margin(1)); + CHECK(cdsShort.dayMSB == Catch::Approx(timeCdsNow.dayMSB).margin(1)); + CHECK(cdsShort.msDay_h == Catch::Approx(timeCdsNow.msDay_h).margin(1)); + CHECK(cdsShort.msDay_hh == Catch::Approx(timeCdsNow.msDay_hh).margin(1)); + CHECK(cdsShort.msDay_l == Catch::Approx(timeCdsNow.msDay_l).margin(1)); + CHECK(cdsShort.msDay_ll == Catch::Approx(timeCdsNow.msDay_ll).margin(5)); + } - /* Check update snapshot was sent. */ - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(messagesSent == 1); + SECTION("VariableNotificationTest") { + /* Acquire subscription interface */ + ProvidesDataPoolSubscriptionIF* subscriptionIF = poolOwner->getSubscriptionInterface(); + REQUIRE(subscriptionIF != nullptr); - /* Should have been reset. */ - CHECK(poolVar->hasChanged() == false); - REQUIRE(mqMock->receiveMessage(&messageSent) == retval::CATCH_OK); - CHECK(messageSent.getCommand() == static_cast( - HousekeepingMessage::UPDATE_SNAPSHOT_VARIABLE)); - /* Now we deserialize the snapshot into a new dataset instance */ - CCSDSTime::CDS_short cdsShort; - lp_var_t varCopy = lp_var_t(lpool::uint8VarGpid); - HousekeepingSnapshot snapshot(&cdsShort, &varCopy); - store_address_t storeId; - HousekeepingMessage::getUpdateSnapshotVariableCommand(&messageSent, &storeId); - ConstAccessorPair accessorPair = tglob::getIpcStoreHandle()->getData(storeId); - REQUIRE(accessorPair.first == retval::CATCH_OK); - const uint8_t* readOnlyPtr = accessorPair.second.data(); - size_t sizeToDeserialize = accessorPair.second.size(); - CHECK(varCopy.value == 0); - /* Fill the dataset and timestamp */ - REQUIRE(snapshot.deSerialize(&readOnlyPtr, &sizeToDeserialize, - SerializeIF::Endianness::MACHINE) == retval::CATCH_OK); - CHECK(varCopy.value == 25); + /* Subscribe for variable update */ + REQUIRE(poolOwner->subscribeWrapperVariableUpdate(lpool::uint8VarId) == retval::CATCH_OK); + lp_var_t* poolVar = + dynamic_cast*>(poolOwner->getPoolObjectHandle(lpool::uint8VarId)); + REQUIRE(poolVar != nullptr); + poolVar->setChanged(true); + REQUIRE(poolVar->hasChanged() == true); + REQUIRE(poolOwner->poolManager.performHkOperation() == retval::CATCH_OK); - /* Now we check that both times are equal */ - CHECK(cdsShort.pField == timeCdsNow.pField); - CHECK(cdsShort.dayLSB == Catch::Approx(timeCdsNow.dayLSB).margin(1)); - CHECK(cdsShort.dayMSB == Catch::Approx(timeCdsNow.dayMSB).margin(1)); - CHECK(cdsShort.msDay_h == Catch::Approx(timeCdsNow.msDay_h).margin(1)); - CHECK(cdsShort.msDay_hh == Catch::Approx(timeCdsNow.msDay_hh).margin(1)); - CHECK(cdsShort.msDay_l == Catch::Approx(timeCdsNow.msDay_l).margin(1)); - CHECK(cdsShort.msDay_ll == Catch::Approx(timeCdsNow.msDay_ll).margin(5)); - } + /* Check update notification was sent. */ + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(messagesSent == 1); + /* Should have been reset. */ + CHECK(poolVar->hasChanged() == false); + REQUIRE(mqMock->receiveMessage(&messageSent) == retval::CATCH_OK); + CHECK(messageSent.getCommand() == + static_cast(HousekeepingMessage::UPDATE_NOTIFICATION_VARIABLE)); + /* Now subscribe for the dataset update (HK and update) again with subscription interface */ + REQUIRE(subscriptionIF->subscribeForSetUpdateMessage(lpool::testSetId, objects::NO_OBJECT, + objects::HK_RECEIVER_MOCK, + false) == retval::CATCH_OK); + REQUIRE(poolOwner->subscribeWrapperSetUpdateHk() == retval::CATCH_OK); - SECTION("VariableNotificationTest") { - /* Acquire subscription interface */ - ProvidesDataPoolSubscriptionIF* subscriptionIF = poolOwner->getSubscriptionInterface(); - REQUIRE(subscriptionIF != nullptr); - - /* Subscribe for variable update */ - REQUIRE(poolOwner->subscribeWrapperVariableUpdate(lpool::uint8VarId) == - retval::CATCH_OK); - lp_var_t* poolVar = dynamic_cast*>( - poolOwner->getPoolObjectHandle(lpool::uint8VarId)); - REQUIRE(poolVar != nullptr); - poolVar->setChanged(true); - REQUIRE(poolVar->hasChanged() == true); - REQUIRE(poolOwner->poolManager.performHkOperation() == retval::CATCH_OK); - - /* Check update notification was sent. */ - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(messagesSent == 1); - /* Should have been reset. */ - CHECK(poolVar->hasChanged() == false); - REQUIRE(mqMock->receiveMessage(&messageSent) == retval::CATCH_OK); - CHECK(messageSent.getCommand() == static_cast( - HousekeepingMessage::UPDATE_NOTIFICATION_VARIABLE)); - /* Now subscribe for the dataset update (HK and update) again with subscription interface */ - REQUIRE(subscriptionIF->subscribeForSetUpdateMessage(lpool::testSetId, - objects::NO_OBJECT, objects::HK_RECEIVER_MOCK, false) == retval::CATCH_OK); - REQUIRE(poolOwner->subscribeWrapperSetUpdateHk() == retval::CATCH_OK); - - poolOwner->dataset.setChanged(true); - REQUIRE(poolOwner->poolManager.performHkOperation() == retval::CATCH_OK); - /* Now two messages should be sent. */ - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(messagesSent == 2); - mqMock->clearMessages(true); - - poolOwner->dataset.setChanged(true); - poolVar->setChanged(true); - REQUIRE(poolOwner->poolManager.performHkOperation() == retval::CATCH_OK); - /* Now three messages should be sent. */ - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(messagesSent == 3); - REQUIRE(mqMock->receiveMessage(&messageSent) == retval::CATCH_OK); - CHECK(messageSent.getCommand() == static_cast( - HousekeepingMessage::UPDATE_NOTIFICATION_VARIABLE)); - REQUIRE(mqMock->receiveMessage(&messageSent) == retval::CATCH_OK); - CHECK(messageSent.getCommand() == static_cast( - HousekeepingMessage::UPDATE_NOTIFICATION_SET)); - REQUIRE(mqMock->receiveMessage(&messageSent) == retval::CATCH_OK); - CHECK(messageSent.getCommand() == static_cast( - HousekeepingMessage::HK_REPORT)); - CommandMessageCleaner::clearCommandMessage(&messageSent); - REQUIRE(mqMock->receiveMessage(&messageSent) == static_cast(MessageQueueIF::EMPTY)); - } - - SECTION("PeriodicHKAndMessaging") { - /* Now we subcribe for a HK periodic generation. Even when it's difficult to simulate - the temporal behaviour correctly the HK manager should generate a HK packet - immediately and the periodic helper depends on HK op function calls anyway instead of - using the clock, so we could also just call performHkOperation multiple times */ - REQUIRE(poolOwner->subscribePeriodicHk(true) == retval::CATCH_OK); - REQUIRE(poolOwner->poolManager.performHkOperation() == retval::CATCH_OK); - /* Now HK packet should be sent as message immediately. */ - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(messagesSent == 1); - CHECK(mqMock->popMessage() == retval::CATCH_OK); - - LocalPoolDataSetBase* setHandle = poolOwner->getDataSetHandle(lpool::testSid); - REQUIRE(setHandle != nullptr); - CHECK(poolOwner->poolManager.generateHousekeepingPacket(lpool::testSid, - setHandle, false) == retval::CATCH_OK); - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(messagesSent == 1); - CHECK(mqMock->popMessage() == retval::CATCH_OK); - - CHECK(setHandle->getReportingEnabled() == true); - CommandMessage hkCmd; - HousekeepingMessage::setToggleReportingCommand(&hkCmd, lpool::testSid, false, false); - CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); - CHECK(setHandle->getReportingEnabled() == false); - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(messagesSent == 1); - CHECK(mqMock->popMessage() == retval::CATCH_OK); - - HousekeepingMessage::setToggleReportingCommand(&hkCmd, lpool::testSid, true, false); - CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); - CHECK(setHandle->getReportingEnabled() == true); - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(mqMock->popMessage() == retval::CATCH_OK); - - HousekeepingMessage::setToggleReportingCommand(&hkCmd, lpool::testSid, false, false); - CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); - CHECK(setHandle->getReportingEnabled() == false); - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(mqMock->popMessage() == retval::CATCH_OK); - - HousekeepingMessage::setCollectionIntervalModificationCommand(&hkCmd, - lpool::testSid, 0.4, false); - CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); - /* For non-diagnostics and a specified minimum frequency of 0.2 seconds, the - resulting collection interval should be 1.0 second */ - CHECK(poolOwner->dataset.getCollectionInterval() == 1.0); - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(messagesSent == 1); - CHECK(mqMock->popMessage() == retval::CATCH_OK); - - HousekeepingMessage::setStructureReportingCommand(&hkCmd, lpool::testSid, false); - REQUIRE(poolOwner->poolManager.performHkOperation() == retval::CATCH_OK); - CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); - /* Now HK packet should be sent as message. */ - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(messagesSent == 1); - CHECK(mqMock->popMessage() == retval::CATCH_OK); - - HousekeepingMessage::setOneShotReportCommand(&hkCmd, lpool::testSid, false); - CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(messagesSent == 1); - CHECK(mqMock->popMessage() == retval::CATCH_OK); - - HousekeepingMessage::setUpdateNotificationSetCommand(&hkCmd, lpool::testSid); - sid_t sidToCheck; - store_address_t storeId; - CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); - CHECK(poolOwner->changedDataSetCallbackWasCalled(sidToCheck, storeId) == true); - CHECK(sidToCheck == lpool::testSid); - - /* Now we test the handling is the dataset is set to diagnostic */ - poolOwner->dataset.setDiagnostic(true); - - HousekeepingMessage::setStructureReportingCommand(&hkCmd, lpool::testSid, false); - CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == - static_cast(LocalDataPoolManager::WRONG_HK_PACKET_TYPE)); - /* We still expect a failure message being sent */ - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(messagesSent == 1); - CHECK(mqMock->popMessage() == retval::CATCH_OK); - - HousekeepingMessage::setCollectionIntervalModificationCommand(&hkCmd, - lpool::testSid, 0.4, false); - CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == - static_cast(LocalDataPoolManager::WRONG_HK_PACKET_TYPE)); - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(messagesSent == 1); - CHECK(mqMock->popMessage() == retval::CATCH_OK); - - HousekeepingMessage::setStructureReportingCommand(&hkCmd, lpool::testSid, false); - CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == - static_cast(LocalDataPoolManager::WRONG_HK_PACKET_TYPE)); - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(messagesSent == 1); - CHECK(mqMock->popMessage() == retval::CATCH_OK); - - HousekeepingMessage::setStructureReportingCommand(&hkCmd, lpool::testSid, true); - CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(messagesSent == 1); - CHECK(mqMock->popMessage() == retval::CATCH_OK); - - HousekeepingMessage::setCollectionIntervalModificationCommand(&hkCmd, lpool::testSid, 0.4, - true); - CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(messagesSent == 1); - CHECK(mqMock->popMessage() == retval::CATCH_OK); - - HousekeepingMessage::setToggleReportingCommand(&hkCmd, lpool::testSid, true, true); - CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(messagesSent == 1); - CHECK(mqMock->popMessage() == retval::CATCH_OK); - - HousekeepingMessage::setToggleReportingCommand(&hkCmd, lpool::testSid, false, true); - CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(messagesSent == 1); - CHECK(mqMock->popMessage() == retval::CATCH_OK); - - HousekeepingMessage::setOneShotReportCommand(&hkCmd, lpool::testSid, false); - CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == - static_cast(LocalDataPoolManager::WRONG_HK_PACKET_TYPE)); - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(messagesSent == 1); - CHECK(mqMock->popMessage() == retval::CATCH_OK); - - HousekeepingMessage::setOneShotReportCommand(&hkCmd, lpool::testSid, true); - CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); - REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); - CHECK(messagesSent == 1); - CHECK(mqMock->popMessage() == retval::CATCH_OK); - - HousekeepingMessage::setUpdateNotificationVariableCommand(&hkCmd, lpool::uint8VarGpid); - gp_id_t gpidToCheck; - CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); - CHECK(poolOwner->changedVariableCallbackWasCalled(gpidToCheck, storeId) == true); - CHECK(gpidToCheck == lpool::uint8VarGpid); - - HousekeepingMessage::setUpdateSnapshotSetCommand(&hkCmd, lpool::testSid, - storeId::INVALID_STORE_ADDRESS); - CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); - CHECK(poolOwner->changedDataSetCallbackWasCalled(sidToCheck, storeId) == true); - CHECK(sidToCheck == lpool::testSid); - - HousekeepingMessage::setUpdateSnapshotVariableCommand(&hkCmd, lpool::uint8VarGpid, - storeId::INVALID_STORE_ADDRESS); - CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); - CHECK(poolOwner->changedVariableCallbackWasCalled(gpidToCheck, storeId) == true); - CHECK(gpidToCheck == lpool::uint8VarGpid); - - poolOwner->poolManager.printPoolEntry(lpool::uint8VarId); - - } - - /* we need to reset the subscription list because the pool owner - is a global object. */ - CHECK(poolOwner->reset() == retval::CATCH_OK); + poolOwner->dataset.setChanged(true); + REQUIRE(poolOwner->poolManager.performHkOperation() == retval::CATCH_OK); + /* Now two messages should be sent. */ + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(messagesSent == 2); mqMock->clearMessages(true); -} + poolOwner->dataset.setChanged(true); + poolVar->setChanged(true); + REQUIRE(poolOwner->poolManager.performHkOperation() == retval::CATCH_OK); + /* Now three messages should be sent. */ + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(messagesSent == 3); + REQUIRE(mqMock->receiveMessage(&messageSent) == retval::CATCH_OK); + CHECK(messageSent.getCommand() == + static_cast(HousekeepingMessage::UPDATE_NOTIFICATION_VARIABLE)); + REQUIRE(mqMock->receiveMessage(&messageSent) == retval::CATCH_OK); + CHECK(messageSent.getCommand() == + static_cast(HousekeepingMessage::UPDATE_NOTIFICATION_SET)); + REQUIRE(mqMock->receiveMessage(&messageSent) == retval::CATCH_OK); + CHECK(messageSent.getCommand() == static_cast(HousekeepingMessage::HK_REPORT)); + CommandMessageCleaner::clearCommandMessage(&messageSent); + REQUIRE(mqMock->receiveMessage(&messageSent) == static_cast(MessageQueueIF::EMPTY)); + } + + SECTION("PeriodicHKAndMessaging") { + /* Now we subcribe for a HK periodic generation. Even when it's difficult to simulate + the temporal behaviour correctly the HK manager should generate a HK packet + immediately and the periodic helper depends on HK op function calls anyway instead of + using the clock, so we could also just call performHkOperation multiple times */ + REQUIRE(poolOwner->subscribePeriodicHk(true) == retval::CATCH_OK); + REQUIRE(poolOwner->poolManager.performHkOperation() == retval::CATCH_OK); + /* Now HK packet should be sent as message immediately. */ + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(messagesSent == 1); + CHECK(mqMock->popMessage() == retval::CATCH_OK); + + LocalPoolDataSetBase* setHandle = poolOwner->getDataSetHandle(lpool::testSid); + REQUIRE(setHandle != nullptr); + CHECK(poolOwner->poolManager.generateHousekeepingPacket(lpool::testSid, setHandle, false) == + retval::CATCH_OK); + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(messagesSent == 1); + CHECK(mqMock->popMessage() == retval::CATCH_OK); + + CHECK(setHandle->getReportingEnabled() == true); + CommandMessage hkCmd; + HousekeepingMessage::setToggleReportingCommand(&hkCmd, lpool::testSid, false, false); + CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); + CHECK(setHandle->getReportingEnabled() == false); + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(messagesSent == 1); + CHECK(mqMock->popMessage() == retval::CATCH_OK); + + HousekeepingMessage::setToggleReportingCommand(&hkCmd, lpool::testSid, true, false); + CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); + CHECK(setHandle->getReportingEnabled() == true); + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(mqMock->popMessage() == retval::CATCH_OK); + + HousekeepingMessage::setToggleReportingCommand(&hkCmd, lpool::testSid, false, false); + CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); + CHECK(setHandle->getReportingEnabled() == false); + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(mqMock->popMessage() == retval::CATCH_OK); + + HousekeepingMessage::setCollectionIntervalModificationCommand(&hkCmd, lpool::testSid, 0.4, + false); + CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); + /* For non-diagnostics and a specified minimum frequency of 0.2 seconds, the + resulting collection interval should be 1.0 second */ + CHECK(poolOwner->dataset.getCollectionInterval() == 1.0); + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(messagesSent == 1); + CHECK(mqMock->popMessage() == retval::CATCH_OK); + + HousekeepingMessage::setStructureReportingCommand(&hkCmd, lpool::testSid, false); + REQUIRE(poolOwner->poolManager.performHkOperation() == retval::CATCH_OK); + CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); + /* Now HK packet should be sent as message. */ + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(messagesSent == 1); + CHECK(mqMock->popMessage() == retval::CATCH_OK); + + HousekeepingMessage::setOneShotReportCommand(&hkCmd, lpool::testSid, false); + CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(messagesSent == 1); + CHECK(mqMock->popMessage() == retval::CATCH_OK); + + HousekeepingMessage::setUpdateNotificationSetCommand(&hkCmd, lpool::testSid); + sid_t sidToCheck; + store_address_t storeId; + CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); + CHECK(poolOwner->changedDataSetCallbackWasCalled(sidToCheck, storeId) == true); + CHECK(sidToCheck == lpool::testSid); + + /* Now we test the handling is the dataset is set to diagnostic */ + poolOwner->dataset.setDiagnostic(true); + + HousekeepingMessage::setStructureReportingCommand(&hkCmd, lpool::testSid, false); + CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == + static_cast(LocalDataPoolManager::WRONG_HK_PACKET_TYPE)); + /* We still expect a failure message being sent */ + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(messagesSent == 1); + CHECK(mqMock->popMessage() == retval::CATCH_OK); + + HousekeepingMessage::setCollectionIntervalModificationCommand(&hkCmd, lpool::testSid, 0.4, + false); + CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == + static_cast(LocalDataPoolManager::WRONG_HK_PACKET_TYPE)); + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(messagesSent == 1); + CHECK(mqMock->popMessage() == retval::CATCH_OK); + + HousekeepingMessage::setStructureReportingCommand(&hkCmd, lpool::testSid, false); + CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == + static_cast(LocalDataPoolManager::WRONG_HK_PACKET_TYPE)); + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(messagesSent == 1); + CHECK(mqMock->popMessage() == retval::CATCH_OK); + + HousekeepingMessage::setStructureReportingCommand(&hkCmd, lpool::testSid, true); + CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(messagesSent == 1); + CHECK(mqMock->popMessage() == retval::CATCH_OK); + + HousekeepingMessage::setCollectionIntervalModificationCommand(&hkCmd, lpool::testSid, 0.4, + true); + CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(messagesSent == 1); + CHECK(mqMock->popMessage() == retval::CATCH_OK); + + HousekeepingMessage::setToggleReportingCommand(&hkCmd, lpool::testSid, true, true); + CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(messagesSent == 1); + CHECK(mqMock->popMessage() == retval::CATCH_OK); + + HousekeepingMessage::setToggleReportingCommand(&hkCmd, lpool::testSid, false, true); + CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(messagesSent == 1); + CHECK(mqMock->popMessage() == retval::CATCH_OK); + + HousekeepingMessage::setOneShotReportCommand(&hkCmd, lpool::testSid, false); + CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == + static_cast(LocalDataPoolManager::WRONG_HK_PACKET_TYPE)); + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(messagesSent == 1); + CHECK(mqMock->popMessage() == retval::CATCH_OK); + + HousekeepingMessage::setOneShotReportCommand(&hkCmd, lpool::testSid, true); + CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); + REQUIRE(mqMock->wasMessageSent(&messagesSent) == true); + CHECK(messagesSent == 1); + CHECK(mqMock->popMessage() == retval::CATCH_OK); + + HousekeepingMessage::setUpdateNotificationVariableCommand(&hkCmd, lpool::uint8VarGpid); + gp_id_t gpidToCheck; + CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); + CHECK(poolOwner->changedVariableCallbackWasCalled(gpidToCheck, storeId) == true); + CHECK(gpidToCheck == lpool::uint8VarGpid); + + HousekeepingMessage::setUpdateSnapshotSetCommand(&hkCmd, lpool::testSid, + storeId::INVALID_STORE_ADDRESS); + CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); + CHECK(poolOwner->changedDataSetCallbackWasCalled(sidToCheck, storeId) == true); + CHECK(sidToCheck == lpool::testSid); + + HousekeepingMessage::setUpdateSnapshotVariableCommand(&hkCmd, lpool::uint8VarGpid, + storeId::INVALID_STORE_ADDRESS); + CHECK(poolOwner->poolManager.handleHousekeepingMessage(&hkCmd) == retval::CATCH_OK); + CHECK(poolOwner->changedVariableCallbackWasCalled(gpidToCheck, storeId) == true); + CHECK(gpidToCheck == lpool::uint8VarGpid); + + poolOwner->poolManager.printPoolEntry(lpool::uint8VarId); + } + + /* we need to reset the subscription list because the pool owner + is a global object. */ + CHECK(poolOwner->reset() == retval::CATCH_OK); + mqMock->clearMessages(true); +} diff --git a/tests/src/fsfw_tests/unit/datapoollocal/LocalPoolOwnerBase.cpp b/tests/src/fsfw_tests/unit/datapoollocal/LocalPoolOwnerBase.cpp index 991314a9..6f054893 100644 --- a/tests/src/fsfw_tests/unit/datapoollocal/LocalPoolOwnerBase.cpp +++ b/tests/src/fsfw_tests/unit/datapoollocal/LocalPoolOwnerBase.cpp @@ -1,141 +1,127 @@ #include "LocalPoolOwnerBase.h" -LocalPoolOwnerBase::LocalPoolOwnerBase(object_id_t objectId): - SystemObject(objectId), poolManager(this, messageQueue), - dataset(this, lpool::testSetId) { - messageQueue = new MessageQueueMockBase(); +LocalPoolOwnerBase::LocalPoolOwnerBase(object_id_t objectId) + : SystemObject(objectId), poolManager(this, messageQueue), dataset(this, lpool::testSetId) { + messageQueue = new MessageQueueMockBase(); } LocalPoolOwnerBase::~LocalPoolOwnerBase() { - QueueFactory::instance()->deleteMessageQueue(messageQueue); + QueueFactory::instance()->deleteMessageQueue(messageQueue); } ReturnValue_t LocalPoolOwnerBase::initializeHkManager() { - if(not initialized) { - initialized = true; - return poolManager.initialize(messageQueue); - } - return HasReturnvaluesIF::RETURN_OK; + if (not initialized) { + initialized = true; + return poolManager.initialize(messageQueue); + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t LocalPoolOwnerBase::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, - LocalDataPoolManager &poolManager) { + LocalDataPoolManager &poolManager) { + // Default initialization empty for now. + localDataPoolMap.emplace(lpool::uint8VarId, new PoolEntry({0})); + localDataPoolMap.emplace(lpool::floatVarId, new PoolEntry({0})); + localDataPoolMap.emplace(lpool::uint32VarId, new PoolEntry({0})); - // Default initialization empty for now. - localDataPoolMap.emplace(lpool::uint8VarId, - new PoolEntry({0})); - localDataPoolMap.emplace(lpool::floatVarId, - new PoolEntry({0})); - localDataPoolMap.emplace(lpool::uint32VarId, - new PoolEntry({0})); - - localDataPoolMap.emplace(lpool::uint16Vec3Id, - new PoolEntry({0, 0, 0})); - localDataPoolMap.emplace(lpool::int64Vec2Id, - new PoolEntry({0, 0})); - return HasReturnvaluesIF::RETURN_OK; + localDataPoolMap.emplace(lpool::uint16Vec3Id, new PoolEntry({0, 0, 0})); + localDataPoolMap.emplace(lpool::int64Vec2Id, new PoolEntry({0, 0})); + return HasReturnvaluesIF::RETURN_OK; } -LocalPoolObjectBase* LocalPoolOwnerBase::getPoolObjectHandle(lp_id_t localPoolId) { - if(localPoolId == lpool::uint8VarId) { - return &testUint8; - } - else if(localPoolId == lpool::uint16Vec3Id) { - return &testUint16Vec; - } - else if(localPoolId == lpool::floatVarId) { - return &testFloat; - } - else if(localPoolId == lpool::int64Vec2Id) { - return &testInt64Vec; - } - else if(localPoolId == lpool::uint32VarId) { - return &testUint32; - } - else { - return &testUint8; - } +LocalPoolObjectBase *LocalPoolOwnerBase::getPoolObjectHandle(lp_id_t localPoolId) { + if (localPoolId == lpool::uint8VarId) { + return &testUint8; + } else if (localPoolId == lpool::uint16Vec3Id) { + return &testUint16Vec; + } else if (localPoolId == lpool::floatVarId) { + return &testFloat; + } else if (localPoolId == lpool::int64Vec2Id) { + return &testInt64Vec; + } else if (localPoolId == lpool::uint32VarId) { + return &testUint32; + } else { + return &testUint8; + } } ReturnValue_t LocalPoolOwnerBase::reset() { - resetSubscriptionList(); - ReturnValue_t status = HasReturnvaluesIF::RETURN_OK; - { - PoolReadGuard readHelper(&dataset); - if(readHelper.getReadResult() != HasReturnvaluesIF::RETURN_OK) { - status = readHelper.getReadResult(); - } - dataset.localPoolVarUint8.value = 0; - dataset.localPoolVarFloat.value = 0.0; - dataset.localPoolUint16Vec.value[0] = 0; - dataset.localPoolUint16Vec.value[1] = 0; - dataset.localPoolUint16Vec.value[2] = 0; - dataset.setValidity(false, true); + resetSubscriptionList(); + ReturnValue_t status = HasReturnvaluesIF::RETURN_OK; + { + PoolReadGuard readHelper(&dataset); + if (readHelper.getReadResult() != HasReturnvaluesIF::RETURN_OK) { + status = readHelper.getReadResult(); } + dataset.localPoolVarUint8.value = 0; + dataset.localPoolVarFloat.value = 0.0; + dataset.localPoolUint16Vec.value[0] = 0; + dataset.localPoolUint16Vec.value[1] = 0; + dataset.localPoolUint16Vec.value[2] = 0; + dataset.setValidity(false, true); + } - { - PoolReadGuard readHelper(&testUint32); - if(readHelper.getReadResult() != HasReturnvaluesIF::RETURN_OK) { - status = readHelper.getReadResult(); - } - testUint32.value = 0; - testUint32.setValid(false); + { + PoolReadGuard readHelper(&testUint32); + if (readHelper.getReadResult() != HasReturnvaluesIF::RETURN_OK) { + status = readHelper.getReadResult(); } + testUint32.value = 0; + testUint32.setValid(false); + } - { - PoolReadGuard readHelper(&testInt64Vec); - if(readHelper.getReadResult() != HasReturnvaluesIF::RETURN_OK) { - status = readHelper.getReadResult(); - } - testInt64Vec.value[0] = 0; - testInt64Vec.value[1] = 0; - testInt64Vec.setValid(false); + { + PoolReadGuard readHelper(&testInt64Vec); + if (readHelper.getReadResult() != HasReturnvaluesIF::RETURN_OK) { + status = readHelper.getReadResult(); } - return status; + testInt64Vec.value[0] = 0; + testInt64Vec.value[1] = 0; + testInt64Vec.setValid(false); + } + return status; } bool LocalPoolOwnerBase::changedDataSetCallbackWasCalled(sid_t &sid, store_address_t &storeId) { - bool condition = false; - if(not this->changedDatasetSid.notSet()) { - condition = true; - } - sid = changedDatasetSid; - storeId = storeIdForChangedSet; - this->changedDatasetSid.raw = sid_t::INVALID_SID; - this->storeIdForChangedSet = storeId::INVALID_STORE_ADDRESS; - return condition; + bool condition = false; + if (not this->changedDatasetSid.notSet()) { + condition = true; + } + sid = changedDatasetSid; + storeId = storeIdForChangedSet; + this->changedDatasetSid.raw = sid_t::INVALID_SID; + this->storeIdForChangedSet = storeId::INVALID_STORE_ADDRESS; + return condition; } void LocalPoolOwnerBase::handleChangedDataset(sid_t sid, store_address_t storeId, - bool* clearMessage) { - this->changedDatasetSid = sid; - this->storeIdForChangedSet = storeId; + bool *clearMessage) { + this->changedDatasetSid = sid; + this->storeIdForChangedSet = storeId; } bool LocalPoolOwnerBase::changedVariableCallbackWasCalled(gp_id_t &gpid, store_address_t &storeId) { - bool condition = false; - if(not this->changedPoolVariableGpid.notSet()) { - condition = true; - } - gpid = changedPoolVariableGpid; - storeId = storeIdForChangedVariable; - this->changedPoolVariableGpid.raw = gp_id_t::INVALID_GPID; - this->storeIdForChangedVariable = storeId::INVALID_STORE_ADDRESS; - return condition; + bool condition = false; + if (not this->changedPoolVariableGpid.notSet()) { + condition = true; + } + gpid = changedPoolVariableGpid; + storeId = storeIdForChangedVariable; + this->changedPoolVariableGpid.raw = gp_id_t::INVALID_GPID; + this->storeIdForChangedVariable = storeId::INVALID_STORE_ADDRESS; + return condition; } ReturnValue_t LocalPoolOwnerBase::initializeHkManagerAfterTaskCreation() { - if(not initializedAfterTaskCreation) { - initializedAfterTaskCreation = true; - return poolManager.initializeAfterTaskCreation(); - } - return HasReturnvaluesIF::RETURN_OK; - + if (not initializedAfterTaskCreation) { + initializedAfterTaskCreation = true; + return poolManager.initializeAfterTaskCreation(); + } + return HasReturnvaluesIF::RETURN_OK; } void LocalPoolOwnerBase::handleChangedPoolVariable(gp_id_t globPoolId, store_address_t storeId, - bool* clearMessage) { - this->changedPoolVariableGpid = globPoolId; - this->storeIdForChangedVariable = storeId; + bool *clearMessage) { + this->changedPoolVariableGpid = globPoolId; + this->storeIdForChangedVariable = storeId; } - diff --git a/tests/src/fsfw_tests/unit/datapoollocal/LocalPoolOwnerBase.h b/tests/src/fsfw_tests/unit/datapoollocal/LocalPoolOwnerBase.h index 1f532568..0bcebc00 100644 --- a/tests/src/fsfw_tests/unit/datapoollocal/LocalPoolOwnerBase.h +++ b/tests/src/fsfw_tests/unit/datapoollocal/LocalPoolOwnerBase.h @@ -1,17 +1,17 @@ #ifndef FSFW_UNITTEST_TESTS_DATAPOOLLOCAL_LOCALPOOLOWNERBASE_H_ #define FSFW_UNITTEST_TESTS_DATAPOOLLOCAL_LOCALPOOLOWNERBASE_H_ -#include "tests/TestsConfig.h" -#include "../mocks/MessageQueueMockBase.h" - +#include #include #include -#include #include #include -#include #include -#include +#include +#include + +#include "../mocks/MessageQueueMockBase.h" +#include "tests/TestsConfig.h" namespace lpool { static constexpr lp_id_t uint8VarId = 0; @@ -30,159 +30,135 @@ static const gp_id_t floatVarGpid = gp_id_t(objects::TEST_LOCAL_POOL_OWNER_BASE, static const gp_id_t uint32Gpid = gp_id_t(objects::TEST_LOCAL_POOL_OWNER_BASE, uint32VarId); static const gp_id_t uint16Vec3Gpid = gp_id_t(objects::TEST_LOCAL_POOL_OWNER_BASE, uint16Vec3Id); static const gp_id_t uint64Vec2Id = gp_id_t(objects::TEST_LOCAL_POOL_OWNER_BASE, int64Vec2Id); -} +} // namespace lpool +class LocalPoolStaticTestDataSet : public StaticLocalDataSet<3> { + public: + LocalPoolStaticTestDataSet() : StaticLocalDataSet(lpool::testSid) {} -class LocalPoolStaticTestDataSet: public StaticLocalDataSet<3> { -public: - LocalPoolStaticTestDataSet(): - StaticLocalDataSet(lpool::testSid) { + LocalPoolStaticTestDataSet(HasLocalDataPoolIF* owner, uint32_t setId) + : StaticLocalDataSet(owner, setId) {} - } + lp_var_t localPoolVarUint8 = lp_var_t(lpool::uint8VarGpid, this); + lp_var_t localPoolVarFloat = lp_var_t(lpool::floatVarGpid, this); + lp_vec_t localPoolUint16Vec = lp_vec_t(lpool::uint16Vec3Gpid, this); - LocalPoolStaticTestDataSet(HasLocalDataPoolIF* owner, uint32_t setId): - StaticLocalDataSet(owner, setId) { - } - - lp_var_t localPoolVarUint8 = lp_var_t(lpool::uint8VarGpid, this); - lp_var_t localPoolVarFloat = lp_var_t(lpool::floatVarGpid, this); - lp_vec_t localPoolUint16Vec = lp_vec_t(lpool::uint16Vec3Gpid, this); - -private: + private: }; -class LocalPoolTestDataSet: public LocalDataSet { -public: - LocalPoolTestDataSet(): - LocalDataSet(lpool::testSid, lpool::dataSetMaxVariables) {} +class LocalPoolTestDataSet : public LocalDataSet { + public: + LocalPoolTestDataSet() : LocalDataSet(lpool::testSid, lpool::dataSetMaxVariables) {} - LocalPoolTestDataSet(HasLocalDataPoolIF* owner, uint32_t setId): - LocalDataSet(owner, setId, lpool::dataSetMaxVariables) { - } + LocalPoolTestDataSet(HasLocalDataPoolIF* owner, uint32_t setId) + : LocalDataSet(owner, setId, lpool::dataSetMaxVariables) {} - lp_var_t localPoolVarUint8 = lp_var_t(lpool::uint8VarGpid, this); - lp_var_t localPoolVarFloat = lp_var_t(lpool::floatVarGpid, this); - lp_vec_t localPoolUint16Vec = lp_vec_t(lpool::uint16Vec3Gpid, this); + lp_var_t localPoolVarUint8 = lp_var_t(lpool::uint8VarGpid, this); + lp_var_t localPoolVarFloat = lp_var_t(lpool::floatVarGpid, this); + lp_vec_t localPoolUint16Vec = lp_vec_t(lpool::uint16Vec3Gpid, this); - void setDiagnostic(bool isDiagnostic) { - LocalPoolDataSetBase::setDiagnostic(isDiagnostic); - } -private: + void setDiagnostic(bool isDiagnostic) { LocalPoolDataSetBase::setDiagnostic(isDiagnostic); } + + private: }; +class LocalPoolOwnerBase : public SystemObject, public HasLocalDataPoolIF { + public: + LocalPoolOwnerBase(object_id_t objectId = objects::TEST_LOCAL_POOL_OWNER_BASE); -class LocalPoolOwnerBase: public SystemObject, public HasLocalDataPoolIF { -public: - LocalPoolOwnerBase(object_id_t objectId = objects::TEST_LOCAL_POOL_OWNER_BASE); + ~LocalPoolOwnerBase(); - ~LocalPoolOwnerBase(); + object_id_t getObjectId() const override { return SystemObject::getObjectId(); } - object_id_t getObjectId() const override { - return SystemObject::getObjectId(); - } + ReturnValue_t initializeHkManager(); - ReturnValue_t initializeHkManager(); + ReturnValue_t initializeHkManagerAfterTaskCreation(); - ReturnValue_t initializeHkManagerAfterTaskCreation(); + /** Command queue for housekeeping messages. */ + MessageQueueId_t getCommandQueue() const override { return messageQueue->getId(); } - /** Command queue for housekeeping messages. */ - MessageQueueId_t getCommandQueue() const override { - return messageQueue->getId(); - } + // This is called by initializeAfterTaskCreation of the HK manager. + virtual ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) override; - // This is called by initializeAfterTaskCreation of the HK manager. - virtual ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, - LocalDataPoolManager& poolManager) override; + LocalDataPoolManager* getHkManagerHandle() override { return &poolManager; } - LocalDataPoolManager* getHkManagerHandle() override { - return &poolManager; - } + dur_millis_t getPeriodicOperationFrequency() const override { return 200; } - dur_millis_t getPeriodicOperationFrequency() const override { - return 200; - } + /** + * This function is used by the pool manager to get a valid dataset + * from a SID + * @param sid Corresponding structure ID + * @return + */ + virtual LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override { return &dataset; } - /** - * This function is used by the pool manager to get a valid dataset - * from a SID - * @param sid Corresponding structure ID - * @return - */ - virtual LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override { - return &dataset; - } + virtual LocalPoolObjectBase* getPoolObjectHandle(lp_id_t localPoolId) override; - virtual LocalPoolObjectBase* getPoolObjectHandle(lp_id_t localPoolId) override; + MessageQueueMockBase* getMockQueueHandle() const { + return dynamic_cast(messageQueue); + } - MessageQueueMockBase* getMockQueueHandle() const { - return dynamic_cast(messageQueue); - } + ReturnValue_t subscribePeriodicHk(bool enableReporting) { + return poolManager.subscribeForPeriodicPacket(lpool::testSid, enableReporting, 0.2, false); + } - ReturnValue_t subscribePeriodicHk(bool enableReporting) { - return poolManager.subscribeForPeriodicPacket(lpool::testSid, enableReporting, 0.2, false); - } + ReturnValue_t subscribeWrapperSetUpdate() { + return poolManager.subscribeForSetUpdateMessage(lpool::testSetId, objects::NO_OBJECT, + objects::HK_RECEIVER_MOCK, false); + } - ReturnValue_t subscribeWrapperSetUpdate() { - return poolManager.subscribeForSetUpdateMessage(lpool::testSetId, - objects::NO_OBJECT, objects::HK_RECEIVER_MOCK, false); - } + ReturnValue_t subscribeWrapperSetUpdateSnapshot() { + return poolManager.subscribeForSetUpdateMessage(lpool::testSetId, objects::NO_OBJECT, + objects::HK_RECEIVER_MOCK, true); + } - ReturnValue_t subscribeWrapperSetUpdateSnapshot() { - return poolManager.subscribeForSetUpdateMessage(lpool::testSetId, - objects::NO_OBJECT, objects::HK_RECEIVER_MOCK, true); - } + ReturnValue_t subscribeWrapperSetUpdateHk(bool diagnostics = false) { + return poolManager.subscribeForUpdatePacket(lpool::testSid, diagnostics, false, + objects::HK_RECEIVER_MOCK); + } - ReturnValue_t subscribeWrapperSetUpdateHk(bool diagnostics = false) { - return poolManager.subscribeForUpdatePacket(lpool::testSid, diagnostics, - false, objects::HK_RECEIVER_MOCK); - } + ReturnValue_t subscribeWrapperVariableUpdate(lp_id_t localPoolId) { + return poolManager.subscribeForVariableUpdateMessage(localPoolId, MessageQueueIF::NO_QUEUE, + objects::HK_RECEIVER_MOCK, false); + } - ReturnValue_t subscribeWrapperVariableUpdate(lp_id_t localPoolId) { - return poolManager.subscribeForVariableUpdateMessage(localPoolId, - MessageQueueIF::NO_QUEUE, objects::HK_RECEIVER_MOCK, false); - } + ReturnValue_t subscribeWrapperVariableSnapshot(lp_id_t localPoolId) { + return poolManager.subscribeForVariableUpdateMessage(localPoolId, MessageQueueIF::NO_QUEUE, + objects::HK_RECEIVER_MOCK, true); + } - ReturnValue_t subscribeWrapperVariableSnapshot(lp_id_t localPoolId) { - return poolManager.subscribeForVariableUpdateMessage(localPoolId, - MessageQueueIF::NO_QUEUE, objects::HK_RECEIVER_MOCK, true); - } + ReturnValue_t reset(); - ReturnValue_t reset(); + void resetSubscriptionList() { poolManager.clearReceiversList(); } - void resetSubscriptionList() { - poolManager.clearReceiversList(); - } + bool changedDataSetCallbackWasCalled(sid_t& sid, store_address_t& storeId); + bool changedVariableCallbackWasCalled(gp_id_t& gpid, store_address_t& storeId); - bool changedDataSetCallbackWasCalled(sid_t& sid, store_address_t& storeId); - bool changedVariableCallbackWasCalled(gp_id_t& gpid, store_address_t& storeId); + LocalDataPoolManager poolManager; + LocalPoolTestDataSet dataset; - LocalDataPoolManager poolManager; - LocalPoolTestDataSet dataset; -private: + private: + void handleChangedDataset(sid_t sid, store_address_t storeId, bool* clearMessage) override; + sid_t changedDatasetSid; + store_address_t storeIdForChangedSet; - void handleChangedDataset(sid_t sid, store_address_t storeId, bool* clearMessage) override; - sid_t changedDatasetSid; - store_address_t storeIdForChangedSet; + void handleChangedPoolVariable(gp_id_t globPoolId, store_address_t storeId, + bool* clearMessage) override; + gp_id_t changedPoolVariableGpid; + store_address_t storeIdForChangedVariable; - void handleChangedPoolVariable(gp_id_t globPoolId, store_address_t storeId, - bool* clearMessage) override; - gp_id_t changedPoolVariableGpid; - store_address_t storeIdForChangedVariable; + lp_var_t testUint8 = lp_var_t(this, lpool::uint8VarId); + lp_var_t testFloat = lp_var_t(this, lpool::floatVarId); + lp_var_t testUint32 = lp_var_t(this, lpool::uint32VarId); - lp_var_t testUint8 = lp_var_t(this, lpool::uint8VarId); - lp_var_t testFloat = lp_var_t(this, lpool::floatVarId); - lp_var_t testUint32 = lp_var_t(this, lpool::uint32VarId); + lp_vec_t testUint16Vec = lp_vec_t(this, lpool::uint16Vec3Id); + lp_vec_t testInt64Vec = lp_vec_t(this, lpool::int64Vec2Id); - lp_vec_t testUint16Vec = lp_vec_t(this, - lpool::uint16Vec3Id); - lp_vec_t testInt64Vec = lp_vec_t(this, - lpool::int64Vec2Id); - - MessageQueueIF* messageQueue = nullptr; - - bool initialized = false; - bool initializedAfterTaskCreation = false; + MessageQueueIF* messageQueue = nullptr; + bool initialized = false; + bool initializedAfterTaskCreation = false; }; #endif /* FSFW_UNITTEST_TESTS_DATAPOOLLOCAL_LOCALPOOLOWNERBASE_H_ */ diff --git a/tests/src/fsfw_tests/unit/datapoollocal/LocalPoolVariableTest.cpp b/tests/src/fsfw_tests/unit/datapoollocal/LocalPoolVariableTest.cpp index b029ec26..73d51d92 100644 --- a/tests/src/fsfw_tests/unit/datapoollocal/LocalPoolVariableTest.cpp +++ b/tests/src/fsfw_tests/unit/datapoollocal/LocalPoolVariableTest.cpp @@ -1,126 +1,111 @@ -#include "LocalPoolOwnerBase.h" -#include "tests/TestsConfig.h" -#include "fsfw_tests/unit/CatchDefinitions.h" - -#include #include +#include #include -TEST_CASE("LocalPoolVariable" , "[LocPoolVarTest]") { - LocalPoolOwnerBase* poolOwner = ObjectManager::instance()-> - get(objects::TEST_LOCAL_POOL_OWNER_BASE); - REQUIRE(poolOwner != nullptr); - REQUIRE(poolOwner->initializeHkManager() == retval::CATCH_OK); - REQUIRE(poolOwner->initializeHkManagerAfterTaskCreation() == retval::CATCH_OK); +#include "LocalPoolOwnerBase.h" +#include "fsfw_tests/unit/CatchDefinitions.h" +#include "tests/TestsConfig.h" - SECTION("Basic Tests") { - /* very basic test. */ - lp_var_t testVariable = lp_var_t( - objects::TEST_LOCAL_POOL_OWNER_BASE, lpool::uint8VarId); - REQUIRE(testVariable.read() == retval::CATCH_OK); - CHECK(testVariable.value == 0); - testVariable.value = 5; - REQUIRE(testVariable.commit() == retval::CATCH_OK); - REQUIRE(testVariable.read() == retval::CATCH_OK); - REQUIRE(testVariable.value == 5); - CHECK(not testVariable.isValid()); - testVariable.setValid(true); - CHECK(testVariable.isValid()); - CHECK(testVariable.commit(true) == retval::CATCH_OK); +TEST_CASE("LocalPoolVariable", "[LocPoolVarTest]") { + LocalPoolOwnerBase* poolOwner = + ObjectManager::instance()->get(objects::TEST_LOCAL_POOL_OWNER_BASE); + REQUIRE(poolOwner != nullptr); + REQUIRE(poolOwner->initializeHkManager() == retval::CATCH_OK); + REQUIRE(poolOwner->initializeHkManagerAfterTaskCreation() == retval::CATCH_OK); - testVariable.setReadWriteMode(pool_rwm_t::VAR_READ); - CHECK(testVariable.getReadWriteMode() == pool_rwm_t::VAR_READ); - testVariable.setReadWriteMode(pool_rwm_t::VAR_READ_WRITE); + SECTION("Basic Tests") { + /* very basic test. */ + lp_var_t testVariable = + lp_var_t(objects::TEST_LOCAL_POOL_OWNER_BASE, lpool::uint8VarId); + REQUIRE(testVariable.read() == retval::CATCH_OK); + CHECK(testVariable.value == 0); + testVariable.value = 5; + REQUIRE(testVariable.commit() == retval::CATCH_OK); + REQUIRE(testVariable.read() == retval::CATCH_OK); + REQUIRE(testVariable.value == 5); + CHECK(not testVariable.isValid()); + testVariable.setValid(true); + CHECK(testVariable.isValid()); + CHECK(testVariable.commit(true) == retval::CATCH_OK); - testVariable.setDataPoolId(22); - CHECK(testVariable.getDataPoolId() == 22); - testVariable.setDataPoolId(lpool::uint8VarId); + testVariable.setReadWriteMode(pool_rwm_t::VAR_READ); + CHECK(testVariable.getReadWriteMode() == pool_rwm_t::VAR_READ); + testVariable.setReadWriteMode(pool_rwm_t::VAR_READ_WRITE); - testVariable.setChanged(true); - CHECK(testVariable.hasChanged()); - testVariable.setChanged(false); + testVariable.setDataPoolId(22); + CHECK(testVariable.getDataPoolId() == 22); + testVariable.setDataPoolId(lpool::uint8VarId); - gp_id_t globPoolId(objects::TEST_LOCAL_POOL_OWNER_BASE, - lpool::uint8VarId); - lp_var_t testVariable2 = lp_var_t(globPoolId); - REQUIRE(testVariable2.read() == retval::CATCH_OK); - CHECK(testVariable2 == 5); - CHECK(testVariable == testVariable2); - testVariable = 10; - CHECK(testVariable != 5); - //CHECK(not testVariable != testVariable2); - uint8_t variableRaw = 0; - uint8_t* varPtr = &variableRaw; - size_t maxSize = testVariable.getSerializedSize(); - CHECK(maxSize == 1); - size_t serSize = 0; - CHECK(testVariable.serialize(&varPtr, &serSize, maxSize, - SerializeIF::Endianness::MACHINE) == retval::CATCH_OK); - CHECK(variableRaw == 10); - const uint8_t* varConstPtr = &variableRaw; - testVariable = 5; - CHECK(testVariable.deSerialize(&varConstPtr, &serSize, - SerializeIF::Endianness::MACHINE) == retval::CATCH_OK); - CHECK(testVariable == 10); - CHECK(testVariable != testVariable2); - CHECK(testVariable2 < testVariable); - CHECK(testVariable2 < 10); - CHECK(testVariable > 5); - CHECK(testVariable > testVariable2); - variableRaw = static_cast(testVariable2); - CHECK(variableRaw == 5); + testVariable.setChanged(true); + CHECK(testVariable.hasChanged()); + testVariable.setChanged(false); - CHECK(testVariable == 10); - testVariable = testVariable2; - CHECK(testVariable == 5); - } + gp_id_t globPoolId(objects::TEST_LOCAL_POOL_OWNER_BASE, lpool::uint8VarId); + lp_var_t testVariable2 = lp_var_t(globPoolId); + REQUIRE(testVariable2.read() == retval::CATCH_OK); + CHECK(testVariable2 == 5); + CHECK(testVariable == testVariable2); + testVariable = 10; + CHECK(testVariable != 5); + // CHECK(not testVariable != testVariable2); + uint8_t variableRaw = 0; + uint8_t* varPtr = &variableRaw; + size_t maxSize = testVariable.getSerializedSize(); + CHECK(maxSize == 1); + size_t serSize = 0; + CHECK(testVariable.serialize(&varPtr, &serSize, maxSize, SerializeIF::Endianness::MACHINE) == + retval::CATCH_OK); + CHECK(variableRaw == 10); + const uint8_t* varConstPtr = &variableRaw; + testVariable = 5; + CHECK(testVariable.deSerialize(&varConstPtr, &serSize, SerializeIF::Endianness::MACHINE) == + retval::CATCH_OK); + CHECK(testVariable == 10); + CHECK(testVariable != testVariable2); + CHECK(testVariable2 < testVariable); + CHECK(testVariable2 < 10); + CHECK(testVariable > 5); + CHECK(testVariable > testVariable2); + variableRaw = static_cast(testVariable2); + CHECK(variableRaw == 5); - SECTION("ErrorHandling") { + CHECK(testVariable == 10); + testVariable = testVariable2; + CHECK(testVariable == 5); + } - /* now try to use a local pool variable which does not exist */ - lp_var_t invalidVariable = lp_var_t( - objects::TEST_LOCAL_POOL_OWNER_BASE, 0xffffffff); - REQUIRE(invalidVariable.read() == - static_cast(localpool::POOL_ENTRY_NOT_FOUND)); + SECTION("ErrorHandling") { + /* now try to use a local pool variable which does not exist */ + lp_var_t invalidVariable = + lp_var_t(objects::TEST_LOCAL_POOL_OWNER_BASE, 0xffffffff); + REQUIRE(invalidVariable.read() == static_cast(localpool::POOL_ENTRY_NOT_FOUND)); - REQUIRE(invalidVariable.commit() == - static_cast(localpool::POOL_ENTRY_NOT_FOUND)); - /* now try to access with wrong type */ - lp_var_t invalidVariable2 = lp_var_t( - objects::TEST_LOCAL_POOL_OWNER_BASE, lpool::uint8VarId); - REQUIRE(invalidVariable2.read() == - static_cast(localpool::POOL_ENTRY_TYPE_CONFLICT)); + REQUIRE(invalidVariable.commit() == static_cast(localpool::POOL_ENTRY_NOT_FOUND)); + /* now try to access with wrong type */ + lp_var_t invalidVariable2 = + lp_var_t(objects::TEST_LOCAL_POOL_OWNER_BASE, lpool::uint8VarId); + REQUIRE(invalidVariable2.read() == static_cast(localpool::POOL_ENTRY_TYPE_CONFLICT)); - lp_var_t readOnlyVar = lp_var_t( - objects::TEST_LOCAL_POOL_OWNER_BASE, lpool::uint8VarId, - nullptr, pool_rwm_t::VAR_READ); - REQUIRE(readOnlyVar.commit() == - static_cast(PoolVariableIF::INVALID_READ_WRITE_MODE)); - lp_var_t writeOnlyVar = lp_var_t( - objects::TEST_LOCAL_POOL_OWNER_BASE, lpool::uint8VarId, - nullptr, pool_rwm_t::VAR_WRITE); - REQUIRE(writeOnlyVar.read() == static_cast( - PoolVariableIF::INVALID_READ_WRITE_MODE)); + lp_var_t readOnlyVar = lp_var_t( + objects::TEST_LOCAL_POOL_OWNER_BASE, lpool::uint8VarId, nullptr, pool_rwm_t::VAR_READ); + REQUIRE(readOnlyVar.commit() == static_cast(PoolVariableIF::INVALID_READ_WRITE_MODE)); + lp_var_t writeOnlyVar = lp_var_t( + objects::TEST_LOCAL_POOL_OWNER_BASE, lpool::uint8VarId, nullptr, pool_rwm_t::VAR_WRITE); + REQUIRE(writeOnlyVar.read() == static_cast(PoolVariableIF::INVALID_READ_WRITE_MODE)); - lp_var_t uint32tVar = lp_var_t( - objects::TEST_LOCAL_POOL_OWNER_BASE, lpool::uint32VarId); + lp_var_t uint32tVar = + lp_var_t(objects::TEST_LOCAL_POOL_OWNER_BASE, lpool::uint32VarId); #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "LocalPoolVariable printout: " < OK */ - lp_var_t invalidObjectVar = lp_var_t( - 0xffffffff, lpool::uint8VarId); - gp_id_t globPoolId(0xffffffff, - lpool::uint8VarId); - lp_var_t invalidObjectVar2 = lp_var_t(globPoolId); - lp_var_t invalidObjectVar3 = lp_var_t(nullptr, - lpool::uint8VarId); - } - - CHECK(poolOwner->reset() == retval::CATCH_OK); + /* for code coverage. If program does not crash -> OK */ + lp_var_t invalidObjectVar = lp_var_t(0xffffffff, lpool::uint8VarId); + gp_id_t globPoolId(0xffffffff, lpool::uint8VarId); + lp_var_t invalidObjectVar2 = lp_var_t(globPoolId); + lp_var_t invalidObjectVar3 = lp_var_t(nullptr, lpool::uint8VarId); + } + CHECK(poolOwner->reset() == retval::CATCH_OK); } - - diff --git a/tests/src/fsfw_tests/unit/datapoollocal/LocalPoolVectorTest.cpp b/tests/src/fsfw_tests/unit/datapoollocal/LocalPoolVectorTest.cpp index 5298e5b9..5932db44 100644 --- a/tests/src/fsfw_tests/unit/datapoollocal/LocalPoolVectorTest.cpp +++ b/tests/src/fsfw_tests/unit/datapoollocal/LocalPoolVectorTest.cpp @@ -1,124 +1,110 @@ -#include "LocalPoolOwnerBase.h" -#include "tests/TestsConfig.h" -#include "fsfw_tests/unit/CatchDefinitions.h" +#include +#include #include -#include -#include +#include "LocalPoolOwnerBase.h" +#include "fsfw_tests/unit/CatchDefinitions.h" +#include "tests/TestsConfig.h" -TEST_CASE("LocalPoolVector" , "[LocPoolVecTest]") { - LocalPoolOwnerBase* poolOwner = ObjectManager::instance()-> - get(objects::TEST_LOCAL_POOL_OWNER_BASE); - REQUIRE(poolOwner != nullptr); - REQUIRE(poolOwner->initializeHkManager() == retval::CATCH_OK); - REQUIRE(poolOwner->initializeHkManagerAfterTaskCreation() - == retval::CATCH_OK); +TEST_CASE("LocalPoolVector", "[LocPoolVecTest]") { + LocalPoolOwnerBase* poolOwner = + ObjectManager::instance()->get(objects::TEST_LOCAL_POOL_OWNER_BASE); + REQUIRE(poolOwner != nullptr); + REQUIRE(poolOwner->initializeHkManager() == retval::CATCH_OK); + REQUIRE(poolOwner->initializeHkManagerAfterTaskCreation() == retval::CATCH_OK); - SECTION("BasicTest") { - // very basic test. - lp_vec_t testVector = lp_vec_t( - objects::TEST_LOCAL_POOL_OWNER_BASE, lpool::uint16Vec3Id); - REQUIRE(testVector.read() == retval::CATCH_OK); - testVector.value[0] = 5; - testVector.value[1] = 232; - testVector.value[2] = 32023; + SECTION("BasicTest") { + // very basic test. + lp_vec_t testVector = + lp_vec_t(objects::TEST_LOCAL_POOL_OWNER_BASE, lpool::uint16Vec3Id); + REQUIRE(testVector.read() == retval::CATCH_OK); + testVector.value[0] = 5; + testVector.value[1] = 232; + testVector.value[2] = 32023; - REQUIRE(testVector.commit(true) == retval::CATCH_OK); - CHECK(testVector.isValid()); + REQUIRE(testVector.commit(true) == retval::CATCH_OK); + CHECK(testVector.isValid()); - testVector.value[0] = 0; - testVector.value[1] = 0; - testVector.value[2] = 0; + testVector.value[0] = 0; + testVector.value[1] = 0; + testVector.value[2] = 0; - CHECK(testVector.read() == retval::CATCH_OK); - CHECK(testVector.value[0] == 5); - CHECK(testVector.value[1] == 232); - CHECK(testVector.value[2] == 32023); + CHECK(testVector.read() == retval::CATCH_OK); + CHECK(testVector.value[0] == 5); + CHECK(testVector.value[1] == 232); + CHECK(testVector.value[2] == 32023); - CHECK(testVector[0] == 5); + CHECK(testVector[0] == 5); - /* This is invalid access, so the last value will be set instead. - (we can't throw exceptions) */ - testVector[4] = 12; - CHECK(testVector[2] == 12); - CHECK(testVector.commit() == retval::CATCH_OK); + /* This is invalid access, so the last value will be set instead. + (we can't throw exceptions) */ + testVector[4] = 12; + CHECK(testVector[2] == 12); + CHECK(testVector.commit() == retval::CATCH_OK); - /* Use read-only reference. */ - const lp_vec_t& roTestVec = testVector; - uint16_t valueOne = roTestVec[0]; - CHECK(valueOne == 5); + /* Use read-only reference. */ + const lp_vec_t& roTestVec = testVector; + uint16_t valueOne = roTestVec[0]; + CHECK(valueOne == 5); - uint16_t lastVal = roTestVec[25]; - CHECK(lastVal == 12); + uint16_t lastVal = roTestVec[25]; + CHECK(lastVal == 12); - size_t maxSize = testVector.getSerializedSize(); - CHECK(maxSize == 6); + size_t maxSize = testVector.getSerializedSize(); + CHECK(maxSize == 6); - uint16_t serializedVector[3]; - uint8_t* vecPtr = reinterpret_cast(serializedVector); - size_t serSize = 0; - REQUIRE(testVector.serialize(&vecPtr, &serSize, - maxSize, SerializeIF::Endianness::MACHINE) == retval::CATCH_OK); + uint16_t serializedVector[3]; + uint8_t* vecPtr = reinterpret_cast(serializedVector); + size_t serSize = 0; + REQUIRE(testVector.serialize(&vecPtr, &serSize, maxSize, SerializeIF::Endianness::MACHINE) == + retval::CATCH_OK); - CHECK(serSize == 6); - CHECK(serializedVector[0] == 5); - CHECK(serializedVector[1] == 232); - CHECK(serializedVector[2] == 12); + CHECK(serSize == 6); + CHECK(serializedVector[0] == 5); + CHECK(serializedVector[1] == 232); + CHECK(serializedVector[2] == 12); - maxSize = 1; - REQUIRE(testVector.serialize(&vecPtr, &serSize, - maxSize, SerializeIF::Endianness::MACHINE) == - static_cast(SerializeIF::BUFFER_TOO_SHORT)); + maxSize = 1; + REQUIRE(testVector.serialize(&vecPtr, &serSize, maxSize, SerializeIF::Endianness::MACHINE) == + static_cast(SerializeIF::BUFFER_TOO_SHORT)); - serializedVector[0] = 16; - serializedVector[1] = 7832; - serializedVector[2] = 39232; + serializedVector[0] = 16; + serializedVector[1] = 7832; + serializedVector[2] = 39232; - const uint8_t* constVecPtr = reinterpret_cast( - serializedVector); - REQUIRE(testVector.deSerialize(&constVecPtr, &serSize, - SerializeIF::Endianness::MACHINE) == retval::CATCH_OK); - CHECK(testVector[0] == 16); - CHECK(testVector[1] == 7832); - CHECK(testVector[2] == 39232); + const uint8_t* constVecPtr = reinterpret_cast(serializedVector); + REQUIRE(testVector.deSerialize(&constVecPtr, &serSize, SerializeIF::Endianness::MACHINE) == + retval::CATCH_OK); + CHECK(testVector[0] == 16); + CHECK(testVector[1] == 7832); + CHECK(testVector[2] == 39232); - serSize = 1; - REQUIRE(testVector.deSerialize(&constVecPtr, &serSize, - SerializeIF::Endianness::MACHINE) == - static_cast(SerializeIF::STREAM_TOO_SHORT)); - } + serSize = 1; + REQUIRE(testVector.deSerialize(&constVecPtr, &serSize, SerializeIF::Endianness::MACHINE) == + static_cast(SerializeIF::STREAM_TOO_SHORT)); + } - SECTION("ErrorHandling") { - /* Now try to use a local pool variable which does not exist */ - lp_vec_t invalidVector = lp_vec_t( - objects::TEST_LOCAL_POOL_OWNER_BASE, 0xffffffff); - REQUIRE(invalidVector.read() == - static_cast(localpool::POOL_ENTRY_NOT_FOUND)); - REQUIRE(invalidVector.commit() == - static_cast(localpool::POOL_ENTRY_NOT_FOUND)); + SECTION("ErrorHandling") { + /* Now try to use a local pool variable which does not exist */ + lp_vec_t invalidVector = + lp_vec_t(objects::TEST_LOCAL_POOL_OWNER_BASE, 0xffffffff); + REQUIRE(invalidVector.read() == static_cast(localpool::POOL_ENTRY_NOT_FOUND)); + REQUIRE(invalidVector.commit() == static_cast(localpool::POOL_ENTRY_NOT_FOUND)); - /* Now try to access with wrong type */ - lp_vec_t invalidVector2 = lp_vec_t( - objects::TEST_LOCAL_POOL_OWNER_BASE, lpool::uint16Vec3Id); - REQUIRE(invalidVector2.read() == - static_cast(localpool::POOL_ENTRY_TYPE_CONFLICT)); - REQUIRE(invalidVector2.commit() == - static_cast(localpool::POOL_ENTRY_TYPE_CONFLICT)); + /* Now try to access with wrong type */ + lp_vec_t invalidVector2 = + lp_vec_t(objects::TEST_LOCAL_POOL_OWNER_BASE, lpool::uint16Vec3Id); + REQUIRE(invalidVector2.read() == static_cast(localpool::POOL_ENTRY_TYPE_CONFLICT)); + REQUIRE(invalidVector2.commit() == static_cast(localpool::POOL_ENTRY_TYPE_CONFLICT)); - lp_vec_t writeOnlyVec = lp_vec_t( - objects::TEST_LOCAL_POOL_OWNER_BASE, lpool::uint16Vec3Id, - nullptr, pool_rwm_t::VAR_WRITE); - REQUIRE(writeOnlyVec.read() == - static_cast(PoolVariableIF::INVALID_READ_WRITE_MODE)); + lp_vec_t writeOnlyVec = lp_vec_t( + objects::TEST_LOCAL_POOL_OWNER_BASE, lpool::uint16Vec3Id, nullptr, pool_rwm_t::VAR_WRITE); + REQUIRE(writeOnlyVec.read() == static_cast(PoolVariableIF::INVALID_READ_WRITE_MODE)); - lp_vec_t readOnlyVec = lp_vec_t( - objects::TEST_LOCAL_POOL_OWNER_BASE, lpool::uint16Vec3Id, - nullptr, pool_rwm_t::VAR_READ); - REQUIRE(readOnlyVec.commit() == - static_cast(PoolVariableIF::INVALID_READ_WRITE_MODE)); - } - poolOwner->reset(); + lp_vec_t readOnlyVec = lp_vec_t( + objects::TEST_LOCAL_POOL_OWNER_BASE, lpool::uint16Vec3Id, nullptr, pool_rwm_t::VAR_READ); + REQUIRE(readOnlyVec.commit() == static_cast(PoolVariableIF::INVALID_READ_WRITE_MODE)); + } + poolOwner->reset(); } - - diff --git a/tests/src/fsfw_tests/unit/globalfunctions/testBitutil.cpp b/tests/src/fsfw_tests/unit/globalfunctions/testBitutil.cpp index 2627adcf..2ddb09df 100644 --- a/tests/src/fsfw_tests/unit/globalfunctions/testBitutil.cpp +++ b/tests/src/fsfw_tests/unit/globalfunctions/testBitutil.cpp @@ -1,64 +1,61 @@ -#include "fsfw/globalfunctions/bitutility.h" #include -TEST_CASE("Bitutility" , "[Bitutility]") { - uint8_t dummyByte = 0; - bool bitSet = false; - for(uint8_t pos = 0; pos < 8; pos++) { - bitutil::set(&dummyByte, pos); - REQUIRE(dummyByte == (1 << (7 - pos))); - bitutil::get(&dummyByte, pos, bitSet); - REQUIRE(bitSet == 1); - dummyByte = 0; - } - - dummyByte = 0xff; - for(uint8_t pos = 0; pos < 8; pos++) { - bitutil::get(&dummyByte, pos, bitSet); - REQUIRE(bitSet == 1); - bitutil::clear(&dummyByte, pos); - bitutil::get(&dummyByte, pos, bitSet); - REQUIRE(bitSet == 0); - dummyByte = 0xff; - } - - dummyByte = 0xf0; - for(uint8_t pos = 0; pos < 8; pos++) { - if(pos < 4) { - bitutil::get(&dummyByte, pos, bitSet); - REQUIRE(bitSet == 1); - bitutil::toggle(&dummyByte, pos); - bitutil::get(&dummyByte, pos, bitSet); - REQUIRE(bitSet == 0); - } - else { - bitutil::get(&dummyByte, pos, bitSet); - REQUIRE(bitSet == false); - bitutil::toggle(&dummyByte, pos); - bitutil::get(&dummyByte, pos, bitSet); - REQUIRE(bitSet == true); - } - } - REQUIRE(dummyByte == 0x0f); +#include "fsfw/globalfunctions/bitutility.h" +TEST_CASE("Bitutility", "[Bitutility]") { + uint8_t dummyByte = 0; + bool bitSet = false; + for (uint8_t pos = 0; pos < 8; pos++) { + bitutil::set(&dummyByte, pos); + REQUIRE(dummyByte == (1 << (7 - pos))); + bitutil::get(&dummyByte, pos, bitSet); + REQUIRE(bitSet == 1); dummyByte = 0; - bitutil::set(&dummyByte, 8); - REQUIRE(dummyByte == 0); - bitutil::set(&dummyByte, -1); - REQUIRE(dummyByte == 0); + } + + dummyByte = 0xff; + for (uint8_t pos = 0; pos < 8; pos++) { + bitutil::get(&dummyByte, pos, bitSet); + REQUIRE(bitSet == 1); + bitutil::clear(&dummyByte, pos); + bitutil::get(&dummyByte, pos, bitSet); + REQUIRE(bitSet == 0); dummyByte = 0xff; - bitutil::clear(&dummyByte, 8); - REQUIRE(dummyByte == 0xff); - bitutil::clear(&dummyByte, -1); - REQUIRE(dummyByte == 0xff); - dummyByte = 0x00; - bitutil::toggle(&dummyByte, 8); - REQUIRE(dummyByte == 0x00); - bitutil::toggle(&dummyByte, -1); - REQUIRE(dummyByte == 0x00); + } - REQUIRE(bitutil::get(&dummyByte, 8, bitSet) == false); + dummyByte = 0xf0; + for (uint8_t pos = 0; pos < 8; pos++) { + if (pos < 4) { + bitutil::get(&dummyByte, pos, bitSet); + REQUIRE(bitSet == 1); + bitutil::toggle(&dummyByte, pos); + bitutil::get(&dummyByte, pos, bitSet); + REQUIRE(bitSet == 0); + } else { + bitutil::get(&dummyByte, pos, bitSet); + REQUIRE(bitSet == false); + bitutil::toggle(&dummyByte, pos); + bitutil::get(&dummyByte, pos, bitSet); + REQUIRE(bitSet == true); + } + } + REQUIRE(dummyByte == 0x0f); + + dummyByte = 0; + bitutil::set(&dummyByte, 8); + REQUIRE(dummyByte == 0); + bitutil::set(&dummyByte, -1); + REQUIRE(dummyByte == 0); + dummyByte = 0xff; + bitutil::clear(&dummyByte, 8); + REQUIRE(dummyByte == 0xff); + bitutil::clear(&dummyByte, -1); + REQUIRE(dummyByte == 0xff); + dummyByte = 0x00; + bitutil::toggle(&dummyByte, 8); + REQUIRE(dummyByte == 0x00); + bitutil::toggle(&dummyByte, -1); + REQUIRE(dummyByte == 0x00); + + REQUIRE(bitutil::get(&dummyByte, 8, bitSet) == false); } - - - diff --git a/tests/src/fsfw_tests/unit/globalfunctions/testDleEncoder.cpp b/tests/src/fsfw_tests/unit/globalfunctions/testDleEncoder.cpp index cffd5308..034cb3a0 100644 --- a/tests/src/fsfw_tests/unit/globalfunctions/testDleEncoder.cpp +++ b/tests/src/fsfw_tests/unit/globalfunctions/testDleEncoder.cpp @@ -1,227 +1,212 @@ -#include "fsfw/globalfunctions/DleEncoder.h" -#include "fsfw_tests/unit/CatchDefinitions.h" -#include "catch2/catch_test_macros.hpp" - #include -const std::vector TEST_ARRAY_0 = { 0, 0, 0, 0, 0 }; -const std::vector TEST_ARRAY_1 = { 0, DleEncoder::DLE_CHAR, 5}; -const std::vector TEST_ARRAY_2 = { 0, DleEncoder::STX_CHAR, 5}; -const std::vector TEST_ARRAY_3 = { 0, DleEncoder::CARRIAGE_RETURN, DleEncoder::ETX_CHAR}; -const std::vector TEST_ARRAY_4 = { DleEncoder::DLE_CHAR, DleEncoder::ETX_CHAR, - DleEncoder::STX_CHAR }; +#include "catch2/catch_test_macros.hpp" +#include "fsfw/globalfunctions/DleEncoder.h" +#include "fsfw_tests/unit/CatchDefinitions.h" -const std::vector TEST_ARRAY_0_ENCODED_ESCAPED = { - DleEncoder::STX_CHAR, 0, 0, 0, 0, 0, DleEncoder::ETX_CHAR -}; +const std::vector TEST_ARRAY_0 = {0, 0, 0, 0, 0}; +const std::vector TEST_ARRAY_1 = {0, DleEncoder::DLE_CHAR, 5}; +const std::vector TEST_ARRAY_2 = {0, DleEncoder::STX_CHAR, 5}; +const std::vector TEST_ARRAY_3 = {0, DleEncoder::CARRIAGE_RETURN, DleEncoder::ETX_CHAR}; +const std::vector TEST_ARRAY_4 = {DleEncoder::DLE_CHAR, DleEncoder::ETX_CHAR, + DleEncoder::STX_CHAR}; + +const std::vector TEST_ARRAY_0_ENCODED_ESCAPED = {DleEncoder::STX_CHAR, 0, 0, 0, 0, 0, + DleEncoder::ETX_CHAR}; const std::vector TEST_ARRAY_0_ENCODED_NON_ESCAPED = { - DleEncoder::DLE_CHAR, DleEncoder::STX_CHAR, 0, 0, 0, 0, 0, - DleEncoder::DLE_CHAR, DleEncoder::ETX_CHAR -}; + DleEncoder::DLE_CHAR, DleEncoder::STX_CHAR, 0, 0, 0, 0, 0, + DleEncoder::DLE_CHAR, DleEncoder::ETX_CHAR}; const std::vector TEST_ARRAY_1_ENCODED_ESCAPED = { - DleEncoder::STX_CHAR, 0, DleEncoder::DLE_CHAR, DleEncoder::DLE_CHAR, 5, DleEncoder::ETX_CHAR -}; + DleEncoder::STX_CHAR, 0, DleEncoder::DLE_CHAR, DleEncoder::DLE_CHAR, 5, DleEncoder::ETX_CHAR}; const std::vector TEST_ARRAY_1_ENCODED_NON_ESCAPED = { - DleEncoder::DLE_CHAR, DleEncoder::STX_CHAR, 0, DleEncoder::DLE_CHAR, DleEncoder::DLE_CHAR, - 5, DleEncoder::DLE_CHAR, DleEncoder::ETX_CHAR -}; + DleEncoder::DLE_CHAR, DleEncoder::STX_CHAR, 0, DleEncoder::DLE_CHAR, DleEncoder::DLE_CHAR, 5, + DleEncoder::DLE_CHAR, DleEncoder::ETX_CHAR}; const std::vector TEST_ARRAY_2_ENCODED_ESCAPED = { - DleEncoder::STX_CHAR, 0, DleEncoder::DLE_CHAR, DleEncoder::STX_CHAR + 0x40, - 5, DleEncoder::ETX_CHAR -}; + DleEncoder::STX_CHAR, 0, DleEncoder::DLE_CHAR, + DleEncoder::STX_CHAR + 0x40, 5, DleEncoder::ETX_CHAR}; const std::vector TEST_ARRAY_2_ENCODED_NON_ESCAPED = { - DleEncoder::DLE_CHAR, DleEncoder::STX_CHAR, 0, - DleEncoder::STX_CHAR, 5, DleEncoder::DLE_CHAR, DleEncoder::ETX_CHAR -}; + DleEncoder::DLE_CHAR, DleEncoder::STX_CHAR, 0, DleEncoder::STX_CHAR, 5, + DleEncoder::DLE_CHAR, DleEncoder::ETX_CHAR}; const std::vector TEST_ARRAY_3_ENCODED_ESCAPED = { - DleEncoder::STX_CHAR, 0, DleEncoder::CARRIAGE_RETURN, - DleEncoder::DLE_CHAR, DleEncoder::ETX_CHAR + 0x40, DleEncoder::ETX_CHAR -}; + DleEncoder::STX_CHAR, 0, + DleEncoder::CARRIAGE_RETURN, DleEncoder::DLE_CHAR, + DleEncoder::ETX_CHAR + 0x40, DleEncoder::ETX_CHAR}; const std::vector TEST_ARRAY_3_ENCODED_NON_ESCAPED = { - DleEncoder::DLE_CHAR, DleEncoder::STX_CHAR, 0, - DleEncoder::CARRIAGE_RETURN, DleEncoder::ETX_CHAR, DleEncoder::DLE_CHAR, - DleEncoder::ETX_CHAR -}; + DleEncoder::DLE_CHAR, DleEncoder::STX_CHAR, 0, + DleEncoder::CARRIAGE_RETURN, DleEncoder::ETX_CHAR, DleEncoder::DLE_CHAR, + DleEncoder::ETX_CHAR}; const std::vector TEST_ARRAY_4_ENCODED_ESCAPED = { - DleEncoder::STX_CHAR, DleEncoder::DLE_CHAR, DleEncoder::DLE_CHAR, - DleEncoder::DLE_CHAR, DleEncoder::ETX_CHAR + 0x40, DleEncoder::DLE_CHAR, - DleEncoder::STX_CHAR + 0x40, DleEncoder::ETX_CHAR -}; + DleEncoder::STX_CHAR, DleEncoder::DLE_CHAR, DleEncoder::DLE_CHAR, + DleEncoder::DLE_CHAR, DleEncoder::ETX_CHAR + 0x40, DleEncoder::DLE_CHAR, + DleEncoder::STX_CHAR + 0x40, DleEncoder::ETX_CHAR}; const std::vector TEST_ARRAY_4_ENCODED_NON_ESCAPED = { - DleEncoder::DLE_CHAR, DleEncoder::STX_CHAR, DleEncoder::DLE_CHAR, DleEncoder::DLE_CHAR, - DleEncoder::ETX_CHAR, DleEncoder::STX_CHAR, DleEncoder::DLE_CHAR, DleEncoder::ETX_CHAR -}; + DleEncoder::DLE_CHAR, DleEncoder::STX_CHAR, DleEncoder::DLE_CHAR, DleEncoder::DLE_CHAR, + DleEncoder::ETX_CHAR, DleEncoder::STX_CHAR, DleEncoder::DLE_CHAR, DleEncoder::ETX_CHAR}; +TEST_CASE("DleEncoder", "[DleEncoder]") { + DleEncoder dleEncoder; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + std::array buffer; -TEST_CASE("DleEncoder" , "[DleEncoder]") { - DleEncoder dleEncoder; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - std::array buffer; + size_t encodedLen = 0; + size_t readLen = 0; + size_t decodedLen = 0; - size_t encodedLen = 0; - size_t readLen = 0; - size_t decodedLen = 0; + auto testLambdaEncode = [&](DleEncoder& encoder, const std::vector& vecToEncode, + const std::vector& expectedVec) { + result = encoder.encode(vecToEncode.data(), vecToEncode.size(), buffer.data(), buffer.size(), + &encodedLen); + REQUIRE(result == retval::CATCH_OK); + for (size_t idx = 0; idx < expectedVec.size(); idx++) { + REQUIRE(buffer[idx] == expectedVec[idx]); + } + REQUIRE(encodedLen == expectedVec.size()); + }; - auto testLambdaEncode = [&](DleEncoder& encoder, const std::vector& vecToEncode, - const std::vector& expectedVec) { - result = encoder.encode(vecToEncode.data(), vecToEncode.size(), - buffer.data(), buffer.size(), &encodedLen); - REQUIRE(result == retval::CATCH_OK); - for(size_t idx = 0; idx < expectedVec.size(); idx++) { - REQUIRE(buffer[idx] == expectedVec[idx]); - } - REQUIRE(encodedLen == expectedVec.size()); + auto testLambdaDecode = [&](DleEncoder& encoder, const std::vector& testVecEncoded, + const std::vector& expectedVec) { + result = encoder.decode(testVecEncoded.data(), testVecEncoded.size(), &readLen, buffer.data(), + buffer.size(), &decodedLen); + REQUIRE(result == retval::CATCH_OK); + REQUIRE(readLen == testVecEncoded.size()); + REQUIRE(decodedLen == expectedVec.size()); + for (size_t idx = 0; idx < decodedLen; idx++) { + REQUIRE(buffer[idx] == expectedVec[idx]); + } + }; + + SECTION("Encoding") { + testLambdaEncode(dleEncoder, TEST_ARRAY_0, TEST_ARRAY_0_ENCODED_ESCAPED); + testLambdaEncode(dleEncoder, TEST_ARRAY_1, TEST_ARRAY_1_ENCODED_ESCAPED); + testLambdaEncode(dleEncoder, TEST_ARRAY_2, TEST_ARRAY_2_ENCODED_ESCAPED); + testLambdaEncode(dleEncoder, TEST_ARRAY_3, TEST_ARRAY_3_ENCODED_ESCAPED); + testLambdaEncode(dleEncoder, TEST_ARRAY_4, TEST_ARRAY_4_ENCODED_ESCAPED); + + auto testFaultyEncoding = [&](const std::vector& vecToEncode, + const std::vector& expectedVec) { + for (size_t faultyDestSize = 0; faultyDestSize < expectedVec.size(); faultyDestSize++) { + result = dleEncoder.encode(vecToEncode.data(), vecToEncode.size(), buffer.data(), + faultyDestSize, &encodedLen); + REQUIRE(result == static_cast(DleEncoder::STREAM_TOO_SHORT)); + } }; - auto testLambdaDecode = [&](DleEncoder& encoder, const std::vector& testVecEncoded, - const std::vector& expectedVec) { - result = encoder.decode(testVecEncoded.data(), - testVecEncoded.size(), - &readLen, buffer.data(), buffer.size(), &decodedLen); - REQUIRE(result == retval::CATCH_OK); - REQUIRE(readLen == testVecEncoded.size()); - REQUIRE(decodedLen == expectedVec.size()); - for(size_t idx = 0; idx < decodedLen; idx++) { - REQUIRE(buffer[idx] == expectedVec[idx]); - } + testFaultyEncoding(TEST_ARRAY_0, TEST_ARRAY_0_ENCODED_ESCAPED); + testFaultyEncoding(TEST_ARRAY_1, TEST_ARRAY_1_ENCODED_ESCAPED); + testFaultyEncoding(TEST_ARRAY_2, TEST_ARRAY_2_ENCODED_ESCAPED); + testFaultyEncoding(TEST_ARRAY_3, TEST_ARRAY_3_ENCODED_ESCAPED); + testFaultyEncoding(TEST_ARRAY_4, TEST_ARRAY_4_ENCODED_ESCAPED); + + dleEncoder.setEscapeMode(false); + testLambdaEncode(dleEncoder, TEST_ARRAY_0, TEST_ARRAY_0_ENCODED_NON_ESCAPED); + testLambdaEncode(dleEncoder, TEST_ARRAY_1, TEST_ARRAY_1_ENCODED_NON_ESCAPED); + testLambdaEncode(dleEncoder, TEST_ARRAY_2, TEST_ARRAY_2_ENCODED_NON_ESCAPED); + testLambdaEncode(dleEncoder, TEST_ARRAY_3, TEST_ARRAY_3_ENCODED_NON_ESCAPED); + testLambdaEncode(dleEncoder, TEST_ARRAY_4, TEST_ARRAY_4_ENCODED_NON_ESCAPED); + + testFaultyEncoding(TEST_ARRAY_0, TEST_ARRAY_0_ENCODED_NON_ESCAPED); + testFaultyEncoding(TEST_ARRAY_1, TEST_ARRAY_1_ENCODED_NON_ESCAPED); + testFaultyEncoding(TEST_ARRAY_2, TEST_ARRAY_2_ENCODED_NON_ESCAPED); + testFaultyEncoding(TEST_ARRAY_3, TEST_ARRAY_3_ENCODED_NON_ESCAPED); + testFaultyEncoding(TEST_ARRAY_4, TEST_ARRAY_4_ENCODED_NON_ESCAPED); + dleEncoder.setEscapeMode(true); + } + + SECTION("Decoding") { + testLambdaDecode(dleEncoder, TEST_ARRAY_0_ENCODED_ESCAPED, TEST_ARRAY_0); + testLambdaDecode(dleEncoder, TEST_ARRAY_1_ENCODED_ESCAPED, TEST_ARRAY_1); + testLambdaDecode(dleEncoder, TEST_ARRAY_2_ENCODED_ESCAPED, TEST_ARRAY_2); + testLambdaDecode(dleEncoder, TEST_ARRAY_3_ENCODED_ESCAPED, TEST_ARRAY_3); + testLambdaDecode(dleEncoder, TEST_ARRAY_4_ENCODED_ESCAPED, TEST_ARRAY_4); + + // Faulty source data + auto testArray1EncodedFaulty = TEST_ARRAY_1_ENCODED_ESCAPED; + testArray1EncodedFaulty[3] = 0; + result = dleEncoder.decode(testArray1EncodedFaulty.data(), testArray1EncodedFaulty.size(), + &readLen, buffer.data(), buffer.size(), &encodedLen); + REQUIRE(result == static_cast(DleEncoder::DECODING_ERROR)); + auto testArray2EncodedFaulty = TEST_ARRAY_2_ENCODED_ESCAPED; + testArray2EncodedFaulty[5] = 0; + result = dleEncoder.decode(testArray2EncodedFaulty.data(), testArray2EncodedFaulty.size(), + &readLen, buffer.data(), buffer.size(), &encodedLen); + REQUIRE(result == static_cast(DleEncoder::DECODING_ERROR)); + auto testArray4EncodedFaulty = TEST_ARRAY_4_ENCODED_ESCAPED; + testArray4EncodedFaulty[2] = 0; + result = dleEncoder.decode(testArray4EncodedFaulty.data(), testArray4EncodedFaulty.size(), + &readLen, buffer.data(), buffer.size(), &encodedLen); + REQUIRE(result == static_cast(DleEncoder::DECODING_ERROR)); + auto testArray4EncodedFaulty2 = TEST_ARRAY_4_ENCODED_ESCAPED; + testArray4EncodedFaulty2[4] = 0; + result = dleEncoder.decode(testArray4EncodedFaulty2.data(), testArray4EncodedFaulty2.size(), + &readLen, buffer.data(), buffer.size(), &encodedLen); + REQUIRE(result == static_cast(DleEncoder::DECODING_ERROR)); + + auto testFaultyDecoding = [&](const std::vector& vecToDecode, + const std::vector& expectedVec) { + for (size_t faultyDestSizes = 0; faultyDestSizes < expectedVec.size(); faultyDestSizes++) { + result = dleEncoder.decode(vecToDecode.data(), vecToDecode.size(), &readLen, buffer.data(), + faultyDestSizes, &decodedLen); + REQUIRE(result == static_cast(DleEncoder::STREAM_TOO_SHORT)); + } }; - SECTION("Encoding") { - testLambdaEncode(dleEncoder, TEST_ARRAY_0, TEST_ARRAY_0_ENCODED_ESCAPED); - testLambdaEncode(dleEncoder, TEST_ARRAY_1, TEST_ARRAY_1_ENCODED_ESCAPED); - testLambdaEncode(dleEncoder, TEST_ARRAY_2, TEST_ARRAY_2_ENCODED_ESCAPED); - testLambdaEncode(dleEncoder, TEST_ARRAY_3, TEST_ARRAY_3_ENCODED_ESCAPED); - testLambdaEncode(dleEncoder, TEST_ARRAY_4, TEST_ARRAY_4_ENCODED_ESCAPED); + testFaultyDecoding(TEST_ARRAY_0_ENCODED_ESCAPED, TEST_ARRAY_0); + testFaultyDecoding(TEST_ARRAY_1_ENCODED_ESCAPED, TEST_ARRAY_1); + testFaultyDecoding(TEST_ARRAY_2_ENCODED_ESCAPED, TEST_ARRAY_2); + testFaultyDecoding(TEST_ARRAY_3_ENCODED_ESCAPED, TEST_ARRAY_3); + testFaultyDecoding(TEST_ARRAY_4_ENCODED_ESCAPED, TEST_ARRAY_4); - auto testFaultyEncoding = [&](const std::vector& vecToEncode, - const std::vector& expectedVec) { + dleEncoder.setEscapeMode(false); + testLambdaDecode(dleEncoder, TEST_ARRAY_0_ENCODED_NON_ESCAPED, TEST_ARRAY_0); + testLambdaDecode(dleEncoder, TEST_ARRAY_1_ENCODED_NON_ESCAPED, TEST_ARRAY_1); + testLambdaDecode(dleEncoder, TEST_ARRAY_2_ENCODED_NON_ESCAPED, TEST_ARRAY_2); + testLambdaDecode(dleEncoder, TEST_ARRAY_3_ENCODED_NON_ESCAPED, TEST_ARRAY_3); + testLambdaDecode(dleEncoder, TEST_ARRAY_4_ENCODED_NON_ESCAPED, TEST_ARRAY_4); - for(size_t faultyDestSize = 0; faultyDestSize < expectedVec.size(); faultyDestSize ++) { - result = dleEncoder.encode(vecToEncode.data(), vecToEncode.size(), - buffer.data(), faultyDestSize, &encodedLen); - REQUIRE(result == static_cast(DleEncoder::STREAM_TOO_SHORT)); - } - }; + testFaultyDecoding(TEST_ARRAY_0_ENCODED_NON_ESCAPED, TEST_ARRAY_0); + testFaultyDecoding(TEST_ARRAY_1_ENCODED_NON_ESCAPED, TEST_ARRAY_1); + testFaultyDecoding(TEST_ARRAY_2_ENCODED_NON_ESCAPED, TEST_ARRAY_2); + testFaultyDecoding(TEST_ARRAY_3_ENCODED_NON_ESCAPED, TEST_ARRAY_3); + testFaultyDecoding(TEST_ARRAY_4_ENCODED_NON_ESCAPED, TEST_ARRAY_4); - testFaultyEncoding(TEST_ARRAY_0, TEST_ARRAY_0_ENCODED_ESCAPED); - testFaultyEncoding(TEST_ARRAY_1, TEST_ARRAY_1_ENCODED_ESCAPED); - testFaultyEncoding(TEST_ARRAY_2, TEST_ARRAY_2_ENCODED_ESCAPED); - testFaultyEncoding(TEST_ARRAY_3, TEST_ARRAY_3_ENCODED_ESCAPED); - testFaultyEncoding(TEST_ARRAY_4, TEST_ARRAY_4_ENCODED_ESCAPED); + // Faulty source data + testArray1EncodedFaulty = TEST_ARRAY_1_ENCODED_NON_ESCAPED; + auto prevVal = testArray1EncodedFaulty[0]; + testArray1EncodedFaulty[0] = 0; + result = dleEncoder.decode(testArray1EncodedFaulty.data(), testArray1EncodedFaulty.size(), + &readLen, buffer.data(), buffer.size(), &encodedLen); + REQUIRE(result == static_cast(DleEncoder::DECODING_ERROR)); + testArray1EncodedFaulty[0] = prevVal; + testArray1EncodedFaulty[1] = 0; + result = dleEncoder.decode(testArray1EncodedFaulty.data(), testArray1EncodedFaulty.size(), + &readLen, buffer.data(), buffer.size(), &encodedLen); + REQUIRE(result == static_cast(DleEncoder::DECODING_ERROR)); - dleEncoder.setEscapeMode(false); - testLambdaEncode(dleEncoder, TEST_ARRAY_0, TEST_ARRAY_0_ENCODED_NON_ESCAPED); - testLambdaEncode(dleEncoder, TEST_ARRAY_1, TEST_ARRAY_1_ENCODED_NON_ESCAPED); - testLambdaEncode(dleEncoder, TEST_ARRAY_2, TEST_ARRAY_2_ENCODED_NON_ESCAPED); - testLambdaEncode(dleEncoder, TEST_ARRAY_3, TEST_ARRAY_3_ENCODED_NON_ESCAPED); - testLambdaEncode(dleEncoder, TEST_ARRAY_4, TEST_ARRAY_4_ENCODED_NON_ESCAPED); + testArray1EncodedFaulty = TEST_ARRAY_1_ENCODED_NON_ESCAPED; + testArray1EncodedFaulty[6] = 0; + result = dleEncoder.decode(testArray1EncodedFaulty.data(), testArray1EncodedFaulty.size(), + &readLen, buffer.data(), buffer.size(), &encodedLen); + REQUIRE(result == static_cast(DleEncoder::DECODING_ERROR)); + testArray1EncodedFaulty = TEST_ARRAY_1_ENCODED_NON_ESCAPED; + testArray1EncodedFaulty[7] = 0; + result = dleEncoder.decode(testArray1EncodedFaulty.data(), testArray1EncodedFaulty.size(), + &readLen, buffer.data(), buffer.size(), &encodedLen); + REQUIRE(result == static_cast(DleEncoder::DECODING_ERROR)); + testArray4EncodedFaulty = TEST_ARRAY_4_ENCODED_NON_ESCAPED; + testArray4EncodedFaulty[3] = 0; + result = dleEncoder.decode(testArray4EncodedFaulty.data(), testArray4EncodedFaulty.size(), + &readLen, buffer.data(), buffer.size(), &encodedLen); + REQUIRE(result == static_cast(DleEncoder::DECODING_ERROR)); - testFaultyEncoding(TEST_ARRAY_0, TEST_ARRAY_0_ENCODED_NON_ESCAPED); - testFaultyEncoding(TEST_ARRAY_1, TEST_ARRAY_1_ENCODED_NON_ESCAPED); - testFaultyEncoding(TEST_ARRAY_2, TEST_ARRAY_2_ENCODED_NON_ESCAPED); - testFaultyEncoding(TEST_ARRAY_3, TEST_ARRAY_3_ENCODED_NON_ESCAPED); - testFaultyEncoding(TEST_ARRAY_4, TEST_ARRAY_4_ENCODED_NON_ESCAPED); - dleEncoder.setEscapeMode(true); - } - - SECTION("Decoding") { - testLambdaDecode(dleEncoder, TEST_ARRAY_0_ENCODED_ESCAPED, TEST_ARRAY_0); - testLambdaDecode(dleEncoder, TEST_ARRAY_1_ENCODED_ESCAPED, TEST_ARRAY_1); - testLambdaDecode(dleEncoder, TEST_ARRAY_2_ENCODED_ESCAPED, TEST_ARRAY_2); - testLambdaDecode(dleEncoder, TEST_ARRAY_3_ENCODED_ESCAPED, TEST_ARRAY_3); - testLambdaDecode(dleEncoder, TEST_ARRAY_4_ENCODED_ESCAPED, TEST_ARRAY_4); - - // Faulty source data - auto testArray1EncodedFaulty = TEST_ARRAY_1_ENCODED_ESCAPED; - testArray1EncodedFaulty[3] = 0; - result = dleEncoder.decode(testArray1EncodedFaulty.data(), testArray1EncodedFaulty.size(), - &readLen, buffer.data(), buffer.size(), &encodedLen); - REQUIRE(result == static_cast(DleEncoder::DECODING_ERROR)); - auto testArray2EncodedFaulty = TEST_ARRAY_2_ENCODED_ESCAPED; - testArray2EncodedFaulty[5] = 0; - result = dleEncoder.decode(testArray2EncodedFaulty.data(), testArray2EncodedFaulty.size(), - &readLen, buffer.data(), buffer.size(), &encodedLen); - REQUIRE(result == static_cast(DleEncoder::DECODING_ERROR)); - auto testArray4EncodedFaulty = TEST_ARRAY_4_ENCODED_ESCAPED; - testArray4EncodedFaulty[2] = 0; - result = dleEncoder.decode(testArray4EncodedFaulty.data(), testArray4EncodedFaulty.size(), - &readLen, buffer.data(), buffer.size(), &encodedLen); - REQUIRE(result == static_cast(DleEncoder::DECODING_ERROR)); - auto testArray4EncodedFaulty2 = TEST_ARRAY_4_ENCODED_ESCAPED; - testArray4EncodedFaulty2[4] = 0; - result = dleEncoder.decode(testArray4EncodedFaulty2.data(), testArray4EncodedFaulty2.size(), - &readLen, buffer.data(), buffer.size(), &encodedLen); - REQUIRE(result == static_cast(DleEncoder::DECODING_ERROR)); - - auto testFaultyDecoding = [&](const std::vector& vecToDecode, - const std::vector& expectedVec) { - for(size_t faultyDestSizes = 0; - faultyDestSizes < expectedVec.size(); - faultyDestSizes ++) { - result = dleEncoder.decode(vecToDecode.data(), - vecToDecode.size(), &readLen, - buffer.data(), faultyDestSizes, &decodedLen); - REQUIRE(result == static_cast(DleEncoder::STREAM_TOO_SHORT)); - } - }; - - testFaultyDecoding(TEST_ARRAY_0_ENCODED_ESCAPED, TEST_ARRAY_0); - testFaultyDecoding(TEST_ARRAY_1_ENCODED_ESCAPED, TEST_ARRAY_1); - testFaultyDecoding(TEST_ARRAY_2_ENCODED_ESCAPED, TEST_ARRAY_2); - testFaultyDecoding(TEST_ARRAY_3_ENCODED_ESCAPED, TEST_ARRAY_3); - testFaultyDecoding(TEST_ARRAY_4_ENCODED_ESCAPED, TEST_ARRAY_4); - - dleEncoder.setEscapeMode(false); - testLambdaDecode(dleEncoder, TEST_ARRAY_0_ENCODED_NON_ESCAPED, TEST_ARRAY_0); - testLambdaDecode(dleEncoder, TEST_ARRAY_1_ENCODED_NON_ESCAPED, TEST_ARRAY_1); - testLambdaDecode(dleEncoder, TEST_ARRAY_2_ENCODED_NON_ESCAPED, TEST_ARRAY_2); - testLambdaDecode(dleEncoder, TEST_ARRAY_3_ENCODED_NON_ESCAPED, TEST_ARRAY_3); - testLambdaDecode(dleEncoder, TEST_ARRAY_4_ENCODED_NON_ESCAPED, TEST_ARRAY_4); - - testFaultyDecoding(TEST_ARRAY_0_ENCODED_NON_ESCAPED, TEST_ARRAY_0); - testFaultyDecoding(TEST_ARRAY_1_ENCODED_NON_ESCAPED, TEST_ARRAY_1); - testFaultyDecoding(TEST_ARRAY_2_ENCODED_NON_ESCAPED, TEST_ARRAY_2); - testFaultyDecoding(TEST_ARRAY_3_ENCODED_NON_ESCAPED, TEST_ARRAY_3); - testFaultyDecoding(TEST_ARRAY_4_ENCODED_NON_ESCAPED, TEST_ARRAY_4); - - // Faulty source data - testArray1EncodedFaulty = TEST_ARRAY_1_ENCODED_NON_ESCAPED; - auto prevVal = testArray1EncodedFaulty[0]; - testArray1EncodedFaulty[0] = 0; - result = dleEncoder.decode(testArray1EncodedFaulty.data(), testArray1EncodedFaulty.size(), - &readLen, buffer.data(), buffer.size(), &encodedLen); - REQUIRE(result == static_cast(DleEncoder::DECODING_ERROR)); - testArray1EncodedFaulty[0] = prevVal; - testArray1EncodedFaulty[1] = 0; - result = dleEncoder.decode(testArray1EncodedFaulty.data(), testArray1EncodedFaulty.size(), - &readLen, buffer.data(), buffer.size(), &encodedLen); - REQUIRE(result == static_cast(DleEncoder::DECODING_ERROR)); - - testArray1EncodedFaulty = TEST_ARRAY_1_ENCODED_NON_ESCAPED; - testArray1EncodedFaulty[6] = 0; - result = dleEncoder.decode(testArray1EncodedFaulty.data(), testArray1EncodedFaulty.size(), - &readLen, buffer.data(), buffer.size(), &encodedLen); - REQUIRE(result == static_cast(DleEncoder::DECODING_ERROR)); - testArray1EncodedFaulty = TEST_ARRAY_1_ENCODED_NON_ESCAPED; - testArray1EncodedFaulty[7] = 0; - result = dleEncoder.decode(testArray1EncodedFaulty.data(), testArray1EncodedFaulty.size(), - &readLen, buffer.data(), buffer.size(), &encodedLen); - REQUIRE(result == static_cast(DleEncoder::DECODING_ERROR)); - testArray4EncodedFaulty = TEST_ARRAY_4_ENCODED_NON_ESCAPED; - testArray4EncodedFaulty[3] = 0; - result = dleEncoder.decode(testArray4EncodedFaulty.data(), testArray4EncodedFaulty.size(), - &readLen, buffer.data(), buffer.size(), &encodedLen); - REQUIRE(result == static_cast(DleEncoder::DECODING_ERROR)); - - dleEncoder.setEscapeMode(true); - testArray1EncodedFaulty = TEST_ARRAY_1_ENCODED_ESCAPED; - testArray1EncodedFaulty[5] = 0; - result = dleEncoder.decode(testArray1EncodedFaulty.data(), testArray1EncodedFaulty.size(), - &readLen, buffer.data(), buffer.size(), &encodedLen); - REQUIRE(result == static_cast(DleEncoder::DECODING_ERROR)); - } + dleEncoder.setEscapeMode(true); + testArray1EncodedFaulty = TEST_ARRAY_1_ENCODED_ESCAPED; + testArray1EncodedFaulty[5] = 0; + result = dleEncoder.decode(testArray1EncodedFaulty.data(), testArray1EncodedFaulty.size(), + &readLen, buffer.data(), buffer.size(), &encodedLen); + REQUIRE(result == static_cast(DleEncoder::DECODING_ERROR)); + } } diff --git a/tests/src/fsfw_tests/unit/globalfunctions/testOpDivider.cpp b/tests/src/fsfw_tests/unit/globalfunctions/testOpDivider.cpp index c02ada83..6044ce15 100644 --- a/tests/src/fsfw_tests/unit/globalfunctions/testOpDivider.cpp +++ b/tests/src/fsfw_tests/unit/globalfunctions/testOpDivider.cpp @@ -1,64 +1,65 @@ -#include "fsfw/globalfunctions/PeriodicOperationDivider.h" #include -TEST_CASE("OpDivider" , "[OpDivider]") { - auto opDivider = PeriodicOperationDivider(1); - REQUIRE(opDivider.getDivider() == 1); - REQUIRE(opDivider.getCounter() == 1); - REQUIRE(opDivider.check() == true); - REQUIRE(opDivider.checkAndIncrement() == true); - REQUIRE(opDivider.getCounter() == 1); - REQUIRE(opDivider.check() == true); - REQUIRE(opDivider.checkAndIncrement() == true); - REQUIRE(opDivider.checkAndIncrement() == true); +#include "fsfw/globalfunctions/PeriodicOperationDivider.h" - opDivider.setDivider(0); - REQUIRE(opDivider.getCounter() == 1); - REQUIRE(opDivider.checkAndIncrement() == true); - REQUIRE(opDivider.getCounter() == 1); - REQUIRE(opDivider.checkAndIncrement() == true); - REQUIRE(opDivider.checkAndIncrement() == true); +TEST_CASE("OpDivider", "[OpDivider]") { + auto opDivider = PeriodicOperationDivider(1); + REQUIRE(opDivider.getDivider() == 1); + REQUIRE(opDivider.getCounter() == 1); + REQUIRE(opDivider.check() == true); + REQUIRE(opDivider.checkAndIncrement() == true); + REQUIRE(opDivider.getCounter() == 1); + REQUIRE(opDivider.check() == true); + REQUIRE(opDivider.checkAndIncrement() == true); + REQUIRE(opDivider.checkAndIncrement() == true); - opDivider.setDivider(2); - opDivider.resetCounter(); - REQUIRE(opDivider.getDivider() == 2); - REQUIRE(opDivider.getCounter() == 1); - REQUIRE(opDivider.check() == false); - REQUIRE(opDivider.checkAndIncrement() == false); - REQUIRE(opDivider.getCounter() == 2); - REQUIRE(opDivider.check() == true); - REQUIRE(opDivider.checkAndIncrement() == true); - REQUIRE(opDivider.getCounter() == 1); - REQUIRE(opDivider.check() == false); - REQUIRE(opDivider.checkAndIncrement() == false); - REQUIRE(opDivider.getCounter() == 2); - REQUIRE(opDivider.checkAndIncrement() == true); - REQUIRE(opDivider.checkAndIncrement() == false); - REQUIRE(opDivider.checkAndIncrement() == true); - REQUIRE(opDivider.checkAndIncrement() == false); + opDivider.setDivider(0); + REQUIRE(opDivider.getCounter() == 1); + REQUIRE(opDivider.checkAndIncrement() == true); + REQUIRE(opDivider.getCounter() == 1); + REQUIRE(opDivider.checkAndIncrement() == true); + REQUIRE(opDivider.checkAndIncrement() == true); - opDivider.setDivider(3); - opDivider.resetCounter(); - REQUIRE(opDivider.checkAndIncrement() == false); - REQUIRE(opDivider.checkAndIncrement() == false); - REQUIRE(opDivider.getCounter() == 3); - REQUIRE(opDivider.checkAndIncrement() == true); - REQUIRE(opDivider.getCounter() == 1); - REQUIRE(opDivider.checkAndIncrement() == false); + opDivider.setDivider(2); + opDivider.resetCounter(); + REQUIRE(opDivider.getDivider() == 2); + REQUIRE(opDivider.getCounter() == 1); + REQUIRE(opDivider.check() == false); + REQUIRE(opDivider.checkAndIncrement() == false); + REQUIRE(opDivider.getCounter() == 2); + REQUIRE(opDivider.check() == true); + REQUIRE(opDivider.checkAndIncrement() == true); + REQUIRE(opDivider.getCounter() == 1); + REQUIRE(opDivider.check() == false); + REQUIRE(opDivider.checkAndIncrement() == false); + REQUIRE(opDivider.getCounter() == 2); + REQUIRE(opDivider.checkAndIncrement() == true); + REQUIRE(opDivider.checkAndIncrement() == false); + REQUIRE(opDivider.checkAndIncrement() == true); + REQUIRE(opDivider.checkAndIncrement() == false); - auto opDividerNonResetting = PeriodicOperationDivider(2, false); - REQUIRE(opDividerNonResetting.getCounter() == 1); - REQUIRE(opDividerNonResetting.check() == false); - REQUIRE(opDividerNonResetting.checkAndIncrement() == false); - REQUIRE(opDividerNonResetting.getCounter() == 2); - REQUIRE(opDividerNonResetting.check() == true); - REQUIRE(opDividerNonResetting.checkAndIncrement() == true); - REQUIRE(opDividerNonResetting.getCounter() == 3); - REQUIRE(opDividerNonResetting.checkAndIncrement() == true); - REQUIRE(opDividerNonResetting.getCounter() == 4); - opDividerNonResetting.resetCounter(); - REQUIRE(opDividerNonResetting.getCounter() == 1); - REQUIRE(opDividerNonResetting.check() == false); - REQUIRE(opDividerNonResetting.checkAndIncrement() == false); - REQUIRE(opDividerNonResetting.getCounter() == 2); + opDivider.setDivider(3); + opDivider.resetCounter(); + REQUIRE(opDivider.checkAndIncrement() == false); + REQUIRE(opDivider.checkAndIncrement() == false); + REQUIRE(opDivider.getCounter() == 3); + REQUIRE(opDivider.checkAndIncrement() == true); + REQUIRE(opDivider.getCounter() == 1); + REQUIRE(opDivider.checkAndIncrement() == false); + + auto opDividerNonResetting = PeriodicOperationDivider(2, false); + REQUIRE(opDividerNonResetting.getCounter() == 1); + REQUIRE(opDividerNonResetting.check() == false); + REQUIRE(opDividerNonResetting.checkAndIncrement() == false); + REQUIRE(opDividerNonResetting.getCounter() == 2); + REQUIRE(opDividerNonResetting.check() == true); + REQUIRE(opDividerNonResetting.checkAndIncrement() == true); + REQUIRE(opDividerNonResetting.getCounter() == 3); + REQUIRE(opDividerNonResetting.checkAndIncrement() == true); + REQUIRE(opDividerNonResetting.getCounter() == 4); + opDividerNonResetting.resetCounter(); + REQUIRE(opDividerNonResetting.getCounter() == 1); + REQUIRE(opDividerNonResetting.check() == false); + REQUIRE(opDividerNonResetting.checkAndIncrement() == false); + REQUIRE(opDividerNonResetting.getCounter() == 2); } diff --git a/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp b/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp index d7e55af5..d2a15137 100644 --- a/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp +++ b/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp @@ -1,112 +1,111 @@ -#include - -#include "fsfw/serviceinterface.h" - -#include "fsfw/container/SimpleRingBuffer.h" -#include "fsfw/container/DynamicFIFO.h" - -#include "fsfw_hal/linux/CommandExecutor.h" -#include "fsfw/platform.h" - #include + +#include #include +#include "fsfw/container/DynamicFIFO.h" +#include "fsfw/container/SimpleRingBuffer.h" +#include "fsfw/platform.h" +#include "fsfw/serviceinterface.h" +#include "fsfw_hal/linux/CommandExecutor.h" + #ifdef PLATFORM_UNIX static const char TEST_FILE_NAME[] = "/tmp/fsfw-unittest-test.txt"; -TEST_CASE( "Command Executor" , "[cmd-exec]") { - // Check blocking mode first - CommandExecutor cmdExecutor(1024); - std::string cmd = "echo \"test\" >> " + std::string(TEST_FILE_NAME); - REQUIRE(cmdExecutor.getCurrentState() == CommandExecutor::States::IDLE); - ReturnValue_t result = cmdExecutor.load(cmd, true, true); - REQUIRE(cmdExecutor.getCurrentState() == CommandExecutor::States::COMMAND_LOADED); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - REQUIRE(cmdExecutor.execute() == HasReturnvaluesIF::RETURN_OK); - // Check that file exists with contents - std::ifstream file(TEST_FILE_NAME); - std::string line; - std::getline(file, line); - CHECK(line == "test"); - std::remove(TEST_FILE_NAME); - REQUIRE(cmdExecutor.getCurrentState() == CommandExecutor::States::IDLE); +TEST_CASE("Command Executor", "[cmd-exec]") { + // Check blocking mode first + CommandExecutor cmdExecutor(1024); + std::string cmd = "echo \"test\" >> " + std::string(TEST_FILE_NAME); + REQUIRE(cmdExecutor.getCurrentState() == CommandExecutor::States::IDLE); + ReturnValue_t result = cmdExecutor.load(cmd, true, true); + REQUIRE(cmdExecutor.getCurrentState() == CommandExecutor::States::COMMAND_LOADED); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + REQUIRE(cmdExecutor.execute() == HasReturnvaluesIF::RETURN_OK); + // Check that file exists with contents + std::ifstream file(TEST_FILE_NAME); + std::string line; + std::getline(file, line); + CHECK(line == "test"); + std::remove(TEST_FILE_NAME); + REQUIRE(cmdExecutor.getCurrentState() == CommandExecutor::States::IDLE); - // Now check non-blocking mode - SimpleRingBuffer outputBuffer(524, true); - DynamicFIFO sizesFifo(12); - cmdExecutor.setRingBuffer(&outputBuffer, &sizesFifo); + // Now check non-blocking mode + SimpleRingBuffer outputBuffer(524, true); + DynamicFIFO sizesFifo(12); + cmdExecutor.setRingBuffer(&outputBuffer, &sizesFifo); - result = cmdExecutor.load("echo \"Hello World\"", false, false); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - cmdExecutor.execute(); - bool bytesHaveBeenRead = false; - size_t limitIdx = 0; - while(result != CommandExecutor::EXECUTION_FINISHED) { - limitIdx++; - result = cmdExecutor.check(bytesHaveBeenRead); - REQUIRE(result != CommandExecutor::COMMAND_ERROR); - usleep(500); - REQUIRE(limitIdx < 5); - } + result = cmdExecutor.load("echo \"Hello World\"", false, false); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + cmdExecutor.execute(); + bool bytesHaveBeenRead = false; + size_t limitIdx = 0; + while (result != CommandExecutor::EXECUTION_FINISHED) { + limitIdx++; + result = cmdExecutor.check(bytesHaveBeenRead); + REQUIRE(result != CommandExecutor::COMMAND_ERROR); + usleep(500); + REQUIRE(limitIdx < 5); + } - limitIdx = 0; - CHECK(bytesHaveBeenRead == true); - CHECK(result == CommandExecutor::EXECUTION_FINISHED); - uint16_t readBytes = 0; - sizesFifo.retrieve(&readBytes); - REQUIRE(readBytes == 12); - REQUIRE(outputBuffer.getAvailableReadData() == 12); - uint8_t readBuffer[32] = {}; - REQUIRE(outputBuffer.readData(readBuffer, 12) == HasReturnvaluesIF::RETURN_OK); - std::string readString(reinterpret_cast(readBuffer)); - std::string cmpString = "Hello World\n"; - CHECK(readString == cmpString); - outputBuffer.deleteData(12, true); - // Test more complex command - result = cmdExecutor.load("ping -c 1 localhost", false, false); - REQUIRE(cmdExecutor.getCurrentState() == CommandExecutor::States::COMMAND_LOADED); - REQUIRE(cmdExecutor.execute() == HasReturnvaluesIF::RETURN_OK); - REQUIRE(cmdExecutor.getCurrentState() == CommandExecutor::States::PENDING); - limitIdx = 0; - while(result != CommandExecutor::EXECUTION_FINISHED) { - limitIdx++; - result = cmdExecutor.check(bytesHaveBeenRead); - REQUIRE(result != CommandExecutor::COMMAND_ERROR); - usleep(500); - REQUIRE(limitIdx < 20); - } - limitIdx = 0; - CHECK(bytesHaveBeenRead == true); - CHECK(result == CommandExecutor::EXECUTION_FINISHED); - REQUIRE(cmdExecutor.getCurrentState() == CommandExecutor::States::IDLE); - readBytes = 0; - sizesFifo.retrieve(&readBytes); - // That's about the size of the reply - bool beTrue = (readBytes > 200) and (readBytes < 300); - REQUIRE(beTrue); - uint8_t largerReadBuffer[1024] = {}; - outputBuffer.readData(largerReadBuffer, readBytes); - // You can also check this output in the debugger - std::string allTheReply(reinterpret_cast(largerReadBuffer)); - // I am just going to assume that this string is the same across ping implementations - // of different Linux systems - REQUIRE(allTheReply.find("localhost ping statistics") != std::string::npos); + limitIdx = 0; + CHECK(bytesHaveBeenRead == true); + CHECK(result == CommandExecutor::EXECUTION_FINISHED); + uint16_t readBytes = 0; + sizesFifo.retrieve(&readBytes); + REQUIRE(readBytes == 12); + REQUIRE(outputBuffer.getAvailableReadData() == 12); + uint8_t readBuffer[32] = {}; + REQUIRE(outputBuffer.readData(readBuffer, 12) == HasReturnvaluesIF::RETURN_OK); + std::string readString(reinterpret_cast(readBuffer)); + std::string cmpString = "Hello World\n"; + CHECK(readString == cmpString); + outputBuffer.deleteData(12, true); + // Test more complex command + result = cmdExecutor.load("ping -c 1 localhost", false, false); + REQUIRE(cmdExecutor.getCurrentState() == CommandExecutor::States::COMMAND_LOADED); + REQUIRE(cmdExecutor.execute() == HasReturnvaluesIF::RETURN_OK); + REQUIRE(cmdExecutor.getCurrentState() == CommandExecutor::States::PENDING); + limitIdx = 0; + while (result != CommandExecutor::EXECUTION_FINISHED) { + limitIdx++; + result = cmdExecutor.check(bytesHaveBeenRead); + REQUIRE(result != CommandExecutor::COMMAND_ERROR); + usleep(500); + REQUIRE(limitIdx < 20); + } + limitIdx = 0; + CHECK(bytesHaveBeenRead == true); + CHECK(result == CommandExecutor::EXECUTION_FINISHED); + REQUIRE(cmdExecutor.getCurrentState() == CommandExecutor::States::IDLE); + readBytes = 0; + sizesFifo.retrieve(&readBytes); + // That's about the size of the reply + bool beTrue = (readBytes > 200) and (readBytes < 300); + REQUIRE(beTrue); + uint8_t largerReadBuffer[1024] = {}; + outputBuffer.readData(largerReadBuffer, readBytes); + // You can also check this output in the debugger + std::string allTheReply(reinterpret_cast(largerReadBuffer)); + // I am just going to assume that this string is the same across ping implementations + // of different Linux systems + REQUIRE(allTheReply.find("localhost ping statistics") != std::string::npos); - // Now check failing command - result = cmdExecutor.load("false", false, false); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - result = cmdExecutor.execute(); - REQUIRE(result == HasReturnvaluesIF::RETURN_OK); - while(result != CommandExecutor::EXECUTION_FINISHED and result != HasReturnvaluesIF::RETURN_FAILED) { - limitIdx++; - result = cmdExecutor.check(bytesHaveBeenRead); - REQUIRE(result != CommandExecutor::COMMAND_ERROR); - usleep(500); - REQUIRE(limitIdx < 20); - } - REQUIRE(result == HasReturnvaluesIF::RETURN_FAILED); - REQUIRE(cmdExecutor.getLastError() == 1); + // Now check failing command + result = cmdExecutor.load("false", false, false); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + result = cmdExecutor.execute(); + REQUIRE(result == HasReturnvaluesIF::RETURN_OK); + while (result != CommandExecutor::EXECUTION_FINISHED and + result != HasReturnvaluesIF::RETURN_FAILED) { + limitIdx++; + result = cmdExecutor.check(bytesHaveBeenRead); + REQUIRE(result != CommandExecutor::COMMAND_ERROR); + usleep(500); + REQUIRE(limitIdx < 20); + } + REQUIRE(result == HasReturnvaluesIF::RETURN_FAILED); + REQUIRE(cmdExecutor.getLastError() == 1); } #endif diff --git a/tests/src/fsfw_tests/unit/mocks/HkReceiverMock.h b/tests/src/fsfw_tests/unit/mocks/HkReceiverMock.h index e7509c59..8d4b4983 100644 --- a/tests/src/fsfw_tests/unit/mocks/HkReceiverMock.h +++ b/tests/src/fsfw_tests/unit/mocks/HkReceiverMock.h @@ -4,17 +4,11 @@ #include #include -class HkReceiverMock: public SystemObject, public AcceptsHkPacketsIF { -public: - HkReceiverMock(object_id_t objectId): SystemObject(objectId) { +class HkReceiverMock : public SystemObject, public AcceptsHkPacketsIF { + public: + HkReceiverMock(object_id_t objectId) : SystemObject(objectId) {} - } - - MessageQueueId_t getHkQueue() const { - return MessageQueueIF::NO_QUEUE; - } + MessageQueueId_t getHkQueue() const { return MessageQueueIF::NO_QUEUE; } }; - - #endif /* FSFW_UNITTEST_TESTS_MOCKS_HKRECEIVERMOCK_H_ */ diff --git a/tests/src/fsfw_tests/unit/mocks/MessageQueueMockBase.h b/tests/src/fsfw_tests/unit/mocks/MessageQueueMockBase.h index 93a00b7a..f60c7402 100644 --- a/tests/src/fsfw_tests/unit/mocks/MessageQueueMockBase.h +++ b/tests/src/fsfw_tests/unit/mocks/MessageQueueMockBase.h @@ -1,123 +1,105 @@ #ifndef FSFW_UNITTEST_TESTS_MOCKS_MESSAGEQUEUEMOCKBASE_H_ #define FSFW_UNITTEST_TESTS_MOCKS_MESSAGEQUEUEMOCKBASE_H_ -#include "fsfw_tests/unit/CatchDefinitions.h" +#include +#include #include "fsfw/ipc/CommandMessage.h" #include "fsfw/ipc/MessageQueueIF.h" #include "fsfw/ipc/MessageQueueMessage.h" +#include "fsfw_tests/unit/CatchDefinitions.h" -#include +class MessageQueueMockBase : public MessageQueueIF { + public: + MessageQueueId_t myQueueId = tconst::testQueueId; + uint8_t messageSentCounter = 0; + bool defaultDestSet = false; + bool messageSent = false; -#include + bool wasMessageSent(uint8_t* messageSentCounter = nullptr, bool resetCounter = true) { + bool tempMessageSent = messageSent; + messageSent = false; + if (messageSentCounter != nullptr) { + *messageSentCounter = this->messageSentCounter; + } + if (resetCounter) { + this->messageSentCounter = 0; + } + return tempMessageSent; + } -class MessageQueueMockBase: public MessageQueueIF { -public: - MessageQueueId_t myQueueId = tconst::testQueueId; - uint8_t messageSentCounter = 0; - bool defaultDestSet = false; - bool messageSent = false; + /** + * Pop a message, clearing it in the process. + * @return + */ + ReturnValue_t popMessage() { + CommandMessage message; + message.clear(); + return receiveMessage(&message); + } + virtual ReturnValue_t reply(MessageQueueMessageIF* message) { + return sendMessage(myQueueId, message); + }; + virtual ReturnValue_t receiveMessage(MessageQueueMessageIF* message, + MessageQueueId_t* receivedFrom) { + return receiveMessage(message); + } - bool wasMessageSent(uint8_t* messageSentCounter = nullptr, - bool resetCounter = true) { - bool tempMessageSent = messageSent; - messageSent = false; - if(messageSentCounter != nullptr) { - *messageSentCounter = this->messageSentCounter; - } - if(resetCounter) { - this->messageSentCounter = 0; - } - return tempMessageSent; - } + virtual ReturnValue_t receiveMessage(MessageQueueMessageIF* message) { + if (messagesSentQueue.empty()) { + return MessageQueueIF::EMPTY; + } - /** - * Pop a message, clearing it in the process. - * @return - */ - ReturnValue_t popMessage() { - CommandMessage message; - message.clear(); - return receiveMessage(&message); - } + std::memcpy(message->getBuffer(), messagesSentQueue.front().getBuffer(), + message->getMessageSize()); + messagesSentQueue.pop(); + return HasReturnvaluesIF::RETURN_OK; + } + virtual ReturnValue_t flush(uint32_t* count) { return HasReturnvaluesIF::RETURN_OK; } + virtual MessageQueueId_t getLastPartner() const { return myQueueId; } + virtual MessageQueueId_t getId() const { return myQueueId; } + virtual ReturnValue_t sendMessageFrom(MessageQueueId_t sendTo, MessageQueueMessageIF* message, + MessageQueueId_t sentFrom, bool ignoreFault = false) { + return sendMessage(sendTo, message); + } + virtual ReturnValue_t sendToDefaultFrom(MessageQueueMessageIF* message, MessageQueueId_t sentFrom, + bool ignoreFault = false) { + return sendMessage(myQueueId, message); + } + virtual ReturnValue_t sendToDefault(MessageQueueMessageIF* message) { + return sendMessage(myQueueId, message); + } + virtual ReturnValue_t sendMessage(MessageQueueId_t sendTo, MessageQueueMessageIF* message, + bool ignoreFault = false) override { + messageSent = true; + messageSentCounter++; + MessageQueueMessage& messageRef = *(dynamic_cast(message)); + messagesSentQueue.push(messageRef); + return HasReturnvaluesIF::RETURN_OK; + } + virtual void setDefaultDestination(MessageQueueId_t defaultDestination) { + myQueueId = defaultDestination; + defaultDestSet = true; + } - virtual ReturnValue_t reply( MessageQueueMessageIF* message ) { - return sendMessage(myQueueId, message); - }; - virtual ReturnValue_t receiveMessage(MessageQueueMessageIF* message, - MessageQueueId_t *receivedFrom) { - return receiveMessage(message); - } + virtual MessageQueueId_t getDefaultDestination() const { return myQueueId; } + virtual bool isDefaultDestinationSet() const { return defaultDestSet; } - virtual ReturnValue_t receiveMessage(MessageQueueMessageIF* message) { - if(messagesSentQueue.empty()) { - return MessageQueueIF::EMPTY; - } + void clearMessages(bool clearCommandMessages = true) { + while (not messagesSentQueue.empty()) { + if (clearCommandMessages) { + CommandMessage message; + std::memcpy(message.getBuffer(), messagesSentQueue.front().getBuffer(), + message.getMessageSize()); + message.clear(); + } + messagesSentQueue.pop(); + } + } - std::memcpy(message->getBuffer(), messagesSentQueue.front().getBuffer(), - message->getMessageSize()); - messagesSentQueue.pop(); - return HasReturnvaluesIF::RETURN_OK; - } - virtual ReturnValue_t flush(uint32_t* count) { - return HasReturnvaluesIF::RETURN_OK; - } - virtual MessageQueueId_t getLastPartner() const { - return myQueueId; - } - virtual MessageQueueId_t getId() const { - return myQueueId; - } - virtual ReturnValue_t sendMessageFrom( MessageQueueId_t sendTo, - MessageQueueMessageIF* message, MessageQueueId_t sentFrom, - bool ignoreFault = false ) { - return sendMessage(sendTo, message); - } - virtual ReturnValue_t sendToDefaultFrom( MessageQueueMessageIF* message, - MessageQueueId_t sentFrom, bool ignoreFault = false ) { - return sendMessage(myQueueId, message); - } - virtual ReturnValue_t sendToDefault( MessageQueueMessageIF* message ) { - return sendMessage(myQueueId, message); - } - virtual ReturnValue_t sendMessage( MessageQueueId_t sendTo, - MessageQueueMessageIF* message, bool ignoreFault = false ) override { - messageSent = true; - messageSentCounter++; - MessageQueueMessage& messageRef = *( - dynamic_cast(message)); - messagesSentQueue.push(messageRef); - return HasReturnvaluesIF::RETURN_OK; - } - virtual void setDefaultDestination(MessageQueueId_t defaultDestination) { - myQueueId = defaultDestination; - defaultDestSet = true; - } - - virtual MessageQueueId_t getDefaultDestination() const { - return myQueueId; - } - virtual bool isDefaultDestinationSet() const { - return defaultDestSet; - } - - void clearMessages(bool clearCommandMessages = true) { - while(not messagesSentQueue.empty()) { - if(clearCommandMessages) { - CommandMessage message; - std::memcpy(message.getBuffer(), - messagesSentQueue.front().getBuffer(), - message.getMessageSize()); - message.clear(); - } - messagesSentQueue.pop(); - } - } - -private: - std::queue messagesSentQueue; + private: + std::queue messagesSentQueue; }; - #endif /* FSFW_UNITTEST_TESTS_MOCKS_MESSAGEQUEUEMOCKBASE_H_ */ diff --git a/tests/src/fsfw_tests/unit/osal/TestMessageQueue.cpp b/tests/src/fsfw_tests/unit/osal/TestMessageQueue.cpp index 07197bf7..232ffb94 100644 --- a/tests/src/fsfw_tests/unit/osal/TestMessageQueue.cpp +++ b/tests/src/fsfw_tests/unit/osal/TestMessageQueue.cpp @@ -1,43 +1,38 @@ -#include "fsfw_tests/unit/CatchDefinitions.h" - #include #include +#include #include -#include +#include "fsfw_tests/unit/CatchDefinitions.h" -TEST_CASE("MessageQueue Basic Test","[TestMq]") { - MessageQueueIF* testSenderMq = - QueueFactory::instance()->createMessageQueue(1); - MessageQueueId_t testSenderMqId = testSenderMq->getId(); +TEST_CASE("MessageQueue Basic Test", "[TestMq]") { + MessageQueueIF* testSenderMq = QueueFactory::instance()->createMessageQueue(1); + MessageQueueId_t testSenderMqId = testSenderMq->getId(); - MessageQueueIF* testReceiverMq = - QueueFactory::instance()->createMessageQueue(1); - MessageQueueId_t testReceiverMqId = testReceiverMq->getId(); - std::array testData { 0 }; - testData[0] = 42; - MessageQueueMessage testMessage(testData.data(), 1); - testSenderMq->setDefaultDestination(testReceiverMqId); - - SECTION("Simple Tests") { - auto result = testSenderMq->sendMessage(testReceiverMqId, &testMessage); - REQUIRE(result == retval::CATCH_OK); - MessageQueueMessage recvMessage; - result = testReceiverMq->receiveMessage(&recvMessage); - REQUIRE(result == retval::CATCH_OK); - CHECK(recvMessage.getData()[0] == 42); - - result = testSenderMq->sendMessage(testReceiverMqId, &testMessage); - REQUIRE(result == retval::CATCH_OK); - MessageQueueId_t senderId = 0; - result = testReceiverMq->receiveMessage(&recvMessage,&senderId); - REQUIRE(result == retval::CATCH_OK); - CHECK(recvMessage.getData()[0] == 42); - CHECK(senderId == testSenderMqId); - senderId = testReceiverMq->getLastPartner(); - CHECK(senderId == testSenderMqId); - } + MessageQueueIF* testReceiverMq = QueueFactory::instance()->createMessageQueue(1); + MessageQueueId_t testReceiverMqId = testReceiverMq->getId(); + std::array testData{0}; + testData[0] = 42; + MessageQueueMessage testMessage(testData.data(), 1); + testSenderMq->setDefaultDestination(testReceiverMqId); + SECTION("Simple Tests") { + auto result = testSenderMq->sendMessage(testReceiverMqId, &testMessage); + REQUIRE(result == retval::CATCH_OK); + MessageQueueMessage recvMessage; + result = testReceiverMq->receiveMessage(&recvMessage); + REQUIRE(result == retval::CATCH_OK); + CHECK(recvMessage.getData()[0] == 42); + result = testSenderMq->sendMessage(testReceiverMqId, &testMessage); + REQUIRE(result == retval::CATCH_OK); + MessageQueueId_t senderId = 0; + result = testReceiverMq->receiveMessage(&recvMessage, &senderId); + REQUIRE(result == retval::CATCH_OK); + CHECK(recvMessage.getData()[0] == 42); + CHECK(senderId == testSenderMqId); + senderId = testReceiverMq->getLastPartner(); + CHECK(senderId == testSenderMqId); + } } diff --git a/tests/src/fsfw_tests/unit/osal/TestSemaphore.cpp b/tests/src/fsfw_tests/unit/osal/TestSemaphore.cpp index f7b25534..6988af5b 100644 --- a/tests/src/fsfw_tests/unit/osal/TestSemaphore.cpp +++ b/tests/src/fsfw_tests/unit/osal/TestSemaphore.cpp @@ -2,44 +2,44 @@ #ifdef LINUX /* -#include "core/CatchDefinitions.h" -#include "catch.hpp" - #include #include +#include "catch.hpp" +#include "core/CatchDefinitions.h" + TEST_CASE("Binary Semaphore Test" , "[BinSemaphore]") { - //perform set-up here - SemaphoreIF* binSemaph = SemaphoreFactory::instance()-> - createBinarySemaphore(); - REQUIRE(binSemaph != nullptr); - SECTION("Simple Test") { - // set-up is run for each section - REQUIRE(binSemaph->getSemaphoreCounter() == 1); - REQUIRE(binSemaph->release() == - static_cast(SemaphoreIF::SEMAPHORE_NOT_OWNED)); - REQUIRE(binSemaph->acquire(SemaphoreIF::POLLING) == - retval::CATCH_OK); - { - // not precise enough on linux.. should use clock instead.. - //Stopwatch stopwatch(false); - //REQUIRE(binSemaph->acquire(SemaphoreIF::TimeoutType::WAITING, 5) == - // SemaphoreIF::SEMAPHORE_TIMEOUT); - //dur_millis_t time = stopwatch.stop(); - //CHECK(time == 5); - } - REQUIRE(binSemaph->getSemaphoreCounter() == 0); - REQUIRE(binSemaph->release() == retval::CATCH_OK); - } - SemaphoreFactory::instance()->deleteSemaphore(binSemaph); - // perform tear-down here + //perform set-up here + SemaphoreIF* binSemaph = SemaphoreFactory::instance()-> + createBinarySemaphore(); + REQUIRE(binSemaph != nullptr); + SECTION("Simple Test") { + // set-up is run for each section + REQUIRE(binSemaph->getSemaphoreCounter() == 1); + REQUIRE(binSemaph->release() == + static_cast(SemaphoreIF::SEMAPHORE_NOT_OWNED)); + REQUIRE(binSemaph->acquire(SemaphoreIF::POLLING) == + retval::CATCH_OK); + { + // not precise enough on linux.. should use clock instead.. + //Stopwatch stopwatch(false); + //REQUIRE(binSemaph->acquire(SemaphoreIF::TimeoutType::WAITING, 5) == + // SemaphoreIF::SEMAPHORE_TIMEOUT); + //dur_millis_t time = stopwatch.stop(); + //CHECK(time == 5); + } + REQUIRE(binSemaph->getSemaphoreCounter() == 0); + REQUIRE(binSemaph->release() == retval::CATCH_OK); + } + SemaphoreFactory::instance()->deleteSemaphore(binSemaph); + // perform tear-down here } TEST_CASE("Counting Semaphore Test" , "[CountingSemaph]") { - SECTION("Simple Test") { + SECTION("Simple Test") { - } + } } */ diff --git a/tests/src/fsfw_tests/unit/printChar.cpp b/tests/src/fsfw_tests/unit/printChar.cpp index 5d4f1b17..0e29fe2b 100644 --- a/tests/src/fsfw_tests/unit/printChar.cpp +++ b/tests/src/fsfw_tests/unit/printChar.cpp @@ -1,10 +1,11 @@ #include "printChar.h" + #include void printChar(const char* character, bool errStream) { - if(errStream) { - std::putc(*character, stderr); - return; - } - std::putc(*character, stdout); + if (errStream) { + std::putc(*character, stderr); + return; + } + std::putc(*character, stdout); } diff --git a/tests/src/fsfw_tests/unit/printChar.h b/tests/src/fsfw_tests/unit/printChar.h index 80e867f6..1991161f 100644 --- a/tests/src/fsfw_tests/unit/printChar.h +++ b/tests/src/fsfw_tests/unit/printChar.h @@ -1,8 +1,6 @@ #ifndef FSFW_UNITTEST_CORE_PRINTCHAR_H_ #define FSFW_UNITTEST_CORE_PRINTCHAR_H_ - extern "C" void printChar(const char*, bool errStream); - #endif /* FSFW_UNITTEST_CORE_PRINTCHAR_H_ */ diff --git a/tests/src/fsfw_tests/unit/serialize/TestSerialBufferAdapter.cpp b/tests/src/fsfw_tests/unit/serialize/TestSerialBufferAdapter.cpp index 01d75881..9b30427f 100644 --- a/tests/src/fsfw_tests/unit/serialize/TestSerialBufferAdapter.cpp +++ b/tests/src/fsfw_tests/unit/serialize/TestSerialBufferAdapter.cpp @@ -1,147 +1,134 @@ -#include "fsfw_tests/unit/CatchDefinitions.h" - #include +#include #include - -#include - +#include "fsfw_tests/unit/CatchDefinitions.h" static bool test_value_bool = true; -static uint16_t tv_uint16 {283}; +static uint16_t tv_uint16{283}; static std::array testArray; TEST_CASE("Serial Buffer Adapter", "[single-file]") { - size_t serialized_size = 0; - test_value_bool = true; - uint8_t * arrayPtr = testArray.data(); - std::array test_serial_buffer {5, 4, 3, 2, 1}; - SerialBufferAdapter tv_serial_buffer_adapter = - SerialBufferAdapter(test_serial_buffer.data(), - test_serial_buffer.size(), false); - tv_uint16 = 16; + size_t serialized_size = 0; + test_value_bool = true; + uint8_t* arrayPtr = testArray.data(); + std::array test_serial_buffer{5, 4, 3, 2, 1}; + SerialBufferAdapter tv_serial_buffer_adapter = + SerialBufferAdapter(test_serial_buffer.data(), test_serial_buffer.size(), false); + tv_uint16 = 16; - SECTION("Serialize without size field") { - SerializeAdapter::serialize(&test_value_bool, &arrayPtr, - &serialized_size, testArray.size(), - SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tv_serial_buffer_adapter, &arrayPtr, - &serialized_size, testArray.size(), - SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tv_uint16, &arrayPtr, &serialized_size, - testArray.size(), SerializeIF::Endianness::MACHINE); + SECTION("Serialize without size field") { + SerializeAdapter::serialize(&test_value_bool, &arrayPtr, &serialized_size, testArray.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tv_serial_buffer_adapter, &arrayPtr, &serialized_size, + testArray.size(), SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tv_uint16, &arrayPtr, &serialized_size, testArray.size(), + SerializeIF::Endianness::MACHINE); - REQUIRE(serialized_size == 8); - REQUIRE(testArray[0] == true); - REQUIRE(testArray[1] == 5); - REQUIRE(testArray[2] == 4); - REQUIRE(testArray[3] == 3); - REQUIRE(testArray[4] == 2); - REQUIRE(testArray[5] == 1); - memcpy(&tv_uint16, testArray.data() + 6, sizeof(tv_uint16)); - REQUIRE(tv_uint16 == 16); - } + REQUIRE(serialized_size == 8); + REQUIRE(testArray[0] == true); + REQUIRE(testArray[1] == 5); + REQUIRE(testArray[2] == 4); + REQUIRE(testArray[3] == 3); + REQUIRE(testArray[4] == 2); + REQUIRE(testArray[5] == 1); + memcpy(&tv_uint16, testArray.data() + 6, sizeof(tv_uint16)); + REQUIRE(tv_uint16 == 16); + } - SECTION("Serialize with size field") { - SerialBufferAdapter tv_serial_buffer_adapter_loc = - SerialBufferAdapter(test_serial_buffer.data(), - test_serial_buffer.size(), true); - serialized_size = 0; - arrayPtr = testArray.data(); - SerializeAdapter::serialize(&test_value_bool, &arrayPtr,&serialized_size, - testArray.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tv_serial_buffer_adapter_loc, &arrayPtr, - &serialized_size, testArray.size(), - SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tv_uint16, &arrayPtr, &serialized_size, - testArray.size(), SerializeIF::Endianness::MACHINE); + SECTION("Serialize with size field") { + SerialBufferAdapter tv_serial_buffer_adapter_loc = + SerialBufferAdapter(test_serial_buffer.data(), test_serial_buffer.size(), true); + serialized_size = 0; + arrayPtr = testArray.data(); + SerializeAdapter::serialize(&test_value_bool, &arrayPtr, &serialized_size, testArray.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tv_serial_buffer_adapter_loc, &arrayPtr, &serialized_size, + testArray.size(), SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tv_uint16, &arrayPtr, &serialized_size, testArray.size(), + SerializeIF::Endianness::MACHINE); - REQUIRE(serialized_size == 9); - REQUIRE(testArray[0] == true); - REQUIRE(testArray[1] == 5); - REQUIRE(testArray[2] == 5); - REQUIRE(testArray[3] == 4); - REQUIRE(testArray[4] == 3); - REQUIRE(testArray[5] == 2); - REQUIRE(testArray[6] == 1); - memcpy(&tv_uint16, testArray.data() + 7, sizeof(tv_uint16)); - REQUIRE(tv_uint16 == 16); - } + REQUIRE(serialized_size == 9); + REQUIRE(testArray[0] == true); + REQUIRE(testArray[1] == 5); + REQUIRE(testArray[2] == 5); + REQUIRE(testArray[3] == 4); + REQUIRE(testArray[4] == 3); + REQUIRE(testArray[5] == 2); + REQUIRE(testArray[6] == 1); + memcpy(&tv_uint16, testArray.data() + 7, sizeof(tv_uint16)); + REQUIRE(tv_uint16 == 16); + } - SECTION("Test set buffer function") { - SerialBufferAdapter tv_serial_buffer_adapter_loc = - SerialBufferAdapter((uint8_t*)nullptr, - 0, true); - tv_serial_buffer_adapter_loc.setBuffer(test_serial_buffer.data(), - test_serial_buffer.size()); - serialized_size = 0; - arrayPtr = testArray.data(); - SerializeAdapter::serialize(&test_value_bool, &arrayPtr,&serialized_size, - testArray.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tv_serial_buffer_adapter_loc, &arrayPtr, - &serialized_size, testArray.size(), - SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tv_uint16, &arrayPtr, &serialized_size, - testArray.size(), SerializeIF::Endianness::MACHINE); - REQUIRE(serialized_size == 9); - REQUIRE(testArray[0] == true); - REQUIRE(testArray[1] == 5); - REQUIRE(testArray[2] == 5); - REQUIRE(testArray[3] == 4); - REQUIRE(testArray[4] == 3); - REQUIRE(testArray[5] == 2); - REQUIRE(testArray[6] == 1); - memcpy(&tv_uint16, testArray.data() + 7, sizeof(tv_uint16)); - REQUIRE(tv_uint16 == 16); - } + SECTION("Test set buffer function") { + SerialBufferAdapter tv_serial_buffer_adapter_loc = + SerialBufferAdapter((uint8_t*)nullptr, 0, true); + tv_serial_buffer_adapter_loc.setBuffer(test_serial_buffer.data(), test_serial_buffer.size()); + serialized_size = 0; + arrayPtr = testArray.data(); + SerializeAdapter::serialize(&test_value_bool, &arrayPtr, &serialized_size, testArray.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tv_serial_buffer_adapter_loc, &arrayPtr, &serialized_size, + testArray.size(), SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tv_uint16, &arrayPtr, &serialized_size, testArray.size(), + SerializeIF::Endianness::MACHINE); + REQUIRE(serialized_size == 9); + REQUIRE(testArray[0] == true); + REQUIRE(testArray[1] == 5); + REQUIRE(testArray[2] == 5); + REQUIRE(testArray[3] == 4); + REQUIRE(testArray[4] == 3); + REQUIRE(testArray[5] == 2); + REQUIRE(testArray[6] == 1); + memcpy(&tv_uint16, testArray.data() + 7, sizeof(tv_uint16)); + REQUIRE(tv_uint16 == 16); + } - SECTION("Deserialization with size field") { - size_t buffer_size = 4; - memcpy(testArray.data(), &buffer_size, sizeof(uint16_t)); - testArray[2] = 1; - testArray[3] = 1; - testArray[4] = 1; - testArray[5] = 0; - std::array test_recv_array; - arrayPtr = testArray.data(); - // copy testArray[1] to testArray[4] into receive buffer, skip - // size field (testArray[0]) for deSerialization. - SerialBufferAdapter tv_serial_buffer_adapter3 = - SerialBufferAdapter(test_recv_array.data(), 4, true); - // Deserialization - size_t size = 6; - auto result = tv_serial_buffer_adapter3.deSerialize( - const_cast(&arrayPtr), &size, - SerializeIF::Endianness::MACHINE); - REQUIRE(result == retval::CATCH_OK); - CHECK(test_recv_array[0] == 1); - CHECK(test_recv_array[1] == 1); - CHECK(test_recv_array[2] == 1); - CHECK(test_recv_array[3] == 0); - } + SECTION("Deserialization with size field") { + size_t buffer_size = 4; + memcpy(testArray.data(), &buffer_size, sizeof(uint16_t)); + testArray[2] = 1; + testArray[3] = 1; + testArray[4] = 1; + testArray[5] = 0; + std::array test_recv_array; + arrayPtr = testArray.data(); + // copy testArray[1] to testArray[4] into receive buffer, skip + // size field (testArray[0]) for deSerialization. + SerialBufferAdapter tv_serial_buffer_adapter3 = + SerialBufferAdapter(test_recv_array.data(), 4, true); + // Deserialization + size_t size = 6; + auto result = tv_serial_buffer_adapter3.deSerialize(const_cast(&arrayPtr), + &size, SerializeIF::Endianness::MACHINE); + REQUIRE(result == retval::CATCH_OK); + CHECK(test_recv_array[0] == 1); + CHECK(test_recv_array[1] == 1); + CHECK(test_recv_array[2] == 1); + CHECK(test_recv_array[3] == 0); + } - SECTION("Deserialization without size field") { - size_t buffer_size = 4; - memcpy(testArray.data(), &buffer_size, sizeof(uint16_t)); - testArray[2] = 1; - testArray[3] = 1; - testArray[4] = 1; - testArray[5] = 0; - std::array test_recv_array; - arrayPtr = testArray.data() + 2; - // copy testArray[1] to testArray[4] into receive buffer, skip - // size field (testArray[0]) - SerialBufferAdapter tv_serial_buffer_adapter3 = - SerialBufferAdapter(test_recv_array.data(), 4, false); - // Deserialization - size_t size = 4; - tv_serial_buffer_adapter3.deSerialize( - const_cast(&arrayPtr), &size, - SerializeIF::Endianness::MACHINE); - CHECK(test_recv_array[0] == 1); - CHECK(test_recv_array[1] == 1); - CHECK(test_recv_array[2] == 1); - CHECK(test_recv_array[3] == 0); - } + SECTION("Deserialization without size field") { + size_t buffer_size = 4; + memcpy(testArray.data(), &buffer_size, sizeof(uint16_t)); + testArray[2] = 1; + testArray[3] = 1; + testArray[4] = 1; + testArray[5] = 0; + std::array test_recv_array; + arrayPtr = testArray.data() + 2; + // copy testArray[1] to testArray[4] into receive buffer, skip + // size field (testArray[0]) + SerialBufferAdapter tv_serial_buffer_adapter3 = + SerialBufferAdapter(test_recv_array.data(), 4, false); + // Deserialization + size_t size = 4; + tv_serial_buffer_adapter3.deSerialize(const_cast(&arrayPtr), &size, + SerializeIF::Endianness::MACHINE); + CHECK(test_recv_array[0] == 1); + CHECK(test_recv_array[1] == 1); + CHECK(test_recv_array[2] == 1); + CHECK(test_recv_array[3] == 0); + } } diff --git a/tests/src/fsfw_tests/unit/serialize/TestSerialLinkedPacket.cpp b/tests/src/fsfw_tests/unit/serialize/TestSerialLinkedPacket.cpp index b6bb214d..e3bdf882 100644 --- a/tests/src/fsfw_tests/unit/serialize/TestSerialLinkedPacket.cpp +++ b/tests/src/fsfw_tests/unit/serialize/TestSerialLinkedPacket.cpp @@ -1,76 +1,73 @@ #include "TestSerialLinkedPacket.h" -#include "fsfw_tests/unit/CatchDefinitions.h" #include +#include #include -#include +#include "fsfw_tests/unit/CatchDefinitions.h" +TEST_CASE("Serial Linked Packet", "[SerLinkPacket]") { + // perform set-up here + uint32_t header = 42; + std::array testArray{1, 2, 3}; + uint32_t tail = 96; + size_t packetMaxSize = 256; + uint8_t packet[packetMaxSize] = {}; + size_t packetLen = 0; -TEST_CASE("Serial Linked Packet" , "[SerLinkPacket]") { - // perform set-up here - uint32_t header = 42; - std::array testArray {1,2,3}; - uint32_t tail = 96; - size_t packetMaxSize = 256; - uint8_t packet [packetMaxSize] = {}; - size_t packetLen = 0; + SECTION("Test Deserialization with Serial Buffer Adapter.") { + // This is a serialization of a packet, made "manually". + // We generate a packet which store data big-endian by swapping some + // values. (like coming from ground). + header = EndianConverter::convertBigEndian(header); + std::memcpy(packet, &header, sizeof(header)); + packetLen += sizeof(header); - SECTION("Test Deserialization with Serial Buffer Adapter.") { - // This is a serialization of a packet, made "manually". - // We generate a packet which store data big-endian by swapping some - // values. (like coming from ground). - header = EndianConverter::convertBigEndian(header); - std::memcpy(packet, &header, sizeof(header)); - packetLen += sizeof(header); + std::copy(testArray.data(), testArray.data() + testArray.size(), packet + packetLen); + packetLen += testArray.size(); - std::copy(testArray.data(), testArray.data() + testArray.size(), - packet + packetLen); - packetLen += testArray.size(); + tail = EndianConverter::convertBigEndian(tail); + std::memcpy(packet + packetLen, &tail, sizeof(tail)); + packetLen += sizeof(tail); - tail = EndianConverter::convertBigEndian(tail); - std::memcpy(packet + packetLen, &tail, sizeof(tail)); - packetLen += sizeof(tail); + // arrayprinter::print(packet, packetLen, OutputType::DEC); - //arrayprinter::print(packet, packetLen, OutputType::DEC); + // This is the buffer which will be filled when testClass.deSerialize + // is called. + std::array bufferAdaptee = {}; + TestPacket testClass(packet, packetLen, bufferAdaptee.data(), bufferAdaptee.size()); + const uint8_t* readOnlyPointer = packet; + // Deserialize big endian packet by setting bigEndian to true. + ReturnValue_t result = + testClass.deSerialize(&readOnlyPointer, &packetLen, SerializeIF::Endianness::BIG); + REQUIRE(result == retval::CATCH_OK); + CHECK(testClass.getHeader() == 42); + // Equivalent check. + // CHECK(testClass.getBuffer()[0] == 1); + CHECK(bufferAdaptee[0] == 1); + CHECK(bufferAdaptee[1] == 2); + CHECK(bufferAdaptee[2] == 3); + CHECK(testClass.getTail() == 96); + } - // This is the buffer which will be filled when testClass.deSerialize - // is called. - std::array bufferAdaptee = {}; - TestPacket testClass(packet, packetLen, bufferAdaptee.data(), - bufferAdaptee.size()); - const uint8_t* readOnlyPointer = packet; - // Deserialize big endian packet by setting bigEndian to true. - ReturnValue_t result = testClass.deSerialize(&readOnlyPointer, - &packetLen, SerializeIF::Endianness::BIG); - REQUIRE(result == retval::CATCH_OK); - CHECK(testClass.getHeader() == 42); - // Equivalent check. - // CHECK(testClass.getBuffer()[0] == 1); - CHECK(bufferAdaptee[0] == 1); - CHECK(bufferAdaptee[1] == 2); - CHECK(bufferAdaptee[2] == 3); - CHECK(testClass.getTail() == 96); - } + SECTION("Test Serialization") { + // Same process as performed in setup, this time using the class + // instead of doing it manually. + TestPacket testClass(header, tail, testArray.data(), testArray.size()); + size_t serializedSize = 0; + uint8_t* packetPointer = packet; + // serialize for ground: bigEndian = true. + ReturnValue_t result = testClass.serialize(&packetPointer, &serializedSize, packetMaxSize, + SerializeIF::Endianness::BIG); + REQUIRE(result == retval::CATCH_OK); + // Result should be big endian now. + CHECK(packet[3] == 42); + CHECK(packet[4] == 1); + CHECK(packet[5] == 2); + CHECK(packet[6] == 3); + CHECK(packet[10] == 96); + } - SECTION("Test Serialization") { - // Same process as performed in setup, this time using the class - // instead of doing it manually. - TestPacket testClass(header, tail, testArray.data(), testArray.size()); - size_t serializedSize = 0; - uint8_t* packetPointer = packet; - // serialize for ground: bigEndian = true. - ReturnValue_t result = testClass.serialize(&packetPointer, - &serializedSize, packetMaxSize, SerializeIF::Endianness::BIG); - REQUIRE(result == retval::CATCH_OK); - // Result should be big endian now. - CHECK(packet[3] == 42); - CHECK(packet[4] == 1); - CHECK(packet[5] == 2); - CHECK(packet[6] == 3); - CHECK(packet[10] == 96); - } - - // perform tear-down here + // perform tear-down here } diff --git a/tests/src/fsfw_tests/unit/serialize/TestSerialLinkedPacket.h b/tests/src/fsfw_tests/unit/serialize/TestSerialLinkedPacket.h index 71f258f9..0cfdd9ff 100644 --- a/tests/src/fsfw_tests/unit/serialize/TestSerialLinkedPacket.h +++ b/tests/src/fsfw_tests/unit/serialize/TestSerialLinkedPacket.h @@ -5,57 +5,46 @@ #include #include #include + #include -class TestPacket: public SerialLinkedListAdapter { -public: - /** - * For Deserialization - */ - TestPacket(const uint8_t *somePacket, size_t size, uint8_t * storePointer, - size_t storeSize): - buffer(storePointer, storeSize) - { - setLinks(); - } +class TestPacket : public SerialLinkedListAdapter { + public: + /** + * For Deserialization + */ + TestPacket(const uint8_t* somePacket, size_t size, uint8_t* storePointer, size_t storeSize) + : buffer(storePointer, storeSize) { + setLinks(); + } - /** - * For Serialization - */ - TestPacket(uint32_t header, uint32_t tail, - const uint8_t* parameters, size_t paramSize): - header(header), buffer(parameters, paramSize), - tail(tail) { - setLinks(); - } + /** + * For Serialization + */ + TestPacket(uint32_t header, uint32_t tail, const uint8_t* parameters, size_t paramSize) + : header(header), buffer(parameters, paramSize), tail(tail) { + setLinks(); + } - uint32_t getHeader() const { - return header.entry; - } + uint32_t getHeader() const { return header.entry; } - const uint8_t * getBuffer() { - return buffer.entry.getConstBuffer(); - } + const uint8_t* getBuffer() { return buffer.entry.getConstBuffer(); } - size_t getBufferLength() { - return buffer.getSerializedSize(); - } + size_t getBufferLength() { return buffer.getSerializedSize(); } + uint16_t getTail() const { return tail.entry; } - uint16_t getTail() const { - return tail.entry; - } -private: - void setLinks() { - setStart(&header); - header.setNext(&buffer); - buffer.setNext(&tail); - tail.setEnd(); - } + private: + void setLinks() { + setStart(&header); + header.setNext(&buffer); + buffer.setNext(&tail); + tail.setEnd(); + } - SerializeElement header = 0; - SerializeElement> buffer; - SerializeElement tail = 0; + SerializeElement header = 0; + SerializeElement> buffer; + SerializeElement tail = 0; }; #endif /* UNITTEST_TESTFW_NEWTESTS_TESTTEMPLATE_H_ */ diff --git a/tests/src/fsfw_tests/unit/serialize/TestSerialization.cpp b/tests/src/fsfw_tests/unit/serialize/TestSerialization.cpp index f883fe78..52cb70f6 100644 --- a/tests/src/fsfw_tests/unit/serialize/TestSerialization.cpp +++ b/tests/src/fsfw_tests/unit/serialize/TestSerialization.cpp @@ -1,216 +1,202 @@ -#include "fsfw_tests/unit/CatchDefinitions.h" +#include #include -#include -#include -#include - #include +#include +#include + +#include "fsfw_tests/unit/CatchDefinitions.h" static bool testBool = true; -static uint8_t tvUint8 {5}; -static uint16_t tvUint16 {283}; -static uint32_t tvUint32 {929221}; -static uint64_t tvUint64 {2929329429}; +static uint8_t tvUint8{5}; +static uint16_t tvUint16{283}; +static uint32_t tvUint32{929221}; +static uint64_t tvUint64{2929329429}; -static int8_t tvInt8 {-16}; -static int16_t tvInt16 {-829}; -static int32_t tvInt32 {-2312}; +static int8_t tvInt8{-16}; +static int16_t tvInt16{-829}; +static int32_t tvInt32{-2312}; -static float tvFloat {8.2149214}; +static float tvFloat{8.2149214}; static float tvSfloat = {-922.2321321}; -static double tvDouble {9.2132142141e8}; -static double tvSdouble {-2.2421e19}; +static double tvDouble{9.2132142141e8}; +static double tvSdouble{-2.2421e19}; static std::array TEST_ARRAY; -TEST_CASE( "Serialization size tests", "[SerSizeTest]") { - //REQUIRE(unitTestClass.test_autoserialization() == 0); - REQUIRE(SerializeAdapter::getSerializedSize(&testBool) == - sizeof(testBool)); - REQUIRE(SerializeAdapter::getSerializedSize(&tvUint8) == - sizeof(tvUint8)); - REQUIRE(SerializeAdapter::getSerializedSize(&tvUint16) == - sizeof(tvUint16)); - REQUIRE(SerializeAdapter::getSerializedSize(&tvUint32 ) == - sizeof(tvUint32)); - REQUIRE(SerializeAdapter::getSerializedSize(&tvUint64) == - sizeof(tvUint64)); - REQUIRE(SerializeAdapter::getSerializedSize(&tvInt8) == - sizeof(tvInt8)); - REQUIRE(SerializeAdapter::getSerializedSize(&tvInt16) == - sizeof(tvInt16)); - REQUIRE(SerializeAdapter::getSerializedSize(&tvInt32) == - sizeof(tvInt32)); - REQUIRE(SerializeAdapter::getSerializedSize(&tvFloat) == - sizeof(tvFloat)); - REQUIRE(SerializeAdapter::getSerializedSize(&tvSfloat) == - sizeof(tvSfloat )); - REQUIRE(SerializeAdapter::getSerializedSize(&tvDouble) == - sizeof(tvDouble)); - REQUIRE(SerializeAdapter::getSerializedSize(&tvSdouble) == - sizeof(tvSdouble)); +TEST_CASE("Serialization size tests", "[SerSizeTest]") { + // REQUIRE(unitTestClass.test_autoserialization() == 0); + REQUIRE(SerializeAdapter::getSerializedSize(&testBool) == sizeof(testBool)); + REQUIRE(SerializeAdapter::getSerializedSize(&tvUint8) == sizeof(tvUint8)); + REQUIRE(SerializeAdapter::getSerializedSize(&tvUint16) == sizeof(tvUint16)); + REQUIRE(SerializeAdapter::getSerializedSize(&tvUint32) == sizeof(tvUint32)); + REQUIRE(SerializeAdapter::getSerializedSize(&tvUint64) == sizeof(tvUint64)); + REQUIRE(SerializeAdapter::getSerializedSize(&tvInt8) == sizeof(tvInt8)); + REQUIRE(SerializeAdapter::getSerializedSize(&tvInt16) == sizeof(tvInt16)); + REQUIRE(SerializeAdapter::getSerializedSize(&tvInt32) == sizeof(tvInt32)); + REQUIRE(SerializeAdapter::getSerializedSize(&tvFloat) == sizeof(tvFloat)); + REQUIRE(SerializeAdapter::getSerializedSize(&tvSfloat) == sizeof(tvSfloat)); + REQUIRE(SerializeAdapter::getSerializedSize(&tvDouble) == sizeof(tvDouble)); + REQUIRE(SerializeAdapter::getSerializedSize(&tvSdouble) == sizeof(tvSdouble)); } TEST_CASE("Auto Serialize Adapter", "[SerAdapter]") { - size_t serializedSize = 0; - uint8_t * pArray = TEST_ARRAY.data(); + size_t serializedSize = 0; + uint8_t* pArray = TEST_ARRAY.data(); - SECTION("SerDe") { - size_t deserSize = 0; - SerializeAdapter::serialize(&testBool, TEST_ARRAY.data(), &deserSize, TEST_ARRAY.size(), - SerializeIF::Endianness::MACHINE); - REQUIRE(deserSize == 1); - REQUIRE(TEST_ARRAY[0] == true); - bool readBack = false; - SerializeAdapter::deSerialize(&readBack, TEST_ARRAY.data(), &deserSize, - SerializeIF::Endianness::MACHINE); - REQUIRE(deserSize == 1); - REQUIRE(readBack == true); - SerializeAdapter::serialize(&tvUint8, TEST_ARRAY.data(), &deserSize, TEST_ARRAY.size(), - SerializeIF::Endianness::MACHINE); - REQUIRE(deserSize == 1); - REQUIRE(TEST_ARRAY[0] == 5); - uint8_t readBackUint8 = 0; - uint8_t* const testPtr = TEST_ARRAY.data(); - uint8_t* const shouldStayConst = testPtr; - SerializeAdapter::deSerialize(&readBackUint8, testPtr, &deserSize, - SerializeIF::Endianness::MACHINE); - REQUIRE(testPtr == shouldStayConst); - REQUIRE(deserSize == 1); - REQUIRE(readBackUint8 == 5); - SerializeAdapter::serialize(&tvUint16, TEST_ARRAY.data(), &deserSize, TEST_ARRAY.size(), - SerializeIF::Endianness::MACHINE); - REQUIRE(deserSize == 2); - deserSize = 0; - uint16_t readBackUint16 = 0; - SerializeAdapter::deSerialize(&readBackUint16, TEST_ARRAY.data(), &deserSize, - SerializeIF::Endianness::MACHINE); - REQUIRE(deserSize == 2); - REQUIRE(readBackUint16 == 283); + SECTION("SerDe") { + size_t deserSize = 0; + SerializeAdapter::serialize(&testBool, TEST_ARRAY.data(), &deserSize, TEST_ARRAY.size(), + SerializeIF::Endianness::MACHINE); + REQUIRE(deserSize == 1); + REQUIRE(TEST_ARRAY[0] == true); + bool readBack = false; + SerializeAdapter::deSerialize(&readBack, TEST_ARRAY.data(), &deserSize, + SerializeIF::Endianness::MACHINE); + REQUIRE(deserSize == 1); + REQUIRE(readBack == true); + SerializeAdapter::serialize(&tvUint8, TEST_ARRAY.data(), &deserSize, TEST_ARRAY.size(), + SerializeIF::Endianness::MACHINE); + REQUIRE(deserSize == 1); + REQUIRE(TEST_ARRAY[0] == 5); + uint8_t readBackUint8 = 0; + uint8_t* const testPtr = TEST_ARRAY.data(); + uint8_t* const shouldStayConst = testPtr; + SerializeAdapter::deSerialize(&readBackUint8, testPtr, &deserSize, + SerializeIF::Endianness::MACHINE); + REQUIRE(testPtr == shouldStayConst); + REQUIRE(deserSize == 1); + REQUIRE(readBackUint8 == 5); + SerializeAdapter::serialize(&tvUint16, TEST_ARRAY.data(), &deserSize, TEST_ARRAY.size(), + SerializeIF::Endianness::MACHINE); + REQUIRE(deserSize == 2); + deserSize = 0; + uint16_t readBackUint16 = 0; + SerializeAdapter::deSerialize(&readBackUint16, TEST_ARRAY.data(), &deserSize, + SerializeIF::Endianness::MACHINE); + REQUIRE(deserSize == 2); + REQUIRE(readBackUint16 == 283); - SerializeAdapter::serialize(&tvUint32, TEST_ARRAY.data(), &deserSize, TEST_ARRAY.size(), - SerializeIF::Endianness::MACHINE); - REQUIRE(deserSize == 4); - uint32_t readBackUint32 = 0; - deserSize = 0; - SerializeAdapter::deSerialize(&readBackUint32, TEST_ARRAY.data(), &deserSize, - SerializeIF::Endianness::MACHINE); - REQUIRE(deserSize == 4); - REQUIRE(readBackUint32 == 929221); + SerializeAdapter::serialize(&tvUint32, TEST_ARRAY.data(), &deserSize, TEST_ARRAY.size(), + SerializeIF::Endianness::MACHINE); + REQUIRE(deserSize == 4); + uint32_t readBackUint32 = 0; + deserSize = 0; + SerializeAdapter::deSerialize(&readBackUint32, TEST_ARRAY.data(), &deserSize, + SerializeIF::Endianness::MACHINE); + REQUIRE(deserSize == 4); + REQUIRE(readBackUint32 == 929221); - SerializeAdapter::serialize(&tvInt16, TEST_ARRAY.data(), &deserSize, TEST_ARRAY.size(), - SerializeIF::Endianness::MACHINE); - REQUIRE(deserSize == 2); - int16_t readBackInt16 = 0; - SerializeAdapter::deSerialize(&readBackInt16, TEST_ARRAY.data(), &deserSize, - SerializeIF::Endianness::MACHINE); - REQUIRE(readBackInt16 == -829); - REQUIRE(deserSize == 2); + SerializeAdapter::serialize(&tvInt16, TEST_ARRAY.data(), &deserSize, TEST_ARRAY.size(), + SerializeIF::Endianness::MACHINE); + REQUIRE(deserSize == 2); + int16_t readBackInt16 = 0; + SerializeAdapter::deSerialize(&readBackInt16, TEST_ARRAY.data(), &deserSize, + SerializeIF::Endianness::MACHINE); + REQUIRE(readBackInt16 == -829); + REQUIRE(deserSize == 2); - SerializeAdapter::serialize(&tvFloat, TEST_ARRAY.data(), &deserSize, TEST_ARRAY.size(), - SerializeIF::Endianness::MACHINE); - float readBackFloat = 0.0; - SerializeAdapter::deSerialize(&readBackFloat, TEST_ARRAY.data(), &deserSize, - SerializeIF::Endianness::MACHINE); - REQUIRE(readBackFloat == Catch::Approx(8.214921)); + SerializeAdapter::serialize(&tvFloat, TEST_ARRAY.data(), &deserSize, TEST_ARRAY.size(), + SerializeIF::Endianness::MACHINE); + float readBackFloat = 0.0; + SerializeAdapter::deSerialize(&readBackFloat, TEST_ARRAY.data(), &deserSize, + SerializeIF::Endianness::MACHINE); + REQUIRE(readBackFloat == Catch::Approx(8.214921)); - SerializeAdapter::serialize(&tvSdouble, TEST_ARRAY.data(), &deserSize, TEST_ARRAY.size(), - SerializeIF::Endianness::MACHINE); - double readBackSignedDouble = 0.0; - SerializeAdapter::deSerialize(&readBackSignedDouble, TEST_ARRAY.data(), &deserSize, - SerializeIF::Endianness::MACHINE); - REQUIRE(readBackSignedDouble == Catch::Approx(-2.2421e19)); + SerializeAdapter::serialize(&tvSdouble, TEST_ARRAY.data(), &deserSize, TEST_ARRAY.size(), + SerializeIF::Endianness::MACHINE); + double readBackSignedDouble = 0.0; + SerializeAdapter::deSerialize(&readBackSignedDouble, TEST_ARRAY.data(), &deserSize, + SerializeIF::Endianness::MACHINE); + REQUIRE(readBackSignedDouble == Catch::Approx(-2.2421e19)); - uint8_t testBuf[4] = {1, 2, 3, 4}; - SerialBufferAdapter bufferAdapter(testBuf, sizeof(testBuf)); - SerializeAdapter::serialize(&bufferAdapter, TEST_ARRAY.data(), &deserSize, - TEST_ARRAY.size(), SerializeIF::Endianness::MACHINE); - REQUIRE(deserSize == 4); - for(uint8_t idx = 0; idx < 4; idx++) { - REQUIRE(TEST_ARRAY[idx] == idx + 1); - } - deserSize = 0; - testBuf[0] = 0; - testBuf[1] = 12; - SerializeAdapter::deSerialize(&bufferAdapter, TEST_ARRAY.data(), &deserSize, - SerializeIF::Endianness::MACHINE); - REQUIRE(deserSize == 4); - for(uint8_t idx = 0; idx < 4; idx++) { - REQUIRE(testBuf[idx] == idx + 1); - } + uint8_t testBuf[4] = {1, 2, 3, 4}; + SerialBufferAdapter bufferAdapter(testBuf, sizeof(testBuf)); + SerializeAdapter::serialize(&bufferAdapter, TEST_ARRAY.data(), &deserSize, TEST_ARRAY.size(), + SerializeIF::Endianness::MACHINE); + REQUIRE(deserSize == 4); + for (uint8_t idx = 0; idx < 4; idx++) { + REQUIRE(TEST_ARRAY[idx] == idx + 1); } + deserSize = 0; + testBuf[0] = 0; + testBuf[1] = 12; + SerializeAdapter::deSerialize(&bufferAdapter, TEST_ARRAY.data(), &deserSize, + SerializeIF::Endianness::MACHINE); + REQUIRE(deserSize == 4); + for (uint8_t idx = 0; idx < 4; idx++) { + REQUIRE(testBuf[idx] == idx + 1); + } + } - SECTION("Serialize incrementing") { - SerializeAdapter::serialize(&testBool, &pArray, &serializedSize, - TEST_ARRAY.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tvUint8, &pArray, &serializedSize, - TEST_ARRAY.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tvUint16, &pArray, &serializedSize, - TEST_ARRAY.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tvUint32, &pArray, &serializedSize, - TEST_ARRAY.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tvInt8, &pArray, &serializedSize, - TEST_ARRAY.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tvInt16, &pArray, &serializedSize, - TEST_ARRAY.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tvInt32, &pArray, &serializedSize, - TEST_ARRAY.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tvUint64, &pArray, &serializedSize, - TEST_ARRAY.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tvFloat, &pArray, &serializedSize, - TEST_ARRAY.size(), SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tvDouble, &pArray, &serializedSize, TEST_ARRAY.size(), - SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tvSfloat, &pArray, &serializedSize, TEST_ARRAY.size(), - SerializeIF::Endianness::MACHINE); - SerializeAdapter::serialize(&tvSdouble, &pArray, &serializedSize, TEST_ARRAY.size(), - SerializeIF::Endianness::MACHINE); - REQUIRE (serializedSize == 47); - } + SECTION("Serialize incrementing") { + SerializeAdapter::serialize(&testBool, &pArray, &serializedSize, TEST_ARRAY.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tvUint8, &pArray, &serializedSize, TEST_ARRAY.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tvUint16, &pArray, &serializedSize, TEST_ARRAY.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tvUint32, &pArray, &serializedSize, TEST_ARRAY.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tvInt8, &pArray, &serializedSize, TEST_ARRAY.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tvInt16, &pArray, &serializedSize, TEST_ARRAY.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tvInt32, &pArray, &serializedSize, TEST_ARRAY.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tvUint64, &pArray, &serializedSize, TEST_ARRAY.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tvFloat, &pArray, &serializedSize, TEST_ARRAY.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tvDouble, &pArray, &serializedSize, TEST_ARRAY.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tvSfloat, &pArray, &serializedSize, TEST_ARRAY.size(), + SerializeIF::Endianness::MACHINE); + SerializeAdapter::serialize(&tvSdouble, &pArray, &serializedSize, TEST_ARRAY.size(), + SerializeIF::Endianness::MACHINE); + REQUIRE(serializedSize == 47); + } - SECTION("Deserialize decrementing") { - pArray = TEST_ARRAY.data(); - size_t remaining_size = serializedSize; - SerializeAdapter::deSerialize(&testBool, const_cast(&pArray), - &remaining_size, SerializeIF::Endianness::MACHINE); - SerializeAdapter::deSerialize(&tvUint8, const_cast(&pArray), - &remaining_size, SerializeIF::Endianness::MACHINE); - SerializeAdapter::deSerialize(&tvUint16, const_cast(&pArray), - &remaining_size, SerializeIF::Endianness::MACHINE); - SerializeAdapter::deSerialize(&tvUint32, const_cast(&pArray), - &remaining_size, SerializeIF::Endianness::MACHINE); - SerializeAdapter::deSerialize(&tvInt8, const_cast(&pArray), - &remaining_size, SerializeIF::Endianness::MACHINE); - SerializeAdapter::deSerialize(&tvInt16, const_cast(&pArray), - &remaining_size, SerializeIF::Endianness::MACHINE); - SerializeAdapter::deSerialize(&tvInt32, const_cast(&pArray), - &remaining_size, SerializeIF::Endianness::MACHINE); - SerializeAdapter::deSerialize(&tvUint64, - const_cast(&pArray), &remaining_size, SerializeIF::Endianness::MACHINE); - SerializeAdapter::deSerialize(&tvFloat, - const_cast(&pArray), &remaining_size, SerializeIF::Endianness::MACHINE); - SerializeAdapter::deSerialize(&tvDouble, - const_cast(&pArray), &remaining_size, SerializeIF::Endianness::MACHINE); - SerializeAdapter::deSerialize(&tvSfloat, - const_cast(&pArray), &remaining_size, SerializeIF::Endianness::MACHINE); - SerializeAdapter::deSerialize(&tvSdouble, - const_cast(&pArray), &remaining_size, SerializeIF::Endianness::MACHINE); + SECTION("Deserialize decrementing") { + pArray = TEST_ARRAY.data(); + size_t remaining_size = serializedSize; + SerializeAdapter::deSerialize(&testBool, const_cast(&pArray), &remaining_size, + SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tvUint8, const_cast(&pArray), &remaining_size, + SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tvUint16, const_cast(&pArray), &remaining_size, + SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tvUint32, const_cast(&pArray), &remaining_size, + SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tvInt8, const_cast(&pArray), &remaining_size, + SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tvInt16, const_cast(&pArray), &remaining_size, + SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tvInt32, const_cast(&pArray), &remaining_size, + SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tvUint64, const_cast(&pArray), &remaining_size, + SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tvFloat, const_cast(&pArray), &remaining_size, + SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tvDouble, const_cast(&pArray), &remaining_size, + SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tvSfloat, const_cast(&pArray), &remaining_size, + SerializeIF::Endianness::MACHINE); + SerializeAdapter::deSerialize(&tvSdouble, const_cast(&pArray), &remaining_size, + SerializeIF::Endianness::MACHINE); - REQUIRE(testBool == true); - REQUIRE(tvUint8 == 5); - REQUIRE(tvUint16 == 283); - REQUIRE(tvUint32 == 929221); - REQUIRE(tvUint64 == 2929329429); - REQUIRE(tvInt8 == -16); - REQUIRE(tvInt16 == -829); - REQUIRE(tvInt32 == -2312); + REQUIRE(testBool == true); + REQUIRE(tvUint8 == 5); + REQUIRE(tvUint16 == 283); + REQUIRE(tvUint32 == 929221); + REQUIRE(tvUint64 == 2929329429); + REQUIRE(tvInt8 == -16); + REQUIRE(tvInt16 == -829); + REQUIRE(tvInt32 == -2312); - REQUIRE(tvFloat == Catch::Approx(8.214921)); - REQUIRE(tvDouble == Catch::Approx(9.2132142141e8)); - REQUIRE(tvSfloat == Catch::Approx(-922.2321321)); - REQUIRE(tvSdouble == Catch::Approx(-2.2421e19)); - } + REQUIRE(tvFloat == Catch::Approx(8.214921)); + REQUIRE(tvDouble == Catch::Approx(9.2132142141e8)); + REQUIRE(tvSfloat == Catch::Approx(-922.2321321)); + REQUIRE(tvSdouble == Catch::Approx(-2.2421e19)); + } } - - diff --git a/tests/src/fsfw_tests/unit/storagemanager/TestNewAccessor.cpp b/tests/src/fsfw_tests/unit/storagemanager/TestNewAccessor.cpp index bd1634b7..e1db9ce0 100644 --- a/tests/src/fsfw_tests/unit/storagemanager/TestNewAccessor.cpp +++ b/tests/src/fsfw_tests/unit/storagemanager/TestNewAccessor.cpp @@ -1,164 +1,159 @@ -#include "fsfw_tests/unit/CatchDefinitions.h" - #include -#include - #include +#include #include -TEST_CASE( "New Accessor" , "[NewAccessor]") { - LocalPool::LocalPoolConfig poolCfg = {{1, 10}}; - LocalPool SimplePool = LocalPool(0, poolCfg); - std::array testDataArray; - std::array receptionArray; - store_address_t testStoreId; - ReturnValue_t result = retval::CATCH_FAILED; +#include "fsfw_tests/unit/CatchDefinitions.h" - for(size_t i = 0; i < testDataArray.size(); i++) { - testDataArray[i] = i; - } - size_t size = 10; +TEST_CASE("New Accessor", "[NewAccessor]") { + LocalPool::LocalPoolConfig poolCfg = {{1, 10}}; + LocalPool SimplePool = LocalPool(0, poolCfg); + std::array testDataArray; + std::array receptionArray; + store_address_t testStoreId; + ReturnValue_t result = retval::CATCH_FAILED; - SECTION ("Simple tests getter functions") { - result = SimplePool.addData(&testStoreId, testDataArray.data(), size); - REQUIRE(result == retval::CATCH_OK); - auto resultPair = SimplePool.getData(testStoreId); - REQUIRE(resultPair.first == retval::CATCH_OK); - resultPair.second.getDataCopy(receptionArray.data(), 20); - CHECK(resultPair.second.getId() == testStoreId); - CHECK(resultPair.second.size() == 10); - for(size_t i = 0; i < size; i++) { - CHECK(receptionArray[i] == i ); - } + for (size_t i = 0; i < testDataArray.size(); i++) { + testDataArray[i] = i; + } + size_t size = 10; - std::copy(resultPair.second.data(), resultPair.second.data() + - resultPair.second.size(), receptionArray.data()); - for(size_t i = 0; i < size; i++) { - CHECK(receptionArray[i] == i ); - } + SECTION("Simple tests getter functions") { + result = SimplePool.addData(&testStoreId, testDataArray.data(), size); + REQUIRE(result == retval::CATCH_OK); + auto resultPair = SimplePool.getData(testStoreId); + REQUIRE(resultPair.first == retval::CATCH_OK); + resultPair.second.getDataCopy(receptionArray.data(), 20); + CHECK(resultPair.second.getId() == testStoreId); + CHECK(resultPair.second.size() == 10); + for (size_t i = 0; i < size; i++) { + CHECK(receptionArray[i] == i); + } - { - auto resultPairLoc = SimplePool.getData(testStoreId); - REQUIRE(resultPairLoc.first == retval::CATCH_OK); - // data should be deleted when accessor goes out of scope. - } - resultPair = SimplePool.getData(testStoreId); - REQUIRE(resultPair.first == (int) StorageManagerIF::DATA_DOES_NOT_EXIST); + std::copy(resultPair.second.data(), resultPair.second.data() + resultPair.second.size(), + receptionArray.data()); + for (size_t i = 0; i < size; i++) { + CHECK(receptionArray[i] == i); + } - result = SimplePool.addData(&testStoreId, testDataArray.data(), size); - REQUIRE(result == retval::CATCH_OK); - { - ConstStorageAccessor constAccessor(testStoreId); - result = SimplePool.getData(testStoreId, constAccessor); - REQUIRE(result == retval::CATCH_OK); - constAccessor.getDataCopy(receptionArray.data(), 20); - for(size_t i = 0; i < size; i++) { - CHECK(receptionArray[i] == i ); - } - // likewise, data should be deleted when accessor gets out of scope. - } - resultPair = SimplePool.getData(testStoreId); - REQUIRE(resultPair.first == (int) StorageManagerIF::DATA_DOES_NOT_EXIST); + { + auto resultPairLoc = SimplePool.getData(testStoreId); + REQUIRE(resultPairLoc.first == retval::CATCH_OK); + // data should be deleted when accessor goes out of scope. + } + resultPair = SimplePool.getData(testStoreId); + REQUIRE(resultPair.first == (int)StorageManagerIF::DATA_DOES_NOT_EXIST); - result = SimplePool.addData(&testStoreId, testDataArray.data(), size); - { - resultPair = SimplePool.getData(testStoreId); - REQUIRE(resultPair.first == retval::CATCH_OK); - resultPair.second.release(); - // now data should not be deleted anymore - } - resultPair = SimplePool.getData(testStoreId); - REQUIRE(resultPair.first == retval::CATCH_OK); - resultPair.second.getDataCopy(receptionArray.data(), 20); - for(size_t i = 0; i < size; i++) { - CHECK(receptionArray[i] == i ); - } - } + result = SimplePool.addData(&testStoreId, testDataArray.data(), size); + REQUIRE(result == retval::CATCH_OK); + { + ConstStorageAccessor constAccessor(testStoreId); + result = SimplePool.getData(testStoreId, constAccessor); + REQUIRE(result == retval::CATCH_OK); + constAccessor.getDataCopy(receptionArray.data(), 20); + for (size_t i = 0; i < size; i++) { + CHECK(receptionArray[i] == i); + } + // likewise, data should be deleted when accessor gets out of scope. + } + resultPair = SimplePool.getData(testStoreId); + REQUIRE(resultPair.first == (int)StorageManagerIF::DATA_DOES_NOT_EXIST); + result = SimplePool.addData(&testStoreId, testDataArray.data(), size); + { + resultPair = SimplePool.getData(testStoreId); + REQUIRE(resultPair.first == retval::CATCH_OK); + resultPair.second.release(); + // now data should not be deleted anymore + } + resultPair = SimplePool.getData(testStoreId); + REQUIRE(resultPair.first == retval::CATCH_OK); + resultPair.second.getDataCopy(receptionArray.data(), 20); + for (size_t i = 0; i < size; i++) { + CHECK(receptionArray[i] == i); + } + } - SECTION("Simple tests modify functions") { - result = SimplePool.addData(&testStoreId, testDataArray.data(), size); - REQUIRE(result == retval::CATCH_OK); - { - StorageAccessor accessor(testStoreId); - result = SimplePool.modifyData(testStoreId, accessor); - REQUIRE(result == retval::CATCH_OK); - CHECK(accessor.getId() == testStoreId); - CHECK(accessor.size() == 10); - accessor.getDataCopy(receptionArray.data(), 20); - for(size_t i = 0; i < size; i++) { - CHECK(receptionArray[i] == i ); - } - std::copy(accessor.data(), accessor.data() + - accessor.size(), receptionArray.data()); - for(size_t i = 0; i < size; i++) { - CHECK(receptionArray[i] == i ); - } - // data should be deleted when accessor goes out of scope - } - auto resultPair = SimplePool.getData(testStoreId); - REQUIRE(resultPair.first == (int) StorageManagerIF::DATA_DOES_NOT_EXIST); + SECTION("Simple tests modify functions") { + result = SimplePool.addData(&testStoreId, testDataArray.data(), size); + REQUIRE(result == retval::CATCH_OK); + { + StorageAccessor accessor(testStoreId); + result = SimplePool.modifyData(testStoreId, accessor); + REQUIRE(result == retval::CATCH_OK); + CHECK(accessor.getId() == testStoreId); + CHECK(accessor.size() == 10); + accessor.getDataCopy(receptionArray.data(), 20); + for (size_t i = 0; i < size; i++) { + CHECK(receptionArray[i] == i); + } + std::copy(accessor.data(), accessor.data() + accessor.size(), receptionArray.data()); + for (size_t i = 0; i < size; i++) { + CHECK(receptionArray[i] == i); + } + // data should be deleted when accessor goes out of scope + } + auto resultPair = SimplePool.getData(testStoreId); + REQUIRE(resultPair.first == (int)StorageManagerIF::DATA_DOES_NOT_EXIST); - result = SimplePool.addData(&testStoreId, testDataArray.data(), size); - REQUIRE(result == retval::CATCH_OK); - { - auto resultPairLoc = SimplePool.modifyData(testStoreId); - REQUIRE(resultPairLoc.first == retval::CATCH_OK); - CHECK(resultPairLoc.second.getId() == testStoreId); - CHECK(resultPairLoc.second.size() == 10); - resultPairLoc.second.getDataCopy(receptionArray.data(), 20); - for(size_t i = 0; i < size; i++) { - CHECK(receptionArray[i] == i ); - } - std::copy(resultPairLoc.second.data(), resultPairLoc.second.data() + - resultPairLoc.second.size(), receptionArray.data()); - for(size_t i = 0; i < size; i++) { - CHECK(receptionArray[i] == i ); - } - resultPairLoc.second.release(); - // data should not be deleted when accessor goes out of scope - } - resultPair = SimplePool.getData(testStoreId); - REQUIRE(resultPair.first == retval::CATCH_OK); - } + result = SimplePool.addData(&testStoreId, testDataArray.data(), size); + REQUIRE(result == retval::CATCH_OK); + { + auto resultPairLoc = SimplePool.modifyData(testStoreId); + REQUIRE(resultPairLoc.first == retval::CATCH_OK); + CHECK(resultPairLoc.second.getId() == testStoreId); + CHECK(resultPairLoc.second.size() == 10); + resultPairLoc.second.getDataCopy(receptionArray.data(), 20); + for (size_t i = 0; i < size; i++) { + CHECK(receptionArray[i] == i); + } + std::copy(resultPairLoc.second.data(), + resultPairLoc.second.data() + resultPairLoc.second.size(), receptionArray.data()); + for (size_t i = 0; i < size; i++) { + CHECK(receptionArray[i] == i); + } + resultPairLoc.second.release(); + // data should not be deleted when accessor goes out of scope + } + resultPair = SimplePool.getData(testStoreId); + REQUIRE(resultPair.first == retval::CATCH_OK); + } + SECTION("Write tests") { + result = SimplePool.addData(&testStoreId, testDataArray.data(), size); + REQUIRE(result == retval::CATCH_OK); + { + auto resultPair = SimplePool.modifyData(testStoreId); + REQUIRE(resultPair.first == retval::CATCH_OK); + testDataArray[9] = 42; + resultPair.second.write(testDataArray.data(), 10, 0); + // now data should not be deleted + resultPair.second.release(); + } + auto resultConstPair = SimplePool.getData(testStoreId); + REQUIRE(resultConstPair.first == retval::CATCH_OK); - SECTION("Write tests") { - result = SimplePool.addData(&testStoreId, testDataArray.data(), size); - REQUIRE(result == retval::CATCH_OK); - { - auto resultPair = SimplePool.modifyData(testStoreId); - REQUIRE(resultPair.first == retval::CATCH_OK); - testDataArray[9] = 42; - resultPair.second.write(testDataArray.data(), 10, 0); - // now data should not be deleted - resultPair.second.release(); - } - auto resultConstPair = SimplePool.getData(testStoreId); - REQUIRE(resultConstPair.first == retval::CATCH_OK); + resultConstPair.second.getDataCopy(receptionArray.data(), 10); + for (size_t i = 0; i < size - 1; i++) { + CHECK(receptionArray[i] == i); + } + CHECK(receptionArray[9] == 42); - resultConstPair.second.getDataCopy(receptionArray.data(), 10); - for(size_t i = 0; i < size-1; i++) { - CHECK(receptionArray[i] == i ); - } - CHECK(receptionArray[9] == 42 ); + auto resultPair = SimplePool.modifyData(testStoreId); + REQUIRE(resultPair.first == retval::CATCH_OK); + result = resultPair.second.write(testDataArray.data(), 20, 0); + REQUIRE(result == retval::CATCH_FAILED); + result = resultPair.second.write(testDataArray.data(), 10, 5); + REQUIRE(result == retval::CATCH_FAILED); - auto resultPair = SimplePool.modifyData(testStoreId); - REQUIRE(resultPair.first == retval::CATCH_OK); - result = resultPair.second.write(testDataArray.data(), 20, 0); - REQUIRE(result == retval::CATCH_FAILED); - result = resultPair.second.write(testDataArray.data(), 10, 5); - REQUIRE(result == retval::CATCH_FAILED); - - std::memset(testDataArray.data(), 42, 5); - result = resultPair.second.write(testDataArray.data(), 5, 5); - REQUIRE(result == retval::CATCH_OK); - resultConstPair = SimplePool.getData(testStoreId); - resultPair.second.getDataCopy(receptionArray.data(), 20); - for(size_t i = 5; i < 10; i++) { - CHECK(receptionArray[i] == 42 ); - } - - } + std::memset(testDataArray.data(), 42, 5); + result = resultPair.second.write(testDataArray.data(), 5, 5); + REQUIRE(result == retval::CATCH_OK); + resultConstPair = SimplePool.getData(testStoreId); + resultPair.second.getDataCopy(receptionArray.data(), 20); + for (size_t i = 5; i < 10; i++) { + CHECK(receptionArray[i] == 42); + } + } } diff --git a/tests/src/fsfw_tests/unit/storagemanager/TestPool.cpp b/tests/src/fsfw_tests/unit/storagemanager/TestPool.cpp index 013ecf86..2cbf951d 100644 --- a/tests/src/fsfw_tests/unit/storagemanager/TestPool.cpp +++ b/tests/src/fsfw_tests/unit/storagemanager/TestPool.cpp @@ -1,292 +1,289 @@ -#include "fsfw_tests/unit/CatchDefinitions.h" - #include #include #include - #include +#include "fsfw_tests/unit/CatchDefinitions.h" -TEST_CASE( "Local Pool Simple Tests [1 Pool]" , "[TestPool]") { - LocalPool::LocalPoolConfig config = {{1, 10}}; - LocalPool simplePool(0, config); - std::array testDataArray; - std::array receptionArray; - store_address_t testStoreId; - ReturnValue_t result = retval::CATCH_FAILED; - uint8_t *pointer = nullptr; - const uint8_t * constPointer = nullptr; +TEST_CASE("Local Pool Simple Tests [1 Pool]", "[TestPool]") { + LocalPool::LocalPoolConfig config = {{1, 10}}; + LocalPool simplePool(0, config); + std::array testDataArray; + std::array receptionArray; + store_address_t testStoreId; + ReturnValue_t result = retval::CATCH_FAILED; + uint8_t* pointer = nullptr; + const uint8_t* constPointer = nullptr; - for(size_t i = 0; i < testDataArray.size(); i++) { - testDataArray[i] = i; - } - size_t size = 10; + for (size_t i = 0; i < testDataArray.size(); i++) { + testDataArray[i] = i; + } + size_t size = 10; - SECTION ( "Basic tests") { - result = simplePool.addData(&testStoreId, testDataArray.data(), size); - REQUIRE(result == retval::CATCH_OK); - result = simplePool.getData(testStoreId, &constPointer, &size); - REQUIRE(result == retval::CATCH_OK); - memcpy(receptionArray.data(), constPointer, size); - for(size_t i = 0; i < size; i++) { - CHECK(receptionArray[i] == i ); - } - memset(receptionArray.data(), 0, size); - result = simplePool.modifyData(testStoreId, &pointer, &size); - memcpy(receptionArray.data(), pointer, size); - REQUIRE(result == retval::CATCH_OK); - for(size_t i = 0; i < size; i++) { - CHECK(receptionArray[i] == i ); - } - result = simplePool.deleteData(testStoreId); - REQUIRE(result == retval::CATCH_OK); - result = simplePool.addData(&testStoreId, testDataArray.data(), 15); - CHECK (result == (int) StorageManagerIF::DATA_TOO_LARGE); - } + SECTION("Basic tests") { + result = simplePool.addData(&testStoreId, testDataArray.data(), size); + REQUIRE(result == retval::CATCH_OK); + result = simplePool.getData(testStoreId, &constPointer, &size); + REQUIRE(result == retval::CATCH_OK); + memcpy(receptionArray.data(), constPointer, size); + for (size_t i = 0; i < size; i++) { + CHECK(receptionArray[i] == i); + } + memset(receptionArray.data(), 0, size); + result = simplePool.modifyData(testStoreId, &pointer, &size); + memcpy(receptionArray.data(), pointer, size); + REQUIRE(result == retval::CATCH_OK); + for (size_t i = 0; i < size; i++) { + CHECK(receptionArray[i] == i); + } + result = simplePool.deleteData(testStoreId); + REQUIRE(result == retval::CATCH_OK); + result = simplePool.addData(&testStoreId, testDataArray.data(), 15); + CHECK(result == (int)StorageManagerIF::DATA_TOO_LARGE); + } - SECTION ( "Reservation Tests ") { - pointer = nullptr; - result = simplePool.getFreeElement(&testStoreId, size, &pointer); - REQUIRE (result == retval::CATCH_OK); - memcpy(pointer, testDataArray.data(), size); - constPointer = nullptr; - result = simplePool.getData(testStoreId, &constPointer, &size); + SECTION("Reservation Tests ") { + pointer = nullptr; + result = simplePool.getFreeElement(&testStoreId, size, &pointer); + REQUIRE(result == retval::CATCH_OK); + memcpy(pointer, testDataArray.data(), size); + constPointer = nullptr; + result = simplePool.getData(testStoreId, &constPointer, &size); - REQUIRE (result == retval::CATCH_OK); - memcpy(receptionArray.data(), constPointer, size); - for(size_t i = 0; i < size; i++) { - CHECK(receptionArray[i] == i ); - } - } + REQUIRE(result == retval::CATCH_OK); + memcpy(receptionArray.data(), constPointer, size); + for (size_t i = 0; i < size; i++) { + CHECK(receptionArray[i] == i); + } + } - SECTION ( "Add, delete, add, add when full") { - result = simplePool.addData(&testStoreId, testDataArray.data(), size); - REQUIRE(result == retval::CATCH_OK); - result = simplePool.getData(testStoreId, &constPointer, &size); - REQUIRE( result == retval::CATCH_OK); - memcpy(receptionArray.data(), constPointer, size); - for(size_t i = 0; i < size; i++) { - CHECK(receptionArray[i] == i ); - } + SECTION("Add, delete, add, add when full") { + result = simplePool.addData(&testStoreId, testDataArray.data(), size); + REQUIRE(result == retval::CATCH_OK); + result = simplePool.getData(testStoreId, &constPointer, &size); + REQUIRE(result == retval::CATCH_OK); + memcpy(receptionArray.data(), constPointer, size); + for (size_t i = 0; i < size; i++) { + CHECK(receptionArray[i] == i); + } - result = simplePool.deleteData(testStoreId); - REQUIRE(result == retval::CATCH_OK); + result = simplePool.deleteData(testStoreId); + REQUIRE(result == retval::CATCH_OK); - result = simplePool.addData(&testStoreId, testDataArray.data(), size); - REQUIRE(result == retval::CATCH_OK); - result = simplePool.getData(testStoreId, &constPointer, &size); - REQUIRE( result == retval::CATCH_OK); - memcpy(receptionArray.data(), constPointer, size); - for(size_t i = 0; i < size; i++) { - CHECK(receptionArray[i] == i ); - } + result = simplePool.addData(&testStoreId, testDataArray.data(), size); + REQUIRE(result == retval::CATCH_OK); + result = simplePool.getData(testStoreId, &constPointer, &size); + REQUIRE(result == retval::CATCH_OK); + memcpy(receptionArray.data(), constPointer, size); + for (size_t i = 0; i < size; i++) { + CHECK(receptionArray[i] == i); + } - store_address_t newAddress; - result = simplePool.addData(&newAddress, testDataArray.data(), size); - REQUIRE(result == (int) StorageManagerIF::DATA_STORAGE_FULL); + store_address_t newAddress; + result = simplePool.addData(&newAddress, testDataArray.data(), size); + REQUIRE(result == (int)StorageManagerIF::DATA_STORAGE_FULL); - // Packet Index to high intentionally - newAddress.packetIndex = 2; - pointer = testDataArray.data(); - result = simplePool.modifyData(newAddress, &pointer, &size); - REQUIRE(result == (int) StorageManagerIF::ILLEGAL_STORAGE_ID); + // Packet Index to high intentionally + newAddress.packetIndex = 2; + pointer = testDataArray.data(); + result = simplePool.modifyData(newAddress, &pointer, &size); + REQUIRE(result == (int)StorageManagerIF::ILLEGAL_STORAGE_ID); - result = simplePool.deleteData(newAddress); - REQUIRE(result == (int) StorageManagerIF::ILLEGAL_STORAGE_ID); + result = simplePool.deleteData(newAddress); + REQUIRE(result == (int)StorageManagerIF::ILLEGAL_STORAGE_ID); - newAddress.packetIndex = 0; - newAddress.poolIndex = 2; - result = simplePool.deleteData(newAddress); - REQUIRE(result == (int) StorageManagerIF::ILLEGAL_STORAGE_ID); - } + newAddress.packetIndex = 0; + newAddress.poolIndex = 2; + result = simplePool.deleteData(newAddress); + REQUIRE(result == (int)StorageManagerIF::ILLEGAL_STORAGE_ID); + } - SECTION ( "Initialize and clear store, delete with pointer") { - result = simplePool.initialize(); - REQUIRE(result == retval::CATCH_OK); - result = simplePool.addData(&testStoreId, testDataArray.data(), size); - REQUIRE(result == retval::CATCH_OK); - simplePool.clearStore(); - result = simplePool.addData(&testStoreId, testDataArray.data(), size); - REQUIRE(result == retval::CATCH_OK); - result = simplePool.modifyData(testStoreId, &pointer, &size); - REQUIRE(result == retval::CATCH_OK); - store_address_t newId; - result = simplePool.deleteData(pointer, size, &testStoreId); - REQUIRE(result == retval::CATCH_OK); - REQUIRE(testStoreId.raw != (uint32_t) StorageManagerIF::INVALID_ADDRESS); - result = simplePool.addData(&testStoreId, testDataArray.data(), size); - REQUIRE(result == retval::CATCH_OK); - } + SECTION("Initialize and clear store, delete with pointer") { + result = simplePool.initialize(); + REQUIRE(result == retval::CATCH_OK); + result = simplePool.addData(&testStoreId, testDataArray.data(), size); + REQUIRE(result == retval::CATCH_OK); + simplePool.clearStore(); + result = simplePool.addData(&testStoreId, testDataArray.data(), size); + REQUIRE(result == retval::CATCH_OK); + result = simplePool.modifyData(testStoreId, &pointer, &size); + REQUIRE(result == retval::CATCH_OK); + store_address_t newId; + result = simplePool.deleteData(pointer, size, &testStoreId); + REQUIRE(result == retval::CATCH_OK); + REQUIRE(testStoreId.raw != (uint32_t)StorageManagerIF::INVALID_ADDRESS); + result = simplePool.addData(&testStoreId, testDataArray.data(), size); + REQUIRE(result == retval::CATCH_OK); + } } int runIdx = 0; -TEST_CASE( "Local Pool Extended Tests [3 Pools]" , "[TestPool2]") { - LocalPool::LocalPoolConfig* config; - if(runIdx == 0) { - config = new LocalPool::LocalPoolConfig{{10, 5}, {5, 10}, {2, 20}}; - } - else { - // shufle the order, they should be sort implictely so that the - // order is ascending for the page sizes. - config = new LocalPool::LocalPoolConfig{{5, 10}, {2, 20}, {10, 5}}; - size_t lastSize = 0; - for(const auto& pair: *config) { - CHECK(pair.second > lastSize); - lastSize = pair.second; - } - } - runIdx++; +TEST_CASE("Local Pool Extended Tests [3 Pools]", "[TestPool2]") { + LocalPool::LocalPoolConfig* config; + if (runIdx == 0) { + config = new LocalPool::LocalPoolConfig{{10, 5}, {5, 10}, {2, 20}}; + } else { + // shufle the order, they should be sort implictely so that the + // order is ascending for the page sizes. + config = new LocalPool::LocalPoolConfig{{5, 10}, {2, 20}, {10, 5}}; + size_t lastSize = 0; + for (const auto& pair : *config) { + CHECK(pair.second > lastSize); + lastSize = pair.second; + } + } + runIdx++; - LocalPool simplePool(0, *config); - std::array testDataArray; - std::array receptionArray; - store_address_t testStoreId; - ReturnValue_t result = retval::CATCH_FAILED; - for(size_t i = 0; i < testDataArray.size(); i++) { - testDataArray[i] = i; - } - size_t size = 0; + LocalPool simplePool(0, *config); + std::array testDataArray; + std::array receptionArray; + store_address_t testStoreId; + ReturnValue_t result = retval::CATCH_FAILED; + for (size_t i = 0; i < testDataArray.size(); i++) { + testDataArray[i] = i; + } + size_t size = 0; - SECTION ("Basic tests") { - size = 8; - result = simplePool.addData(&testStoreId, testDataArray.data(), size); - REQUIRE(result == retval::CATCH_OK); - // Should be on second page of the pool now for 8 bytes - CHECK(testStoreId.poolIndex == 1); - CHECK(testStoreId.packetIndex == 0); + SECTION("Basic tests") { + size = 8; + result = simplePool.addData(&testStoreId, testDataArray.data(), size); + REQUIRE(result == retval::CATCH_OK); + // Should be on second page of the pool now for 8 bytes + CHECK(testStoreId.poolIndex == 1); + CHECK(testStoreId.packetIndex == 0); - size = 15; - result = simplePool.addData(&testStoreId, testDataArray.data(), size); - REQUIRE(result == retval::CATCH_OK); - // Should be on third page of the pool now for 15 bytes - CHECK(testStoreId.poolIndex == 2); - CHECK(testStoreId.packetIndex == 0); + size = 15; + result = simplePool.addData(&testStoreId, testDataArray.data(), size); + REQUIRE(result == retval::CATCH_OK); + // Should be on third page of the pool now for 15 bytes + CHECK(testStoreId.poolIndex == 2); + CHECK(testStoreId.packetIndex == 0); - result = simplePool.addData(&testStoreId, testDataArray.data(), size); - REQUIRE(result == retval::CATCH_OK); - // Should be on third page of the pool now for 15 bytes - CHECK(testStoreId.poolIndex == 2); - CHECK(testStoreId.packetIndex == 1); + result = simplePool.addData(&testStoreId, testDataArray.data(), size); + REQUIRE(result == retval::CATCH_OK); + // Should be on third page of the pool now for 15 bytes + CHECK(testStoreId.poolIndex == 2); + CHECK(testStoreId.packetIndex == 1); - result = simplePool.addData(&testStoreId, testDataArray.data(), size); - // Should be on third page of the pool now for 15 bytes - REQUIRE(result == (int) LocalPool::DATA_STORAGE_FULL); + result = simplePool.addData(&testStoreId, testDataArray.data(), size); + // Should be on third page of the pool now for 15 bytes + REQUIRE(result == (int)LocalPool::DATA_STORAGE_FULL); - size = 8; - result = simplePool.addData(&testStoreId, testDataArray.data(), size); - REQUIRE(result == retval::CATCH_OK); - // Should still work - CHECK(testStoreId.poolIndex == 1); - CHECK(testStoreId.packetIndex == 1); + size = 8; + result = simplePool.addData(&testStoreId, testDataArray.data(), size); + REQUIRE(result == retval::CATCH_OK); + // Should still work + CHECK(testStoreId.poolIndex == 1); + CHECK(testStoreId.packetIndex == 1); - // fill the rest of the pool - for(uint8_t idx = 2; idx < 5; idx++) { - result = simplePool.addData(&testStoreId, testDataArray.data(), size); - REQUIRE(result == retval::CATCH_OK); - CHECK(testStoreId.poolIndex == 1); - CHECK(testStoreId.packetIndex == idx); - } - } + // fill the rest of the pool + for (uint8_t idx = 2; idx < 5; idx++) { + result = simplePool.addData(&testStoreId, testDataArray.data(), size); + REQUIRE(result == retval::CATCH_OK); + CHECK(testStoreId.poolIndex == 1); + CHECK(testStoreId.packetIndex == idx); + } + } - SECTION ("Fill Count and Clearing") { - //SECTION("Basic tests"); - uint8_t bytesWritten = 0; - simplePool.getFillCount(receptionArray.data(), &bytesWritten); - // fill count should be all zeros now. - CHECK(bytesWritten == 4); - CHECK(receptionArray[0] == 0); - CHECK(receptionArray[1] == 0); - CHECK(receptionArray[2] == 0); - CHECK(receptionArray[3] == 0); + SECTION("Fill Count and Clearing") { + // SECTION("Basic tests"); + uint8_t bytesWritten = 0; + simplePool.getFillCount(receptionArray.data(), &bytesWritten); + // fill count should be all zeros now. + CHECK(bytesWritten == 4); + CHECK(receptionArray[0] == 0); + CHECK(receptionArray[1] == 0); + CHECK(receptionArray[2] == 0); + CHECK(receptionArray[3] == 0); - // now fill the store completely. - size = 5; - for(uint8_t idx = 0; idx < 10; idx++) { - result = simplePool.addData(&testStoreId, testDataArray.data(), size); - REQUIRE(result == retval::CATCH_OK); - CHECK(testStoreId.poolIndex == 0); - CHECK(testStoreId.packetIndex == idx); - } - size = 10; - for(uint8_t idx = 0; idx < 5; idx++) { - result = simplePool.addData(&testStoreId, testDataArray.data(), size); - REQUIRE(result == retval::CATCH_OK); - CHECK(testStoreId.poolIndex == 1); - CHECK(testStoreId.packetIndex == idx); - } - size = 20; - for(uint8_t idx = 0; idx < 2; idx++) { - result = simplePool.addData(&testStoreId, testDataArray.data(), size); - REQUIRE(result == retval::CATCH_OK); - CHECK(testStoreId.poolIndex == 2); - CHECK(testStoreId.packetIndex == idx); - } - bytesWritten = 0; - simplePool.getFillCount(receptionArray.data(), &bytesWritten); - // fill count should be all 100 now. - CHECK(bytesWritten == 4); - CHECK(receptionArray[0] == 100); - CHECK(receptionArray[1] == 100); - CHECK(receptionArray[2] == 100); - CHECK(receptionArray[3] == 100); + // now fill the store completely. + size = 5; + for (uint8_t idx = 0; idx < 10; idx++) { + result = simplePool.addData(&testStoreId, testDataArray.data(), size); + REQUIRE(result == retval::CATCH_OK); + CHECK(testStoreId.poolIndex == 0); + CHECK(testStoreId.packetIndex == idx); + } + size = 10; + for (uint8_t idx = 0; idx < 5; idx++) { + result = simplePool.addData(&testStoreId, testDataArray.data(), size); + REQUIRE(result == retval::CATCH_OK); + CHECK(testStoreId.poolIndex == 1); + CHECK(testStoreId.packetIndex == idx); + } + size = 20; + for (uint8_t idx = 0; idx < 2; idx++) { + result = simplePool.addData(&testStoreId, testDataArray.data(), size); + REQUIRE(result == retval::CATCH_OK); + CHECK(testStoreId.poolIndex == 2); + CHECK(testStoreId.packetIndex == idx); + } + bytesWritten = 0; + simplePool.getFillCount(receptionArray.data(), &bytesWritten); + // fill count should be all 100 now. + CHECK(bytesWritten == 4); + CHECK(receptionArray[0] == 100); + CHECK(receptionArray[1] == 100); + CHECK(receptionArray[2] == 100); + CHECK(receptionArray[3] == 100); - // now clear the store - simplePool.clearStore(); - bytesWritten = 0; - simplePool.getFillCount(receptionArray.data(), &bytesWritten); - CHECK(bytesWritten == 4); - CHECK(receptionArray[0] == 0); - CHECK(receptionArray[1] == 0); - CHECK(receptionArray[2] == 0); - CHECK(receptionArray[3] == 0); + // now clear the store + simplePool.clearStore(); + bytesWritten = 0; + simplePool.getFillCount(receptionArray.data(), &bytesWritten); + CHECK(bytesWritten == 4); + CHECK(receptionArray[0] == 0); + CHECK(receptionArray[1] == 0); + CHECK(receptionArray[2] == 0); + CHECK(receptionArray[3] == 0); - // now fill one page - size = 5; - for(uint8_t idx = 0; idx < 10; idx++) { - result = simplePool.addData(&testStoreId, testDataArray.data(), size); - REQUIRE(result == retval::CATCH_OK); - CHECK(testStoreId.poolIndex == 0); - CHECK(testStoreId.packetIndex == idx); - } - bytesWritten = 0; - simplePool.getFillCount(receptionArray.data(), &bytesWritten); - // First page full, median fill count is 33 % - CHECK(bytesWritten == 4); - CHECK(receptionArray[0] == 100); - CHECK(receptionArray[1] == 0); - CHECK(receptionArray[2] == 0); - CHECK(receptionArray[3] == 33); + // now fill one page + size = 5; + for (uint8_t idx = 0; idx < 10; idx++) { + result = simplePool.addData(&testStoreId, testDataArray.data(), size); + REQUIRE(result == retval::CATCH_OK); + CHECK(testStoreId.poolIndex == 0); + CHECK(testStoreId.packetIndex == idx); + } + bytesWritten = 0; + simplePool.getFillCount(receptionArray.data(), &bytesWritten); + // First page full, median fill count is 33 % + CHECK(bytesWritten == 4); + CHECK(receptionArray[0] == 100); + CHECK(receptionArray[1] == 0); + CHECK(receptionArray[2] == 0); + CHECK(receptionArray[3] == 33); - // now fill second page - size = 10; - for(uint8_t idx = 0; idx < 5; idx++) { - result = simplePool.addData(&testStoreId, testDataArray.data(), size); - REQUIRE(result == retval::CATCH_OK); - CHECK(testStoreId.poolIndex == 1); - CHECK(testStoreId.packetIndex == idx); - } - bytesWritten = 0; - simplePool.getFillCount(receptionArray.data(), &bytesWritten); - // First and second page full, median fill count is 66 % - CHECK(bytesWritten == 4); - CHECK(receptionArray[0] == 100); - CHECK(receptionArray[1] == 100); - CHECK(receptionArray[2] == 0); - CHECK(receptionArray[3] == 66); + // now fill second page + size = 10; + for (uint8_t idx = 0; idx < 5; idx++) { + result = simplePool.addData(&testStoreId, testDataArray.data(), size); + REQUIRE(result == retval::CATCH_OK); + CHECK(testStoreId.poolIndex == 1); + CHECK(testStoreId.packetIndex == idx); + } + bytesWritten = 0; + simplePool.getFillCount(receptionArray.data(), &bytesWritten); + // First and second page full, median fill count is 66 % + CHECK(bytesWritten == 4); + CHECK(receptionArray[0] == 100); + CHECK(receptionArray[1] == 100); + CHECK(receptionArray[2] == 0); + CHECK(receptionArray[3] == 66); - // now clear first page - simplePool.clearSubPool(0); - bytesWritten = 0; - simplePool.getFillCount(receptionArray.data(), &bytesWritten); - // Second page full, median fill count is 33 % - CHECK(bytesWritten == 4); - CHECK(receptionArray[0] == 0); - CHECK(receptionArray[1] == 100); - CHECK(receptionArray[2] == 0); - CHECK(receptionArray[3] == 33); - } + // now clear first page + simplePool.clearSubPool(0); + bytesWritten = 0; + simplePool.getFillCount(receptionArray.data(), &bytesWritten); + // Second page full, median fill count is 33 % + CHECK(bytesWritten == 4); + CHECK(receptionArray[0] == 0); + CHECK(receptionArray[1] == 100); + CHECK(receptionArray[2] == 0); + CHECK(receptionArray[3] == 33); + } - delete(config); + delete (config); } diff --git a/tests/src/fsfw_tests/unit/testcfg/devices/logicalAddresses.cpp b/tests/src/fsfw_tests/unit/testcfg/devices/logicalAddresses.cpp index c7ce314d..56860906 100644 --- a/tests/src/fsfw_tests/unit/testcfg/devices/logicalAddresses.cpp +++ b/tests/src/fsfw_tests/unit/testcfg/devices/logicalAddresses.cpp @@ -1,5 +1 @@ #include "logicalAddresses.h" - - - - diff --git a/tests/src/fsfw_tests/unit/testcfg/devices/logicalAddresses.h b/tests/src/fsfw_tests/unit/testcfg/devices/logicalAddresses.h index d7b73e15..788c124f 100644 --- a/tests/src/fsfw_tests/unit/testcfg/devices/logicalAddresses.h +++ b/tests/src/fsfw_tests/unit/testcfg/devices/logicalAddresses.h @@ -6,10 +6,8 @@ #include namespace addresses { - /* Logical addresses have uint32_t datatype */ - enum logicalAddresses: address_t { - }; -} - +/* Logical addresses have uint32_t datatype */ +enum logicalAddresses : address_t {}; +} // namespace addresses #endif /* CONFIG_DEVICES_LOGICALADDRESSES_H_ */ diff --git a/tests/src/fsfw_tests/unit/testcfg/devices/powerSwitcherList.cpp b/tests/src/fsfw_tests/unit/testcfg/devices/powerSwitcherList.cpp index 343f78d0..7b14318f 100644 --- a/tests/src/fsfw_tests/unit/testcfg/devices/powerSwitcherList.cpp +++ b/tests/src/fsfw_tests/unit/testcfg/devices/powerSwitcherList.cpp @@ -1,4 +1 @@ #include "powerSwitcherList.h" - - - diff --git a/tests/src/fsfw_tests/unit/testcfg/devices/powerSwitcherList.h b/tests/src/fsfw_tests/unit/testcfg/devices/powerSwitcherList.h index 86ddea57..84fd5342 100644 --- a/tests/src/fsfw_tests/unit/testcfg/devices/powerSwitcherList.h +++ b/tests/src/fsfw_tests/unit/testcfg/devices/powerSwitcherList.h @@ -2,11 +2,9 @@ #define CONFIG_DEVICES_POWERSWITCHERLIST_H_ namespace switches { - /* Switches are uint8_t datatype and go from 0 to 255 */ - enum switcherList { - }; - -} +/* Switches are uint8_t datatype and go from 0 to 255 */ +enum switcherList {}; +} // namespace switches #endif /* CONFIG_DEVICES_POWERSWITCHERLIST_H_ */ diff --git a/tests/src/fsfw_tests/unit/testcfg/events/subsystemIdRanges.h b/tests/src/fsfw_tests/unit/testcfg/events/subsystemIdRanges.h index b14c4bc5..d8e00cc1 100644 --- a/tests/src/fsfw_tests/unit/testcfg/events/subsystemIdRanges.h +++ b/tests/src/fsfw_tests/unit/testcfg/events/subsystemIdRanges.h @@ -1,9 +1,9 @@ #ifndef CONFIG_EVENTS_SUBSYSTEMIDRANGES_H_ #define CONFIG_EVENTS_SUBSYSTEMIDRANGES_H_ -#include "fsfw/events/fwSubsystemIdRanges.h" #include +#include "fsfw/events/fwSubsystemIdRanges.h" /** * @brief Custom subsystem IDs can be added here @@ -11,9 +11,9 @@ * Subsystem IDs are used to create unique events. */ namespace SUBSYSTEM_ID { -enum: uint8_t { - SUBSYSTEM_ID_START = FW_SUBSYSTEM_ID_RANGE, - SUBSYSTEM_ID_END // [EXPORT] : [END] +enum : uint8_t { + SUBSYSTEM_ID_START = FW_SUBSYSTEM_ID_RANGE, + SUBSYSTEM_ID_END // [EXPORT] : [END] }; } diff --git a/tests/src/fsfw_tests/unit/testcfg/ipc/MissionMessageTypes.cpp b/tests/src/fsfw_tests/unit/testcfg/ipc/MissionMessageTypes.cpp index d68cb58c..fa1c4877 100644 --- a/tests/src/fsfw_tests/unit/testcfg/ipc/MissionMessageTypes.cpp +++ b/tests/src/fsfw_tests/unit/testcfg/ipc/MissionMessageTypes.cpp @@ -3,10 +3,8 @@ #include void messagetypes::clearMissionMessage(CommandMessage* message) { - switch(message->getMessageType()) { - default: - break; - } + switch (message->getMessageType()) { + default: + break; + } } - - diff --git a/tests/src/fsfw_tests/unit/testcfg/ipc/MissionMessageTypes.h b/tests/src/fsfw_tests/unit/testcfg/ipc/MissionMessageTypes.h index 832d8e58..1d93ba21 100644 --- a/tests/src/fsfw_tests/unit/testcfg/ipc/MissionMessageTypes.h +++ b/tests/src/fsfw_tests/unit/testcfg/ipc/MissionMessageTypes.h @@ -11,12 +11,12 @@ class CommandMessage; * * @param message Generic Command Message */ -namespace messagetypes{ +namespace messagetypes { enum MESSAGE_TYPE { - MISSION_MESSAGE_TYPE_START = FW_MESSAGES_COUNT, + MISSION_MESSAGE_TYPE_START = FW_MESSAGES_COUNT, }; void clearMissionMessage(CommandMessage* message); -} +} // namespace messagetypes #endif /* CONFIG_IPC_MISSIONMESSAGETYPES_H_ */ diff --git a/tests/src/fsfw_tests/unit/testcfg/objects/systemObjectList.h b/tests/src/fsfw_tests/unit/testcfg/objects/systemObjectList.h index accf0d81..3eba1484 100644 --- a/tests/src/fsfw_tests/unit/testcfg/objects/systemObjectList.h +++ b/tests/src/fsfw_tests/unit/testcfg/objects/systemObjectList.h @@ -1,28 +1,29 @@ #ifndef HOSTED_CONFIG_OBJECTS_SYSTEMOBJECTLIST_H_ #define HOSTED_CONFIG_OBJECTS_SYSTEMOBJECTLIST_H_ -#include "fsfw/objectmanager/frameworkObjects.h" #include +#include "fsfw/objectmanager/frameworkObjects.h" + // The objects will be instantiated in the ID order namespace objects { - enum sourceObjects: uint32_t { - /* All addresses between start and end are reserved for the FSFW */ - FSFW_CONFIG_RESERVED_START = PUS_SERVICE_1_VERIFICATION, - FSFW_CONFIG_RESERVED_END = TM_STORE, +enum sourceObjects : uint32_t { + /* All addresses between start and end are reserved for the FSFW */ + FSFW_CONFIG_RESERVED_START = PUS_SERVICE_1_VERIFICATION, + FSFW_CONFIG_RESERVED_END = TM_STORE, - UDP_BRIDGE = 15, - UDP_POLLING_TASK = 16, + UDP_BRIDGE = 15, + UDP_POLLING_TASK = 16, - TEST_ECHO_COM_IF = 20, - TEST_DEVICE = 21, + TEST_ECHO_COM_IF = 20, + TEST_DEVICE = 21, - HK_RECEIVER_MOCK = 22, - TEST_LOCAL_POOL_OWNER_BASE = 25, + HK_RECEIVER_MOCK = 22, + TEST_LOCAL_POOL_OWNER_BASE = 25, - SHARED_SET_ID = 26 + SHARED_SET_ID = 26 - }; +}; } #endif /* BSP_CONFIG_OBJECTS_SYSTEMOBJECTLIST_H_ */ diff --git a/tests/src/fsfw_tests/unit/testcfg/pollingsequence/PollingSequenceFactory.cpp b/tests/src/fsfw_tests/unit/testcfg/pollingsequence/PollingSequenceFactory.cpp index 1d29ef86..0c44f6a2 100644 --- a/tests/src/fsfw_tests/unit/testcfg/pollingsequence/PollingSequenceFactory.cpp +++ b/tests/src/fsfw_tests/unit/testcfg/pollingsequence/PollingSequenceFactory.cpp @@ -1,39 +1,30 @@ #include "PollingSequenceFactory.h" +#include +#include +#include + #include "tests/TestsConfig.h" -#include -#include -#include +ReturnValue_t pst::pollingSequenceInitDefault(FixedTimeslotTaskIF *thisSequence) { + /* Length of a communication cycle */ + uint32_t length = thisSequence->getPeriodMs(); -ReturnValue_t pst::pollingSequenceInitDefault( - FixedTimeslotTaskIF *thisSequence) { - /* Length of a communication cycle */ - uint32_t length = thisSequence->getPeriodMs(); + /* Add polling sequence table here */ + thisSequence->addSlot(objects::TEST_DEVICE, 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::TEST_DEVICE, 0.3, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::TEST_DEVICE, 0.45 * length, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::TEST_DEVICE, 0.6 * length, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::TEST_DEVICE, 0.8 * length, DeviceHandlerIF::GET_READ); - /* Add polling sequence table here */ - thisSequence->addSlot(objects::TEST_DEVICE, 0, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::TEST_DEVICE, 0.3, - DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::TEST_DEVICE, 0.45 * length, - DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::TEST_DEVICE, 0.6 * length, - DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::TEST_DEVICE, 0.8 * length, - DeviceHandlerIF::GET_READ); - - if (thisSequence->checkSequence() == HasReturnvaluesIF::RETURN_OK) { - return HasReturnvaluesIF::RETURN_OK; - } - else { + if (thisSequence->checkSequence() == HasReturnvaluesIF::RETURN_OK) { + return HasReturnvaluesIF::RETURN_OK; + } else { #if FSFW_CPP_OSTREAM_ENABLED - sif::error << "pst::pollingSequenceInitDefault: Sequence invalid!" - << std::endl; + sif::error << "pst::pollingSequenceInitDefault: Sequence invalid!" << std::endl; #else - sif::printError("pst::pollingSequenceInitDefault: Sequence invalid!"); + sif::printError("pst::pollingSequenceInitDefault: Sequence invalid!"); #endif - return HasReturnvaluesIF::RETURN_FAILED; - } + return HasReturnvaluesIF::RETURN_FAILED; + } } - diff --git a/tests/src/fsfw_tests/unit/testcfg/pollingsequence/PollingSequenceFactory.h b/tests/src/fsfw_tests/unit/testcfg/pollingsequence/PollingSequenceFactory.h index c5d41b7d..fc9891b2 100644 --- a/tests/src/fsfw_tests/unit/testcfg/pollingsequence/PollingSequenceFactory.h +++ b/tests/src/fsfw_tests/unit/testcfg/pollingsequence/PollingSequenceFactory.h @@ -18,7 +18,8 @@ class FixedTimeslotTaskIF; * The task is created using the FixedTimeslotTaskIF, * which utilises the underlying Operating System Abstraction Layer (OSAL) * - * @param thisSequence FixedTimeslotTaskIF * object is passed inside the Factory class when creating the PST + * @param thisSequence FixedTimeslotTaskIF * object is passed inside the Factory class when creating + * the PST * @return */ namespace pst { @@ -26,7 +27,6 @@ namespace pst { /* Default PST */ ReturnValue_t pollingSequenceInitDefault(FixedTimeslotTaskIF *thisSequence); - -} +} // namespace pst #endif /* POLLINGSEQUENCEINIT_H_ */ diff --git a/tests/src/fsfw_tests/unit/testcfg/returnvalues/classIds.h b/tests/src/fsfw_tests/unit/testcfg/returnvalues/classIds.h index 1001d012..99325dcb 100644 --- a/tests/src/fsfw_tests/unit/testcfg/returnvalues/classIds.h +++ b/tests/src/fsfw_tests/unit/testcfg/returnvalues/classIds.h @@ -8,9 +8,8 @@ */ namespace CLASS_ID { enum { - MISSION_CLASS_ID_START = FW_CLASS_ID_COUNT, + MISSION_CLASS_ID_START = FW_CLASS_ID_COUNT, }; } - #endif /* CONFIG_RETURNVALUES_CLASSIDS_H_ */ diff --git a/tests/src/fsfw_tests/unit/testcfg/tmtc/apid.h b/tests/src/fsfw_tests/unit/testcfg/tmtc/apid.h index c0231bca..b507242d 100644 --- a/tests/src/fsfw_tests/unit/testcfg/tmtc/apid.h +++ b/tests/src/fsfw_tests/unit/testcfg/tmtc/apid.h @@ -11,8 +11,7 @@ * Chose APID(s) for mission and define it here. */ namespace apid { - static const uint16_t DEFAULT_APID = 0x00; +static const uint16_t DEFAULT_APID = 0x00; } - #endif /* CONFIG_TMTC_APID_H_ */ diff --git a/tests/src/fsfw_tests/unit/testcfg/tmtc/pusIds.h b/tests/src/fsfw_tests/unit/testcfg/tmtc/pusIds.h index 821a9982..47b0ed4c 100644 --- a/tests/src/fsfw_tests/unit/testcfg/tmtc/pusIds.h +++ b/tests/src/fsfw_tests/unit/testcfg/tmtc/pusIds.h @@ -4,21 +4,21 @@ #include namespace pus { -enum Ids: uint8_t { - PUS_SERVICE_1 = 1, - PUS_SERVICE_2 = 2, - PUS_SERVICE_3 = 3, - PUS_SERVICE_5 = 5, - PUS_SERVICE_6 = 6, - PUS_SERVICE_8 = 8, - PUS_SERVICE_9 = 9, - PUS_SERVICE_11 = 11, - PUS_SERVICE_17 = 17, - PUS_SERVICE_19 = 19, - PUS_SERVICE_20 = 20, - PUS_SERVICE_23 = 23, - PUS_SERVICE_200 = 200, - PUS_SERVICE_201 = 201, +enum Ids : uint8_t { + PUS_SERVICE_1 = 1, + PUS_SERVICE_2 = 2, + PUS_SERVICE_3 = 3, + PUS_SERVICE_5 = 5, + PUS_SERVICE_6 = 6, + PUS_SERVICE_8 = 8, + PUS_SERVICE_9 = 9, + PUS_SERVICE_11 = 11, + PUS_SERVICE_17 = 17, + PUS_SERVICE_19 = 19, + PUS_SERVICE_20 = 20, + PUS_SERVICE_23 = 23, + PUS_SERVICE_200 = 200, + PUS_SERVICE_201 = 201, }; }; diff --git a/tests/src/fsfw_tests/unit/testtemplate/TestTemplate.cpp b/tests/src/fsfw_tests/unit/testtemplate/TestTemplate.cpp index a779d80c..0318abf6 100644 --- a/tests/src/fsfw_tests/unit/testtemplate/TestTemplate.cpp +++ b/tests/src/fsfw_tests/unit/testtemplate/TestTemplate.cpp @@ -1,6 +1,7 @@ -#include "fsfw_tests/unit/CatchDefinitions.h" #include +#include "fsfw_tests/unit/CatchDefinitions.h" + /** * @brief Template test file * @details @@ -18,13 +19,13 @@ * - https://github.com/catchorg/Catch2/blob/master/docs/assertions.md * - https://github.com/catchorg/Catch2/blob/master/docs/test-cases-and-sections.md */ -TEST_CASE("Dummy Test" , "[DummyTest]") { - uint8_t testVariable = 1; - //perform set-up here - CHECK(testVariable == 1); - SECTION("TestSection") { - // set-up is run for each section - REQUIRE(testVariable == 1); - } - // perform tear-down here +TEST_CASE("Dummy Test", "[DummyTest]") { + uint8_t testVariable = 1; + // perform set-up here + CHECK(testVariable == 1); + SECTION("TestSection") { + // set-up is run for each section + REQUIRE(testVariable == 1); + } + // perform tear-down here } diff --git a/tests/src/fsfw_tests/unit/timemanager/TestCountdown.cpp b/tests/src/fsfw_tests/unit/timemanager/TestCountdown.cpp index b1b26679..bc39b02e 100644 --- a/tests/src/fsfw_tests/unit/timemanager/TestCountdown.cpp +++ b/tests/src/fsfw_tests/unit/timemanager/TestCountdown.cpp @@ -1,27 +1,28 @@ -#include "fsfw_tests/unit/CatchDefinitions.h" #include + #include +#include "fsfw_tests/unit/CatchDefinitions.h" -TEST_CASE( "Countdown Tests", "[TestCountdown]") { - INFO("Countdown Tests"); - Countdown count(20); - REQUIRE(count.timeout == 20); - REQUIRE(count.setTimeout(100) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(count.timeout == 100); - REQUIRE(count.setTimeout(150) == static_cast(HasReturnvaluesIF::RETURN_OK)); - REQUIRE(count.isBusy()); - REQUIRE(not count.hasTimedOut()); - uint32_t number = count.getRemainingMillis(); - REQUIRE(number > 0); - bool blocked = false; - while(not count.hasTimedOut()){ - blocked = true; - }; - REQUIRE(blocked); - number = count.getRemainingMillis(); - REQUIRE(number==0); - count.resetTimer(); - REQUIRE(not count.hasTimedOut()); - REQUIRE(count.isBusy()); +TEST_CASE("Countdown Tests", "[TestCountdown]") { + INFO("Countdown Tests"); + Countdown count(20); + REQUIRE(count.timeout == 20); + REQUIRE(count.setTimeout(100) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(count.timeout == 100); + REQUIRE(count.setTimeout(150) == static_cast(HasReturnvaluesIF::RETURN_OK)); + REQUIRE(count.isBusy()); + REQUIRE(not count.hasTimedOut()); + uint32_t number = count.getRemainingMillis(); + REQUIRE(number > 0); + bool blocked = false; + while (not count.hasTimedOut()) { + blocked = true; + }; + REQUIRE(blocked); + number = count.getRemainingMillis(); + REQUIRE(number == 0); + count.resetTimer(); + REQUIRE(not count.hasTimedOut()); + REQUIRE(count.isBusy()); } diff --git a/tests/src/fsfw_tests/unit/tmtcpacket/PusTmTest.cpp b/tests/src/fsfw_tests/unit/tmtcpacket/PusTmTest.cpp index b28b04f6..8b137891 100644 --- a/tests/src/fsfw_tests/unit/tmtcpacket/PusTmTest.cpp +++ b/tests/src/fsfw_tests/unit/tmtcpacket/PusTmTest.cpp @@ -1,3 +1 @@ - - diff --git a/tests/src/fsfw_tests/unit/tmtcpacket/testCcsds.cpp b/tests/src/fsfw_tests/unit/tmtcpacket/testCcsds.cpp index 8f531805..d395449d 100644 --- a/tests/src/fsfw_tests/unit/tmtcpacket/testCcsds.cpp +++ b/tests/src/fsfw_tests/unit/tmtcpacket/testCcsds.cpp @@ -2,10 +2,10 @@ #include "fsfw/tmtcpacket/SpacePacket.h" -TEST_CASE( "CCSDS Test" , "[ccsds]") { - REQUIRE(spacepacket::getTcSpacePacketIdFromApid(0x22) == 0x1822); - REQUIRE(spacepacket::getTmSpacePacketIdFromApid(0x22) == 0x0822); +TEST_CASE("CCSDS Test", "[ccsds]") { + REQUIRE(spacepacket::getTcSpacePacketIdFromApid(0x22) == 0x1822); + REQUIRE(spacepacket::getTmSpacePacketIdFromApid(0x22) == 0x0822); - REQUIRE(spacepacket::getTcSpacePacketIdFromApid(0x7ff) == 0x1fff); - REQUIRE(spacepacket::getTmSpacePacketIdFromApid(0x7ff) == 0xfff); + REQUIRE(spacepacket::getTcSpacePacketIdFromApid(0x7ff) == 0x1fff); + REQUIRE(spacepacket::getTmSpacePacketIdFromApid(0x7ff) == 0xfff); } From ad5bb4c69452e10ab9afdf56f3f9011198661ca2 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 2 Feb 2022 10:40:00 +0100 Subject: [PATCH 27/56] update changelog.md --- CHANGELOG => CHANGELOG.md | 168 +++++++++++++++++++++++++++++++++++++- 1 file changed, 166 insertions(+), 2 deletions(-) rename CHANGELOG => CHANGELOG.md (57%) diff --git a/CHANGELOG b/CHANGELOG.md similarity index 57% rename from CHANGELOG rename to CHANGELOG.md index 8f86c147..e7d4f880 100644 --- a/CHANGELOG +++ b/CHANGELOG.md @@ -1,4 +1,168 @@ -# Changed from ASTP 1.1.0 to 1.2.0 +Change Log +======= + +All notable changes to this project will be documented in this file. + +The format is based on [Keep a Changelog](http://keepachangelog.com/) +and this project adheres to [Semantic Versioning](http://semver.org/). + +# [unreleased] + +# [v4.0.0] + +## Additions + +- CFDP Packet Stack and related tests added. It also refactors the existing TMTC infastructure to + allow sending of CFDP packets to the CCSDS handlers. + PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/528 + +## Changes + +- Applied the `clang-format` auto-formatter to all source code + +## Bugfix + +- CMake fixes in PR https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/533 , was problematic + if the uppermost user `CMakeLists.txt` did not have the include paths set up properly, which + could lead to compile errors that `#include "fsfw/FSFW.h"` was not found. + +## API Changes + +- Aforementioned changes to existing TMTC stack + +# [v3.0.0] + +## API Changes + +#### TCP Socket Changes + +* Keep Open TCP Implementation #496 + * The socket will now kept open after disconnect. This allows reconnecting. + * Only one connection is allowed + * No internal influence but clients need to change their Code. + +### GPIO IF + +* Add feature to open GPIO by line name #506 + +### Bitutil + +* Unittests for Op Divider and Bitutility #510 + +### Filesystem IF changed + +* Filesystem Base Interface: Use IF instead of void pointer #511 + +### STM32 + +* STM32 SPI Updates #518 + +## Bugfixes + +* Small bugfix for LIS3 handler #504 +* Spelling fixed for function names #509 +* CMakeLists fixes #517 +* Out of bound reads and writes in unittests #519 +* Bug in TmPacketStoredPusC (#478) +* Windows ifdef fixed #529 + +## Enhancement + +* FSFW.h.in more default values #491 +* Minor updates for PUS services #498 +* HasReturnvaluesIF naming for parameter #499 +* Tests can now be built as part of FSFW and versioning moved to CMake #500 +* Added integration test code #508 +* More printouts for rejected TC packets #505 +* Arrayprinter format improvements #514 +* Adding code for CI with docker and jenkins #520 +* Added new function in SerializeAdapter #513 + * Enables simple deSerialize if you keep track of the buffer position yourself + * `` static ReturnValue_t deSerialize(T *object, const uint8_t* buffer, + size_t* deserSize, SerializeIF::Endianness streamEndianness) `` +* Unittest helper scripts has a new Parameter to open the coverage html in the webrowser #525 + * ``'-o', '--open', Open coverage data in webbrowser`` +* Documentation updated. Sphinx Documentation can now be build with python script #526 + +## Known bugs + +* + + +All Pull Requests: + +Milestone: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/milestone/19 + +# [v2.0.0] + +## API Changes + + +### File Structure changed to fit more common structure + +* See pull request (#445) + * HAL is now part of the main project + * **See Instructions below:** + +#### Instruction how to update existing / user code + +* Changes in `#include`: + * Rename `internalError` in includes to `internalerror` + * Rename `fsfw/hal` to `fsfw_hal` + * Rename `fsfw/tests` to `fsfw_tests` + * Rename `osal/FreeRTOS` to `osal/freertos` + +* Changes in `CMakeLists.txt`: + * Rename `OS_FSFW` to `FSFW_OSAL` + +* Changes in `DleEncoder.cpp` + * Create an instance of the `DleEncoder` first before calling the `encode` and `decode` functions + +### Removed osal/linux/Timer (#486) + +* Was redundant to timemanager/Countdown + +#### Instruction how to update existing / user code + +* Use timemanager/Countdown instead + +## Bugfixes + +### TM Stack + +* Increased TM stack robustness by introducing `nullptr` checks and more printouts (#483) + +#### Host OSAL / FreeRTOS + +* QueueMapManager Bugfix (NO_QUEUE was used as MessageQueueId) (#444) + +#### Events + +* Event output is now consistent (#447) + +#### DLE Encoder + +* Fixed possible out of bounds access in DLE Encoder (#492) + +## Enhancment + +* HAL as major new feature, also includes three MEMS devicehandlers as part of #481 +* Linux HAL updates (#456) +* FreeRTOS Header cleaning update and Cmake tweaks (#442) +* Printer updates (#453) +* New returnvalue for for empty PST (#485) +* TMTC Bridge: Increase limit of packets stored (#484) + +## Known bugs + +* Bug in TmPacketStoredPusC (#478) + + +All Pull Requests: + +Milestone: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/milestone/5 + +# [v1.2.0] ## API Changes @@ -27,7 +191,7 @@ - See API changes chapter. This change will keep the internal API consistent in the future -# Changes from ASTP 1.0.0 to 1.1.0 +# [v1.1.0] ## API Changes From 79936a33356d021ca99b27d2cbe1576f2a99afea Mon Sep 17 00:00:00 2001 From: Jakob Meier Date: Thu, 3 Feb 2022 10:14:47 +0100 Subject: [PATCH 28/56] uio mapper --- hal/src/fsfw_hal/linux/uio/CMakeLists.txt | 3 + hal/src/fsfw_hal/linux/uio/UioMapper.cpp | 80 +++++++++++++++++++++++ hal/src/fsfw_hal/linux/uio/UioMapper.h | 58 ++++++++++++++++ 3 files changed, 141 insertions(+) create mode 100644 hal/src/fsfw_hal/linux/uio/CMakeLists.txt create mode 100644 hal/src/fsfw_hal/linux/uio/UioMapper.cpp create mode 100644 hal/src/fsfw_hal/linux/uio/UioMapper.h diff --git a/hal/src/fsfw_hal/linux/uio/CMakeLists.txt b/hal/src/fsfw_hal/linux/uio/CMakeLists.txt new file mode 100644 index 00000000..e98a0865 --- /dev/null +++ b/hal/src/fsfw_hal/linux/uio/CMakeLists.txt @@ -0,0 +1,3 @@ +target_sources(${LIB_FSFW_NAME} PUBLIC + UioMapper.cpp +) diff --git a/hal/src/fsfw_hal/linux/uio/UioMapper.cpp b/hal/src/fsfw_hal/linux/uio/UioMapper.cpp new file mode 100644 index 00000000..bc2d06eb --- /dev/null +++ b/hal/src/fsfw_hal/linux/uio/UioMapper.cpp @@ -0,0 +1,80 @@ +#include "UioMapper.h" + +#include +#include + +#include +#include +#include + +#include "fsfw/serviceinterface.h" + +const char UioMapper::UIO_PATH_PREFIX[] = "/sys/class/uio/"; +const char UioMapper::MAP_SUBSTR[] = "/maps/map"; +const char UioMapper::SIZE_FILE_PATH[] = "/size"; + +UioMapper::UioMapper(std::string uioFile, int mapNum) : uioFile(uioFile), mapNum(mapNum) {} + +UioMapper::~UioMapper() {} + +ReturnValue_t UioMapper::getMappedAdress(uint32_t** address, Permissions permissions) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + int fd = open(uioFile.c_str(), O_RDWR); + if (fd < 1) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "PtmeAxiConfig::initialize: Invalid UIO device file" << std::endl; +#endif + return HasReturnvaluesIF::RETURN_FAILED; + } + size_t size = 0; + result = getMapSize(&size); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + *address = static_cast( + mmap(NULL, size, static_cast(permissions), MAP_SHARED, fd, mapNum * getpagesize())); + + if (*address == MAP_FAILED) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "UioMapper::getMappedAdress: Failed to map physical address of uio device " + << uioFile.c_str() << " and map" << static_cast(mapNum) << std::endl; +#endif + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t UioMapper::getMapSize(size_t* size) { + std::stringstream namestream; + namestream << UIO_PATH_PREFIX << uioFile.substr(5, std::string::npos) << MAP_SUBSTR << mapNum + << SIZE_FILE_PATH; + FILE* fp; + fp = fopen(namestream.str().c_str(), "r"); + if (fp == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "UioMapper::getMapSize: Failed to open file " << namestream.str() << std::endl; +#endif + return HasReturnvaluesIF::RETURN_FAILED; + } + char hexstring[SIZE_HEX_STRING] = ""; + int items = fscanf(fp, "%s", hexstring); + if (items != 1) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "UioMapper::getMapSize: Failed with error code " << errno + << " to read size " + "string from file " + << namestream.str() << std::endl; +#endif + return HasReturnvaluesIF::RETURN_FAILED; + } + items = sscanf(hexstring, "%lx", size); + if (items != 1) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "UioMapper::getMapSize: Failed with error code " << errno << "to convert " + << "size of map" << mapNum << " to integer" << std::endl; +#endif + return HasReturnvaluesIF::RETURN_FAILED; + } + fclose(fp); + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/hal/src/fsfw_hal/linux/uio/UioMapper.h b/hal/src/fsfw_hal/linux/uio/UioMapper.h new file mode 100644 index 00000000..20c90b4d --- /dev/null +++ b/hal/src/fsfw_hal/linux/uio/UioMapper.h @@ -0,0 +1,58 @@ +#ifndef FSFW_HAL_SRC_FSFW_HAL_LINUX_UIO_UIOMAPPER_H_ +#define FSFW_HAL_SRC_FSFW_HAL_LINUX_UIO_UIOMAPPER_H_ + +#include + +#include + +#include "fsfw/returnvalues/HasReturnvaluesIF.h" + +/** + * @brief Class to help opening uio device files and mapping the physical addresses into the user + * address space. + * + * @author J. Meier + */ +class UioMapper { + public: + enum class Permissions : int { + READ_ONLY = PROT_READ, + WRITE_ONLY = PROT_WRITE, + READ_WRITE = PROT_READ | PROT_WRITE + }; + + /** + * @brief Constructor + * + * @param uioFile The device file of the uiO to open + * @param uioMap Number of memory map. Most UIO drivers have only one map which has than 0. + */ + UioMapper(std::string uioFile, int mapNum = 0); + virtual ~UioMapper(); + + /** + * @brief Maps the physical address into user address space and returns the mapped address + * + * @address The mapped user space address + * @permissions Specifies the read/write permissions of the address region + */ + ReturnValue_t getMappedAdress(uint32_t** address, Permissions permissions); + + private: + static const char UIO_PATH_PREFIX[]; + static const char MAP_SUBSTR[]; + static const char SIZE_FILE_PATH[]; + static constexpr int SIZE_HEX_STRING = 10; + + std::string uioFile; + int mapNum = 0; + + /** + * @brief Reads the map size from the associated sysfs size file + * + * @param size The read map size + */ + ReturnValue_t getMapSize(size_t* size); +}; + +#endif /* FSFW_HAL_SRC_FSFW_HAL_LINUX_UIO_UIOMAPPER_H_ */ From 2d52042ed6923103ac4942b6961a00b77f52830c Mon Sep 17 00:00:00 2001 From: Jakob Meier Date: Thu, 3 Feb 2022 10:16:06 +0100 Subject: [PATCH 29/56] add uio subdir --- hal/src/fsfw_hal/linux/CMakeLists.txt | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/hal/src/fsfw_hal/linux/CMakeLists.txt b/hal/src/fsfw_hal/linux/CMakeLists.txt index 5944b0e5..0fb2d385 100644 --- a/hal/src/fsfw_hal/linux/CMakeLists.txt +++ b/hal/src/fsfw_hal/linux/CMakeLists.txt @@ -4,10 +4,15 @@ endif() target_sources(${LIB_FSFW_NAME} PRIVATE UnixFileGuard.cpp + CommandExecutor.cpp utility.cpp ) -add_subdirectory(gpio) -add_subdirectory(spi) -add_subdirectory(i2c) -add_subdirectory(uart) \ No newline at end of file +if(FSFW_HAL_LINUX_ADD_PERIPHERAL_DRIVERS) + add_subdirectory(gpio) + add_subdirectory(spi) + add_subdirectory(i2c) + add_subdirectory(uart) +endif() + +add_subdirectory(uio) From 40329a33b2b28b0d96e80ba8dc005f23a00f2245 Mon Sep 17 00:00:00 2001 From: Jakob Meier Date: Thu, 3 Feb 2022 10:19:33 +0100 Subject: [PATCH 30/56] prepared for proper pr --- hal/src/fsfw_hal/linux/CMakeLists.txt | 12 ++++-------- 1 file changed, 4 insertions(+), 8 deletions(-) diff --git a/hal/src/fsfw_hal/linux/CMakeLists.txt b/hal/src/fsfw_hal/linux/CMakeLists.txt index 0fb2d385..056b59c8 100644 --- a/hal/src/fsfw_hal/linux/CMakeLists.txt +++ b/hal/src/fsfw_hal/linux/CMakeLists.txt @@ -4,15 +4,11 @@ endif() target_sources(${LIB_FSFW_NAME} PRIVATE UnixFileGuard.cpp - CommandExecutor.cpp utility.cpp ) -if(FSFW_HAL_LINUX_ADD_PERIPHERAL_DRIVERS) - add_subdirectory(gpio) - add_subdirectory(spi) - add_subdirectory(i2c) - add_subdirectory(uart) -endif() - +add_subdirectory(gpio) +add_subdirectory(spi) +add_subdirectory(i2c) +add_subdirectory(uart) add_subdirectory(uio) From e9b0951a95aeb7e4aa1f16e7cf38bb4851b9b7f6 Mon Sep 17 00:00:00 2001 From: Jakob Meier Date: Thu, 3 Feb 2022 10:37:07 +0100 Subject: [PATCH 31/56] virtual function to print datasets --- src/fsfw/datapoollocal/LocalPoolDataSetBase.cpp | 2 ++ src/fsfw/datapoollocal/LocalPoolDataSetBase.h | 5 +++++ 2 files changed, 7 insertions(+) diff --git a/src/fsfw/datapoollocal/LocalPoolDataSetBase.cpp b/src/fsfw/datapoollocal/LocalPoolDataSetBase.cpp index e2fe7d39..4a076212 100644 --- a/src/fsfw/datapoollocal/LocalPoolDataSetBase.cpp +++ b/src/fsfw/datapoollocal/LocalPoolDataSetBase.cpp @@ -291,3 +291,5 @@ float LocalPoolDataSetBase::getCollectionInterval() const { return 0.0; } } + +void LocalPoolDataSetBase::printSet() { return; } diff --git a/src/fsfw/datapoollocal/LocalPoolDataSetBase.h b/src/fsfw/datapoollocal/LocalPoolDataSetBase.h index c2de2c54..17cf8be2 100644 --- a/src/fsfw/datapoollocal/LocalPoolDataSetBase.h +++ b/src/fsfw/datapoollocal/LocalPoolDataSetBase.h @@ -171,6 +171,11 @@ class LocalPoolDataSetBase : public PoolDataSetBase, public MarkChangedIF { */ float getCollectionInterval() const; + /** + * @brief Can be overwritten by a specific implementation of a dataset to print the set. + */ + virtual void printSet(); + protected: sid_t sid; //! This mutex is used if the data is created by one object only. From 06ffe27fcc5e8008d5a1b8d53cbead2e08951aef Mon Sep 17 00:00:00 2001 From: Jakob Meier Date: Thu, 3 Feb 2022 10:46:14 +0100 Subject: [PATCH 32/56] do send read hook --- src/fsfw/devicehandlers/DeviceHandlerBase.cpp | 7 +++++++ src/fsfw/devicehandlers/DeviceHandlerBase.h | 6 ++++++ 2 files changed, 13 insertions(+) diff --git a/src/fsfw/devicehandlers/DeviceHandlerBase.cpp b/src/fsfw/devicehandlers/DeviceHandlerBase.cpp index 08d7c1d8..ea1fcdf1 100644 --- a/src/fsfw/devicehandlers/DeviceHandlerBase.cpp +++ b/src/fsfw/devicehandlers/DeviceHandlerBase.cpp @@ -665,6 +665,11 @@ void DeviceHandlerBase::doGetWrite() { void DeviceHandlerBase::doSendRead() { ReturnValue_t result; + result = doSendReadHook(); + if (result != RETURN_OK) { + return; + } + size_t replyLen = 0; if (cookieInfo.pendingCommand != deviceCommandMap.end()) { replyLen = getNextReplyLength(cookieInfo.pendingCommand->first); @@ -920,6 +925,8 @@ void DeviceHandlerBase::commandSwitch(ReturnValue_t onOff) { } } +ReturnValue_t DeviceHandlerBase::doSendReadHook() { return RETURN_OK; } + ReturnValue_t DeviceHandlerBase::getSwitches(const uint8_t** switches, uint8_t* numberOfSwitches) { return DeviceHandlerBase::NO_SWITCH; } diff --git a/src/fsfw/devicehandlers/DeviceHandlerBase.h b/src/fsfw/devicehandlers/DeviceHandlerBase.h index f3dda5c8..037f4bd7 100644 --- a/src/fsfw/devicehandlers/DeviceHandlerBase.h +++ b/src/fsfw/devicehandlers/DeviceHandlerBase.h @@ -1082,6 +1082,12 @@ class DeviceHandlerBase : public DeviceHandlerIF, */ void commandSwitch(ReturnValue_t onOff); + /** + * @brief This function can be used to insert device specific code during the do-send-read + * step. + */ + virtual ReturnValue_t doSendReadHook(); + private: /** * State a cookie is in. From f08d291e3e22950e729c327c101d22a943910e9b Mon Sep 17 00:00:00 2001 From: Jakob Meier Date: Thu, 3 Feb 2022 11:07:51 +0100 Subject: [PATCH 33/56] fix to remove compiler warning --- hal/src/fsfw_hal/linux/uio/UioMapper.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/hal/src/fsfw_hal/linux/uio/UioMapper.cpp b/hal/src/fsfw_hal/linux/uio/UioMapper.cpp index bc2d06eb..b29ed63e 100644 --- a/hal/src/fsfw_hal/linux/uio/UioMapper.cpp +++ b/hal/src/fsfw_hal/linux/uio/UioMapper.cpp @@ -67,7 +67,11 @@ ReturnValue_t UioMapper::getMapSize(size_t* size) { #endif return HasReturnvaluesIF::RETURN_FAILED; } - items = sscanf(hexstring, "%lx", size); + uint32_t sizeTmp = 0; + items = sscanf(hexstring, "%x", &sizeTmp); + if(size != nullptr) { + *size = sizeTmp; + } if (items != 1) { #if FSFW_CPP_OSTREAM_ENABLED == 1 sif::warning << "UioMapper::getMapSize: Failed with error code " << errno << "to convert " From 1b41153ee6f4002c6215493bd50ec076fd0806df Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 4 Feb 2022 10:16:37 +0100 Subject: [PATCH 34/56] add uio subdirectory --- hal/src/fsfw_hal/linux/CMakeLists.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/hal/src/fsfw_hal/linux/CMakeLists.txt b/hal/src/fsfw_hal/linux/CMakeLists.txt index 5ec8af06..0fb2d385 100644 --- a/hal/src/fsfw_hal/linux/CMakeLists.txt +++ b/hal/src/fsfw_hal/linux/CMakeLists.txt @@ -14,3 +14,5 @@ if(FSFW_HAL_LINUX_ADD_PERIPHERAL_DRIVERS) add_subdirectory(i2c) add_subdirectory(uart) endif() + +add_subdirectory(uio) From 80a610141ae21dda993fe960ff170d14d433f083 Mon Sep 17 00:00:00 2001 From: Ulrich Mohr Date: Fri, 4 Feb 2022 13:45:09 +0100 Subject: [PATCH 35/56] added v3.0.1 to changelog --- CHANGELOG.md | 20 +++++++++++++++++++- 1 file changed, 19 insertions(+), 1 deletion(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index e7d4f880..b6adddf0 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -30,6 +30,24 @@ and this project adheres to [Semantic Versioning](http://semver.org/). - Aforementioned changes to existing TMTC stack +# [v3.0.1] + +## API Changes + +* + +## Bugfixes + +* Version number was not updated for v3.0.0 #542 + +## Enhancement + +* + +## Known bugs + +* + # [v3.0.0] ## API Changes @@ -86,7 +104,7 @@ and this project adheres to [Semantic Versioning](http://semver.org/). ## Known bugs -* +* Version number was not updated for v3.0.0 #542 All Pull Requests: From baddbf7340c78223e1494dac71dc735dfbef403d Mon Sep 17 00:00:00 2001 From: Ulrich Mohr Date: Mon, 7 Feb 2022 13:44:25 +0100 Subject: [PATCH 36/56] Updated changelog for v4.0.0 --- CHANGELOG.md | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index b6adddf0..c3cb934d 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -15,10 +15,17 @@ and this project adheres to [Semantic Versioning](http://semver.org/). - CFDP Packet Stack and related tests added. It also refactors the existing TMTC infastructure to allow sending of CFDP packets to the CCSDS handlers. PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/528 +- Linux Command Executor, which can execute shell commands in blocking and non-blocking mode + PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/536 +- added virtual function to print datasets + PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/544 ## Changes - Applied the `clang-format` auto-formatter to all source code + PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/534 +- Updated Catch2 to v3.0.0-preview4, might fail installing with cmake, see known bugs below + PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/538 ## Bugfix @@ -30,6 +37,11 @@ and this project adheres to [Semantic Versioning](http://semver.org/). - Aforementioned changes to existing TMTC stack +## Known bugs + +* on some platforms building Catch2 from cmake might fail. In this case, it is advised to build and + install locally from git, see automation/Dockerfile for an example + # [v3.0.1] ## API Changes From 6dc34fc1f006d147555af68c4dfc1e52c3865f03 Mon Sep 17 00:00:00 2001 From: Ulrich Mohr Date: Mon, 7 Feb 2022 15:41:10 +0100 Subject: [PATCH 37/56] removed cmake warning as I have a workaround --- CHANGELOG.md | 16 +++++++++++----- 1 file changed, 11 insertions(+), 5 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index c3cb934d..5869a0a9 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -15,16 +15,23 @@ and this project adheres to [Semantic Versioning](http://semver.org/). - CFDP Packet Stack and related tests added. It also refactors the existing TMTC infastructure to allow sending of CFDP packets to the CCSDS handlers. PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/528 -- Linux Command Executor, which can execute shell commands in blocking and non-blocking mode - PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/536 - added virtual function to print datasets PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/544 +- doSendRead Hook + PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/545 + +### HAL additions + +- Linux Command Executor, which can execute shell commands in blocking and non-blocking mode + PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/536 +- uio Mapper + PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/543 ## Changes - Applied the `clang-format` auto-formatter to all source code PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/534 -- Updated Catch2 to v3.0.0-preview4, might fail installing with cmake, see known bugs below +- Updated Catch2 to v3.0.0-preview4 PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/538 ## Bugfix @@ -39,8 +46,7 @@ and this project adheres to [Semantic Versioning](http://semver.org/). ## Known bugs -* on some platforms building Catch2 from cmake might fail. In this case, it is advised to build and - install locally from git, see automation/Dockerfile for an example +- # [v3.0.1] From 2e4cd8055617568bc66725aa43f63b6125631b03 Mon Sep 17 00:00:00 2001 From: Ulrich Mohr Date: Mon, 7 Feb 2022 15:51:06 +0100 Subject: [PATCH 38/56] workaround for build regression catch2-v3.0.0-preview4 --- CMakeLists.txt | 2 ++ automation/Dockerfile | 6 ------ 2 files changed, 2 insertions(+), 6 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 9b090ca8..19fedb64 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -60,6 +60,8 @@ if(FSFW_BUILD_UNITTESTS) ) FetchContent_MakeAvailable(Catch2) + #fixes regression -preview4, to be confirmed in later releases + set_target_properties(Catch2 PROPERTIES DEBUG_POSTFIX "") endif() set(FSFW_CONFIG_PATH tests/src/fsfw_tests/unit/testcfg) diff --git a/automation/Dockerfile b/automation/Dockerfile index a530a671..9df67fc8 100644 --- a/automation/Dockerfile +++ b/automation/Dockerfile @@ -6,9 +6,3 @@ RUN apt-get --yes upgrade #tzdata is a dependency, won't install otherwise ARG DEBIAN_FRONTEND=noninteractive RUN apt-get --yes install gcc g++ cmake make lcov git valgrind nano iputils-ping - -RUN git clone https://github.com/catchorg/Catch2.git && \ - cd Catch2 && \ - git checkout v3.0.0-preview4 && \ - cmake -Bbuild -H. -DBUILD_TESTING=OFF && \ - cmake --build build/ --target install From 7a83289b3d4e62a20547c1652d850533756a5291 Mon Sep 17 00:00:00 2001 From: Ulrich Mohr Date: Mon, 7 Feb 2022 16:48:41 +0100 Subject: [PATCH 39/56] using prebuild, static docker image --- automation/Jenkinsfile | 8 +------- 1 file changed, 1 insertion(+), 7 deletions(-) diff --git a/automation/Jenkinsfile b/automation/Jenkinsfile index dae2da2c..f76496d1 100644 --- a/automation/Jenkinsfile +++ b/automation/Jenkinsfile @@ -3,13 +3,7 @@ pipeline { BUILDDIR = 'build-tests' } agent { - dockerfile { - dir 'automation' - //force docker to redownload base image and rebuild all steps instead of caching them - //this way, we always get an up to date docker image one each build - additionalBuildArgs '--no-cache --pull' - reuseNode true - } + docker { image: fsfw-ci:d1} } stages { stage('Clean') { From 54f3d7bd2df092776d0e3ae2170428a18e7896b7 Mon Sep 17 00:00:00 2001 From: Ulrich Mohr Date: Mon, 7 Feb 2022 16:49:42 +0100 Subject: [PATCH 40/56] Jenkinsfile typo --- automation/Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/automation/Jenkinsfile b/automation/Jenkinsfile index f76496d1..abd4532b 100644 --- a/automation/Jenkinsfile +++ b/automation/Jenkinsfile @@ -3,7 +3,7 @@ pipeline { BUILDDIR = 'build-tests' } agent { - docker { image: fsfw-ci:d1} + docker { image: 'fsfw-ci:d1'} } stages { stage('Clean') { From 720813963090b28faa66a08b6e324aa99830e6ca Mon Sep 17 00:00:00 2001 From: Ulrich Mohr Date: Mon, 7 Feb 2022 16:50:59 +0100 Subject: [PATCH 41/56] Jenkinsfile another typo --- automation/Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/automation/Jenkinsfile b/automation/Jenkinsfile index abd4532b..3424f986 100644 --- a/automation/Jenkinsfile +++ b/automation/Jenkinsfile @@ -3,7 +3,7 @@ pipeline { BUILDDIR = 'build-tests' } agent { - docker { image: 'fsfw-ci:d1'} + docker { image 'fsfw-ci:d1'} } stages { stage('Clean') { From c6d152a01d9e1691065040883df7ffcf7aa358e1 Mon Sep 17 00:00:00 2001 From: Ulrich Mohr Date: Mon, 7 Feb 2022 17:11:04 +0100 Subject: [PATCH 42/56] updated changelog --- CHANGELOG.md | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 5869a0a9..cda8037c 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -33,12 +33,16 @@ and this project adheres to [Semantic Versioning](http://semver.org/). PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/534 - Updated Catch2 to v3.0.0-preview4 PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/538 +- Changed CI to use prebuilt docker image + PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/549 ## Bugfix - CMake fixes in PR https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/533 , was problematic if the uppermost user `CMakeLists.txt` did not have the include paths set up properly, which could lead to compile errors that `#include "fsfw/FSFW.h"` was not found. +- Fix for build regression in Catch2 v3.0.0-preview4 + PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/548 ## API Changes From b25555a533dfd20c8b36bff409a4af963a79e7b8 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 10 Feb 2022 13:53:01 +0100 Subject: [PATCH 43/56] started DHB docs --- docs/devicehandlers.rst | 102 ++++++++++++++++++++++++++++++++++++++++ 1 file changed, 102 insertions(+) diff --git a/docs/devicehandlers.rst b/docs/devicehandlers.rst index 58c2df78..d1a5fb67 100644 --- a/docs/devicehandlers.rst +++ b/docs/devicehandlers.rst @@ -1,3 +1,105 @@ Device Handlers ================== +Device handler components rerpresent, control and monitor equipment, for example sensors or actuators of a spacecraft or the payload. + +Most device handlers have the same common functionality or +requirements, which are fulfilled by implementing an certain interface: + +- The handler/device needs to be commandable: :cpp:class:`HasActionsIF` +- The handler needs to communicate with the physical device via a dedicated + communication bus, for example SpaceWire, UART or SPI: :cpp:class:`DeviceCommunicationIF` +- The handler has housekeeping data which has to be exposed to the operator and/or other software + components: :cpp:class:`HasLocalDataPoolIF` +- The handler has configurable parameters +- The handler has health states, for example to indicate a broken device: + :cpp:class:`HasHealthIF` +- The handler has modes. For example there are the core modes `MODE_ON`, `MODE_OFF` + and `MODE_NORMAL` provided by the FSFW. `MODE_ON` means that a device is physically powered + but that it is not periodically polling data from the + physical device, `MODE_NORMAL` means that it is able to do that: :cpp:class`HasModesIF` + +The device handler base therefore provides abstractions for a lot of common +functionality, which can potentially avoid high amounts or logic and code duplication. + +Template Device Handler Base File +---------------------------------- + +This is an example template device handler header file with all necessary +functions implemented: + +.. code-block:: cpp + + #ifndef __TESTDEVICEHANDLER_H_ + #define __TESTDEVICEHANDLER_H_ + + #include + + class TestDeviceHandler: DeviceHandlerBase { + public: + TestDeviceHandler(object_id_t objectId, object_id_t comIF, CookieIF* cookie); + private: + void doStartUp() override; + void doShutDown() override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t* id) override; + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t* id) override; + void fillCommandAndReplyMap() override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t* commandData, + size_t commandDataLen) override; + ReturnValue_t scanForReply(const uint8_t* start, size_t remainingSize, DeviceCommandId_t* foundId, + size_t* foundLen) override; + ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t* packet) override; + uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) override; + + }; + + #endif /* __TESTDEVICEHANDLER_H_ */ + +and the respective source file with sensible default return values: + +.. code-block:: cpp + #include "TestDeviceHandler.h" + + TestDeviceHandler::TestDeviceHandler(object_id_t objectId, object_id_t comIF, CookieIF* cookie) + : DeviceHandlerBase(objectId, comIF, cookie) {} + + void TestDeviceHandler::doStartUp() {} + + void TestDeviceHandler::doShutDown() {} + + ReturnValue_t TestDeviceHandler::buildNormalDeviceCommand(DeviceCommandId_t* id) { + return HasReturnvaluesIF::RETURN_OK; + } + + ReturnValue_t TestDeviceHandler::buildTransitionDeviceCommand(DeviceCommandId_t* id) { + return HasReturnvaluesIF::RETURN_OK; + } + + void TestDeviceHandler::fillCommandAndReplyMap() {} + + ReturnValue_t TestDeviceHandler::buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t* commandData, + size_t commandDataLen) { + return HasReturnvaluesIF::RETURN_OK; + } + + ReturnValue_t TestDeviceHandler::scanForReply(const uint8_t* start, size_t remainingSize, + DeviceCommandId_t* foundId, size_t* foundLen) { + return HasReturnvaluesIF::RETURN_OK; + } + + ReturnValue_t TestDeviceHandler::interpretDeviceReply(DeviceCommandId_t id, + const uint8_t* packet) { + return HasReturnvaluesIF::RETURN_OK; + } + + uint32_t TestDeviceHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { + return 10000; + } + + ReturnValue_t TestDeviceHandler::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) { + return HasReturnvaluesIF::RETURN_OK; + } From cdf2a90f90ed8119a6d23e05efc40b4220b8e7c5 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 10 Feb 2022 14:02:30 +0100 Subject: [PATCH 44/56] fixed up cross-ref --- docs/devicehandlers.rst | 8 ++++++-- docs/highlevel.rst | 2 +- 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/docs/devicehandlers.rst b/docs/devicehandlers.rst index d1a5fb67..affaa6d9 100644 --- a/docs/devicehandlers.rst +++ b/docs/devicehandlers.rst @@ -1,7 +1,10 @@ +.. _dhb-prim-doc: + Device Handlers ================== -Device handler components rerpresent, control and monitor equipment, for example sensors or actuators of a spacecraft or the payload. +Device handler components represent, control and monitor equipment, for example sensors or actuators +of a spacecraft or the payload. Most device handlers have the same common functionality or requirements, which are fulfilled by implementing an certain interface: @@ -17,7 +20,7 @@ requirements, which are fulfilled by implementing an certain interface: - The handler has modes. For example there are the core modes `MODE_ON`, `MODE_OFF` and `MODE_NORMAL` provided by the FSFW. `MODE_ON` means that a device is physically powered but that it is not periodically polling data from the - physical device, `MODE_NORMAL` means that it is able to do that: :cpp:class`HasModesIF` + physical device, `MODE_NORMAL` means that it is able to do that: :cpp:class:`HasModesIF` The device handler base therefore provides abstractions for a lot of common functionality, which can potentially avoid high amounts or logic and code duplication. @@ -60,6 +63,7 @@ functions implemented: and the respective source file with sensible default return values: .. code-block:: cpp + #include "TestDeviceHandler.h" TestDeviceHandler::TestDeviceHandler(object_id_t objectId, object_id_t comIF, CookieIF* cookie) diff --git a/docs/highlevel.rst b/docs/highlevel.rst index 08f44777..04eb5e7b 100644 --- a/docs/highlevel.rst +++ b/docs/highlevel.rst @@ -118,7 +118,7 @@ The DH has mechanisms to monitor the communication with the physical device whic for FDIR reaction. Device Handlers can be created by implementing ``DeviceHandlerBase``. A standard FDIR component for the DH will be created automatically but can be overwritten by the user. More information on DeviceHandlers can be found in the -related [documentation section](doc/README-devicehandlers.md#top). +related :ref:`documentation section `. Modes and Health -------------------- From 2dcf896ccad5c99130148cd67a84d70caa1a1215 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 10 Feb 2022 14:04:23 +0100 Subject: [PATCH 45/56] this sounds better --- docs/devicehandlers.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/devicehandlers.rst b/docs/devicehandlers.rst index affaa6d9..80b9e7a3 100644 --- a/docs/devicehandlers.rst +++ b/docs/devicehandlers.rst @@ -7,7 +7,7 @@ Device handler components represent, control and monitor equipment, for example of a spacecraft or the payload. Most device handlers have the same common functionality or -requirements, which are fulfilled by implementing an certain interface: +requirements, which are fulfilled by implementing certain interfaces: - The handler/device needs to be commandable: :cpp:class:`HasActionsIF` - The handler needs to communicate with the physical device via a dedicated From 4f87e24f603653cdf7013074e100b54df3468065 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 10 Feb 2022 14:08:52 +0100 Subject: [PATCH 46/56] increase test limit --- tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp b/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp index d2a15137..a6360338 100644 --- a/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp +++ b/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp @@ -72,7 +72,7 @@ TEST_CASE("Command Executor", "[cmd-exec]") { result = cmdExecutor.check(bytesHaveBeenRead); REQUIRE(result != CommandExecutor::COMMAND_ERROR); usleep(500); - REQUIRE(limitIdx < 20); + REQUIRE(limitIdx < 50); } limitIdx = 0; CHECK(bytesHaveBeenRead == true); @@ -102,7 +102,7 @@ TEST_CASE("Command Executor", "[cmd-exec]") { result = cmdExecutor.check(bytesHaveBeenRead); REQUIRE(result != CommandExecutor::COMMAND_ERROR); usleep(500); - REQUIRE(limitIdx < 20); + REQUIRE(limitIdx < 50); } REQUIRE(result == HasReturnvaluesIF::RETURN_FAILED); REQUIRE(cmdExecutor.getLastError() == 1); From 9897f5130720fd5a6c9a1dc40da3bf5b895fb29f Mon Sep 17 00:00:00 2001 From: Jakob Meier Date: Mon, 14 Feb 2022 08:43:10 +0100 Subject: [PATCH 47/56] added flose and changed warning message to error message --- hal/src/fsfw_hal/linux/uio/UioMapper.cpp | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/hal/src/fsfw_hal/linux/uio/UioMapper.cpp b/hal/src/fsfw_hal/linux/uio/UioMapper.cpp index b29ed63e..6a7673e3 100644 --- a/hal/src/fsfw_hal/linux/uio/UioMapper.cpp +++ b/hal/src/fsfw_hal/linux/uio/UioMapper.cpp @@ -22,7 +22,7 @@ ReturnValue_t UioMapper::getMappedAdress(uint32_t** address, Permissions permiss int fd = open(uioFile.c_str(), O_RDWR); if (fd < 1) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "PtmeAxiConfig::initialize: Invalid UIO device file" << std::endl; + sif::error << "PtmeAxiConfig::initialize: Invalid UIO device file" << std::endl; #endif return HasReturnvaluesIF::RETURN_FAILED; } @@ -36,7 +36,7 @@ ReturnValue_t UioMapper::getMappedAdress(uint32_t** address, Permissions permiss if (*address == MAP_FAILED) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "UioMapper::getMappedAdress: Failed to map physical address of uio device " + sif::error << "UioMapper::getMappedAdress: Failed to map physical address of uio device " << uioFile.c_str() << " and map" << static_cast(mapNum) << std::endl; #endif return HasReturnvaluesIF::RETURN_FAILED; @@ -52,19 +52,21 @@ ReturnValue_t UioMapper::getMapSize(size_t* size) { fp = fopen(namestream.str().c_str(), "r"); if (fp == nullptr) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "UioMapper::getMapSize: Failed to open file " << namestream.str() << std::endl; + sif::error << "UioMapper::getMapSize: Failed to open file " << namestream.str() << std::endl; #endif + fclose(fp); return HasReturnvaluesIF::RETURN_FAILED; } char hexstring[SIZE_HEX_STRING] = ""; int items = fscanf(fp, "%s", hexstring); if (items != 1) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "UioMapper::getMapSize: Failed with error code " << errno + sif::error << "UioMapper::getMapSize: Failed with error code " << errno << " to read size " "string from file " << namestream.str() << std::endl; #endif + fclose(fp); return HasReturnvaluesIF::RETURN_FAILED; } uint32_t sizeTmp = 0; @@ -74,9 +76,10 @@ ReturnValue_t UioMapper::getMapSize(size_t* size) { } if (items != 1) { #if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "UioMapper::getMapSize: Failed with error code " << errno << "to convert " + sif::error << "UioMapper::getMapSize: Failed with error code " << errno << "to convert " << "size of map" << mapNum << " to integer" << std::endl; #endif + fclose(fp); return HasReturnvaluesIF::RETURN_FAILED; } fclose(fp); From 120750f22aab31cfa6f3d8edec1fe784a707b64e Mon Sep 17 00:00:00 2001 From: Jakob Meier Date: Mon, 14 Feb 2022 08:51:53 +0100 Subject: [PATCH 48/56] removed one fclose --- hal/src/fsfw_hal/linux/uio/UioMapper.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/hal/src/fsfw_hal/linux/uio/UioMapper.cpp b/hal/src/fsfw_hal/linux/uio/UioMapper.cpp index 6a7673e3..5eb44c5e 100644 --- a/hal/src/fsfw_hal/linux/uio/UioMapper.cpp +++ b/hal/src/fsfw_hal/linux/uio/UioMapper.cpp @@ -54,7 +54,6 @@ ReturnValue_t UioMapper::getMapSize(size_t* size) { #if FSFW_CPP_OSTREAM_ENABLED == 1 sif::error << "UioMapper::getMapSize: Failed to open file " << namestream.str() << std::endl; #endif - fclose(fp); return HasReturnvaluesIF::RETURN_FAILED; } char hexstring[SIZE_HEX_STRING] = ""; From 9e958e752e2565da2ac704a6752f7f47d3cec026 Mon Sep 17 00:00:00 2001 From: Ulrich Mohr Date: Mon, 14 Feb 2022 14:54:20 +0100 Subject: [PATCH 49/56] applied clang format --- hal/src/fsfw_hal/linux/uio/UioMapper.cpp | 12 +++++------ src/fsfw/datalinklayer/DataLinkLayer.h | 2 +- .../datalinklayer/VirtualChannelReception.cpp | 4 ++-- src/fsfw/globalfunctions/CRC.cpp | 4 ++-- src/fsfw/modes/ModeMessage.h | 16 +++++++-------- src/fsfw/osal/linux/PeriodicPosixTask.h | 4 ++-- src/fsfw/osal/rtems/PeriodicTask.h | 4 ++-- src/fsfw/osal/rtems/RTEMSTaskBase.h | 4 ++-- src/fsfw/rmap/RMAP.h | 18 ++++++++--------- src/fsfw/rmap/RMAPChannelIF.h | 20 +++++++++---------- src/fsfw/rmap/rmapStructs.h | 6 +++--- 11 files changed, 47 insertions(+), 47 deletions(-) diff --git a/hal/src/fsfw_hal/linux/uio/UioMapper.cpp b/hal/src/fsfw_hal/linux/uio/UioMapper.cpp index 5eb44c5e..43ca2727 100644 --- a/hal/src/fsfw_hal/linux/uio/UioMapper.cpp +++ b/hal/src/fsfw_hal/linux/uio/UioMapper.cpp @@ -37,7 +37,7 @@ ReturnValue_t UioMapper::getMappedAdress(uint32_t** address, Permissions permiss if (*address == MAP_FAILED) { #if FSFW_CPP_OSTREAM_ENABLED == 1 sif::error << "UioMapper::getMappedAdress: Failed to map physical address of uio device " - << uioFile.c_str() << " and map" << static_cast(mapNum) << std::endl; + << uioFile.c_str() << " and map" << static_cast(mapNum) << std::endl; #endif return HasReturnvaluesIF::RETURN_FAILED; } @@ -61,22 +61,22 @@ ReturnValue_t UioMapper::getMapSize(size_t* size) { if (items != 1) { #if FSFW_CPP_OSTREAM_ENABLED == 1 sif::error << "UioMapper::getMapSize: Failed with error code " << errno - << " to read size " - "string from file " - << namestream.str() << std::endl; + << " to read size " + "string from file " + << namestream.str() << std::endl; #endif fclose(fp); return HasReturnvaluesIF::RETURN_FAILED; } uint32_t sizeTmp = 0; items = sscanf(hexstring, "%x", &sizeTmp); - if(size != nullptr) { + if (size != nullptr) { *size = sizeTmp; } if (items != 1) { #if FSFW_CPP_OSTREAM_ENABLED == 1 sif::error << "UioMapper::getMapSize: Failed with error code " << errno << "to convert " - << "size of map" << mapNum << " to integer" << std::endl; + << "size of map" << mapNum << " to integer" << std::endl; #endif fclose(fp); return HasReturnvaluesIF::RETURN_FAILED; diff --git a/src/fsfw/datalinklayer/DataLinkLayer.h b/src/fsfw/datalinklayer/DataLinkLayer.h index edfba8a6..8735feb6 100644 --- a/src/fsfw/datalinklayer/DataLinkLayer.h +++ b/src/fsfw/datalinklayer/DataLinkLayer.h @@ -30,7 +30,7 @@ class DataLinkLayer : public CCSDSReturnValuesIF { //! [EXPORT] : [COMMENT] A previously found Bit Lock signal was lost. P1: raw BLO state, P2: 0 static const Event BIT_LOCK_LOST = MAKE_EVENT(3, severity::INFO); // static const Event RF_CHAIN_LOST = MAKE_EVENT(4, severity::INFO); //!< The CCSDS Board - //detected that either bit lock or RF available or both are lost. No parameters. + // detected that either bit lock or RF available or both are lost. No parameters. //! [EXPORT] : [COMMENT] The CCSDS Board could not interpret a TC static const Event FRAME_PROCESSING_FAILED = MAKE_EVENT(5, severity::LOW); /** diff --git a/src/fsfw/datalinklayer/VirtualChannelReception.cpp b/src/fsfw/datalinklayer/VirtualChannelReception.cpp index 4ee0c008..258bc1e6 100644 --- a/src/fsfw/datalinklayer/VirtualChannelReception.cpp +++ b/src/fsfw/datalinklayer/VirtualChannelReception.cpp @@ -30,9 +30,9 @@ ReturnValue_t VirtualChannelReception::mapDemultiplexing(TcTransferFrame* frame) mapChannelIterator iter = mapChannels.find(mapId); if (iter == mapChannels.end()) { // error << "VirtualChannelReception::mapDemultiplexing on VC " << std::hex << (int) - //channelId + // channelId // << ": MapChannel " << (int) mapId << std::dec << " not found." << - //std::endl; + // std::endl; return VC_NOT_FOUND; } else { return (iter->second)->extractPackets(frame); diff --git a/src/fsfw/globalfunctions/CRC.cpp b/src/fsfw/globalfunctions/CRC.cpp index 942e4a1a..6b8140c5 100644 --- a/src/fsfw/globalfunctions/CRC.cpp +++ b/src/fsfw/globalfunctions/CRC.cpp @@ -116,8 +116,8 @@ uint16_t CRC::crc16ccitt(uint8_t const input[], uint32_t length, uint16_t starti // for (int i=0; i<16 ;i++) // { // if (xor_out[i] == true) - // crc_value = crc_value + pow(2,(15 -i)); // reverse CrC result before Final - //XOR + // crc_value = crc_value + pow(2,(15 -i)); // reverse CrC result before + //Final XOR // } // // crc_value = 0;// for debug mode diff --git a/src/fsfw/modes/ModeMessage.h b/src/fsfw/modes/ModeMessage.h index e3638ee0..84429e84 100644 --- a/src/fsfw/modes/ModeMessage.h +++ b/src/fsfw/modes/ModeMessage.h @@ -14,30 +14,30 @@ class ModeMessage { static const uint8_t MESSAGE_ID = messagetypes::MODE_COMMAND; static const Command_t CMD_MODE_COMMAND = 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, - //!as this will break the subsystem mode machine!! + //! REPLY_WRONG_MODE_REPLY, and REPLY_REJECTED; don't add any replies, + //! as this will break the subsystem mode machine!! static const Command_t CMD_MODE_COMMAND_FORCED = MAKE_COMMAND_ID( 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 - //!replies, as this will break the subsystem mode machine!! + //! are: REPLY_MODE_REPLY, REPLY_WRONG_MODE_REPLY, and REPLY_REJECTED; don't add any + //! replies, as this will break the subsystem mode machine!! static const Command_t REPLY_MODE_REPLY = MAKE_COMMAND_ID(0x02); //!> Reply to a CMD_MODE_COMMAND or CMD_MODE_READ static const Command_t REPLY_MODE_INFO = 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_CANT_REACH_MODE = MAKE_COMMAND_ID( 0x04); //!> Reply in case a mode command can't be executed. Par1: returnCode, Par2: 0 static const Command_t REPLY_WRONG_MODE_REPLY = 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 - //!the mode that was reached + //! and a transition started but was aborted; the parameters contain + //! the mode that was reached static const Command_t CMD_MODE_READ = MAKE_COMMAND_ID( 0x06); //!> Command to read the current mode and reply with a REPLY_MODE_REPLY static const Command_t CMD_MODE_ANNOUNCE = MAKE_COMMAND_ID( 0x07); //!> Command to trigger an ModeInfo Event. This command does NOT have a reply. static const Command_t CMD_MODE_ANNOUNCE_RECURSIVELY = 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 Mode_t getMode(const CommandMessage* message); static Submode_t getSubmode(const CommandMessage* message); diff --git a/src/fsfw/osal/linux/PeriodicPosixTask.h b/src/fsfw/osal/linux/PeriodicPosixTask.h index e2db042d..3c9a3a0d 100644 --- a/src/fsfw/osal/linux/PeriodicPosixTask.h +++ b/src/fsfw/osal/linux/PeriodicPosixTask.h @@ -65,8 +65,8 @@ class PeriodicPosixTask : public PosixThread, public PeriodicTaskIF { /** * @brief The function containing the actual functionality of the task. * @details The method sets and starts - * the task's period, then enters a loop that is repeated indefinitely. Within the loop, - * all performOperation methods of the added objects are called. Afterwards the task will be + * the task's period, then enters a loop that is repeated indefinitely. Within the + * loop, all performOperation methods of the added objects are called. Afterwards the task will be * blocked until the next period. On missing the deadline, the deadlineMissedFunction is executed. */ virtual void taskFunctionality(void); diff --git a/src/fsfw/osal/rtems/PeriodicTask.h b/src/fsfw/osal/rtems/PeriodicTask.h index e2643ec7..ff8617fc 100644 --- a/src/fsfw/osal/rtems/PeriodicTask.h +++ b/src/fsfw/osal/rtems/PeriodicTask.h @@ -13,8 +13,8 @@ class ExecutableObjectIF; * @brief This class represents a specialized task for periodic activities of multiple objects. * * @details MultiObjectTask is an extension to ObjectTask in the way that it is able to execute - * multiple objects that implement the ExecutableObjectIF interface. The objects must - * be added prior to starting the task. + * multiple objects that implement the ExecutableObjectIF interface. The objects + * must be added prior to starting the task. * @author baetz * @ingroup task_handling */ diff --git a/src/fsfw/osal/rtems/RTEMSTaskBase.h b/src/fsfw/osal/rtems/RTEMSTaskBase.h index 784d3594..9ae9e755 100644 --- a/src/fsfw/osal/rtems/RTEMSTaskBase.h +++ b/src/fsfw/osal/rtems/RTEMSTaskBase.h @@ -25,8 +25,8 @@ class RTEMSTaskBase { * all other attributes are set with default values. * @param priority Sets the priority of a task. Values range from a low 0 to a high 99. * @param stack_size The stack size reserved by the operating system for the task. - * @param nam The name of the Task, as a null-terminated String. Currently max 4 chars - * supported (excluding Null-terminator), rest will be truncated + * @param nam The name of the Task, as a null-terminated String. Currently max 4 + * chars supported (excluding Null-terminator), rest will be truncated */ RTEMSTaskBase(rtems_task_priority priority, size_t stack_size, const char *name); /** diff --git a/src/fsfw/rmap/RMAP.h b/src/fsfw/rmap/RMAP.h index d46fc318..42ee1ac5 100644 --- a/src/fsfw/rmap/RMAP.h +++ b/src/fsfw/rmap/RMAP.h @@ -51,9 +51,9 @@ class RMAP : public HasReturnvaluesIF { // MAKE_RETURN_CODE(0xE4); //the data that was to be sent was too long for the hw to handle (write // command) or the expected len was bigger than maximal expected len (read command) command was // not sent - // replaced by DeviceCommunicationIF::NULLPOINTER static const ReturnValue_t COMMAND_NULLPOINTER - // = MAKE_RETURN_CODE(0xE5); //datalen was != 0 but data was == NULL in write command, or - // nullpointer in read command + // replaced by DeviceCommunicationIF::NULLPOINTER static const ReturnValue_t + // COMMAND_NULLPOINTER = MAKE_RETURN_CODE(0xE5); //datalen was != 0 but data was == NULL in write + // command, or nullpointer in read command static const ReturnValue_t COMMAND_CHANNEL_DEACTIVATED = MAKE_RETURN_CODE(0xE6); // the channel has no port set static const ReturnValue_t COMMAND_PORT_OUT_OF_RANGE = @@ -73,8 +73,8 @@ class RMAP : public HasReturnvaluesIF { static const ReturnValue_t REPLY_MISSMATCH = MAKE_RETURN_CODE( 0xD3); // a read command was issued, but get_write_rply called, or other way round static const ReturnValue_t REPLY_TIMEOUT = MAKE_RETURN_CODE(0xD4); // timeout - // replaced by DeviceCommunicationIF::NULLPOINTER static const ReturnValue_t REPLY_NULLPOINTER = - // MAKE_RETURN_CODE(0xD5);//one of the arguments in a read reply was NULL return values for + // replaced by DeviceCommunicationIF::NULLPOINTER static const ReturnValue_t REPLY_NULLPOINTER + // = MAKE_RETURN_CODE(0xD5);//one of the arguments in a read reply was NULL return values for // get_reply static const ReturnValue_t REPLY_INTERFACE_BUSY = MAKE_RETURN_CODE(0xC0); // Interface is busy (transmission buffer still being processed) @@ -169,8 +169,8 @@ class RMAP : public HasReturnvaluesIF { * @param buffer the data to write * @param length length of data * @return - * - @c COMMAND_NULLPOINTER datalen was != 0 but data was == NULL in write - * command + * - @c COMMAND_NULLPOINTER datalen was != 0 but data was == NULL in + * write command * - return codes of RMAPChannelIF::sendCommand() */ static ReturnValue_t sendWriteCommand(RMAPCookie *cookie, const uint8_t *buffer, size_t length); @@ -205,8 +205,8 @@ class RMAP : public HasReturnvaluesIF { * @param cookie to cookie to read from * @param expLength the expected maximum length of the reply * @return - * - @c COMMAND_NULLPOINTER datalen was != 0 but data was == NULL in write - * command, or nullpointer in read command + * - @c COMMAND_NULLPOINTER datalen was != 0 but data was == NULL in + * write command, or nullpointer in read command * - return codes of RMAPChannelIF::sendCommand() */ static ReturnValue_t sendReadCommand(RMAPCookie *cookie, uint32_t expLength); diff --git a/src/fsfw/rmap/RMAPChannelIF.h b/src/fsfw/rmap/RMAPChannelIF.h index 77b56eb9..20dfd5f8 100644 --- a/src/fsfw/rmap/RMAPChannelIF.h +++ b/src/fsfw/rmap/RMAPChannelIF.h @@ -73,16 +73,16 @@ class RMAPChannelIF { * @param datalen length of data * @return * - @c RETURN_OK - * - @c COMMAND_NO_DESCRIPTORS_AVAILABLE no descriptors available for sending command; - * command was not sent - * - @c COMMAND_BUFFER_FULL no receiver buffer available for expected len; command - * was not sent - * - @c COMMAND_TOO_BIG the data that was to be sent was too long for the hw to - * handle (write command) or the expected len was bigger than maximal expected len (read command) + * - @c COMMAND_NO_DESCRIPTORS_AVAILABLE no descriptors available for sending + * command; command was not sent + * - @c COMMAND_BUFFER_FULL no receiver buffer available for expected len; * command was not sent + * - @c COMMAND_TOO_BIG the data that was to be sent was too long for the hw + * to handle (write command) or the expected len was bigger than maximal expected len (read + * command) command was not sent * - @c COMMAND_CHANNEL_DEACTIVATED the channel has no port set - * - @c NOT_SUPPORTED if you dont feel like implementing - * something... + * - @c NOT_SUPPORTED if you dont feel like + * implementing something... */ virtual ReturnValue_t sendCommand(RMAPCookie *cookie, uint8_t instruction, const uint8_t *data, size_t datalen) = 0; @@ -97,8 +97,8 @@ class RMAPChannelIF { * - @c REPLY_NO_REPLY no reply was received * - @c REPLY_NOT_SENT command was not sent, implies no reply * - @c REPLY_NOT_YET_SENT command is still waiting to be sent - * - @c WRITE_REPLY_INTERFACE_BUSY Interface is busy (transmission buffer still being - * processed) + * - @c WRITE_REPLY_INTERFACE_BUSY Interface is busy (transmission buffer still + * being processed) * - @c WRITE_REPLY_TRANSMISSION_ERROR Interface encountered errors during last * operation, data could not be processed. (transmission error) * - @c WRITE_REPLY_INVALID_DATA Invalid data (amount / value) diff --git a/src/fsfw/rmap/rmapStructs.h b/src/fsfw/rmap/rmapStructs.h index 44eedc16..55e32606 100644 --- a/src/fsfw/rmap/rmapStructs.h +++ b/src/fsfw/rmap/rmapStructs.h @@ -32,10 +32,10 @@ static const uint8_t RMAP_COMMAND_READ = ((1 << RMAP_COMMAND_BIT) | (1 << RMAP_C static const uint8_t RMAP_REPLY_WRITE = ((1 << RMAP_COMMAND_BIT_WRITE) | (1 << RMAP_COMMAND_BIT_REPLY)); static const uint8_t RMAP_REPLY_READ = ((1 << RMAP_COMMAND_BIT_REPLY)); -//#define RMAP_COMMAND_WRITE ((1< Date: Mon, 14 Feb 2022 16:00:43 +0100 Subject: [PATCH 50/56] increase test limit --- tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp b/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp index a6360338..5ced030b 100644 --- a/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp +++ b/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp @@ -71,8 +71,9 @@ TEST_CASE("Command Executor", "[cmd-exec]") { limitIdx++; result = cmdExecutor.check(bytesHaveBeenRead); REQUIRE(result != CommandExecutor::COMMAND_ERROR); + // This ensures that the tests do not block indefinitely usleep(500); - REQUIRE(limitIdx < 50); + REQUIRE(limitIdx < 500); } limitIdx = 0; CHECK(bytesHaveBeenRead == true); @@ -101,8 +102,9 @@ TEST_CASE("Command Executor", "[cmd-exec]") { limitIdx++; result = cmdExecutor.check(bytesHaveBeenRead); REQUIRE(result != CommandExecutor::COMMAND_ERROR); + // This ensures that the tests do not block indefinitely usleep(500); - REQUIRE(limitIdx < 50); + REQUIRE(limitIdx < 500); } REQUIRE(result == HasReturnvaluesIF::RETURN_FAILED); REQUIRE(cmdExecutor.getLastError() == 1); From 0d38ac62d8e5e3a51bc456f60810abebc9a19c83 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 14 Feb 2022 16:12:48 +0100 Subject: [PATCH 51/56] this should work an ALL systems --- tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp b/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp index 5ced030b..e2e1e9d7 100644 --- a/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp +++ b/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp @@ -90,7 +90,7 @@ TEST_CASE("Command Executor", "[cmd-exec]") { std::string allTheReply(reinterpret_cast(largerReadBuffer)); // I am just going to assume that this string is the same across ping implementations // of different Linux systems - REQUIRE(allTheReply.find("localhost ping statistics") != std::string::npos); + REQUIRE(allTheReply.find("PING localhost") != std::string::npos); // Now check failing command result = cmdExecutor.load("false", false, false); From 22bc300902b134f36b01fe71ae4d85c4a03dbcec Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 14 Feb 2022 16:14:14 +0100 Subject: [PATCH 52/56] increase other limits --- tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp b/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp index e2e1e9d7..3ad26876 100644 --- a/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp +++ b/tests/src/fsfw_tests/unit/hal/testCommandExecutor.cpp @@ -45,7 +45,7 @@ TEST_CASE("Command Executor", "[cmd-exec]") { result = cmdExecutor.check(bytesHaveBeenRead); REQUIRE(result != CommandExecutor::COMMAND_ERROR); usleep(500); - REQUIRE(limitIdx < 5); + REQUIRE(limitIdx < 500); } limitIdx = 0; From 074ef29b86409568783f6c2ac11f0f086eda9bf4 Mon Sep 17 00:00:00 2001 From: Steffen Gaisser Date: Mon, 14 Feb 2022 15:19:47 +0100 Subject: [PATCH 53/56] Fixed valgrind python script --- scripts/helper.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/scripts/helper.py b/scripts/helper.py index 4e8a62b4..68693c40 100755 --- a/scripts/helper.py +++ b/scripts/helper.py @@ -143,7 +143,10 @@ def handle_tests_type(args, build_dir_list: list): if which("valgrind") is None: print("Please install valgrind first") sys.exit(1) - os.chdir(UNITTEST_FOLDER_NAME) + if os.path.split(os.getcwd())[1] != UNITTEST_FOLDER_NAME: + # If we are in a different directory we try to switch into it but + # this might fail + os.chdir(UNITTEST_FOLDER_NAME) os.system("valgrind --leak-check=full ./fsfw-tests") os.chdir("..") From a612fb446cb72b732d73358b17202ee3dfb96b7a Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 14 Feb 2022 16:23:21 +0100 Subject: [PATCH 54/56] added two links --- docs/devicehandlers.rst | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/docs/devicehandlers.rst b/docs/devicehandlers.rst index 80b9e7a3..0008edb3 100644 --- a/docs/devicehandlers.rst +++ b/docs/devicehandlers.rst @@ -14,7 +14,8 @@ requirements, which are fulfilled by implementing certain interfaces: communication bus, for example SpaceWire, UART or SPI: :cpp:class:`DeviceCommunicationIF` - The handler has housekeeping data which has to be exposed to the operator and/or other software components: :cpp:class:`HasLocalDataPoolIF` -- The handler has configurable parameters +- The handler has configurable parameters: :cpp:class:`ReceivesParameterMessagesIF` which + also implements :cpp:class:`HasParametersIF` - The handler has health states, for example to indicate a broken device: :cpp:class:`HasHealthIF` - The handler has modes. For example there are the core modes `MODE_ON`, `MODE_OFF` From 6744a55b9b7faf8c72bb9bf4d7bff83ce87c8952 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 14 Feb 2022 16:31:13 +0100 Subject: [PATCH 55/56] docs update --- README.md | 36 ++++++++++++++++++++++++++++++++++++ docs/getting_started.rst | 25 +++++++++++++++++++++++-- 2 files changed, 59 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index a2261c99..89a10f4b 100644 --- a/README.md +++ b/README.md @@ -107,6 +107,42 @@ cmake --build . -- fsfw-tests_coverage -j The `coverage.py` script located in the `script` folder can also be used to do this conveniently. +## Building the documentations + +The FSFW documentation is built using the tools Sphinx, doxygen and breathe based on the +instructions provided in [this blogpost](https://devblogs.microsoft.com/cppblog/clear-functional-c-documentation-with-sphinx-breathe-doxygen-cmake/). If you +want to do this locally, set up the prerequisites first. This requires a ``python3`` +installation as well. Example here is for Ubuntu. + +```sh +sudo apt-get install doxygen graphviz +``` + +And the following Python packages + +```sh +python3 -m pip install sphinx breathe +``` + +You can set up a documentation build system using the following commands + +```sh +mkdir build-docs && cd build-docs +cmake -DFSFW_BUILD_DOCS=ON -DFSFW_OSAL=host .. +``` + +Then you can generate the documentation using + +```sh +cmake --build . -j +``` + +You can find the generated documentation inside the `docs/sphinx` folder inside the build +folder. Simply open the `index.html` in the webbrowser of your choice. + +The `helper.py` script located in the script` folder can also be used to create, build +and open the documentation conveniently. Try `helper.py -h for more information. + ## Formatting the sources The formatting is done by the `clang-format` tool. The configuration is contained within the diff --git a/docs/getting_started.rst b/docs/getting_started.rst index 069e98cd..34547211 100644 --- a/docs/getting_started.rst +++ b/docs/getting_started.rst @@ -90,8 +90,21 @@ Building the documentation ---------------------------- The FSFW documentation is built using the tools Sphinx, doxygen and breathe based on the -instructions provided in `this blogpost `_. You can set up a -documentation build system using the following commands +instructions provided in `this blogpost `_. If you +want to do this locally, set up the prerequisites first. This requires a ``python3`` +installation as well. Example here is for Ubuntu. + +.. code-block:: console + + sudo apt-get install doxygen graphviz + +And the following Python packages + +.. code-block:: console + + python3 -m pip install sphinx breathe + +You can set up a documentation build system using the following commands .. code-block:: bash @@ -110,6 +123,14 @@ folder. Simply open the ``index.html`` in the webbrowser of your choice. The ``helper.py`` script located in the ``script`` folder can also be used to create, build and open the documentation conveniently. Try ``helper.py -h`` for more information. +Formatting the source +----------------------- + +The formatting is done by the ``clang-format`` tool. The configuration is contained within the +``.clang-format`` file in the repository root. As long as ``clang-format`` is installed, you +can run the ``apply-clang-format.sh`` helper script to format all source files consistently. + + .. _`Hosted FSFW example`: https://egit.irs.uni-stuttgart.de/fsfw/fsfw-example-hosted .. _`Catch2 library`: https://github.com/catchorg/Catch2 .. _`Code coverage`: https://github.com/bilke/cmake-modules/tree/master From c3d78120eace13652b8c7dcb2f4913efebdf7d7e Mon Sep 17 00:00:00 2001 From: Ulrich Mohr Date: Mon, 14 Feb 2022 16:42:40 +0100 Subject: [PATCH 56/56] preparing 4.0.0 --- CHANGELOG.md | 6 ++++++ CMakeLists.txt | 4 ++-- 2 files changed, 8 insertions(+), 2 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index cda8037c..335c0f7b 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -19,6 +19,8 @@ and this project adheres to [Semantic Versioning](http://semver.org/). PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/544 - doSendRead Hook PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/545 +- Dockumentation for DHB + PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/551 ### HAL additions @@ -43,6 +45,10 @@ and this project adheres to [Semantic Versioning](http://semver.org/). could lead to compile errors that `#include "fsfw/FSFW.h"` was not found. - Fix for build regression in Catch2 v3.0.0-preview4 PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/548 +- Fix in unittest which failed on CI + PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/552 +- Fix in helper script + PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/553 ## API Changes diff --git a/CMakeLists.txt b/CMakeLists.txt index 19fedb64..79258db2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,8 +1,8 @@ cmake_minimum_required(VERSION 3.13) -set(FSFW_VERSION 3) +set(FSFW_VERSION 4) set(FSFW_SUBVERSION 0) -set(FSFW_REVISION 1) +set(FSFW_REVISION 0) # Add the cmake folder so the FindSphinx module is found set(CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake" ${CMAKE_MODULE_PATH})