Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
35 commits
Select commit Hold shift + click to select a range
36fe485
updated fprime zephyr version
ineskhou Oct 3, 2025
15d6d7a
Initial radio addition
LeStarch Oct 3, 2025
daa9740
Add LoRa transmit
LeStarch Oct 3, 2025
868fc66
Add com delay component
LeStarch Oct 4, 2025
30fe619
Create custom_space_data_link.py
ineskhou Oct 5, 2025
e677465
Allows Makefile with F Prime version and run GDS with camera
ineskhou Oct 5, 2025
b21abcf
Add circuit pass-through
LeStarch Oct 4, 2025
221c9e1
Update to use aggregation
LeStarch Oct 6, 2025
925ea7e
Update to use aggregation
LeStarch Oct 6, 2025
3369a2e
Appease Linter
Mikefly123 Oct 6, 2025
5ecb939
Ran Linter
Mikefly123 Oct 6, 2025
4b868ad
Merge pull request #42 from Open-Source-Space-Foundation/run-make-fmt…
Mikefly123 Oct 6, 2025
b2deade
Fix Submodules
Mikefly123 Oct 7, 2025
a67e02b
Merge branch 'main' into radio
Mikefly123 Oct 7, 2025
f3d422a
Merge branch 'main' into radio
Mikefly123 Oct 8, 2025
690b31c
try
nateinaction Oct 8, 2025
4469434
Apply suggestion from @nateinaction
nateinaction Oct 8, 2025
6c8d5ee
changed the aggregator
ineskhou Oct 8, 2025
bdbc8e5
Merge branch 'radio' of github.com:Open-Source-Space-Foundation/prove…
ineskhou Oct 8, 2025
1b8c4f7
Merge branch 'main' of github.com:open-source-space-foundation/proves…
nateinaction Oct 10, 2025
ceb570f
Revert bootloadertrigger change
nateinaction Oct 10, 2025
2810ace
Merge branch 'main' of github.com:open-source-space-foundation/proves…
nateinaction Oct 11, 2025
72beeda
spacing
nateinaction Oct 11, 2025
60881fa
Merged
LeStarch Oct 12, 2025
6017947
updated instrcutions and flow to run the circuitpython radio example
ineskhou Oct 12, 2025
e9b81b2
Add in com splitter and UART com
LeStarch Oct 12, 2025
e591397
Merge remote-tracking branch 'origin/radio' into radio
LeStarch Oct 12, 2025
caac355
Fix format errors
LeStarch Oct 12, 2025
cd4dcce
letting ComIn be valid
ineskhou Oct 13, 2025
1b34f98
Update to correct miss-aggregations
LeStarch Oct 17, 2025
ce40252
Fix LoRa beaconing
LeStarch Oct 17, 2025
d3dc80f
Update code.py
ineskhou Oct 17, 2025
d918459
Merge branch 'main' into radio
ineskhou Oct 17, 2025
b2a3f3c
Lint
LeStarch Oct 17, 2025
bfa55e5
change back to do bc broncospace is out of cs and need to run integra…
ineskhou Oct 17, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions .codespell-ignore-words.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
comIn
1 change: 1 addition & 0 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 2 additions & 0 deletions FprimeZephyrReference/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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/")
12 changes: 12 additions & 0 deletions FprimeZephyrReference/ComCcsdsUart/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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
)
203 changes: 203 additions & 0 deletions FprimeZephyrReference/ComCcsdsUart/ComCcsds.fpp
Original file line number Diff line number Diff line change
@@ -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
9 changes: 9 additions & 0 deletions FprimeZephyrReference/ComCcsdsUart/PingEntries.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@

#ifndef COMCCSDS_PINGENTRIES_HPP
#define COMCCSDS_PINGENTRIES_HPP

namespace PingEntries {
// No ping-enabled components in ComCcsds subtopology
}

#endif
20 changes: 20 additions & 0 deletions FprimeZephyrReference/ComCcsdsUart/SubtopologyTopologyDefs.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
#ifndef COMCCSDSSUBTOPOLOGY_DEFS_HPP
#define COMCCSDSSUBTOPOLOGY_DEFS_HPP

#include <Fw/Types/MallocAllocator.hpp>
#include <Svc/BufferManager/BufferManager.hpp>
#include <Svc/FrameAccumulator/FrameDetector/CcsdsTcFrameDetector.hpp>
#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
5 changes: 5 additions & 0 deletions FprimeZephyrReference/ComCcsdsUart/docs/sdd.md
Original file line number Diff line number Diff line change
@@ -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)
1 change: 0 additions & 1 deletion FprimeZephyrReference/Components/ComDelay/ComDelay.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
}

Expand Down
3 changes: 0 additions & 3 deletions FprimeZephyrReference/Components/ComDelay/ComDelay.fpp
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
2 changes: 2 additions & 0 deletions FprimeZephyrReference/ReferenceDeployment/Main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
#include <zephyr/sys/printk.h>

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 **//
Expand All @@ -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;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,11 @@ telemetry packets ReferenceDeploymentPackets {

packet Health id 1 group 1 {
CdhCore.cmdDisp.CommandsDispatched
CdhCore.cmdDisp.CommandsDropped
ComCcsds.comQueue.comQueueDepth
ComCcsds.commsBufferManager.HiBuffs
ComCcsdsUart.comQueue.comQueueDepth
ComCcsdsUart.commsBufferManager.HiBuffs
ReferenceDeployment.rateGroup10Hz.RgMaxTime
ReferenceDeployment.rateGroup1Hz.RgMaxTime
}
Expand All @@ -12,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
}
Expand All @@ -21,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
}

Expand All @@ -41,6 +49,10 @@ telemetry packets ReferenceDeploymentPackets {
ReferenceDeployment.lis2mdlManager.MagneticField
}

packet LoRa id 7 group 4 {
lora.LastRssi
lora.LastSnr
}


} omit {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +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 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);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
6 changes: 6 additions & 0 deletions FprimeZephyrReference/ReferenceDeployment/Top/instances.fpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,4 +75,10 @@ module ReferenceDeployment {
instance prmDb: Components.NullPrmDb base id 0x10024000

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
}
Loading