From 36fe4858a39ab3624ad9c9ab2004918780e4ff3b Mon Sep 17 00:00:00 2001 From: ineskhou Date: Fri, 3 Oct 2025 10:40:05 -0700 Subject: [PATCH 01/32] 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 4a149bb..931354e 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 02/32] 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 08ac562..daf0253 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 0000000..b779a42 --- /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 0000000..f4aa07f --- /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 0000000..87265a5 --- /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 0000000..534c729 --- /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 0000000..512c907 --- /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 e3148ff..1747956 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 4a0e736..c108ef2 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 4e3bb31..fb6a47f 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 3912dbb..81064f6 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 1dff4a2..ef0819a 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 4f42fd3..72d7135 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 15360ff..5b37d3b 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 0000000..30da130 --- /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 a0257cf..9cba1b9 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 3adfa68..b77fcc7 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 96f2024..3b99c34 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 abb09e4..7fbe130 160000 --- a/lib/fprime +++ b/lib/fprime @@ -1 +1 @@ -Subproject commit abb09e4a681cd586ac719a7517430637cdc46199 +Subproject commit 7fbe13086ad5eafe4e896513c480b3cdb2e47557 diff --git a/prj.conf b/prj.conf index 96d07ad..f171594 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 d27e929..dde51b9 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 03/32] 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 5b37d3b..c10dca3 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 0000000..3d8f73e --- /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 04/32] 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 daf0253..0485725 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 0000000..5f5d5ce --- /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 0000000..a94cdef --- /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 0000000..9510799 --- /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 0000000..82368b0 --- /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 0000000..969c970 --- /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 ef0819a..e53880b 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 72d7135..9a75b9c 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 0e1f0e2..0000000 --- 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 0000000..7145707 --- /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 05/32] 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 0000000..0439afd --- /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 06/32] 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 2b79461..f7cf75d 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 From b21abcf4c058fa76766332eeb88bdeaea34926fb Mon Sep 17 00:00:00 2001 From: M Starch Date: Fri, 3 Oct 2025 18:18:07 -0700 Subject: [PATCH 07/32] Add circuit pass-through --- circuit-python-lora-passthrough/boot.py | 2 ++ circuit-python-lora-passthrough/code.py | 39 +++++++++++++++++++++++++ 2 files changed, 41 insertions(+) create mode 100644 circuit-python-lora-passthrough/boot.py create mode 100644 circuit-python-lora-passthrough/code.py diff --git a/circuit-python-lora-passthrough/boot.py b/circuit-python-lora-passthrough/boot.py new file mode 100644 index 0000000..ae26ce6 --- /dev/null +++ b/circuit-python-lora-passthrough/boot.py @@ -0,0 +1,2 @@ +import usb_cdc +usb_cdc.enable(console=True, data=True) \ No newline at end of file diff --git a/circuit-python-lora-passthrough/code.py b/circuit-python-lora-passthrough/code.py new file mode 100644 index 0000000..974e0cd --- /dev/null +++ b/circuit-python-lora-passthrough/code.py @@ -0,0 +1,39 @@ +""" +CircuitPython Feather RP2350 LoRa Radio forwarder + +This code will forward any received LoRa packets to the serial console (sys.stdout). It cycles through neo pixel colors +to indicate packet reception. +""" +import time +import board +import digitalio +import adafruit_rfm9x +import usb_cdc + +# Radio constants +RADIO_FREQ_MHZ = 437.4 +CS = digitalio.DigitalInOut(board.SPI0_CS0) +RESET = digitalio.DigitalInOut(board.RF1_RST) + +rfm95 = adafruit_rfm9x.RFM9x(board.SPI(), CS, RESET, RADIO_FREQ_MHZ) +rfm95.spreading_factor = 8 +rfm95.signal_bandwidth = 125000 +rfm95.coding_rate = 5 +rfm95.preamble_length = 8 +time_start = time.time() +packet_count = 0 +print("[INFO] LoRa Receiver receiving packets") +while True: + # Look for a new packet - wait up to 2 seconds: + packet = rfm95.receive(timeout=2.0) + # If no packet was received during the timeout then None is returned. + if packet is not None: + usb_cdc.data.write(packet) + packet_count += 1 + time_delta = time.time() - time_start + if time_delta > 10: + print(f"[INFO] Packets received: {packet_count}") + time_start = time.time() + data = usb_cdc.data.read(usb_cdc.data.in_waiting) + if len(data) > 0: + rfm95.send(data) From 221c9e1708b7b56b62c78730d70d63f6dd18889f Mon Sep 17 00:00:00 2001 From: M Starch Date: Sun, 5 Oct 2025 19:34:34 -0700 Subject: [PATCH 08/32] Update to use aggregation --- FprimeZephyrReference/Components/ComDelay/ComDelay.cpp | 1 + FprimeZephyrReference/Components/ComDelay/ComDelay.fpp | 3 +++ FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp | 2 ++ FprimeZephyrReference/project/config/ComCcsdsConfig.fpp | 2 ++ FprimeZephyrReference/project/config/ComCfg.fpp | 1 + FprimeZephyrReference/project/config/FpConfig.h | 2 +- lib/fprime | 2 +- 7 files changed, 11 insertions(+), 2 deletions(-) diff --git a/FprimeZephyrReference/Components/ComDelay/ComDelay.cpp b/FprimeZephyrReference/Components/ComDelay/ComDelay.cpp index a94cdef..2d1c073 100644 --- a/FprimeZephyrReference/Components/ComDelay/ComDelay.cpp +++ b/FprimeZephyrReference/Components/ComDelay/ComDelay.cpp @@ -51,6 +51,7 @@ void ComDelay ::run_handler(FwIndexType portNum, U32 context) { bool valid = this->m_last_status_valid.compare_exchange_strong(expected, false); if (valid) { this->comStatusOut_out(0, this->m_last_status); + this->timeout_out(0, 0); } } diff --git a/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp b/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp index 9510799..028ec21 100644 --- a/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp +++ b/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp @@ -5,6 +5,9 @@ module Components { @ Rate schedule port used to trigger radio transmission sync input port run: Svc.Sched + @ Rate schedule port used to trigger aggregation timeout + output port timeout: Svc.Sched + @ Input comStatus from radio component sync input port comStatusIn: Fw.SuccessCondition diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp b/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp index 9a75b9c..d843d4c 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp +++ b/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp @@ -80,6 +80,8 @@ module ReferenceDeployment { lora.dataReturnOut -> ComCcsds.framer.dataReturnIn lora.comStatusOut -> comDelay.comStatusIn comDelay.comStatusOut ->ComCcsds.framer.comStatusIn + + comDelay.timeout -> ComCcsds.aggregator.timeout } connections RateGroups { diff --git a/FprimeZephyrReference/project/config/ComCcsdsConfig.fpp b/FprimeZephyrReference/project/config/ComCcsdsConfig.fpp index 4f8bc6d..25acc69 100644 --- a/FprimeZephyrReference/project/config/ComCcsdsConfig.fpp +++ b/FprimeZephyrReference/project/config/ComCcsdsConfig.fpp @@ -4,10 +4,12 @@ module ComCcsdsConfig { module QueueSizes { constant comQueue = 10 + constant aggregator = 2 } module StackSizes { constant comQueue = 8 * 1024 # Must match prj.conf thread stack size + constant aggregator = 8 * 1024 # Must match prj.conf thread stack size } module Priorities { diff --git a/FprimeZephyrReference/project/config/ComCfg.fpp b/FprimeZephyrReference/project/config/ComCfg.fpp index 30da130..af6ac4b 100644 --- a/FprimeZephyrReference/project/config/ComCfg.fpp +++ b/FprimeZephyrReference/project/config/ComCfg.fpp @@ -17,6 +17,7 @@ module ComCfg { # - 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 + constant AggregationSize = TmFrameFixedSize - 6 - 6 - 1 - 2 # 2 header (6) + 1 idle byte + 2 trailer bytes @ APIDs are 11 bits in the Space Packet protocol, so we use U16. Max value 7FF enum Apid : FwPacketDescriptorType { diff --git a/FprimeZephyrReference/project/config/FpConfig.h b/FprimeZephyrReference/project/config/FpConfig.h index b77fcc7..0540e19 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 235 +#define FW_COM_BUFFER_MAX_SIZE 233 #endif // Specifies the size of the buffer attached to state machine signals. diff --git a/lib/fprime b/lib/fprime index 7fbe130..5ebe10d 160000 --- a/lib/fprime +++ b/lib/fprime @@ -1 +1 @@ -Subproject commit 7fbe13086ad5eafe4e896513c480b3cdb2e47557 +Subproject commit 5ebe10d0d0eb3e9d4e2cc22ac984b7f5127ce819 From 925ea7ee72d4cdc374898b82a02a0f6793ad5a8a Mon Sep 17 00:00:00 2001 From: M Starch Date: Sun, 5 Oct 2025 19:34:34 -0700 Subject: [PATCH 09/32] Update to use aggregation --- FprimeZephyrReference/Components/ComDelay/ComDelay.cpp | 1 + FprimeZephyrReference/Components/ComDelay/ComDelay.fpp | 3 +++ FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp | 2 ++ FprimeZephyrReference/project/config/ComCcsdsConfig.fpp | 4 +++- FprimeZephyrReference/project/config/ComCfg.fpp | 1 + FprimeZephyrReference/project/config/FpConfig.h | 2 +- fprime-gds.yml | 1 + lib/fprime | 2 +- prj.conf | 2 +- 9 files changed, 14 insertions(+), 4 deletions(-) diff --git a/FprimeZephyrReference/Components/ComDelay/ComDelay.cpp b/FprimeZephyrReference/Components/ComDelay/ComDelay.cpp index a94cdef..2d1c073 100644 --- a/FprimeZephyrReference/Components/ComDelay/ComDelay.cpp +++ b/FprimeZephyrReference/Components/ComDelay/ComDelay.cpp @@ -51,6 +51,7 @@ void ComDelay ::run_handler(FwIndexType portNum, U32 context) { bool valid = this->m_last_status_valid.compare_exchange_strong(expected, false); if (valid) { this->comStatusOut_out(0, this->m_last_status); + this->timeout_out(0, 0); } } diff --git a/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp b/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp index 9510799..028ec21 100644 --- a/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp +++ b/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp @@ -5,6 +5,9 @@ module Components { @ Rate schedule port used to trigger radio transmission sync input port run: Svc.Sched + @ Rate schedule port used to trigger aggregation timeout + output port timeout: Svc.Sched + @ Input comStatus from radio component sync input port comStatusIn: Fw.SuccessCondition diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp b/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp index 9a75b9c..d843d4c 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp +++ b/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp @@ -80,6 +80,8 @@ module ReferenceDeployment { lora.dataReturnOut -> ComCcsds.framer.dataReturnIn lora.comStatusOut -> comDelay.comStatusIn comDelay.comStatusOut ->ComCcsds.framer.comStatusIn + + comDelay.timeout -> ComCcsds.aggregator.timeout } connections RateGroups { diff --git a/FprimeZephyrReference/project/config/ComCcsdsConfig.fpp b/FprimeZephyrReference/project/config/ComCcsdsConfig.fpp index 4f8bc6d..94f091e 100644 --- a/FprimeZephyrReference/project/config/ComCcsdsConfig.fpp +++ b/FprimeZephyrReference/project/config/ComCcsdsConfig.fpp @@ -3,11 +3,13 @@ module ComCcsdsConfig { constant BASE_ID = 0x02000000 module QueueSizes { - constant comQueue = 10 + constant comQueue = 10 + constant aggregator = 5 } module StackSizes { constant comQueue = 8 * 1024 # Must match prj.conf thread stack size + constant aggregator = 8 * 1024 # Must match prj.conf thread stack size } module Priorities { diff --git a/FprimeZephyrReference/project/config/ComCfg.fpp b/FprimeZephyrReference/project/config/ComCfg.fpp index 30da130..af6ac4b 100644 --- a/FprimeZephyrReference/project/config/ComCfg.fpp +++ b/FprimeZephyrReference/project/config/ComCfg.fpp @@ -17,6 +17,7 @@ module ComCfg { # - 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 + constant AggregationSize = TmFrameFixedSize - 6 - 6 - 1 - 2 # 2 header (6) + 1 idle byte + 2 trailer bytes @ APIDs are 11 bits in the Space Packet protocol, so we use U16. Max value 7FF enum Apid : FwPacketDescriptorType { diff --git a/FprimeZephyrReference/project/config/FpConfig.h b/FprimeZephyrReference/project/config/FpConfig.h index b77fcc7..0540e19 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 235 +#define FW_COM_BUFFER_MAX_SIZE 233 #endif // Specifies the size of the buffer attached to state machine signals. diff --git a/fprime-gds.yml b/fprime-gds.yml index 7145707..c4ef300 100644 --- a/fprime-gds.yml +++ b/fprime-gds.yml @@ -4,3 +4,4 @@ command-line-options: no-app: dictionary: build-artifacts/zephyr/fprime-zephyr-deployment/dict/ReferenceDeploymentTopologyDictionary.json output-unframed-data: "-" + frame-size: 248 diff --git a/lib/fprime b/lib/fprime index 7fbe130..9c010a2 160000 --- a/lib/fprime +++ b/lib/fprime @@ -1 +1 @@ -Subproject commit 7fbe13086ad5eafe4e896513c480b3cdb2e47557 +Subproject commit 9c010a240eaf09cbde46376bc12b34f09650329d diff --git a/prj.conf b/prj.conf index f171594..32909b3 100644 --- a/prj.conf +++ b/prj.conf @@ -36,7 +36,7 @@ CONFIG_DYNAMIC_THREAD=y CONFIG_KERNEL_MEM_POOL=y CONFIG_DYNAMIC_THREAD_ALLOC=n CONFIG_DYNAMIC_THREAD_PREFER_POOL=y -CONFIG_DYNAMIC_THREAD_POOL_SIZE=10 +CONFIG_DYNAMIC_THREAD_POOL_SIZE=12 # Num threads in the thread pool CONFIG_DYNAMIC_THREAD_STACK_SIZE=8192 # Size of thread stack in thread pool, must be >= Thread Pool size in F' From 3369a2ee3b85b605367e5d30797ac912e0109dcb Mon Sep 17 00:00:00 2001 From: Michael Pham <61564344+Mikefly123@users.noreply.github.com> Date: Sun, 5 Oct 2025 22:34:20 -0700 Subject: [PATCH 10/32] Appease Linter --- FprimeZephyrReference/Components/ComDelay/ComDelay.fpp | 2 +- FprimeZephyrReference/Components/ComDelay/docs/sdd.md | 2 +- .../ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp | 2 +- FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp | 4 ++-- FprimeZephyrReference/project/config/FpConfig.h | 1 - FprimeZephyrReference/project/config/LoRaCfg.hpp | 4 ++-- circuit-python-lora-passthrough/boot.py | 3 ++- circuit-python-lora-passthrough/code.py | 4 +++- lib/fprime | 2 +- lib/fprime-zephyr | 2 +- 10 files changed, 14 insertions(+), 12 deletions(-) diff --git a/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp b/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp index 028ec21..6c14f0c 100644 --- a/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp +++ b/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp @@ -48,4 +48,4 @@ module Components { @Port to set the value of a parameter param set port prmSetOut } -} \ No newline at end of file +} diff --git a/FprimeZephyrReference/Components/ComDelay/docs/sdd.md b/FprimeZephyrReference/Components/ComDelay/docs/sdd.md index 969c970..dded32e 100644 --- a/FprimeZephyrReference/Components/ComDelay/docs/sdd.md +++ b/FprimeZephyrReference/Components/ComDelay/docs/sdd.md @@ -14,4 +14,4 @@ | Name | Description | |---------|-----------------------------------------------------------| -| DIVIDER | Number of rate group ticks received before sending status | \ No newline at end of file +| DIVIDER | Number of rate group ticks received before sending status | diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp b/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp index fb6a47f..5dda239 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp +++ b/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp @@ -79,7 +79,7 @@ void setupTopology(const TopologyState& state) { // Uplink is configured for receive so a socket task is started // We dont need UART, as we are sending coms directly to lora - //comDriver.configure(state.uartDevice, state.baudRate); + // comDriver.configure(state.uartDevice, state.baudRate); lora.start(state.loraDevice); } diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp b/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp index d843d4c..d69e0ee 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp +++ b/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp @@ -70,7 +70,7 @@ module ReferenceDeployment { connections Communications { lora.allocate -> ComCcsds.commsBufferManager.bufferGetCallee lora.deallocate -> ComCcsds.commsBufferManager.bufferSendIn - + # ComDriver <-> ComStub (Uplink) lora.dataOut -> ComCcsds.frameAccumulator.dataIn ComCcsds.frameAccumulator.dataReturnOut -> lora.dataReturnIn @@ -113,7 +113,7 @@ module ReferenceDeployment { imuManager.temperatureGet -> lsm6dsoManager.temperatureGet } - + } diff --git a/FprimeZephyrReference/project/config/FpConfig.h b/FprimeZephyrReference/project/config/FpConfig.h index 0540e19..bf1fe7b 100644 --- a/FprimeZephyrReference/project/config/FpConfig.h +++ b/FprimeZephyrReference/project/config/FpConfig.h @@ -331,7 +331,6 @@ extern "C" { #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/LoRaCfg.hpp b/FprimeZephyrReference/project/config/LoRaCfg.hpp index 3d8f73e..0de46af 100644 --- a/FprimeZephyrReference/project/config/LoRaCfg.hpp +++ b/FprimeZephyrReference/project/config/LoRaCfg.hpp @@ -3,10 +3,10 @@ #include #include namespace LoRaConfig { -const U32 FREQUENCY = 437400000; //!< LoRa frequency in Hz +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 +#endif // LORA_CFG_HPP diff --git a/circuit-python-lora-passthrough/boot.py b/circuit-python-lora-passthrough/boot.py index ae26ce6..6776ff3 100644 --- a/circuit-python-lora-passthrough/boot.py +++ b/circuit-python-lora-passthrough/boot.py @@ -1,2 +1,3 @@ import usb_cdc -usb_cdc.enable(console=True, data=True) \ No newline at end of file + +usb_cdc.enable(console=True, data=True) diff --git a/circuit-python-lora-passthrough/code.py b/circuit-python-lora-passthrough/code.py index 974e0cd..4efd89f 100644 --- a/circuit-python-lora-passthrough/code.py +++ b/circuit-python-lora-passthrough/code.py @@ -4,10 +4,12 @@ This code will forward any received LoRa packets to the serial console (sys.stdout). It cycles through neo pixel colors to indicate packet reception. """ + import time + +import adafruit_rfm9x import board import digitalio -import adafruit_rfm9x import usb_cdc # Radio constants diff --git a/lib/fprime b/lib/fprime index 5ebe10d..abb09e4 160000 --- a/lib/fprime +++ b/lib/fprime @@ -1 +1 @@ -Subproject commit 5ebe10d0d0eb3e9d4e2cc22ac984b7f5127ce819 +Subproject commit abb09e4a681cd586ac719a7517430637cdc46199 diff --git a/lib/fprime-zephyr b/lib/fprime-zephyr index 931354e..4a149bb 160000 --- a/lib/fprime-zephyr +++ b/lib/fprime-zephyr @@ -1 +1 @@ -Subproject commit 931354e26e39cb711f846e1ca8bb1337ede83b7c +Subproject commit 4a149bbed5c7c86fbac44ab8a65791eff97370f9 From 5ecb9399edb92d384fc24717a3f0af8b571da4e6 Mon Sep 17 00:00:00 2001 From: Michael Pham <61564344+Mikefly123@users.noreply.github.com> Date: Mon, 6 Oct 2025 09:36:21 -0700 Subject: [PATCH 11/32] Ran Linter --- FprimeZephyrReference/Components/ComDelay/ComDelay.fpp | 2 +- FprimeZephyrReference/Components/ComDelay/docs/sdd.md | 2 +- .../ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp | 2 +- FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp | 4 ++-- FprimeZephyrReference/project/config/FpConfig.h | 1 - FprimeZephyrReference/project/config/LoRaCfg.hpp | 4 ++-- circuit-python-lora-passthrough/boot.py | 3 ++- circuit-python-lora-passthrough/code.py | 4 +++- 8 files changed, 12 insertions(+), 10 deletions(-) diff --git a/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp b/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp index 028ec21..6c14f0c 100644 --- a/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp +++ b/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp @@ -48,4 +48,4 @@ module Components { @Port to set the value of a parameter param set port prmSetOut } -} \ No newline at end of file +} diff --git a/FprimeZephyrReference/Components/ComDelay/docs/sdd.md b/FprimeZephyrReference/Components/ComDelay/docs/sdd.md index 969c970..dded32e 100644 --- a/FprimeZephyrReference/Components/ComDelay/docs/sdd.md +++ b/FprimeZephyrReference/Components/ComDelay/docs/sdd.md @@ -14,4 +14,4 @@ | Name | Description | |---------|-----------------------------------------------------------| -| DIVIDER | Number of rate group ticks received before sending status | \ No newline at end of file +| DIVIDER | Number of rate group ticks received before sending status | diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp b/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp index fb6a47f..5dda239 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp +++ b/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp @@ -79,7 +79,7 @@ void setupTopology(const TopologyState& state) { // Uplink is configured for receive so a socket task is started // We dont need UART, as we are sending coms directly to lora - //comDriver.configure(state.uartDevice, state.baudRate); + // comDriver.configure(state.uartDevice, state.baudRate); lora.start(state.loraDevice); } diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp b/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp index d843d4c..d69e0ee 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp +++ b/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp @@ -70,7 +70,7 @@ module ReferenceDeployment { connections Communications { lora.allocate -> ComCcsds.commsBufferManager.bufferGetCallee lora.deallocate -> ComCcsds.commsBufferManager.bufferSendIn - + # ComDriver <-> ComStub (Uplink) lora.dataOut -> ComCcsds.frameAccumulator.dataIn ComCcsds.frameAccumulator.dataReturnOut -> lora.dataReturnIn @@ -113,7 +113,7 @@ module ReferenceDeployment { imuManager.temperatureGet -> lsm6dsoManager.temperatureGet } - + } diff --git a/FprimeZephyrReference/project/config/FpConfig.h b/FprimeZephyrReference/project/config/FpConfig.h index 0540e19..bf1fe7b 100644 --- a/FprimeZephyrReference/project/config/FpConfig.h +++ b/FprimeZephyrReference/project/config/FpConfig.h @@ -331,7 +331,6 @@ extern "C" { #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/LoRaCfg.hpp b/FprimeZephyrReference/project/config/LoRaCfg.hpp index 3d8f73e..0de46af 100644 --- a/FprimeZephyrReference/project/config/LoRaCfg.hpp +++ b/FprimeZephyrReference/project/config/LoRaCfg.hpp @@ -3,10 +3,10 @@ #include #include namespace LoRaConfig { -const U32 FREQUENCY = 437400000; //!< LoRa frequency in Hz +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 +#endif // LORA_CFG_HPP diff --git a/circuit-python-lora-passthrough/boot.py b/circuit-python-lora-passthrough/boot.py index ae26ce6..6776ff3 100644 --- a/circuit-python-lora-passthrough/boot.py +++ b/circuit-python-lora-passthrough/boot.py @@ -1,2 +1,3 @@ import usb_cdc -usb_cdc.enable(console=True, data=True) \ No newline at end of file + +usb_cdc.enable(console=True, data=True) diff --git a/circuit-python-lora-passthrough/code.py b/circuit-python-lora-passthrough/code.py index 974e0cd..4efd89f 100644 --- a/circuit-python-lora-passthrough/code.py +++ b/circuit-python-lora-passthrough/code.py @@ -4,10 +4,12 @@ This code will forward any received LoRa packets to the serial console (sys.stdout). It cycles through neo pixel colors to indicate packet reception. """ + import time + +import adafruit_rfm9x import board import digitalio -import adafruit_rfm9x import usb_cdc # Radio constants From b2deadef533183a53360868a5fa0e0e9f90709a8 Mon Sep 17 00:00:00 2001 From: Michael Pham <61564344+Mikefly123@users.noreply.github.com> Date: Mon, 6 Oct 2025 17:54:34 -0700 Subject: [PATCH 12/32] Fix Submodules --- lib/fprime | 2 +- lib/fprime-zephyr | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/lib/fprime b/lib/fprime index abb09e4..5ebe10d 160000 --- a/lib/fprime +++ b/lib/fprime @@ -1 +1 @@ -Subproject commit abb09e4a681cd586ac719a7517430637cdc46199 +Subproject commit 5ebe10d0d0eb3e9d4e2cc22ac984b7f5127ce819 diff --git a/lib/fprime-zephyr b/lib/fprime-zephyr index 4a149bb..931354e 160000 --- a/lib/fprime-zephyr +++ b/lib/fprime-zephyr @@ -1 +1 @@ -Subproject commit 4a149bbed5c7c86fbac44ab8a65791eff97370f9 +Subproject commit 931354e26e39cb711f846e1ca8bb1337ede83b7c From 690b31c5017ed97a8445c381df28be9659b9de5c Mon Sep 17 00:00:00 2001 From: Nate Gay Date: Wed, 8 Oct 2025 17:45:05 -0500 Subject: [PATCH 13/32] try --- FprimeZephyrReference/test/bootloader_trigger.py | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/FprimeZephyrReference/test/bootloader_trigger.py b/FprimeZephyrReference/test/bootloader_trigger.py index c1e9c20..85d7a66 100644 --- a/FprimeZephyrReference/test/bootloader_trigger.py +++ b/FprimeZephyrReference/test/bootloader_trigger.py @@ -1,4 +1,5 @@ import os +import signal import subprocess import time @@ -6,9 +7,14 @@ from fprime_gds.common.testing_fw.api import IntegrationTestAPI -@pytest.fixture(scope="session", autouse=True) +@pytest.fixture(scope="session") def start_gds(fprime_test_api_session: IntegrationTestAPI): - process = subprocess.Popen(["make", "gds-integration"], cwd=os.getcwd()) + pro = subprocess.Popen( + ["make", "gds-integration"], + cwd=os.getcwd(), + stdout=subprocess.PIPE, + preexec_fn=os.setsid, + ) gds_working = False timeout_time = time.time() + 30 @@ -24,7 +30,7 @@ def start_gds(fprime_test_api_session: IntegrationTestAPI): assert gds_working yield - process.kill() + os.killpg(os.getpgid(pro.pid), signal.SIGTERM) def test_bootloader(fprime_test_api: IntegrationTestAPI): From 4469434a9be86137940b4484c1a76dc03aa80dc9 Mon Sep 17 00:00:00 2001 From: Nate Gay Date: Wed, 8 Oct 2025 18:00:44 -0500 Subject: [PATCH 14/32] Apply suggestion from @nateinaction --- settings.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/settings.ini b/settings.ini index dde51b9..d27e929 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_v5d/rp2350a/m33 + BOARD=proves_flight_control_board_v5c/rp2350a/m33 From 6c8d5ee79dc82c685495291e6b7a2bc8b98cc226 Mon Sep 17 00:00:00 2001 From: ineskhou Date: Wed, 8 Oct 2025 16:24:31 -0700 Subject: [PATCH 15/32] changed the aggregator --- FprimeZephyrReference/project/config/ComCcsdsConfig.fpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/FprimeZephyrReference/project/config/ComCcsdsConfig.fpp b/FprimeZephyrReference/project/config/ComCcsdsConfig.fpp index 25acc69..0f4f5ac 100644 --- a/FprimeZephyrReference/project/config/ComCcsdsConfig.fpp +++ b/FprimeZephyrReference/project/config/ComCcsdsConfig.fpp @@ -4,7 +4,7 @@ module ComCcsdsConfig { module QueueSizes { constant comQueue = 10 - constant aggregator = 2 + constant aggregator = 5 } module StackSizes { From ceb570f6d785c76579486f7c34e32afe0d641538 Mon Sep 17 00:00:00 2001 From: Nate Gay Date: Fri, 10 Oct 2025 18:58:04 -0500 Subject: [PATCH 16/32] Revert bootloadertrigger change --- FprimeZephyrReference/test/bootloader_trigger.py | 12 +++--------- 1 file changed, 3 insertions(+), 9 deletions(-) diff --git a/FprimeZephyrReference/test/bootloader_trigger.py b/FprimeZephyrReference/test/bootloader_trigger.py index 85d7a66..c1e9c20 100644 --- a/FprimeZephyrReference/test/bootloader_trigger.py +++ b/FprimeZephyrReference/test/bootloader_trigger.py @@ -1,5 +1,4 @@ import os -import signal import subprocess import time @@ -7,14 +6,9 @@ from fprime_gds.common.testing_fw.api import IntegrationTestAPI -@pytest.fixture(scope="session") +@pytest.fixture(scope="session", autouse=True) def start_gds(fprime_test_api_session: IntegrationTestAPI): - pro = subprocess.Popen( - ["make", "gds-integration"], - cwd=os.getcwd(), - stdout=subprocess.PIPE, - preexec_fn=os.setsid, - ) + process = subprocess.Popen(["make", "gds-integration"], cwd=os.getcwd()) gds_working = False timeout_time = time.time() + 30 @@ -30,7 +24,7 @@ def start_gds(fprime_test_api_session: IntegrationTestAPI): assert gds_working yield - os.killpg(os.getpgid(pro.pid), signal.SIGTERM) + process.kill() def test_bootloader(fprime_test_api: IntegrationTestAPI): From 72beedaf16d08f4a12b7ee0d121f847ac742d710 Mon Sep 17 00:00:00 2001 From: Nate Gay Date: Fri, 10 Oct 2025 19:19:04 -0500 Subject: [PATCH 17/32] spacing --- FprimeZephyrReference/project/config/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/FprimeZephyrReference/project/config/CMakeLists.txt b/FprimeZephyrReference/project/config/CMakeLists.txt index c10dca3..cf115d7 100644 --- a/FprimeZephyrReference/project/config/CMakeLists.txt +++ b/FprimeZephyrReference/project/config/CMakeLists.txt @@ -11,7 +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}/LoRaCfg.hpp" "${CMAKE_CURRENT_LIST_DIR}/FpConfig.h" "${CMAKE_CURRENT_LIST_DIR}/TlmPacketizerCfg.hpp" INTERFACE From 6017947aba9457d9254d3b8f6ce4d13c230e179d Mon Sep 17 00:00:00 2001 From: ineskhou Date: Sun, 12 Oct 2025 15:08:50 -0700 Subject: [PATCH 18/32] updated instrcutions and flow to run the circuitpython radio example --- README.md | 29 +++++++++++++++++++++++++ circuit-python-lora-passthrough/code.py | 2 +- 2 files changed, 30 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index ef4019b..da45089 100644 --- a/README.md +++ b/README.md @@ -72,3 +72,32 @@ Then, in another terminal, run the following command to execute the integration ```sh make test-integration ``` + +## Running The Radio With CircuitPython + +To test the radio setup easily, you can use CircuitPython code on one board and fprime-zephyr on another. This provides a simple client/server setup and lets you observe what data is being sent through the radio. + + +On the board you want to receive data, make sure you have CircuitPython installed. Follow [these instructions](https://proveskit.github.io/pysquared/getting-started/). You can install the flight software or ground station code from that tutorial as these have the libraries you need, or simply install the CircuitPython firmware and manually add the required libraries. + + +Once you have CircuitPython running, upload the files from the ```circuit-python-lora-passthrough``` folder in this repo. Make sure to overwrite any existing ```boot.py``` and ```code.py``` files on your CircuitPython board with the ones from this folder. + +```boot.py``` enables both virtual serial ports that the device presents over USB. This allows you to use one for the console and one for data. ```code.py``` acts as a LoRa radio forwarder over USB serial: The console port is used for logging and debugging, and is the first serial port that appears when the board is connected. The data port is used for actual data transfer, and is the second serial port. + +1. Open the console port on your computer. This is the first serial port that opens when you plug in the circuitpython board. It should start by printing: + +``` +[INFO] LoRa Receiver receiving packets +[INFO] Packets received: 0 +``` + +Once you have the board running the proves-core-reference radio code (make sure its plugged in!), you should start receiving packets and seeing this on the serial port + +2. + +Now you want to be able to send commands through the radio. To do this, connect the gds to the circuitpython data port. Run the fprime-gds with the --uart-device parameter set to the serial port that is the second serial port that shows up when you plug in your circuitpython board + +Depending on the comdelay, the gds should turn green every time a packet is sent. If you want to change this parameter use + +```ReferenceDeployment.comDelay.DIVIDER_PRM_SET``` on the gds. You can set it down to 2, but setting it to 1 may cause issues. diff --git a/circuit-python-lora-passthrough/code.py b/circuit-python-lora-passthrough/code.py index 4efd89f..a8543d3 100644 --- a/circuit-python-lora-passthrough/code.py +++ b/circuit-python-lora-passthrough/code.py @@ -7,9 +7,9 @@ import time -import adafruit_rfm9x import board import digitalio +import lib.adafruit_rfm.rfm9x as adafruit_rfm9x import usb_cdc # Radio constants From e9b81b2347668a4f5204a6f45e0b2b5caa92a6ee Mon Sep 17 00:00:00 2001 From: M Starch Date: Sun, 12 Oct 2025 15:39:50 -0700 Subject: [PATCH 19/32] Add in com splitter and UART com --- FprimeZephyrReference/CMakeLists.txt | 2 + .../ComCcsdsUart/CMakeLists.txt | 12 ++ .../ComCcsdsUart/ComCcsds.fpp | 203 ++++++++++++++++++ .../ComCcsdsUart/PingEntries.hpp | 9 + .../ComCcsdsUart/SubtopologyTopologyDefs.hpp | 20 ++ .../ComCcsdsUart/docs/sdd.md | 5 + .../Top/ReferenceDeploymentPackets.fppi | 7 + .../Top/ReferenceDeploymentTopology.cpp | 1 + .../ReferenceDeployment/Top/instances.fpp | 4 + .../ReferenceDeployment/Top/topology.fpp | 34 ++- .../project/config/ComCcsdsConfig.fpp | 11 +- lib/fprime-zephyr | 2 +- prj.conf | 2 +- 13 files changed, 302 insertions(+), 10 deletions(-) create mode 100644 FprimeZephyrReference/ComCcsdsUart/CMakeLists.txt create mode 100644 FprimeZephyrReference/ComCcsdsUart/ComCcsds.fpp create mode 100644 FprimeZephyrReference/ComCcsdsUart/PingEntries.hpp create mode 100644 FprimeZephyrReference/ComCcsdsUart/SubtopologyTopologyDefs.hpp create mode 100644 FprimeZephyrReference/ComCcsdsUart/docs/sdd.md diff --git a/FprimeZephyrReference/CMakeLists.txt b/FprimeZephyrReference/CMakeLists.txt index 70c1681..95ee3b9 100644 --- a/FprimeZephyrReference/CMakeLists.txt +++ b/FprimeZephyrReference/CMakeLists.txt @@ -1,6 +1,8 @@ # This CMake file is intended to register project-wide objects. # This allows for reuse between deployments, or other projects. +# Keep me first add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/project/config") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Components") +add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ComCcsdsUart/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ReferenceDeployment/") diff --git a/FprimeZephyrReference/ComCcsdsUart/CMakeLists.txt b/FprimeZephyrReference/ComCcsdsUart/CMakeLists.txt new file mode 100644 index 0000000..a95400b --- /dev/null +++ b/FprimeZephyrReference/ComCcsdsUart/CMakeLists.txt @@ -0,0 +1,12 @@ + +register_fprime_module( + EXCLUDE_FROM_ALL + AUTOCODER_INPUTS + "${CMAKE_CURRENT_LIST_DIR}/ComCcsds.fpp" + HEADERS + "${CMAKE_CURRENT_LIST_DIR}/SubtopologyTopologyDefs.hpp" + "${CMAKE_CURRENT_LIST_DIR}/PingEntries.hpp" + DEPENDS + Svc_Subtopologies_ComCcsds_ComCcsdsConfig + INTERFACE +) diff --git a/FprimeZephyrReference/ComCcsdsUart/ComCcsds.fpp b/FprimeZephyrReference/ComCcsdsUart/ComCcsds.fpp new file mode 100644 index 0000000..d67869f --- /dev/null +++ b/FprimeZephyrReference/ComCcsdsUart/ComCcsds.fpp @@ -0,0 +1,203 @@ +module ComCcsdsUart { + + # ComPacket Queue enum for queue types + enum Ports_ComPacketQueue { + EVENTS, + TELEMETRY + } + + enum Ports_ComBufferQueue { + FILE + } + + # ---------------------------------------------------------------------- + # Active Components + # ---------------------------------------------------------------------- + instance comQueue: Svc.ComQueue base id ComCcsdsConfig.BASE_ID_UART + 0x00000 \ + queue size ComCcsdsConfig.QueueSizes.comQueue \ + stack size ComCcsdsConfig.StackSizes.comQueue \ + priority ComCcsdsConfig.Priorities.comQueue \ + { + phase Fpp.ToCpp.Phases.configComponents """ + using namespace ComCcsdsUart; + Svc::ComQueue::QueueConfigurationTable configurationTableUart; + + // Events (highest-priority) + configurationTableUart.entries[Ports_ComPacketQueue::EVENTS].depth = ComCcsdsConfig::QueueDepths::events; + configurationTableUart.entries[Ports_ComPacketQueue::EVENTS].priority = ComCcsdsConfig::QueuePriorities::events; + + // Telemetry + configurationTableUart.entries[Ports_ComPacketQueue::TELEMETRY].depth = ComCcsdsConfig::QueueDepths::tlm; + configurationTableUart.entries[Ports_ComPacketQueue::TELEMETRY].priority = ComCcsdsConfig::QueuePriorities::tlm; + + // File Downlink Queue (buffer queue using NUM_CONSTANTS offset) + configurationTableUart.entries[Ports_ComPacketQueue::NUM_CONSTANTS + Ports_ComBufferQueue::FILE].depth = ComCcsdsConfig::QueueDepths::file; + configurationTableUart.entries[Ports_ComPacketQueue::NUM_CONSTANTS + Ports_ComBufferQueue::FILE].priority = ComCcsdsConfig::QueuePriorities::file; + + // Allocation identifier is 0 as the MallocAllocator discards it + ComCcsdsUart::comQueue.configure(configurationTableUart, 0, ComCcsds::Allocation::memAllocator); + """ + phase Fpp.ToCpp.Phases.tearDownComponents """ + ComCcsdsUart::comQueue.cleanup(); + """ + } + + instance aggregator: Svc.ComAggregator base id ComCcsdsConfig.BASE_ID_UART + 0x06000 \ + queue size ComCcsdsConfig.QueueSizes.aggregator \ + stack size ComCcsdsConfig.StackSizes.aggregator + + # ---------------------------------------------------------------------- + # Passive Components + # ---------------------------------------------------------------------- + instance frameAccumulator: Svc.FrameAccumulator base id ComCcsdsConfig.BASE_ID_UART + 0x01000 \ + { + + phase Fpp.ToCpp.Phases.configObjects """ + Svc::FrameDetectors::CcsdsTcFrameDetector frameDetector; + """ + phase Fpp.ToCpp.Phases.configComponents """ + ComCcsdsUart::frameAccumulator.configure( + ConfigObjects::ComCcsdsUart_frameAccumulator::frameDetector, + 1, + ComCcsds::Allocation::memAllocator, + ComCcsdsConfig::BuffMgr::frameAccumulatorSize + ); + """ + + phase Fpp.ToCpp.Phases.tearDownComponents """ + ComCcsdsUart::frameAccumulator.cleanup(); + """ + } + + instance commsBufferManager: Svc.BufferManager base id ComCcsdsConfig.BASE_ID_UART + 0x02000 \ + { + phase Fpp.ToCpp.Phases.configObjects """ + Svc::BufferManager::BufferBins bins; + """ + + phase Fpp.ToCpp.Phases.configComponents """ + memset(&ConfigObjects::ComCcsdsUart_commsBufferManager::bins, 0, sizeof(ConfigObjects::ComCcsdsUart_commsBufferManager::bins)); + ConfigObjects::ComCcsdsUart_commsBufferManager::bins.bins[0].bufferSize = ComCcsdsConfig::BuffMgr::commsBuffSize; + ConfigObjects::ComCcsdsUart_commsBufferManager::bins.bins[0].numBuffers = ComCcsdsConfig::BuffMgr::commsBuffCount; + ConfigObjects::ComCcsdsUart_commsBufferManager::bins.bins[1].bufferSize = ComCcsdsConfig::BuffMgr::commsFileBuffSize; + ConfigObjects::ComCcsdsUart_commsBufferManager::bins.bins[1].numBuffers = ComCcsdsConfig::BuffMgr::commsFileBuffCount; + ComCcsdsUart::commsBufferManager.setup( + ComCcsdsConfig::BuffMgr::commsBuffMgrId, + 0, + ComCcsds::Allocation::memAllocator, + ConfigObjects::ComCcsdsUart_commsBufferManager::bins + ); + """ + + phase Fpp.ToCpp.Phases.tearDownComponents """ + ComCcsdsUart::commsBufferManager.cleanup(); + """ + } + + instance fprimeRouter: Svc.FprimeRouter base id ComCcsdsConfig.BASE_ID_UART + 0x03000 + + instance tcDeframer: Svc.Ccsds.TcDeframer base id ComCcsdsConfig.BASE_ID_UART + 0x04000 + + instance spacePacketDeframer: Svc.Ccsds.SpacePacketDeframer base id ComCcsdsConfig.BASE_ID_UART + 0x05000 + + # NOTE: name 'framer' is used for the framer that connects to the Com Adapter Interface for better subtopology interoperability + instance framer: Svc.Ccsds.TmFramer base id ComCcsdsConfig.BASE_ID_UART + 0x07000 + + instance spacePacketFramer: Svc.Ccsds.SpacePacketFramer base id ComCcsdsConfig.BASE_ID_UART + 0x08000 + + instance apidManager: Svc.Ccsds.ApidManager base id ComCcsdsConfig.BASE_ID_UART + 0x09000 + + instance comStub: Svc.ComStub base id ComCcsdsConfig.BASE_ID_UART + 0x0A000 + + topology FramingSubtopology { + # Usage Note: + # + # When importing this subtopology, users shall establish 5 port connections with a component implementing + # the Svc.Com (Svc/Interfaces/Com.fpp) interface. They are as follows: + # + # 1) Outputs: + # - ComCcsds.framer.dataOut -> [Svc.Com].dataIn + # - ComCcsds.frameAccumulator.dataReturnOut -> [Svc.Com].dataReturnIn + # 2) Inputs: + # - [Svc.Com].dataReturnOut -> ComCcsds.framer.dataReturnIn + # - [Svc.Com].comStatusOut -> ComCcsds.framer.comStatusIn + # - [Svc.Com].dataOut -> ComCcsds.frameAccumulator.dataIn + + + # Active Components + instance comQueue + + # Passive Components + instance commsBufferManager + instance frameAccumulator + instance fprimeRouter + instance tcDeframer + instance spacePacketDeframer + instance framer + instance spacePacketFramer + instance apidManager + instance aggregator + + connections Downlink { + # ComQueue <-> SpacePacketFramer + comQueue.dataOut -> spacePacketFramer.dataIn + spacePacketFramer.dataReturnOut -> comQueue.dataReturnIn + # SpacePacketFramer buffer and APID management + spacePacketFramer.bufferAllocate -> commsBufferManager.bufferGetCallee + spacePacketFramer.bufferDeallocate -> commsBufferManager.bufferSendIn + spacePacketFramer.getApidSeqCount -> apidManager.getApidSeqCountIn + # SpacePacketFramer <-> TmFramer + spacePacketFramer.dataOut -> aggregator.dataIn + aggregator.dataOut -> framer.dataIn + + framer.dataReturnOut -> aggregator.dataReturnIn + aggregator.dataReturnOut -> spacePacketFramer.dataReturnIn + + # ComStatus + framer.comStatusOut -> aggregator.comStatusIn + aggregator.comStatusOut -> spacePacketFramer.comStatusIn + spacePacketFramer.comStatusOut -> comQueue.comStatusIn + # (Outgoing) Framer <-> ComInterface connections shall be established by the user + } + + connections Uplink { + # (Incoming) ComInterface <-> FrameAccumulator connections shall be established by the user + # FrameAccumulator buffer allocations + frameAccumulator.bufferDeallocate -> commsBufferManager.bufferSendIn + frameAccumulator.bufferAllocate -> commsBufferManager.bufferGetCallee + # FrameAccumulator <-> TcDeframer + frameAccumulator.dataOut -> tcDeframer.dataIn + tcDeframer.dataReturnOut -> frameAccumulator.dataReturnIn + # TcDeframer <-> SpacePacketDeframer + tcDeframer.dataOut -> spacePacketDeframer.dataIn + spacePacketDeframer.dataReturnOut -> tcDeframer.dataReturnIn + # SpacePacketDeframer APID validation + spacePacketDeframer.validateApidSeqCount -> apidManager.validateApidSeqCountIn + # SpacePacketDeframer <-> Router + spacePacketDeframer.dataOut -> fprimeRouter.dataIn + fprimeRouter.dataReturnOut -> spacePacketDeframer.dataReturnIn + # Router buffer allocations + fprimeRouter.bufferAllocate -> commsBufferManager.bufferGetCallee + fprimeRouter.bufferDeallocate -> commsBufferManager.bufferSendIn + } + } # end FramingSubtopology + + # This subtopology uses FramingSubtopology with a ComStub component for Com Interface + topology Subtopology { + import FramingSubtopology + + instance comStub + + connections ComStub { + # Framer <-> ComStub (Downlink) + framer.dataOut -> comStub.dataIn + comStub.dataReturnOut -> framer.dataReturnIn + comStub.comStatusOut -> framer.comStatusIn + + # ComStub <-> FrameAccumulator (Uplink) + comStub.dataOut -> frameAccumulator.dataIn + frameAccumulator.dataReturnOut -> comStub.dataReturnIn + } + } # end Subtopology + +} # end ComCcsds diff --git a/FprimeZephyrReference/ComCcsdsUart/PingEntries.hpp b/FprimeZephyrReference/ComCcsdsUart/PingEntries.hpp new file mode 100644 index 0000000..eeadc7d --- /dev/null +++ b/FprimeZephyrReference/ComCcsdsUart/PingEntries.hpp @@ -0,0 +1,9 @@ + +#ifndef COMCCSDS_PINGENTRIES_HPP +#define COMCCSDS_PINGENTRIES_HPP + +namespace PingEntries { +// No ping-enabled components in ComCcsds subtopology +} + +#endif diff --git a/FprimeZephyrReference/ComCcsdsUart/SubtopologyTopologyDefs.hpp b/FprimeZephyrReference/ComCcsdsUart/SubtopologyTopologyDefs.hpp new file mode 100644 index 0000000..d130ae3 --- /dev/null +++ b/FprimeZephyrReference/ComCcsdsUart/SubtopologyTopologyDefs.hpp @@ -0,0 +1,20 @@ +#ifndef COMCCSDSSUBTOPOLOGY_DEFS_HPP +#define COMCCSDSSUBTOPOLOGY_DEFS_HPP + +#include +#include +#include +#include "ComCcsdsConfig/ComCcsdsSubtopologyConfig.hpp" +#include "Svc/Subtopologies/ComCcsds/ComCcsdsConfig/FppConstantsAc.hpp" + +namespace ComCcsds { +struct SubtopologyState { + // Empty - no external state needed for ComCcsds subtopology +}; + +struct TopologyState { + SubtopologyState comCcsds; +}; +} // namespace ComCcsds + +#endif diff --git a/FprimeZephyrReference/ComCcsdsUart/docs/sdd.md b/FprimeZephyrReference/ComCcsdsUart/docs/sdd.md new file mode 100644 index 0000000..69a021a --- /dev/null +++ b/FprimeZephyrReference/ComCcsdsUart/docs/sdd.md @@ -0,0 +1,5 @@ +# ComCcsdsUart + +This is a clone with a renamed module of the F Prime's Svc::ComCcsds. + +See: [Svc::ComCcsds](../../../lib/fprime/Svc/Subtopologies/ComCcsds/docs/sdd.md) \ No newline at end of file diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentPackets.fppi b/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentPackets.fppi index c108ef2..4c2e3fc 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentPackets.fppi +++ b/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentPackets.fppi @@ -5,6 +5,8 @@ telemetry packets ReferenceDeploymentPackets { CdhCore.cmdDisp.CommandsDropped ComCcsds.comQueue.comQueueDepth ComCcsds.commsBufferManager.HiBuffs + ComCcsdsUart.comQueue.comQueueDepth + ComCcsdsUart.commsBufferManager.HiBuffs ReferenceDeployment.rateGroup10Hz.RgMaxTime ReferenceDeployment.rateGroup1Hz.RgMaxTime } @@ -13,6 +15,8 @@ telemetry packets ReferenceDeploymentPackets { CdhCore.$health.PingLateWarnings ComCcsds.commsBufferManager.NoBuffs ComCcsds.commsBufferManager.EmptyBuffs + ComCcsdsUart.commsBufferManager.NoBuffs + ComCcsdsUart.commsBufferManager.EmptyBuffs ReferenceDeployment.rateGroup10Hz.RgCycleSlips ReferenceDeployment.rateGroup1Hz.RgCycleSlips } @@ -22,6 +26,9 @@ telemetry packets ReferenceDeploymentPackets { ComCcsds.commsBufferManager.TotalBuffs ComCcsds.commsBufferManager.CurrBuffs ComCcsds.comQueue.buffQueueDepth + ComCcsdsUart.commsBufferManager.TotalBuffs + ComCcsdsUart.commsBufferManager.CurrBuffs + ComCcsdsUart.comQueue.buffQueueDepth CdhCore.tlmSend.SendLevel } diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp b/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp index 5480fe3..0c7db66 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp +++ b/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp @@ -85,6 +85,7 @@ void setupTopology(const TopologyState& state) { // We dont need UART, as we are sending coms directly to lora // comDriver.configure(state.uartDevice, state.baudRate); lora.start(state.loraDevice); + comDriver.configure(state.uartDevice, state.baudRate); } void startRateGroups() { diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/instances.fpp b/FprimeZephyrReference/ReferenceDeployment/Top/instances.fpp index 76f59bd..bdbb36a 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/instances.fpp +++ b/FprimeZephyrReference/ReferenceDeployment/Top/instances.fpp @@ -77,4 +77,8 @@ module ReferenceDeployment { instance comDelay: Components.ComDelay base id 0x10025000 instance lora: Zephyr.LoRa base id 0x10026000 + + instance comSplitterEvents: Svc.ComSplitter base id 0x10027000 + + instance comSplitterTelemetry: Svc.ComSplitter base id 0x10028000 } diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp b/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp index dafc535..fb42af6 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp +++ b/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp @@ -16,6 +16,7 @@ module ReferenceDeployment { # ---------------------------------------------------------------------- import CdhCore.Subtopology import ComCcsds.FramingSubtopology + import ComCcsdsUart.Subtopology # ---------------------------------------------------------------------- # Instances used in the topology @@ -37,6 +38,10 @@ module ReferenceDeployment { instance bootloaderTrigger instance comDelay instance burnwire + instance comSplitterEvents + instance comSplitterTelemetry + # For UART sideband communication + instance comDriver # ---------------------------------------------------------------------- # Pattern graph specifiers @@ -62,16 +67,23 @@ module ReferenceDeployment { connections ComCcsds_CdhCore { # Core events and telemetry to communication queue - CdhCore.events.PktSend -> ComCcsds.comQueue.comPacketQueueIn[ComCcsds.Ports_ComPacketQueue.EVENTS] - CdhCore.tlmSend.PktSend -> ComCcsds.comQueue.comPacketQueueIn[ComCcsds.Ports_ComPacketQueue.TELEMETRY] + CdhCore.events.PktSend -> comSplitterEvents.comIn + comSplitterEvents.comOut-> ComCcsds.comQueue.comPacketQueueIn[ComCcsds.Ports_ComPacketQueue.EVENTS] + comSplitterEvents.comOut-> ComCcsdsUart.comQueue.comPacketQueueIn[ComCcsds.Ports_ComPacketQueue.EVENTS] + + CdhCore.tlmSend.PktSend -> comSplitterTelemetry.comIn + comSplitterTelemetry.comOut -> ComCcsds.comQueue.comPacketQueueIn[ComCcsds.Ports_ComPacketQueue.TELEMETRY] + comSplitterTelemetry.comOut -> ComCcsdsUart.comQueue.comPacketQueueIn[ComCcsds.Ports_ComPacketQueue.TELEMETRY] # Router to Command Dispatcher ComCcsds.fprimeRouter.commandOut -> CdhCore.cmdDisp.seqCmdBuff CdhCore.cmdDisp.seqCmdStatus -> ComCcsds.fprimeRouter.cmdResponseIn + ComCcsdsUart.fprimeRouter.commandOut -> CdhCore.cmdDisp.seqCmdBuff + CdhCore.cmdDisp.seqCmdStatus -> ComCcsdsUart.fprimeRouter.cmdResponseIn } - connections Communications { + connections CommunicationsRadio { lora.allocate -> ComCcsds.commsBufferManager.bufferGetCallee lora.deallocate -> ComCcsds.commsBufferManager.bufferSendIn @@ -88,12 +100,28 @@ module ReferenceDeployment { comDelay.timeout -> ComCcsds.aggregator.timeout } + connections CommunicationsUart { + # ComDriver buffer allocations + comDriver.allocate -> ComCcsdsUart.commsBufferManager.bufferGetCallee + comDriver.deallocate -> ComCcsdsUart.commsBufferManager.bufferSendIn + + # ComDriver <-> ComStub (Uplink) + comDriver.$recv -> ComCcsdsUart.comStub.drvReceiveIn + ComCcsdsUart.comStub.drvReceiveReturnOut -> comDriver.recvReturnIn + + # ComStub <-> ComDriver (Downlink) + ComCcsdsUart.comStub.drvSendOut -> comDriver.$send + comDriver.ready -> ComCcsdsUart.comStub.drvConnected + } + connections RateGroups { # timer to drive rate group timer.CycleOut -> rateGroupDriver.CycleIn # High rate (10Hz) rate group rateGroupDriver.CycleOut[Ports_RateGroups.rateGroup10Hz] -> rateGroup10Hz.CycleIn + rateGroup10Hz.RateGroupMemberOut[0] -> comDriver.schedIn + rateGroup10Hz.RateGroupMemberOut[1] -> ComCcsdsUart.aggregator.timeout # Slow rate (1Hz) rate group rateGroupDriver.CycleOut[Ports_RateGroups.rateGroup1Hz] -> rateGroup1Hz.CycleIn diff --git a/FprimeZephyrReference/project/config/ComCcsdsConfig.fpp b/FprimeZephyrReference/project/config/ComCcsdsConfig.fpp index 94f091e..5061f1f 100644 --- a/FprimeZephyrReference/project/config/ComCcsdsConfig.fpp +++ b/FprimeZephyrReference/project/config/ComCcsdsConfig.fpp @@ -1,9 +1,10 @@ module ComCcsdsConfig { #Base ID for the ComCcsds Subtopology, all components are offsets from this base ID constant BASE_ID = 0x02000000 + constant BASE_ID_UART = 0x21000000 module QueueSizes { - constant comQueue = 10 + constant comQueue = 5 constant aggregator = 5 } @@ -18,8 +19,8 @@ module ComCcsdsConfig { # Queue configuration constants module QueueDepths { - constant events = 20 - constant tlm = 20 + constant events = 10 + constant tlm = 5 constant file = 1 } @@ -31,8 +32,8 @@ module ComCcsdsConfig { # Buffer management constants module BuffMgr { - constant frameAccumulatorSize = 2048 - constant commsBuffSize = 2048 + constant frameAccumulatorSize = 256 + constant commsBuffSize = 256 constant commsFileBuffSize = 1 constant commsBuffCount = 5 constant commsFileBuffCount = 1 diff --git a/lib/fprime-zephyr b/lib/fprime-zephyr index 931354e..6c6058a 160000 --- a/lib/fprime-zephyr +++ b/lib/fprime-zephyr @@ -1 +1 @@ -Subproject commit 931354e26e39cb711f846e1ca8bb1337ede83b7c +Subproject commit 6c6058a4ff35b45b134ce3138e20b1a76340d316 diff --git a/prj.conf b/prj.conf index 32909b3..72c56e2 100644 --- a/prj.conf +++ b/prj.conf @@ -36,7 +36,7 @@ CONFIG_DYNAMIC_THREAD=y CONFIG_KERNEL_MEM_POOL=y CONFIG_DYNAMIC_THREAD_ALLOC=n CONFIG_DYNAMIC_THREAD_PREFER_POOL=y -CONFIG_DYNAMIC_THREAD_POOL_SIZE=12 +CONFIG_DYNAMIC_THREAD_POOL_SIZE=15 # Num threads in the thread pool CONFIG_DYNAMIC_THREAD_STACK_SIZE=8192 # Size of thread stack in thread pool, must be >= Thread Pool size in F' From caac355839df84c07683f11a554d5b88e58dc2e2 Mon Sep 17 00:00:00 2001 From: M Starch Date: Sun, 12 Oct 2025 15:49:55 -0700 Subject: [PATCH 20/32] Fix format errors --- FprimeZephyrReference/ComCcsdsUart/ComCcsds.fpp | 4 ++-- FprimeZephyrReference/ComCcsdsUart/docs/sdd.md | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/FprimeZephyrReference/ComCcsdsUart/ComCcsds.fpp b/FprimeZephyrReference/ComCcsdsUart/ComCcsds.fpp index d67869f..293f630 100644 --- a/FprimeZephyrReference/ComCcsdsUart/ComCcsds.fpp +++ b/FprimeZephyrReference/ComCcsdsUart/ComCcsds.fpp @@ -3,7 +3,7 @@ module ComCcsdsUart { # ComPacket Queue enum for queue types enum Ports_ComPacketQueue { EVENTS, - TELEMETRY + TELEMETRY } enum Ports_ComBufferQueue { @@ -49,7 +49,7 @@ module ComCcsdsUart { # ---------------------------------------------------------------------- # Passive Components # ---------------------------------------------------------------------- - instance frameAccumulator: Svc.FrameAccumulator base id ComCcsdsConfig.BASE_ID_UART + 0x01000 \ + instance frameAccumulator: Svc.FrameAccumulator base id ComCcsdsConfig.BASE_ID_UART + 0x01000 \ { phase Fpp.ToCpp.Phases.configObjects """ diff --git a/FprimeZephyrReference/ComCcsdsUart/docs/sdd.md b/FprimeZephyrReference/ComCcsdsUart/docs/sdd.md index 69a021a..9ebc9be 100644 --- a/FprimeZephyrReference/ComCcsdsUart/docs/sdd.md +++ b/FprimeZephyrReference/ComCcsdsUart/docs/sdd.md @@ -2,4 +2,4 @@ This is a clone with a renamed module of the F Prime's Svc::ComCcsds. -See: [Svc::ComCcsds](../../../lib/fprime/Svc/Subtopologies/ComCcsds/docs/sdd.md) \ No newline at end of file +See: [Svc::ComCcsds](../../../lib/fprime/Svc/Subtopologies/ComCcsds/docs/sdd.md) From cd4dcce2e5e7ab8613c6654f011e29065a9fe5f9 Mon Sep 17 00:00:00 2001 From: ineskhou Date: Sun, 12 Oct 2025 17:31:21 -0700 Subject: [PATCH 21/32] letting ComIn be valid --- .codespell-ignore-words.txt | 1 + .pre-commit-config.yaml | 1 + 2 files changed, 2 insertions(+) create mode 100644 .codespell-ignore-words.txt diff --git a/.codespell-ignore-words.txt b/.codespell-ignore-words.txt new file mode 100644 index 0000000..f5f10d4 --- /dev/null +++ b/.codespell-ignore-words.txt @@ -0,0 +1 @@ +comIn diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 794b0d8..1b6e454 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -12,6 +12,7 @@ repos: rev: v2.4.1 hooks: - id: codespell + args: [--ignore-words=.codespell-ignore-words.txt] - repo: https://github.com/pre-commit/mirrors-clang-format rev: v20.1.8 From 1b34f9822adea7f9616bea93e7a5625f76928399 Mon Sep 17 00:00:00 2001 From: M Starch Date: Thu, 16 Oct 2025 19:02:15 -0700 Subject: [PATCH 22/32] Update to correct miss-aggregations --- .../Components/ComDelay/ComDelay.cpp | 1 - .../Components/ComDelay/ComDelay.fpp | 3 - .../ReferenceDeployment/Top/topology.fpp | 3 +- Makefile | 3 - custom_space_data_link.py | 198 ------------------ lib/fprime | 2 +- lib/fprime-zephyr | 2 +- 7 files changed, 3 insertions(+), 209 deletions(-) delete mode 100644 custom_space_data_link.py diff --git a/FprimeZephyrReference/Components/ComDelay/ComDelay.cpp b/FprimeZephyrReference/Components/ComDelay/ComDelay.cpp index 2d1c073..a94cdef 100644 --- a/FprimeZephyrReference/Components/ComDelay/ComDelay.cpp +++ b/FprimeZephyrReference/Components/ComDelay/ComDelay.cpp @@ -51,7 +51,6 @@ void ComDelay ::run_handler(FwIndexType portNum, U32 context) { bool valid = this->m_last_status_valid.compare_exchange_strong(expected, false); if (valid) { this->comStatusOut_out(0, this->m_last_status); - this->timeout_out(0, 0); } } diff --git a/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp b/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp index 6c14f0c..a0122ff 100644 --- a/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp +++ b/FprimeZephyrReference/Components/ComDelay/ComDelay.fpp @@ -5,9 +5,6 @@ module Components { @ Rate schedule port used to trigger radio transmission sync input port run: Svc.Sched - @ Rate schedule port used to trigger aggregation timeout - output port timeout: Svc.Sched - @ Input comStatus from radio component sync input port comStatusIn: Fw.SuccessCondition diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp b/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp index fb42af6..97b921f 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp +++ b/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp @@ -96,8 +96,6 @@ module ReferenceDeployment { lora.dataReturnOut -> ComCcsds.framer.dataReturnIn lora.comStatusOut -> comDelay.comStatusIn comDelay.comStatusOut ->ComCcsds.framer.comStatusIn - - comDelay.timeout -> ComCcsds.aggregator.timeout } connections CommunicationsUart { @@ -122,6 +120,7 @@ module ReferenceDeployment { rateGroupDriver.CycleOut[Ports_RateGroups.rateGroup10Hz] -> rateGroup10Hz.CycleIn rateGroup10Hz.RateGroupMemberOut[0] -> comDriver.schedIn rateGroup10Hz.RateGroupMemberOut[1] -> ComCcsdsUart.aggregator.timeout + rateGroup10Hz.RateGroupMemberOut[1] -> ComCcsds.aggregator.timeout # Slow rate (1Hz) rate group rateGroupDriver.CycleOut[Ports_RateGroups.rateGroup1Hz] -> rateGroup1Hz.CycleIn diff --git a/Makefile b/Makefile index 64fb2f4..bfd761f 100644 --- a/Makefile +++ b/Makefile @@ -19,9 +19,6 @@ fprime-venv: ## Create a virtual environment @$(UV) venv fprime-venv @$(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 @test -d lib/zephyr-workspace/modules/hal/rpi_pico || test -d ../lib/zephyr-workspace/modules/hal/rpi_pico || { \ diff --git a/custom_space_data_link.py b/custom_space_data_link.py deleted file mode 100644 index 0439afd..0000000 --- a/custom_space_data_link.py +++ /dev/null @@ -1,198 +0,0 @@ -"""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 diff --git a/lib/fprime b/lib/fprime index 2581b65..626473f 160000 --- a/lib/fprime +++ b/lib/fprime @@ -1 +1 @@ -Subproject commit 2581b65da571e082fab76bae0276bdbca09b1ad8 +Subproject commit 626473fc4e89e491d43ad95bb0d1b7727014c80d diff --git a/lib/fprime-zephyr b/lib/fprime-zephyr index 6c6058a..2abcff0 160000 --- a/lib/fprime-zephyr +++ b/lib/fprime-zephyr @@ -1 +1 @@ -Subproject commit 6c6058a4ff35b45b134ce3138e20b1a76340d316 +Subproject commit 2abcff04d3175b2869f43511e16cc3e1c98a0223 From ce4025254e4fd2bf04162bdc7aa1ca8033ee9f0d Mon Sep 17 00:00:00 2001 From: M Starch Date: Fri, 17 Oct 2025 11:33:03 -0700 Subject: [PATCH 23/32] Fix LoRa beaconing --- .../Top/ReferenceDeploymentTopology.cpp | 7 +++---- .../ReferenceDeployment/Top/topology.fpp | 2 +- FprimeZephyrReference/project/config/ComCcsdsConfig.fpp | 9 +++++---- lib/fprime-zephyr | 2 +- 4 files changed, 10 insertions(+), 10 deletions(-) diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp b/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp index 0c7db66..2130696 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp +++ b/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp @@ -81,10 +81,9 @@ void setupTopology(const TopologyState& state) { // Autocoded task kick-off (active components). Function provided by autocoder. startTasks(state); - // Uplink is configured for receive so a socket task is started - // We dont need UART, as we are sending coms directly to lora - // comDriver.configure(state.uartDevice, state.baudRate); - lora.start(state.loraDevice); + // We have a pipeline for both the LoRa and UART drive to allow for ground harness debugging an + // for over-the-air communications. + lora.start(state.loraDevice, Zephyr::TransmitState::DISABLED); comDriver.configure(state.uartDevice, state.baudRate); } diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp b/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp index 97b921f..89626e3 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp +++ b/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp @@ -120,7 +120,7 @@ module ReferenceDeployment { rateGroupDriver.CycleOut[Ports_RateGroups.rateGroup10Hz] -> rateGroup10Hz.CycleIn rateGroup10Hz.RateGroupMemberOut[0] -> comDriver.schedIn rateGroup10Hz.RateGroupMemberOut[1] -> ComCcsdsUart.aggregator.timeout - rateGroup10Hz.RateGroupMemberOut[1] -> ComCcsds.aggregator.timeout + rateGroup10Hz.RateGroupMemberOut[2] -> ComCcsds.aggregator.timeout # Slow rate (1Hz) rate group rateGroupDriver.CycleOut[Ports_RateGroups.rateGroup1Hz] -> rateGroup1Hz.CycleIn diff --git a/FprimeZephyrReference/project/config/ComCcsdsConfig.fpp b/FprimeZephyrReference/project/config/ComCcsdsConfig.fpp index 5061f1f..c39d377 100644 --- a/FprimeZephyrReference/project/config/ComCcsdsConfig.fpp +++ b/FprimeZephyrReference/project/config/ComCcsdsConfig.fpp @@ -5,7 +5,7 @@ module ComCcsdsConfig { module QueueSizes { constant comQueue = 5 - constant aggregator = 5 + constant aggregator = 15 } module StackSizes { @@ -14,7 +14,8 @@ module ComCcsdsConfig { } module Priorities { - constant comQueue = 5 + constant aggregator = 5 # Aggregator (consumer) must have higher priority than comQueue (producer) + constant comQueue = 6 # ComQueue has higher priority than data producers (e.g. events, telemetry) } # Queue configuration constants @@ -32,8 +33,8 @@ module ComCcsdsConfig { # Buffer management constants module BuffMgr { - constant frameAccumulatorSize = 256 - constant commsBuffSize = 256 + constant frameAccumulatorSize = 1024 # Must be at least as large as the comm buffer size + constant commsBuffSize = 1024 # Size of ring buffer constant commsFileBuffSize = 1 constant commsBuffCount = 5 constant commsFileBuffCount = 1 diff --git a/lib/fprime-zephyr b/lib/fprime-zephyr index 2abcff0..dc83bef 160000 --- a/lib/fprime-zephyr +++ b/lib/fprime-zephyr @@ -1 +1 @@ -Subproject commit 2abcff04d3175b2869f43511e16cc3e1c98a0223 +Subproject commit dc83bef61c25c65d3854cf65b045daf42a6a58f9 From d3dc80f3d5903f19db385cf0c718b70f95186388 Mon Sep 17 00:00:00 2001 From: ineskhou <127782958+ineskhou@users.noreply.github.com> Date: Fri, 17 Oct 2025 11:34:56 -0700 Subject: [PATCH 24/32] Update code.py --- circuit-python-lora-passthrough/code.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/circuit-python-lora-passthrough/code.py b/circuit-python-lora-passthrough/code.py index a8543d3..6863def 100644 --- a/circuit-python-lora-passthrough/code.py +++ b/circuit-python-lora-passthrough/code.py @@ -9,7 +9,7 @@ import board import digitalio -import lib.adafruit_rfm.rfm9x as adafruit_rfm9x +import adafruit_rfm9x import usb_cdc # Radio constants From b2a3f3c011725e69e767712b5dfd7687a3d58d28 Mon Sep 17 00:00:00 2001 From: M Starch Date: Fri, 17 Oct 2025 11:39:12 -0700 Subject: [PATCH 25/32] Lint --- circuit-python-lora-passthrough/code.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/circuit-python-lora-passthrough/code.py b/circuit-python-lora-passthrough/code.py index 6863def..4efd89f 100644 --- a/circuit-python-lora-passthrough/code.py +++ b/circuit-python-lora-passthrough/code.py @@ -7,9 +7,9 @@ import time +import adafruit_rfm9x import board import digitalio -import adafruit_rfm9x import usb_cdc # Radio constants From bfa55e53c6e1d4470b51bfad6f234be723530440 Mon Sep 17 00:00:00 2001 From: ineskhou <127782958+ineskhou@users.noreply.github.com> Date: Fri, 17 Oct 2025 13:29:54 -0700 Subject: [PATCH 26/32] change back to do bc broncospace is out of cs and need to run integration test on lav sorry nate!!! --- settings.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/settings.ini b/settings.ini index d27e929..dde51b9 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 a2a17b23ffa5ca36a2673d62a53fe208dd9e4d24 Mon Sep 17 00:00:00 2001 From: M Starch Date: Fri, 17 Oct 2025 18:13:41 -0700 Subject: [PATCH 27/32] Hacked for Zephyr --- .codespell-ignore-words.txt | 1 + CMakeLists.txt | 9 +++++- .../ReferenceDeployment/CMakeLists.txt | 3 ++ .../ReferenceDeployment/Main.cpp | 21 +++++++++++++- ...roves_flight_control_board_v5-pinctrl.dtsi | 10 +++++++ .../proves_flight_control_board_v5.dtsi | 29 +++++++++++++++++++ lib/fprime | 2 +- lib/fprime-zephyr | 2 +- prj.conf | 11 +++++++ settings.ini | 3 ++ 10 files changed, 87 insertions(+), 4 deletions(-) diff --git a/.codespell-ignore-words.txt b/.codespell-ignore-words.txt index f5f10d4..c72c89e 100644 --- a/.codespell-ignore-words.txt +++ b/.codespell-ignore-words.txt @@ -1 +1,2 @@ comIn +Ines diff --git a/CMakeLists.txt b/CMakeLists.txt index 488e62f..383ce06 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -4,6 +4,7 @@ #### cmake_minimum_required(VERSION 3.24.2) +add_compile_definitions(_POSIX_C_SOURCE=200809L) # Set BOARD_ROOT to find custom boards # The structure is BOARD_ROOT/boards/vendor/board @@ -33,6 +34,12 @@ fprime_setup_included_code() # This includes project-wide objects add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/FprimeZephyrReference") - +if (FPRIME_USE_POSIX) + set_target_properties(Drv_Ip PROPERTIES EXCLUDE_FROM_ALL TRUE) + set_target_properties(Drv_TcpServer PROPERTIES EXCLUDE_FROM_ALL TRUE) + set_target_properties(Drv_TcpClient PROPERTIES EXCLUDE_FROM_ALL TRUE) + set_target_properties(Drv_Udp PROPERTIES EXCLUDE_FROM_ALL TRUE) + target_compile_definitions(Os_File_Posix_Implementation PRIVATE SYNTHETIC_FALLOCATE) +endif() set_target_properties(Svc_FatalHandler PROPERTIES EXCLUDE_FROM_ALL TRUE) set_target_properties(fprime-zephyr_Drv_ZephyrSpiDriver PROPERTIES EXCLUDE_FROM_ALL TRUE) diff --git a/FprimeZephyrReference/ReferenceDeployment/CMakeLists.txt b/FprimeZephyrReference/ReferenceDeployment/CMakeLists.txt index 2643839..19c7aa7 100644 --- a/FprimeZephyrReference/ReferenceDeployment/CMakeLists.txt +++ b/FprimeZephyrReference/ReferenceDeployment/CMakeLists.txt @@ -20,5 +20,8 @@ if (FPRIME_PLATFORM STREQUAL "Zephyr") "${CMAKE_CURRENT_LIST_DIR}/Main.cpp" DEPENDS ${FPRIME_CURRENT_MODULE}_Top + CHOOSES_IMPLEMENTATIONS + # Can remain stubs for now + Os_File_Posix ) endif() diff --git a/FprimeZephyrReference/ReferenceDeployment/Main.cpp b/FprimeZephyrReference/ReferenceDeployment/Main.cpp index 1747956..4d008e1 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Main.cpp +++ b/FprimeZephyrReference/ReferenceDeployment/Main.cpp @@ -9,6 +9,7 @@ #include #include +#include const struct device* serial = DEVICE_DT_GET(DT_NODELABEL(cdc_acm_uart0)); const struct device* lora = DEVICE_DT_GET(DT_NODELABEL(lora0)); @@ -19,7 +20,25 @@ int main(int argc, char* argv[]) { // This sleep is necessary to allow the USB CDC ACM interface to initialize before // the application starts writing to it. k_sleep(K_MSEC(3000)); - + Os::File file; + U8 message[] = "Hello Ines\n"; + U8 message1[sizeof(message) + 1] = {0}; + Os::File::Status status; + FwSizeType size; + // = file.open("/tmp1", Os::File::Mode::OPEN_CREATE); + // Os::File::Status status = file.open("/tmp1", Os::File::Mode::OPEN_CREATE); + // FwSizeType size = static_cast(sizeof(message)); + // printk("Status: %d - open\n", static_cast(status)); + // status = file.write(message, size); + // printk("Status: %d - write %" PRI_FwSizeType "\n", static_cast(status), size); + // file.close(); + status = file.open("/tmp1", Os::File::Mode::OPEN_READ); + printk("Status: %d - open (R)\n", static_cast(status)); + size = static_cast(sizeof(message)); + status = file.read(message1, size); + printk("Status: %d - read %" PRI_FwSizeType "\n", static_cast(status), size); + message1[sizeof(message)] = 0; + printk("Message: %s\n", message1); Os::init(); // Object for communicating state to the topology ReferenceDeployment::TopologyState inputs; diff --git a/boards/bronco_space/proves_flight_control_board_v5/proves_flight_control_board_v5-pinctrl.dtsi b/boards/bronco_space/proves_flight_control_board_v5/proves_flight_control_board_v5-pinctrl.dtsi index 0ae79cf..34fd8f3 100644 --- a/boards/bronco_space/proves_flight_control_board_v5/proves_flight_control_board_v5-pinctrl.dtsi +++ b/boards/bronco_space/proves_flight_control_board_v5/proves_flight_control_board_v5-pinctrl.dtsi @@ -1,6 +1,16 @@ #include &pinctrl { + spi0_default: spi0_default { + group1 { + pinmux = , ; + }; + + group2 { + pinmux = ; + input-enable; + }; + }; spi1_default: spi1_default { group1 { pinmux = , ; diff --git a/boards/bronco_space/proves_flight_control_board_v5/proves_flight_control_board_v5.dtsi b/boards/bronco_space/proves_flight_control_board_v5/proves_flight_control_board_v5.dtsi index 397708c..11db77d 100644 --- a/boards/bronco_space/proves_flight_control_board_v5/proves_flight_control_board_v5.dtsi +++ b/boards/bronco_space/proves_flight_control_board_v5/proves_flight_control_board_v5.dtsi @@ -14,6 +14,17 @@ zephyr,code-partition = &code_partition; }; + fstab { + compatible = "zephyr,fstab"; + ffs1: ffs1 { + compatible = "zephyr,fstab,fatfs"; + automount; + disk-access; + mount-point = "/"; + }; + }; + + aliases { watchdog0 = &wdt0; }; @@ -89,6 +100,24 @@ zephyr_udc0: &usbd { status = "okay"; }; +&spi0 { + status = "okay"; + cs-gpios = <&gpio0 15 GPIO_ACTIVE_LOW>; + pinctrl-0 = <&spi0_default>; + pinctrl-names = "default"; + sdhc0: sdhc@0 { + compatible = "zephyr,sdhc-spi-slot"; + reg = <0>; + status = "okay"; + mmc { + compatible = "zephyr,sdmmc-disk"; + disk-name = "SD"; + status = "okay"; + }; + spi-max-frequency = <24000000>; + }; +}; + &spi1 { status = "okay"; cs-gpios = <&gpio0 9 GPIO_ACTIVE_LOW>; diff --git a/lib/fprime b/lib/fprime index 626473f..3af5b0f 160000 --- a/lib/fprime +++ b/lib/fprime @@ -1 +1 @@ -Subproject commit 626473fc4e89e491d43ad95bb0d1b7727014c80d +Subproject commit 3af5b0f5b5e7e7f33051de7e4659f13e10f056af diff --git a/lib/fprime-zephyr b/lib/fprime-zephyr index dc83bef..5697c11 160000 --- a/lib/fprime-zephyr +++ b/lib/fprime-zephyr @@ -1 +1 @@ -Subproject commit dc83bef61c25c65d3854cf65b045daf42a6a58f9 +Subproject commit 5697c1102bd1e2dfab83cde21c8887e5f4ade4a3 diff --git a/prj.conf b/prj.conf index 72c56e2..b1e3567 100644 --- a/prj.conf +++ b/prj.conf @@ -54,3 +54,14 @@ CONFIG_LOG=n CONFIG_LOG_DEFAULT_LEVEL=3 CONFIG_CBPRINTF_FP_SUPPORT=y + + +CONFIG_POSIX_AEP_CHOICE_PSE52=y +CONFIG_POSIX_FILE_SYSTEM=y +CONFIG_FILE_SYSTEM=y +CONFIG_SDHC=y +CONFIG_DISK_ACCESS=y +CONFIG_FAT_FILESYSTEM_ELM=y +CONFIG_FS_FATFS_EXFAT=y +CONFIG_FS_FATFS_MOUNT_MKFS=y +CONFIG_FS_FATFS_FSTAB_AUTOMOUNT=y diff --git a/settings.ini b/settings.ini index dde51b9..cf24077 100644 --- a/settings.ini +++ b/settings.ini @@ -8,3 +8,6 @@ default_cmake_options: FPRIME_ENABLE_FRAMEWORK_UTS=OFF FPRIME_ENABLE_AUTOCODER_UTS=OFF BOARD_ROOT=. BOARD=proves_flight_control_board_v5d/rp2350a/m33 + FPRIME_USE_POSIX=ON + FPRIME_CMAKE_QUIET=ON + FPRIME_INSTALL_STATIC_LIBRARIES=OFF From 517bcc24b24c5668e17234e55e349502cef39ea2 Mon Sep 17 00:00:00 2001 From: M Starch Date: Fri, 31 Oct 2025 11:34:21 -0700 Subject: [PATCH 28/32] Add in prmDb --- .../ReferenceDeployment/Main.cpp | 20 ------------------- .../Top/ReferenceDeploymentTopology.cpp | 2 ++ .../ReferenceDeployment/Top/instances.fpp | 7 +++++-- lib/fprime | 2 +- lib/fprime-zephyr | 2 +- 5 files changed, 9 insertions(+), 24 deletions(-) diff --git a/FprimeZephyrReference/ReferenceDeployment/Main.cpp b/FprimeZephyrReference/ReferenceDeployment/Main.cpp index 4d008e1..705a7f2 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Main.cpp +++ b/FprimeZephyrReference/ReferenceDeployment/Main.cpp @@ -9,7 +9,6 @@ #include #include -#include const struct device* serial = DEVICE_DT_GET(DT_NODELABEL(cdc_acm_uart0)); const struct device* lora = DEVICE_DT_GET(DT_NODELABEL(lora0)); @@ -20,25 +19,6 @@ int main(int argc, char* argv[]) { // This sleep is necessary to allow the USB CDC ACM interface to initialize before // the application starts writing to it. k_sleep(K_MSEC(3000)); - Os::File file; - U8 message[] = "Hello Ines\n"; - U8 message1[sizeof(message) + 1] = {0}; - Os::File::Status status; - FwSizeType size; - // = file.open("/tmp1", Os::File::Mode::OPEN_CREATE); - // Os::File::Status status = file.open("/tmp1", Os::File::Mode::OPEN_CREATE); - // FwSizeType size = static_cast(sizeof(message)); - // printk("Status: %d - open\n", static_cast(status)); - // status = file.write(message, size); - // printk("Status: %d - write %" PRI_FwSizeType "\n", static_cast(status), size); - // file.close(); - status = file.open("/tmp1", Os::File::Mode::OPEN_READ); - printk("Status: %d - open (R)\n", static_cast(status)); - size = static_cast(sizeof(message)); - status = file.read(message1, size); - printk("Status: %d - read %" PRI_FwSizeType "\n", static_cast(status), size); - message1[sizeof(message)] = 0; - printk("Message: %s\n", message1); Os::init(); // Object for communicating state to the topology ReferenceDeployment::TopologyState inputs; diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp b/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp index 2130696..ccef907 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp +++ b/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentTopology.cpp @@ -50,6 +50,7 @@ U32 rateGroup1HzContext[Svc::ActiveRateGroup::CONNECTION_COUNT_MAX] = {getRateGr * desired, but is extracted here for clarity. */ void configureTopology() { + prmDb.configure("/prmDb.dat"); // Rate group driver needs a divisor list rateGroupDriver.configure(rateGroupDivisorsSet); // Rate groups require context arrays. @@ -77,6 +78,7 @@ void setupTopology(const TopologyState& state) { // Project-specific component configuration. Function provided above. May be inlined, if desired. configureTopology(); // Autocoded parameter loading. Function provided by autocoder. + prmDb.readParamFile(); loadParameters(); // Autocoded task kick-off (active components). Function provided by autocoder. startTasks(state); diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/instances.fpp b/FprimeZephyrReference/ReferenceDeployment/Top/instances.fpp index e18b143..ec9dbbd 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/instances.fpp +++ b/FprimeZephyrReference/ReferenceDeployment/Top/instances.fpp @@ -37,6 +37,11 @@ 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 5 + # ---------------------------------------------------------------------- # Queued component instances # ---------------------------------------------------------------------- @@ -73,8 +78,6 @@ module ReferenceDeployment { instance gpioBurnwire1: Zephyr.ZephyrGpioDriver base id 0x10023000 - instance prmDb: Components.NullPrmDb base id 0x10024000 - instance comDelay: Components.ComDelay base id 0x10025000 instance lora: Zephyr.LoRa base id 0x10026000 diff --git a/lib/fprime b/lib/fprime index ecff73a..064b645 160000 --- a/lib/fprime +++ b/lib/fprime @@ -1 +1 @@ -Subproject commit ecff73ab1ba75ee5fb53143360921727c87361b2 +Subproject commit 064b64553f1c0dce5afd43453bbf58993004e1e2 diff --git a/lib/fprime-zephyr b/lib/fprime-zephyr index 6d756e1..11c2a10 160000 --- a/lib/fprime-zephyr +++ b/lib/fprime-zephyr @@ -1 +1 @@ -Subproject commit 6d756e1b9583c5e3bd0151a3cb6520b30a7f2b01 +Subproject commit 11c2a109c0225745237c46a0f45902ffc598500b From 9d8c1ce46e1911b20a51d7ea8f889e67c7946a4a Mon Sep 17 00:00:00 2001 From: M Starch Date: Fri, 31 Oct 2025 12:12:14 -0700 Subject: [PATCH 29/32] Add FS telemetry component --- .../Components/CMakeLists.txt | 1 + .../Components/FsSpace/CMakeLists.txt | 36 +++++++++++++++++ .../Components/FsSpace/FsSpace.cpp | 36 +++++++++++++++++ .../Components/FsSpace/FsSpace.fpp | 27 +++++++++++++ .../Components/FsSpace/FsSpace.hpp | 40 +++++++++++++++++++ .../Components/FsSpace/docs/sdd.md | 15 +++++++ .../Top/ReferenceDeploymentPackets.fppi | 2 + .../ReferenceDeployment/Top/instances.fpp | 2 + .../ReferenceDeployment/Top/topology.fpp | 3 ++ 9 files changed, 162 insertions(+) create mode 100644 FprimeZephyrReference/Components/FsSpace/CMakeLists.txt create mode 100644 FprimeZephyrReference/Components/FsSpace/FsSpace.cpp create mode 100644 FprimeZephyrReference/Components/FsSpace/FsSpace.fpp create mode 100644 FprimeZephyrReference/Components/FsSpace/FsSpace.hpp create mode 100644 FprimeZephyrReference/Components/FsSpace/docs/sdd.md diff --git a/FprimeZephyrReference/Components/CMakeLists.txt b/FprimeZephyrReference/Components/CMakeLists.txt index 5245d97..26405d0 100644 --- a/FprimeZephyrReference/Components/CMakeLists.txt +++ b/FprimeZephyrReference/Components/CMakeLists.txt @@ -9,3 +9,4 @@ add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Watchdog") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Burnwire/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/BootloaderTrigger/") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/AntennaDeployer/") +add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/FsSpace/") diff --git a/FprimeZephyrReference/Components/FsSpace/CMakeLists.txt b/FprimeZephyrReference/Components/FsSpace/CMakeLists.txt new file mode 100644 index 0000000..dabc113 --- /dev/null +++ b/FprimeZephyrReference/Components/FsSpace/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}/FsSpace.fpp" + SOURCES + "${CMAKE_CURRENT_LIST_DIR}/FsSpace.cpp" +# DEPENDS +# MyPackage_MyOtherModule +) + +### Unit Tests ### +# register_fprime_ut( +# AUTOCODER_INPUTS +# "${CMAKE_CURRENT_LIST_DIR}/FsSpace.fpp" +# SOURCES +# "${CMAKE_CURRENT_LIST_DIR}/test/ut/FsSpaceTestMain.cpp" +# "${CMAKE_CURRENT_LIST_DIR}/test/ut/FsSpaceTester.cpp" +# DEPENDS +# STest # For rules-based testing +# UT_AUTO_HELPERS +# ) diff --git a/FprimeZephyrReference/Components/FsSpace/FsSpace.cpp b/FprimeZephyrReference/Components/FsSpace/FsSpace.cpp new file mode 100644 index 0000000..4c5e44f --- /dev/null +++ b/FprimeZephyrReference/Components/FsSpace/FsSpace.cpp @@ -0,0 +1,36 @@ +// ====================================================================== +// \title FsSpace.cpp +// \author starchmd +// \brief cpp file for FsSpace component implementation class +// ====================================================================== + +#include "FprimeZephyrReference/Components/FsSpace/FsSpace.hpp" +#include +#include +#include "Os/FileSystem.hpp" + +namespace Components { + +// ---------------------------------------------------------------------- +// Component construction and destruction +// ---------------------------------------------------------------------- + +FsSpace ::FsSpace(const char* const compName) : FsSpaceComponentBase(compName) {} + +FsSpace ::~FsSpace() {} + +// ---------------------------------------------------------------------- +// Handler implementations for typed input ports +// ---------------------------------------------------------------------- + +void FsSpace ::run_handler(FwIndexType portNum, U32 context) { + FwSizeType freeBytes = 0; + FwSizeType totalBytes = 0; + Os::FileSystem::Status status = Os::FileSystem::getFreeSpace("/prmDb.dat", totalBytes, freeBytes); + if (status == Os::FileSystem::OP_OK) { + this->tlmWrite_FreeSpace(freeBytes); + this->tlmWrite_TotalSpace(totalBytes); + } +} + +} // namespace Components diff --git a/FprimeZephyrReference/Components/FsSpace/FsSpace.fpp b/FprimeZephyrReference/Components/FsSpace/FsSpace.fpp new file mode 100644 index 0000000..5ffa4a9 --- /dev/null +++ b/FprimeZephyrReference/Components/FsSpace/FsSpace.fpp @@ -0,0 +1,27 @@ +module Components { + @ Read free space + passive component FsSpace { + + ############################################################################## + #### Uncomment the following examples to start customizing your component #### + ############################################################################## + + @ Free disk space telemetry channel + telemetry FreeSpace: FwSizeType + + @ Total disk space telemetry channel + telemetry TotalSpace: FwSizeType + + sync input port run: Svc.Sched + + ############################################################################### + # Standard AC Ports: Required for Channels, Events, Commands, and Parameters # + ############################################################################### + @ Port for requesting the current time + time get port timeCaller + + @ Port for sending telemetry channels to downlink + telemetry port tlmOut + + } +} diff --git a/FprimeZephyrReference/Components/FsSpace/FsSpace.hpp b/FprimeZephyrReference/Components/FsSpace/FsSpace.hpp new file mode 100644 index 0000000..d242dc3 --- /dev/null +++ b/FprimeZephyrReference/Components/FsSpace/FsSpace.hpp @@ -0,0 +1,40 @@ +// ====================================================================== +// \title FsSpace.hpp +// \author starchmd +// \brief hpp file for FsSpace component implementation class +// ====================================================================== + +#ifndef Components_FsSpace_HPP +#define Components_FsSpace_HPP + +#include "FprimeZephyrReference/Components/FsSpace/FsSpaceComponentAc.hpp" + +namespace Components { + +class FsSpace final : public FsSpaceComponentBase { + public: + // ---------------------------------------------------------------------- + // Component construction and destruction + // ---------------------------------------------------------------------- + + //! Construct FsSpace object + FsSpace(const char* const compName //!< The component name + ); + + //! Destroy FsSpace object + ~FsSpace(); + + private: + // ---------------------------------------------------------------------- + // Handler implementations for typed input ports + // ---------------------------------------------------------------------- + + //! Handler implementation for run + void run_handler(FwIndexType portNum, //!< The port number + U32 context //!< The call order + ) override; +}; + +} // namespace Components + +#endif diff --git a/FprimeZephyrReference/Components/FsSpace/docs/sdd.md b/FprimeZephyrReference/Components/FsSpace/docs/sdd.md new file mode 100644 index 0000000..46f4172 --- /dev/null +++ b/FprimeZephyrReference/Components/FsSpace/docs/sdd.md @@ -0,0 +1,15 @@ +# Components::FsSpace + +Read free space from the filesystem (specifically the filesystem containing /prmDb.dat)/ + +## Telemetry +| Name | Description | +|---|---| +| FreeSpace | Free space in bytes | +| TotalSpace | Total space in bytes | + + +## Change Log +| Date | Description | +|---|---| +|---| Initial Draft | diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentPackets.fppi b/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentPackets.fppi index c836a04..43f0bbf 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentPackets.fppi +++ b/FprimeZephyrReference/ReferenceDeployment/Top/ReferenceDeploymentPackets.fppi @@ -36,6 +36,8 @@ telemetry packets ReferenceDeploymentPackets { CdhCore.version.FrameworkVersion CdhCore.version.ProjectVersion CdhCore.version.LibraryVersion01 + fsSpace.FreeSpace + fsSpace.TotalSpace } packet Led id 5 group 4 { diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/instances.fpp b/FprimeZephyrReference/ReferenceDeployment/Top/instances.fpp index ec9dbbd..26eebbf 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/instances.fpp +++ b/FprimeZephyrReference/ReferenceDeployment/Top/instances.fpp @@ -87,4 +87,6 @@ module ReferenceDeployment { instance comSplitterTelemetry: Svc.ComSplitter base id 0x10028000 instance antennaDeployer: Components.AntennaDeployer base id 0x10029000 + + instance fsSpace: Components.FsSpace base id 0x10030000 } diff --git a/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp b/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp index 6a9d248..ec3bcfb 100644 --- a/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp +++ b/FprimeZephyrReference/ReferenceDeployment/Top/topology.fpp @@ -43,6 +43,8 @@ module ReferenceDeployment { instance comSplitterTelemetry # For UART sideband communication instance comDriver + instance fsSpace + # ---------------------------------------------------------------------- # Pattern graph specifiers @@ -134,6 +136,7 @@ module ReferenceDeployment { rateGroup1Hz.RateGroupMemberOut[6] -> comDelay.run rateGroup1Hz.RateGroupMemberOut[7] -> burnwire.schedIn rateGroup1Hz.RateGroupMemberOut[8] -> antennaDeployer.schedIn + rateGroup1Hz.RateGroupMemberOut[9] -> fsSpace.run } From 607ec61eff41857413b285765eff884083d93c2c Mon Sep 17 00:00:00 2001 From: ineskhou Date: Fri, 31 Oct 2025 15:41:07 -0700 Subject: [PATCH 30/32] added the fatfs support in the west.yml --- west.yml | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/west.yml b/west.yml index 5e9079d..c1a61d8 100644 --- a/west.yml +++ b/west.yml @@ -84,6 +84,13 @@ manifest: groups: - bootloader + # FAT Filesystem support + - name: fatfs + revision: 16245c7c41d2b79e74984f49b5202551786b8a9b + path: lib/zephyr-workspace/modules/fs/fatfs + groups: + - fs + self: path: . west-commands: west-commands.yml From b8183edd4ceff947627db473b6ce6dff06099641 Mon Sep 17 00:00:00 2001 From: ineskhou Date: Fri, 31 Oct 2025 15:51:00 -0700 Subject: [PATCH 31/32] make the update good --- lib/makelib/zephyr.mk | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/lib/makelib/zephyr.mk b/lib/makelib/zephyr.mk index 5c3a9e0..6296d38 100644 --- a/lib/makelib/zephyr.mk +++ b/lib/makelib/zephyr.mk @@ -24,11 +24,8 @@ clean-zephyr-config: ## Remove west configuration .PHONY: zephyr-workspace zephyr-workspace: fprime-venv ## Setup Zephyr bootloader, modules, and tools directories - @test -d ../lib/zephyr-workspace/bootloader || \ - test -d ../lib/zephyr-workspace/modules || \ - test -d ../lib/zephyr-workspace/tools || { \ - $(WESTX) update; \ - } + $(WESTX) update; \ + .PHONY: clean-zephyr-workspace clean-zephyr-workspace: ## Remove Zephyr bootloader, modules, and tools directories From 659f35a97b29f4dd1c7c9d4680876d0870fda02e Mon Sep 17 00:00:00 2001 From: M Starch Date: Fri, 31 Oct 2025 16:00:15 -0700 Subject: [PATCH 32/32] Remove SYNTHETIC_FALLOCATE definition Remove the SYNTHETIC_FALLOCATE compile definition from Os_File_Posix_Implementation. --- CMakeLists.txt | 1 - 1 file changed, 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 383ce06..b6a82d4 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -39,7 +39,6 @@ if (FPRIME_USE_POSIX) set_target_properties(Drv_TcpServer PROPERTIES EXCLUDE_FROM_ALL TRUE) set_target_properties(Drv_TcpClient PROPERTIES EXCLUDE_FROM_ALL TRUE) set_target_properties(Drv_Udp PROPERTIES EXCLUDE_FROM_ALL TRUE) - target_compile_definitions(Os_File_Posix_Implementation PRIVATE SYNTHETIC_FALLOCATE) endif() set_target_properties(Svc_FatalHandler PROPERTIES EXCLUDE_FROM_ALL TRUE) set_target_properties(fprime-zephyr_Drv_ZephyrSpiDriver PROPERTIES EXCLUDE_FROM_ALL TRUE)