From 36fe4858a39ab3624ad9c9ab2004918780e4ff3b Mon Sep 17 00:00:00 2001 From: ineskhou Date: Fri, 3 Oct 2025 10:40:05 -0700 Subject: [PATCH 1/6] updated fprime zephyr version --- lib/fprime-zephyr | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lib/fprime-zephyr b/lib/fprime-zephyr index 4a149bbe..931354e2 160000 --- a/lib/fprime-zephyr +++ b/lib/fprime-zephyr @@ -1 +1 @@ -Subproject commit 4a149bbed5c7c86fbac44ab8a65791eff97370f9 +Subproject commit 931354e26e39cb711f846e1ca8bb1337ede83b7c From 15d6d7a6bc3f64f7fc215afe7a310644e59a612c Mon Sep 17 00:00:00 2001 From: M Starch Date: Fri, 3 Oct 2025 13:57:12 -0700 Subject: [PATCH 2/6] Initial radio addition --- .../Components/CMakeLists.txt | 1 + .../Components/NullPrmDb/CMakeLists.txt | 36 +++++++++++++ .../Components/NullPrmDb/NullPrmDb.cpp | 29 +++++++++++ .../Components/NullPrmDb/NullPrmDb.fpp | 10 ++++ .../Components/NullPrmDb/NullPrmDb.hpp | 52 +++++++++++++++++++ .../Components/NullPrmDb/docs/sdd.md | 24 +++++++++ .../ReferenceDeployment/Main.cpp | 2 + .../Top/ReferenceDeploymentPackets.fppi | 5 ++ .../Top/ReferenceDeploymentTopology.cpp | 4 +- .../Top/ReferenceDeploymentTopologyDefs.hpp | 1 + .../ReferenceDeployment/Top/instances.fpp | 9 ++-- .../ReferenceDeployment/Top/topology.fpp | 25 +++++---- .../project/config/CMakeLists.txt | 1 + .../project/config/ComCfg.fpp | 51 ++++++++++++++++++ .../config/CommandDispatcherImplCfg.hpp | 2 +- .../project/config/FpConfig.h | 7 ++- .../project/config/TlmPacketizerCfg.hpp | 2 +- lib/fprime | 2 +- prj.conf | 2 +- settings.ini | 2 +- 20 files changed, 244 insertions(+), 23 deletions(-) create mode 100644 FprimeZephyrReference/Components/NullPrmDb/CMakeLists.txt create mode 100644 FprimeZephyrReference/Components/NullPrmDb/NullPrmDb.cpp create mode 100644 FprimeZephyrReference/Components/NullPrmDb/NullPrmDb.fpp create mode 100644 FprimeZephyrReference/Components/NullPrmDb/NullPrmDb.hpp create mode 100644 FprimeZephyrReference/Components/NullPrmDb/docs/sdd.md create mode 100644 FprimeZephyrReference/project/config/ComCfg.fpp diff --git a/FprimeZephyrReference/Components/CMakeLists.txt b/FprimeZephyrReference/Components/CMakeLists.txt index 08ac562c..daf02536 100644 --- a/FprimeZephyrReference/Components/CMakeLists.txt +++ b/FprimeZephyrReference/Components/CMakeLists.txt @@ -3,5 +3,6 @@ add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Drv/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/FatalHandler") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ImuManager/") +add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/NullPrmDb/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Watchdog") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/BootloaderTrigger/") diff --git a/FprimeZephyrReference/Components/NullPrmDb/CMakeLists.txt b/FprimeZephyrReference/Components/NullPrmDb/CMakeLists.txt new file mode 100644 index 00000000..b779a42b --- /dev/null +++ b/FprimeZephyrReference/Components/NullPrmDb/CMakeLists.txt @@ -0,0 +1,36 @@ +#### +# F Prime CMakeLists.txt: +# +# SOURCES: list of source files (to be compiled) +# AUTOCODER_INPUTS: list of files to be passed to the autocoders +# DEPENDS: list of libraries that this module depends on +# +# More information in the F´ CMake API documentation: +# https://fprime.jpl.nasa.gov/latest/docs/reference/api/cmake/API/ +# +#### + +# Module names are derived from the path from the nearest project/library/framework +# root when not specifically overridden by the developer. i.e. The module defined by +# `Ref/SignalGen/CMakeLists.txt` will be named `Ref_SignalGen`. + +register_fprime_library( + AUTOCODER_INPUTS + "${CMAKE_CURRENT_LIST_DIR}/NullPrmDb.fpp" + SOURCES + "${CMAKE_CURRENT_LIST_DIR}/NullPrmDb.cpp" +# DEPENDS +# MyPackage_MyOtherModule +) + +### Unit Tests ### +# register_fprime_ut( +# AUTOCODER_INPUTS +# "${CMAKE_CURRENT_LIST_DIR}/NullPrmDb.fpp" +# SOURCES +# "${CMAKE_CURRENT_LIST_DIR}/test/ut/NullPrmDbTestMain.cpp" +# "${CMAKE_CURRENT_LIST_DIR}/test/ut/NullPrmDbTester.cpp" +# DEPENDS +# STest # For rules-based testing +# UT_AUTO_HELPERS +# ) diff --git a/FprimeZephyrReference/Components/NullPrmDb/NullPrmDb.cpp b/FprimeZephyrReference/Components/NullPrmDb/NullPrmDb.cpp new file mode 100644 index 00000000..f4aa07f3 --- /dev/null +++ b/FprimeZephyrReference/Components/NullPrmDb/NullPrmDb.cpp @@ -0,0 +1,29 @@ +// ====================================================================== +// \title NullPrmDb.cpp +// \author starchmd +// \brief cpp file for NullPrmDb component implementation class +// ====================================================================== + +#include "FprimeZephyrReference/Components/NullPrmDb/NullPrmDb.hpp" + +namespace Components { + +// ---------------------------------------------------------------------- +// Component construction and destruction +// ---------------------------------------------------------------------- + +NullPrmDb ::NullPrmDb(const char* const compName) : NullPrmDbComponentBase(compName) {} + +NullPrmDb ::~NullPrmDb() {} + +// ---------------------------------------------------------------------- +// Handler implementations for typed input ports +// ---------------------------------------------------------------------- + +Fw::ParamValid NullPrmDb ::getPrm_handler(FwIndexType portNum, FwPrmIdType id, Fw::ParamBuffer& val) { + return Fw::ParamValid::INVALID; +} + +void NullPrmDb ::setPrm_handler(FwIndexType portNum, FwPrmIdType id, Fw::ParamBuffer& val) {} + +} // namespace Components diff --git a/FprimeZephyrReference/Components/NullPrmDb/NullPrmDb.fpp b/FprimeZephyrReference/Components/NullPrmDb/NullPrmDb.fpp new file mode 100644 index 00000000..87265a5d --- /dev/null +++ b/FprimeZephyrReference/Components/NullPrmDb/NullPrmDb.fpp @@ -0,0 +1,10 @@ +module Components { + @ Null parameter database + passive component NullPrmDb { + @ Port to get parameter values + sync input port getPrm: Fw.PrmGet + + @ Port to update parameters + sync input port setPrm: Fw.PrmSet + } +} diff --git a/FprimeZephyrReference/Components/NullPrmDb/NullPrmDb.hpp b/FprimeZephyrReference/Components/NullPrmDb/NullPrmDb.hpp new file mode 100644 index 00000000..534c7299 --- /dev/null +++ b/FprimeZephyrReference/Components/NullPrmDb/NullPrmDb.hpp @@ -0,0 +1,52 @@ +// ====================================================================== +// \title NullPrmDb.hpp +// \author starchmd +// \brief hpp file for NullPrmDb component implementation class +// ====================================================================== + +#ifndef Components_NullPrmDb_HPP +#define Components_NullPrmDb_HPP + +#include "FprimeZephyrReference/Components/NullPrmDb/NullPrmDbComponentAc.hpp" + +namespace Components { + +class NullPrmDb final : public NullPrmDbComponentBase { + public: + // ---------------------------------------------------------------------- + // Component construction and destruction + // ---------------------------------------------------------------------- + + //! Construct NullPrmDb object + NullPrmDb(const char* const compName //!< The component name + ); + + //! Destroy NullPrmDb object + ~NullPrmDb(); + + private: + // ---------------------------------------------------------------------- + // Handler implementations for typed input ports + // ---------------------------------------------------------------------- + + //! Handler implementation for getPrm + //! + //! Port to get parameter values + Fw::ParamValid getPrm_handler(FwIndexType portNum, //!< The port number + FwPrmIdType id, //!< Parameter ID + Fw::ParamBuffer& val //!< Buffer containing serialized parameter value. + //!< Unmodified if param not found. + ) override; + + //! Handler implementation for setPrm + //! + //! Port to update parameters + void setPrm_handler(FwIndexType portNum, //!< The port number + FwPrmIdType id, //!< Parameter ID + Fw::ParamBuffer& val //!< Buffer containing serialized parameter value + ) override; +}; + +} // namespace Components + +#endif diff --git a/FprimeZephyrReference/Components/NullPrmDb/docs/sdd.md b/FprimeZephyrReference/Components/NullPrmDb/docs/sdd.md new file mode 100644 index 00000000..512c9071 --- /dev/null +++ b/FprimeZephyrReference/Components/NullPrmDb/docs/sdd.md @@ -0,0 +1,24 @@ +# Components::NullPrmDb + +Null parameter database. Returns error status on any call. + +## Requirements + +| Name | Description | Validation | +|---|---|---| +|NULL-PRM-DB-001| Return error on any port call | Inspection| + +## Usage Examples + +Add the instance to a topology: + +``` +param connections instance nullPrmDb +``` + + +## Port Descriptions +| Name | Description | +|---|---| +| getPrm | Get parameter, returns `Fw::ParamValid::INVALID` | +| setPrm | No-op | diff --git a/FprimeZephyrReference/ReferenceDeployment/Main.cpp b/FprimeZephyrReference/ReferenceDeployment/Main.cpp index e3148ff0..17479569 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Main.cpp +++ b/FprimeZephyrReference/ReferenceDeployment/Main.cpp @@ -11,6 +11,7 @@ #include const struct device* serial = DEVICE_DT_GET(DT_NODELABEL(cdc_acm_uart0)); +const struct device* lora = DEVICE_DT_GET(DT_NODELABEL(lora0)); int main(int argc, char* argv[]) { // ** DO NOT REMOVE **// @@ -22,6 +23,7 @@ int main(int argc, char* argv[]) { Os::init(); // Object for communicating state to the topology ReferenceDeployment::TopologyState inputs; + inputs.loraDevice = lora; inputs.uartDevice = serial; inputs.baudRate = 115200; diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentPackets.fppi b/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentPackets.fppi index 4a0e736f..c108ef21 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentPackets.fppi +++ b/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentPackets.fppi @@ -2,6 +2,7 @@ telemetry packets ReferenceDeploymentPackets { packet Health id 1 group 1 { CdhCore.cmdDisp.CommandsDispatched + CdhCore.cmdDisp.CommandsDropped ComCcsds.comQueue.comQueueDepth ComCcsds.commsBufferManager.HiBuffs ReferenceDeployment.rateGroup10Hz.RgMaxTime @@ -41,6 +42,10 @@ telemetry packets ReferenceDeploymentPackets { ReferenceDeployment.lis2mdlManager.MagneticField } + packet LoRa id 7 group 4 { + lora.LastRssi + lora.LastSnr + } } omit { diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp b/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp index 4e3bb311..fb6a47f4 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp +++ b/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp @@ -78,7 +78,9 @@ void setupTopology(const TopologyState& state) { startTasks(state); // Uplink is configured for receive so a socket task is started - comDriver.configure(state.uartDevice, state.baudRate); + // We dont need UART, as we are sending coms directly to lora + //comDriver.configure(state.uartDevice, state.baudRate); + lora.start(state.loraDevice); } void startRateGroups() { diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopologyDefs.hpp b/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopologyDefs.hpp index 3912dbb4..81064f65 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopologyDefs.hpp +++ b/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopologyDefs.hpp @@ -70,6 +70,7 @@ namespace ReferenceDeployment { */ struct TopologyState { const device* uartDevice; //!< UART device path for communication + const device* loraDevice; //!< LoRa device path for communication U32 baudRate; //!< Baud rate for UART communication CdhCore::SubtopologyState cdhCore; //!< Subtopology state for CdhCore ComCcsds::SubtopologyState comCcsds; //!< Subtopology state for ComCcsds diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/instances.fpp b/FprimeZephyrReference/ReferenceDeployment/Top/instances.fpp index 1dff4a28..ef0819a7 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/instances.fpp +++ b/FprimeZephyrReference/ReferenceDeployment/Top/instances.fpp @@ -36,11 +36,6 @@ module ReferenceDeployment { stack size Default.STACK_SIZE \ priority 4 - instance prmDb: Svc.PrmDb base id 0x10003000 \ - queue size Default.QUEUE_SIZE \ - stack size Default.STACK_SIZE \ - priority 6 - # ---------------------------------------------------------------------- # Queued component instances # ---------------------------------------------------------------------- @@ -70,4 +65,8 @@ module ReferenceDeployment { instance lsm6dsoManager: Drv.Lsm6dsoManager base id 0x10019000 instance bootloaderTrigger: Components.BootloaderTrigger base id 0x10020000 + + instance lora: Zephyr.LoRa base id 0x10021000 + + instance prmDb: Components.NullPrmDb base id 0x10022000 } diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp b/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp index 4f42fd3b..72d71354 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp +++ b/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp @@ -15,7 +15,7 @@ module ReferenceDeployment { # Subtopology imports # ---------------------------------------------------------------------- import CdhCore.Subtopology - import ComCcsds.Subtopology + import ComCcsds.FramingSubtopology # ---------------------------------------------------------------------- # Instances used in the topology @@ -24,7 +24,7 @@ module ReferenceDeployment { instance rateGroup1Hz instance rateGroupDriver instance timer - instance comDriver + instance lora instance gpioDriver instance watchdog instance prmDb @@ -67,17 +67,19 @@ module ReferenceDeployment { } connections Communications { - # ComDriver buffer allocations - comDriver.allocate -> ComCcsds.commsBufferManager.bufferGetCallee - comDriver.deallocate -> ComCcsds.commsBufferManager.bufferSendIn - + lora.allocate -> ComCcsds.commsBufferManager.bufferGetCallee + lora.deallocate -> ComCcsds.commsBufferManager.bufferSendIn + # ComDriver <-> ComStub (Uplink) - comDriver.$recv -> ComCcsds.comStub.drvReceiveIn - ComCcsds.comStub.drvReceiveReturnOut -> comDriver.recvReturnIn + lora.dataOut -> ComCcsds.frameAccumulator.dataIn + ComCcsds.frameAccumulator.dataReturnOut -> lora.dataReturnIn # ComStub <-> ComDriver (Downlink) - ComCcsds.comStub.drvSendOut -> comDriver.$send - comDriver.ready -> ComCcsds.comStub.drvConnected + ComCcsds.framer.dataOut -> lora.dataIn + lora.dataReturnOut -> ComCcsds.framer.dataReturnIn + lora.comStatusOut -> ComCcsds.framer.comStatusIn + + } connections RateGroups { @@ -86,7 +88,6 @@ module ReferenceDeployment { # High rate (10Hz) rate group rateGroupDriver.CycleOut[Ports_RateGroups.rateGroup10Hz] -> rateGroup10Hz.CycleIn - rateGroup10Hz.RateGroupMemberOut[0] -> comDriver.schedIn # Slow rate (1Hz) rate group rateGroupDriver.CycleOut[Ports_RateGroups.rateGroup1Hz] -> rateGroup1Hz.CycleIn @@ -109,6 +110,8 @@ module ReferenceDeployment { imuManager.temperatureGet -> lsm6dsoManager.temperatureGet } + + } } diff --git a/FprimeZephyrReference/project/config/CMakeLists.txt b/FprimeZephyrReference/project/config/CMakeLists.txt index 15360ffd..5b37d3b0 100644 --- a/FprimeZephyrReference/project/config/CMakeLists.txt +++ b/FprimeZephyrReference/project/config/CMakeLists.txt @@ -9,6 +9,7 @@ register_fprime_config( "${CMAKE_CURRENT_LIST_DIR}/CdhCoreTlmConfig.fpp" "${CMAKE_CURRENT_LIST_DIR}/CdhCoreFatalHandlerConfig.fpp" "${CMAKE_CURRENT_LIST_DIR}/ComCcsdsConfig.fpp" + "${CMAKE_CURRENT_LIST_DIR}/ComCfg.fpp" "${CMAKE_CURRENT_LIST_DIR}/CommandDispatcherImplCfg.hpp" "${CMAKE_CURRENT_LIST_DIR}/FpConfig.h" "${CMAKE_CURRENT_LIST_DIR}/TlmPacketizerCfg.hpp" diff --git a/FprimeZephyrReference/project/config/ComCfg.fpp b/FprimeZephyrReference/project/config/ComCfg.fpp new file mode 100644 index 00000000..30da1306 --- /dev/null +++ b/FprimeZephyrReference/project/config/ComCfg.fpp @@ -0,0 +1,51 @@ +# ====================================================================== +# FPP file for configuration of the communications stack +# +# The only reason to modify these definitions is if you are writing your own +# Framer/Deframer implementations and need more contextual data than what is +# defined +# ====================================================================== + +@ The width of packet descriptors when they are serialized by the framework +type FwPacketDescriptorType = U16 + +module ComCfg { + + # Needed in dictionary: + # - spacecraftId + # - TmFrameFixedSize + # - potentially APID enum ? + constant SpacecraftId = 0x0044 # Spacecraft ID (10 bits) + constant TmFrameFixedSize = 248 # Needs to be at least COM_BUFFER_MAX_SIZE + (2 * SpacePacketHeaderSize) + 1 + + @ APIDs are 11 bits in the Space Packet protocol, so we use U16. Max value 7FF + enum Apid : FwPacketDescriptorType { + # APIDs prefixed with FW are reserved for F Prime and need to be present + # in the enumeration. Their values can be changed + FW_PACKET_COMMAND = 0x0000 @< Command packet type - incoming + FW_PACKET_TELEM = 0x0001 @< Telemetry packet type - outgoing + FW_PACKET_LOG = 0x0002 @< Log type - outgoing + FW_PACKET_FILE = 0x0003 @< File type - incoming and outgoing + FW_PACKET_PACKETIZED_TLM = 0x0004 @< Packetized telemetry packet type + FW_PACKET_DP = 0x0005 @< Data Product packet type + FW_PACKET_IDLE = 0x0006 @< F Prime idle + FW_PACKET_HAND = 0x00FE @< F Prime handshake + FW_PACKET_UNKNOWN = 0x00FF @< F Prime unknown packet + SPP_IDLE_PACKET = 0x07FF @< Per Space Packet Standard, all 1s (11bits) is reserved for Idle Packets + INVALID_UNINITIALIZED = 0x0800 @< Anything equal or higher value is invalid and should not be used + } default INVALID_UNINITIALIZED + + @ Type used to pass context info between components during framing/deframing + struct FrameContext { + comQueueIndex: FwIndexType @< Queue Index used by the ComQueue, other components shall not modify + apid: Apid @< 11 bits APID in CCSDS + sequenceCount: U16 @< 14 bit Sequence count - sequence count is incremented per APID + vcId: U8 @< 6 bit Virtual Channel ID - used for TC and TM + } default { + comQueueIndex = 0 + apid = Apid.FW_PACKET_UNKNOWN + sequenceCount = 0 + vcId = 1 + } + +} diff --git a/FprimeZephyrReference/project/config/CommandDispatcherImplCfg.hpp b/FprimeZephyrReference/project/config/CommandDispatcherImplCfg.hpp index a0257cff..9cba1b92 100644 --- a/FprimeZephyrReference/project/config/CommandDispatcherImplCfg.hpp +++ b/FprimeZephyrReference/project/config/CommandDispatcherImplCfg.hpp @@ -11,7 +11,7 @@ // Define configuration values for dispatcher enum { - CMD_DISPATCHER_DISPATCH_TABLE_SIZE = 21, // !< The size of the table holding opcodes to dispatch + CMD_DISPATCHER_DISPATCH_TABLE_SIZE = 25, // !< The size of the table holding opcodes to dispatch CMD_DISPATCHER_SEQUENCER_TABLE_SIZE = 10, // !< The size of the table holding commands in progress }; diff --git a/FprimeZephyrReference/project/config/FpConfig.h b/FprimeZephyrReference/project/config/FpConfig.h index 3adfa68c..b77fcc77 100644 --- a/FprimeZephyrReference/project/config/FpConfig.h +++ b/FprimeZephyrReference/project/config/FpConfig.h @@ -166,7 +166,7 @@ extern "C" { // Specifies the size of the buffer that contains a communications packet. #ifndef FW_COM_BUFFER_MAX_SIZE -#define FW_COM_BUFFER_MAX_SIZE 512 +#define FW_COM_BUFFER_MAX_SIZE 235 #endif // Specifies the size of the buffer attached to state machine signals. @@ -327,6 +327,11 @@ extern "C" { #define FW_FILE_CHUNK_SIZE 512 //!< Chunk size for working with files in the OSAL layer #endif +#ifndef FW_ASSERT_COUNT_MAX +#define FW_ASSERT_COUNT_MAX 4 +#endif + + // *** NOTE configuration checks are in Fw/Cfg/ConfigCheck.cpp in order to have // the type definitions in Fw/Types/BasicTypes available. #ifdef __cplusplus diff --git a/FprimeZephyrReference/project/config/TlmPacketizerCfg.hpp b/FprimeZephyrReference/project/config/TlmPacketizerCfg.hpp index 96f20246..3b99c34e 100644 --- a/FprimeZephyrReference/project/config/TlmPacketizerCfg.hpp +++ b/FprimeZephyrReference/project/config/TlmPacketizerCfg.hpp @@ -16,7 +16,7 @@ #include namespace Svc { -static const FwChanIdType MAX_PACKETIZER_PACKETS = 6; +static const FwChanIdType MAX_PACKETIZER_PACKETS = 7; static const FwChanIdType TLMPACKETIZER_NUM_TLM_HASH_SLOTS = 15; // !< Number of slots in the hash table. // Works best when set to about twice the number of components producing telemetry diff --git a/lib/fprime b/lib/fprime index abb09e4a..7fbe1308 160000 --- a/lib/fprime +++ b/lib/fprime @@ -1 +1 @@ -Subproject commit abb09e4a681cd586ac719a7517430637cdc46199 +Subproject commit 7fbe13086ad5eafe4e896513c480b3cdb2e47557 diff --git a/prj.conf b/prj.conf index 96d07ad7..f1715943 100644 --- a/prj.conf +++ b/prj.conf @@ -50,7 +50,7 @@ CONFIG_COMMON_LIBC_MALLOC=y CONFIG_SENSOR=y -CONFIG_LOG=y +CONFIG_LOG=n CONFIG_LOG_DEFAULT_LEVEL=3 CONFIG_CBPRINTF_FP_SUPPORT=y diff --git a/settings.ini b/settings.ini index d27e929f..dde51b9e 100644 --- a/settings.ini +++ b/settings.ini @@ -7,4 +7,4 @@ default_toolchain: zephyr default_cmake_options: FPRIME_ENABLE_FRAMEWORK_UTS=OFF FPRIME_ENABLE_AUTOCODER_UTS=OFF BOARD_ROOT=. - BOARD=proves_flight_control_board_v5c/rp2350a/m33 + BOARD=proves_flight_control_board_v5d/rp2350a/m33 From daa97403f2d42a4d6425c90ba0b8a5c6e5623262 Mon Sep 17 00:00:00 2001 From: M Starch Date: Fri, 3 Oct 2025 14:58:08 -0700 Subject: [PATCH 3/6] Add LoRa transmit --- FprimeZephyrReference/project/config/CMakeLists.txt | 1 + FprimeZephyrReference/project/config/LoRaCfg.hpp | 12 ++++++++++++ 2 files changed, 13 insertions(+) create mode 100644 FprimeZephyrReference/project/config/LoRaCfg.hpp diff --git a/FprimeZephyrReference/project/config/CMakeLists.txt b/FprimeZephyrReference/project/config/CMakeLists.txt index 5b37d3b0..c10dca39 100644 --- a/FprimeZephyrReference/project/config/CMakeLists.txt +++ b/FprimeZephyrReference/project/config/CMakeLists.txt @@ -11,6 +11,7 @@ register_fprime_config( "${CMAKE_CURRENT_LIST_DIR}/ComCcsdsConfig.fpp" "${CMAKE_CURRENT_LIST_DIR}/ComCfg.fpp" "${CMAKE_CURRENT_LIST_DIR}/CommandDispatcherImplCfg.hpp" + "${CMAKE_CURRENT_LIST_DIR}/LoRaCfg.hpp" "${CMAKE_CURRENT_LIST_DIR}/FpConfig.h" "${CMAKE_CURRENT_LIST_DIR}/TlmPacketizerCfg.hpp" INTERFACE diff --git a/FprimeZephyrReference/project/config/LoRaCfg.hpp b/FprimeZephyrReference/project/config/LoRaCfg.hpp new file mode 100644 index 00000000..3d8f73e6 --- /dev/null +++ b/FprimeZephyrReference/project/config/LoRaCfg.hpp @@ -0,0 +1,12 @@ +#ifndef LORA_CFG_HPP +#define LORA_CFG_HPP +#include +#include +namespace LoRaConfig { +const U32 FREQUENCY = 437400000; //!< LoRa frequency in Hz +lora_signal_bandwidth BANDWIDTH = BW_125_KHZ; //!< LoRa bandwidth +const I8 TX_POWER = 14; //!< LoRa transmission power in dBm +const U16 PREAMBLE_LENGTH = 8; //!< LoRa preamble length +U8 HEADER[] = {0, 0, 0, 0}; //!< LoRa header (not used) +} // namespace LoRaConfig +#endif // LORA_CFG_HPP \ No newline at end of file From 868fc66938ddb200631dfb3a895c86cda178f134 Mon Sep 17 00:00:00 2001 From: M Starch Date: Fri, 3 Oct 2025 17:42:03 -0700 Subject: [PATCH 4/6] Add com delay component --- .../Components/CMakeLists.txt | 1 + .../Components/ComDelay/CMakeLists.txt | 36 ++++++++++ .../Components/ComDelay/ComDelay.cpp | 70 +++++++++++++++++++ .../Components/ComDelay/ComDelay.fpp | 48 +++++++++++++ .../Components/ComDelay/ComDelay.hpp | 61 ++++++++++++++++ .../Components/ComDelay/docs/sdd.md | 17 +++++ .../ReferenceDeployment/Top/instances.fpp | 2 + .../ReferenceDeployment/Top/topology.fpp | 7 +- fprime-gds.yaml | 4 -- fprime-gds.yml | 6 ++ 10 files changed, 245 insertions(+), 7 deletions(-) create mode 100644 FprimeZephyrReference/Components/ComDelay/CMakeLists.txt create mode 100644 FprimeZephyrReference/Components/ComDelay/ComDelay.cpp create mode 100644 FprimeZephyrReference/Components/ComDelay/ComDelay.fpp create mode 100644 FprimeZephyrReference/Components/ComDelay/ComDelay.hpp create mode 100644 FprimeZephyrReference/Components/ComDelay/docs/sdd.md delete mode 100644 fprime-gds.yaml create mode 100644 fprime-gds.yml diff --git a/FprimeZephyrReference/Components/CMakeLists.txt b/FprimeZephyrReference/Components/CMakeLists.txt index daf02536..04857251 100644 --- a/FprimeZephyrReference/Components/CMakeLists.txt +++ b/FprimeZephyrReference/Components/CMakeLists.txt @@ -1,6 +1,7 @@ # Include project-wide components here add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Drv/") +add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ComDelay/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/FatalHandler") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ImuManager/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/NullPrmDb/") diff --git a/FprimeZephyrReference/Components/ComDelay/CMakeLists.txt b/FprimeZephyrReference/Components/ComDelay/CMakeLists.txt new file mode 100644 index 00000000..5f5d5ce4 --- /dev/null +++ b/FprimeZephyrReference/Components/ComDelay/CMakeLists.txt @@ -0,0 +1,36 @@ +#### +# F Prime CMakeLists.txt: +# +# SOURCES: list of source files (to be compiled) +# AUTOCODER_INPUTS: list of files to be passed to the autocoders +# DEPENDS: list of libraries that this module depends on +# +# More information in the F´ CMake API documentation: +# https://fprime.jpl.nasa.gov/latest/docs/reference/api/cmake/API/ +# +#### + +# Module names are derived from the path from the nearest project/library/framework +# root when not specifically overridden by the developer. i.e. The module defined by +# `Ref/SignalGen/CMakeLists.txt` will be named `Ref_SignalGen`. + +register_fprime_library( + AUTOCODER_INPUTS + "${CMAKE_CURRENT_LIST_DIR}/ComDelay.fpp" + SOURCES + "${CMAKE_CURRENT_LIST_DIR}/ComDelay.cpp" +# DEPENDS +# MyPackage_MyOtherModule +) + +### Unit Tests ### +# register_fprime_ut( +# AUTOCODER_INPUTS +# "${CMAKE_CURRENT_LIST_DIR}/ComDelay.fpp" +# SOURCES +# "${CMAKE_CURRENT_LIST_DIR}/test/ut/ComDelayTestMain.cpp" +# "${CMAKE_CURRENT_LIST_DIR}/test/ut/ComDelayTester.cpp" +# DEPENDS +# STest # For rules-based testing +# UT_AUTO_HELPERS +# ) diff --git a/FprimeZephyrReference/Components/ComDelay/ComDelay.cpp b/FprimeZephyrReference/Components/ComDelay/ComDelay.cpp new file mode 100644 index 00000000..a94cdef2 --- /dev/null +++ b/FprimeZephyrReference/Components/ComDelay/ComDelay.cpp @@ -0,0 +1,70 @@ +// ====================================================================== +// \title ComDelay.cpp +// \author starchmd +// \brief cpp file for ComDelay component implementation class +// ====================================================================== + +#include "FprimeZephyrReference/Components/ComDelay/ComDelay.hpp" +#include "FprimeZephyrReference/Components/ComDelay/FppConstantsAc.hpp" + +namespace Components { + +// ---------------------------------------------------------------------- +// Component construction and destruction +// ---------------------------------------------------------------------- + +ComDelay ::ComDelay(const char* const compName) + : ComDelayComponentBase(compName), m_last_status_valid(false), m_last_status(Fw::Success::FAILURE) {} + +ComDelay ::~ComDelay() {} + +void ComDelay ::parameterUpdated(FwPrmIdType id) { + switch (id) { + case ComDelay::PARAMID_DIVIDER: { + Fw::ParamValid is_valid; + U8 new_divider = this->paramGet_DIVIDER(is_valid); + if ((is_valid != Fw::ParamValid::INVALID) && (is_valid != Fw::ParamValid::UNINIT)) { + this->log_ACTIVITY_HI_DividerSet(new_divider); + } + } break; + default: + FW_ASSERT(0); + break; // Fallthrough from assert (static analysis) + } +} + +// ---------------------------------------------------------------------- +// Handler implementations for typed input ports +// ---------------------------------------------------------------------- + +void ComDelay ::comStatusIn_handler(FwIndexType portNum, Fw::Success& condition) { + this->m_last_status = condition; + this->m_last_status_valid = true; +} + +void ComDelay ::run_handler(FwIndexType portNum, U32 context) { + // On the cycle after the tick count is reset, attempt to output any current com status + if (this->m_tick_count == 0) { + bool expected = true; + // Receive the current "last status" validity flag and atomically exchange it with false. This effectively + // "consumes" a valid status. When valid, the last status is sent out. + bool valid = this->m_last_status_valid.compare_exchange_strong(expected, false); + if (valid) { + this->comStatusOut_out(0, this->m_last_status); + } + } + + // Unless there is corruption, the parameter should always be valid via its default value; however, in the interest + // of failing-safe and continuing some sort of communication we default the current_divisor to the default value. + Fw::ParamValid is_valid; + U8 current_divisor = this->paramGet_DIVIDER(is_valid); + + // Increment and module the tick count by the divisor + if ((is_valid == Fw::ParamValid::INVALID) || (is_valid == Fw::ParamValid::UNINIT)) { + current_divisor = Components::DEFAULT_DIVIDER; + } + // Count this new tick, resetting whenever the current count is at or higher than the current divider. + this->m_tick_count = (this->m_tick_count >= current_divisor) ? 0 : this->m_tick_count + 1; +} + +} // namespace Components diff --git a/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp b/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp new file mode 100644 index 00000000..9510799e --- /dev/null +++ b/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp @@ -0,0 +1,48 @@ +module Components { + constant DEFAULT_DIVIDER = 30 + @ A component to delay com status until some further point + passive component ComDelay { + @ Rate schedule port used to trigger radio transmission + sync input port run: Svc.Sched + + @ Input comStatus from radio component + sync input port comStatusIn: Fw.SuccessCondition + + @ Output comStatus to be called on rate group + output port comStatusOut: Fw.SuccessCondition + + @ Divider of the incoming rate tick + param DIVIDER: U8 default DEFAULT_DIVIDER # Start slow i.e. on a 1S tick, transmit every 30S + + @ Divider set event + event DividerSet(divider: U8) severity activity high \ + format "Set divider to: {}" + + ############################################################################### + # Standard AC Ports: Required for Channels, Events, Commands, and Parameters # + ############################################################################### + @ Port for requesting the current time + time get port timeCaller + + @ Port for sending command registrations + command reg port cmdRegOut + + @ Port for receiving commands + command recv port cmdIn + + @ Port for sending command responses + command resp port cmdResponseOut + + @ Port for sending textual representation of events + text event port logTextOut + + @ Port for sending events to downlink + event port logOut + + @ Port to return the value of a parameter + param get port prmGetOut + + @Port to set the value of a parameter + param set port prmSetOut + } +} \ No newline at end of file diff --git a/FprimeZephyrReference/Components/ComDelay/ComDelay.hpp b/FprimeZephyrReference/Components/ComDelay/ComDelay.hpp new file mode 100644 index 00000000..82368b02 --- /dev/null +++ b/FprimeZephyrReference/Components/ComDelay/ComDelay.hpp @@ -0,0 +1,61 @@ +// ====================================================================== +// \title ComDelay.hpp +// \author starchmd +// \brief hpp file for ComDelay component implementation class +// ====================================================================== + +#ifndef Components_ComDelay_HPP +#define Components_ComDelay_HPP + +#include +#include "FprimeZephyrReference/Components/ComDelay/ComDelayComponentAc.hpp" + +namespace Components { + +class ComDelay final : public ComDelayComponentBase { + public: + // ---------------------------------------------------------------------- + // Component construction and destruction + // ---------------------------------------------------------------------- + + //! Construct ComDelay object + ComDelay(const char* const compName //!< The component name + ); + + //! Destroy ComDelay object + ~ComDelay(); + + private: + void parameterUpdated(FwPrmIdType id //!< The parameter ID + ) override; + + // ---------------------------------------------------------------------- + // Handler implementations for typed input ports + // ---------------------------------------------------------------------- + + //! Handler implementation for comStatusIn + //! + //! Input comStatus from radio component + void comStatusIn_handler(FwIndexType portNum, //!< The port number + Fw::Success& condition //!< Condition success/failure + ) override; + + //! Handler implementation for run + //! + //! Rate schedule port used to trigger radio transmission + void run_handler(FwIndexType portNum, //!< The port number + U32 context //!< The call order + ) override; + + private: + //! Count of incoming run ticks + U8 m_tick_count; + //! Stores if the last status is currently valid + std::atomic m_last_status_valid; + //! Stores the last status + Fw::Success m_last_status; +}; + +} // namespace Components + +#endif diff --git a/FprimeZephyrReference/Components/ComDelay/docs/sdd.md b/FprimeZephyrReference/Components/ComDelay/docs/sdd.md new file mode 100644 index 00000000..969c9702 --- /dev/null +++ b/FprimeZephyrReference/Components/ComDelay/docs/sdd.md @@ -0,0 +1,17 @@ +# Components::ComDelay + +`Components::ComDelay` is a parameterized rate group schedule divider. On the initial run invocation and on each multiple of the divider thereafter any received com status is sent out. This effectively delays the com status until the next (divided) run call. + +# 1 Requirements + +| Requirement ID | Description | Validation | +|----------------|----------------------------------------------------------------------|------------| +| COM_DELAY_001 | The `Svc::ComDelay` component shall accept com status in. | Unit-Test | +| COM_DELAY_002 | The `Svc::ComDelay` component shall emit com status once for each DIVIDER number of rate group ticks. | Unit-Test | +| COM_DELAY_003 | The `Svc::ComDelay` component shall set the DIVIDER via a parameter. | Unit-Test | + +# 2 Parameters + +| Name | Description | +|---------|-----------------------------------------------------------| +| DIVIDER | Number of rate group ticks received before sending status | \ No newline at end of file diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/instances.fpp b/FprimeZephyrReference/ReferenceDeployment/Top/instances.fpp index ef0819a7..e53880b0 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/instances.fpp +++ b/FprimeZephyrReference/ReferenceDeployment/Top/instances.fpp @@ -69,4 +69,6 @@ module ReferenceDeployment { instance lora: Zephyr.LoRa base id 0x10021000 instance prmDb: Components.NullPrmDb base id 0x10022000 + + instance comDelay: Components.ComDelay base id 0x10023000 } diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp b/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp index 72d71354..9a75b9c1 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp +++ b/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp @@ -33,6 +33,7 @@ module ReferenceDeployment { instance lis2mdlManager instance lsm6dsoManager instance bootloaderTrigger + instance comDelay # ---------------------------------------------------------------------- # Pattern graph specifiers # ---------------------------------------------------------------------- @@ -77,9 +78,8 @@ module ReferenceDeployment { # ComStub <-> ComDriver (Downlink) ComCcsds.framer.dataOut -> lora.dataIn lora.dataReturnOut -> ComCcsds.framer.dataReturnIn - lora.comStatusOut -> ComCcsds.framer.comStatusIn - - + lora.comStatusOut -> comDelay.comStatusIn + comDelay.comStatusOut ->ComCcsds.framer.comStatusIn } connections RateGroups { @@ -97,6 +97,7 @@ module ReferenceDeployment { rateGroup1Hz.RateGroupMemberOut[3] -> CdhCore.tlmSend.Run rateGroup1Hz.RateGroupMemberOut[4] -> watchdog.run rateGroup1Hz.RateGroupMemberOut[5] -> imuManager.run + rateGroup1Hz.RateGroupMemberOut[6] -> comDelay.run } connections Watchdog { diff --git a/fprime-gds.yaml b/fprime-gds.yaml deleted file mode 100644 index 0e1f0e23..00000000 --- a/fprime-gds.yaml +++ /dev/null @@ -1,4 +0,0 @@ -command-line-options: - communication-selection: uart - uart-baud: 115200 - no-app: diff --git a/fprime-gds.yml b/fprime-gds.yml new file mode 100644 index 00000000..71457076 --- /dev/null +++ b/fprime-gds.yml @@ -0,0 +1,6 @@ +command-line-options: + communication-selection: uart + uart-baud: 115200 + no-app: + dictionary: build-artifacts/zephyr/fprime-zephyr-deployment/dict/ReferenceDeploymentTopologyDictionary.json + output-unframed-data: "-" From 30fe6193149e641dbd949093c39398e02d444224 Mon Sep 17 00:00:00 2001 From: ineskhou <127782958+ineskhou@users.noreply.github.com> Date: Sat, 4 Oct 2025 22:27:28 -0700 Subject: [PATCH 5/6] Create custom_space_data_link.py this is for a patch for the gds accepting da packages --- custom_space_data_link.py | 198 ++++++++++++++++++++++++++++++++++++++ 1 file changed, 198 insertions(+) create mode 100644 custom_space_data_link.py diff --git a/custom_space_data_link.py b/custom_space_data_link.py new file mode 100644 index 00000000..0439afdc --- /dev/null +++ b/custom_space_data_link.py @@ -0,0 +1,198 @@ +"""F Prime Framer/Deframer Implementation of the CCSDS Space Data Link (TC/TM) Protocols""" + +import copy +import struct +import sys + +import crc +from fprime_gds.common.communication.framing import FramerDeframer +from fprime_gds.plugin.definitions import gds_plugin_implementation + + +class SpaceDataLinkFramerDeframer(FramerDeframer): + """CCSDS Framer/Deframer Implementation for the TC (uplink / framing) and TM (downlink / deframing) + protocols. This FramerDeframer is used for framing TC data for uplink and deframing TM data for downlink. + """ + + SEQUENCE_NUMBER_MAXIMUM = 256 + TC_HEADER_SIZE = 5 + TM_HEADER_SIZE = 6 + TM_FIXED_FRAME_SIZE = 248 + TM_TRAILER_SIZE = 2 + TC_TRAILER_SIZE = 2 + + # As per CCSDS standard, use CRC-16 CCITT config with init value + # all 1s and final XOR value of 0x0000 + CRC_CCITT_CONFIG = crc.Configuration( + width=16, + polynomial=0x1021, + init_value=0xFFFF, + final_xor_value=0x0000, + ) + CRC_CALCULATOR = crc.Calculator(CRC_CCITT_CONFIG) + + def __init__(self, scid, vcid): + """ """ + self.scid = scid + self.vcid = vcid + self.sequence_number = 0 + + def frame(self, data): + """Frame the supplied data in a TC frame""" + space_packet_bytes = data + # CCSDS TC protocol defines the length token as number of bytes in full frame, minus 1 + # so we add to packet size the size of the header and trailer and subtract 1 + length = ( + len(space_packet_bytes) + self.TC_HEADER_SIZE + self.TC_TRAILER_SIZE - 1 + ) + assert length < (pow(2, 10) - 1), "Length too-large for CCSDS format" + + # CCSDS TC Header: + # 2b - 00 - TF version number + # 1b - 0/1 - 0 enable FARM checks, 1 bypass FARM + # 1b - 0/1 - 0 = data (Type-D), 1 = control information (Type-C) + # 2b - 00 - Reserved + # 10b - XX - Spacecraft id + # 6b - XX - Virtual Channel ID + # 10b - XX - Frame length + # 8b - XX - Frame sequence number + + # First 16 bits: + header_val1_u16 = ( + (0 << 14) # TF version number (2 bits) + | (1 << 13) # Bypass FARM (1 bit) + | (0 << 12) # Type-D (1 bit) + | (0 << 10) # Reserved (2 bits) + | (self.scid & 0x3FF) # SCID (10 bits) + ) + # Second 16 bits: + header_val2_u16 = ( + ((self.vcid & 0x3F) << 10) # VCID (6 bits) + | (length & 0x3FF) # Frame length (10 bits) + ) + # 8 bit sequence number - always 0 in bypass FARM mode + header_val3_u8 = 0 + header_bytes = struct.pack( + ">HHB", header_val1_u16, header_val2_u16, header_val3_u8 + ) + full_bytes_no_crc = header_bytes + space_packet_bytes + assert len(header_bytes) == self.TC_HEADER_SIZE, ( + "CCSDS primary header must be 5 octets long" + ) + assert len(full_bytes_no_crc) == self.TC_HEADER_SIZE + len(data), ( + "Malformed packet generated" + ) + + full_bytes = full_bytes_no_crc + struct.pack( + ">H", self.CRC_CALCULATOR.checksum(full_bytes_no_crc) + ) + return full_bytes + + def get_sequence_number(self): + """Get the sequence number and increment - used for TM deframing + + This function will return the current sequence number and then increment the sequence number for the next round. + + Return: + current sequence number + """ + sequence = self.sequence_number + self.sequence_number = (self.sequence_number + 1) % self.SEQUENCE_NUMBER_MAXIMUM + return sequence + + def deframe(self, data, no_copy=False): + """Deframe TM frames""" + discarded = b"" + if not no_copy: + data = copy.copy(data) + # Continue until there is not enough data for the header, or until a packet is found (return) + while len(data) >= self.TM_FIXED_FRAME_SIZE: + # Read header information + sc_and_channel_ids = struct.unpack_from(">H", data) + spacecraft_id = (sc_and_channel_ids[0] & 0x3FF0) >> 4 + virtual_channel_id = (sc_and_channel_ids[0] & 0x000E) >> 1 + # Check if the header is correct with regards to expected spacecraft and VC IDs + if spacecraft_id != self.scid or virtual_channel_id != self.vcid: + # If the header is invalid, rotate away a Byte and keep processing + discarded += data[0:1] + data = data[1:] + continue + # Spacecraft ID and Virtual Channel ID match, so we look at end of frame for CRC + crc_offset = self.TM_FIXED_FRAME_SIZE - self.TM_TRAILER_SIZE + transmitted_crc = struct.unpack_from(">H", data, crc_offset)[0] + if transmitted_crc == self.CRC_CALCULATOR.checksum(data[:crc_offset]): + # CRC is valid, so we return the deframed data + deframed_data_len = ( + self.TM_FIXED_FRAME_SIZE + - self.TM_TRAILER_SIZE + - self.TM_HEADER_SIZE + ) + deframed = struct.unpack_from( + f">{deframed_data_len}s", data, self.TM_HEADER_SIZE + )[0] + # Consume the fixed size frame + data = data[self.TM_FIXED_FRAME_SIZE :] + return deframed, data, discarded + + print( + "[WARNING] Checksum validation failed.", + file=sys.stderr, + ) + # Bad checksum, rotate 1 and keep looking for non-garbage + discarded += data[0:1] + data = data[1:] + continue + return None, data, discarded + + @classmethod + def get_arguments(cls): + """Arguments to request from the CLI""" + return { + ("--scid",): { + "type": lambda input_arg: int(input_arg, 0), + "help": "Spacecraft ID", + "default": 0x44, + "required": False, + }, + ("--vcid",): { + "type": lambda input_arg: int(input_arg, 0), + "help": "Virtual channel ID", + "default": 1, + "required": False, + }, + } + + @classmethod + def check_arguments(cls, scid, vcid): + """Check arguments from the CLI + + Confirms that the input arguments are valid for this framer/deframer. + + Args: + scid: spacecraft id + vcid: virtual channel id + """ + if scid is None: + raise TypeError("Spacecraft ID not specified") + if scid < 0: + raise TypeError(f"Spacecraft ID {scid} is negative") + if scid > 0x3FF: + raise TypeError(f"Spacecraft ID {scid} is larger than {0x3FF}") + + if vcid is None: + raise TypeError("Virtual Channel ID not specified") + if vcid < 0: + raise TypeError(f"Virtual Channel ID {vcid} is negative") + if vcid > 0x3F: + raise TypeError(f"Virtual Channel ID {vcid} is larger than {0x3FF}") + + @classmethod + def get_name(cls): + """Name of this implementation provided to CLI""" + return "raw-space-data-link" + + @classmethod + @gds_plugin_implementation + def register_framing_plugin(cls): + """Register the MyPlugin plugin""" + return cls From e677465c166487177b48e146132d7faa870d4837 Mon Sep 17 00:00:00 2001 From: ineskhou <127782958+ineskhou@users.noreply.github.com> Date: Sat, 4 Oct 2025 22:40:26 -0700 Subject: [PATCH 6/6] Allows Makefile with F Prime version and run GDS with camera --- Makefile | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Makefile b/Makefile index 2b794612..f7cf75dc 100644 --- a/Makefile +++ b/Makefile @@ -17,7 +17,10 @@ fprime-venv: ## Create a virtual environment @$(MAKE) uv @echo "Creating virtual environment..." @$(UV) venv fprime-venv - @$(UV) pip install --requirement requirements.txt + @$(UV) pip install --prerelease=allow --requirement requirements.txt + +patch-gps-package: + cp custom_space_data_link.py fprime-venv/lib/python3.13/site-packages/fprime_gds/common/communication/ccsds/space_data_link.py .PHONY: zephyr-setup zephyr-setup: fprime-venv ## Set up Zephyr environment