mirror of
https://github.com/nasa/fprime.git
synced 2025-12-11 04:35:25 -06:00
Restructure core subtopologies and add Svc_Subtopologies target (#3904)
* Modify Com/Ccsds/Fprime ComDriverConfig & TopologyDefs for easier ComDriver config * Fix BaseID collision * Removed restrict platform, UART/TCP driver configs different files, CMake switch depending on FPRIME_HAS_SOCKETS * Add Exclude_FROM_ALL to all subtopology cmake modules * remove exclude from ComCcsds (needed for Ref) * Remove exclude from all for testing * Exclude_from_all only on comLoggerTee, comFprime (not used in Ref) * Added Svc_Subtopologies target * Use add_custom_target, spelling fix * Add Configs to Svc_Subtopologies target * Removed comDriver as instance within subtopologies, now within project topology * Take out cmdSeq from ComSubtopologies, put in FileHandling * Added Subtopology States for all, common pattern users can follow * Fix Extra newline * Moved Phased comDriver code into RefTopology.cpp * Update metadata check-spelling run (pull_request_target) for subtopology-config-phasing-updates Signed-off-by: check-spelling-bot <check-spelling-bot@users.noreply.github.com> on-behalf-of: @check-spelling <check-spelling-bot@check-spelling.dev> * Fixed call to default stack size * Moved cmdSeq from FileHandling subtopology to Ref Root Topology * Fix integration test * Remove unneeded Os includes in RefTopology.cpp * Fix BaseIds * Add comment for BaseIDs, comDriver configuration order fix * Restructure of enums within Com Subtopologies * Correct include for ComCcsds enum headers * Using namespace syntax change * Fix BaseIds * Update metadata check-spelling run (pull_request_target) for subtopology-config-phasing-updates Signed-off-by: check-spelling-bot <check-spelling-bot@users.noreply.github.com> on-behalf-of: @check-spelling <check-spelling-bot@check-spelling.dev> * Remove unneeded Dependency * Add enum at the top * Fix RefTopology.cpp * Update Comment --------- Signed-off-by: check-spelling-bot <check-spelling-bot@users.noreply.github.com> Co-authored-by: Moises Mata <moisesmata@users.noreply.github.com>
This commit is contained in:
parent
1fe6a7cb04
commit
268e168f23
14
.github/actions/spelling/expect.txt
vendored
14
.github/actions/spelling/expect.txt
vendored
@ -14,7 +14,6 @@ ANamespace
|
||||
apid
|
||||
APIDOCS
|
||||
APPENDFILE
|
||||
aps
|
||||
arduino
|
||||
ARef
|
||||
argcomplete
|
||||
@ -65,6 +64,7 @@ ccsds
|
||||
ccsparc
|
||||
cdh
|
||||
CDHCORE
|
||||
CDHCORESUBTOPOLOGY
|
||||
cerrno
|
||||
CFDP
|
||||
cff
|
||||
@ -122,7 +122,6 @@ crckermit
|
||||
CRCs
|
||||
crcstat
|
||||
CREATEDIRECTORY
|
||||
Crosscompiling
|
||||
crsmith
|
||||
crt
|
||||
CRTSCTS
|
||||
@ -132,6 +131,7 @@ ctest
|
||||
ctu
|
||||
culates
|
||||
cuz
|
||||
Cxxx
|
||||
CYCLEOUT
|
||||
DATAPRODUCTS
|
||||
DATAPRODUCTSSUBTOPOLOGY
|
||||
@ -178,6 +178,7 @@ DRAINBUFFERS
|
||||
drv
|
||||
drvtcpserversocket
|
||||
dspal
|
||||
DSSC
|
||||
Dstate
|
||||
DVI
|
||||
DWN
|
||||
@ -256,8 +257,6 @@ gcgandhi
|
||||
gcov
|
||||
gdiplus
|
||||
GENHUB
|
||||
getfooter
|
||||
getstatements
|
||||
gettime
|
||||
getty
|
||||
ghprb
|
||||
@ -400,7 +399,6 @@ mman
|
||||
MMAPALLOCATOR
|
||||
MML
|
||||
modbus
|
||||
MOSI
|
||||
MOVEFILE
|
||||
msc
|
||||
mscfile
|
||||
@ -496,7 +494,6 @@ PRMDBIMPL
|
||||
PRMDBIMPLTESTERCFG
|
||||
PRMDBLIMPLCFG
|
||||
PRMDBTESTER
|
||||
PRMLEDINITSTATE
|
||||
PROCBUFFERSENDOUT
|
||||
PRODUCTGETIN
|
||||
PRODUCTREQUESTIN
|
||||
@ -551,10 +548,7 @@ RHH
|
||||
Rizvi
|
||||
ROOTDIR
|
||||
rpi
|
||||
RPIDEMO
|
||||
RPIDEMOCOMPONENTIMPLCFG
|
||||
rptr
|
||||
RXD
|
||||
SAlias
|
||||
sanitizers
|
||||
sats
|
||||
@ -586,7 +580,6 @@ SHAREDSTATEDIR
|
||||
SHELLCOMMAND
|
||||
showinitializer
|
||||
sideeffect
|
||||
sighandler
|
||||
Signedness
|
||||
Silveira
|
||||
sitofp
|
||||
@ -682,7 +675,6 @@ tparam
|
||||
TPP
|
||||
trinomials
|
||||
tts
|
||||
TXD
|
||||
typedef'ed
|
||||
typedef
|
||||
uart
|
||||
|
||||
3
.github/workflows/cppcheck-scan.yml
vendored
3
.github/workflows/cppcheck-scan.yml
vendored
@ -47,6 +47,9 @@ jobs:
|
||||
run: |
|
||||
fprime-util generate -DCMAKE_EXPORT_COMPILE_COMMANDS=ON
|
||||
fprime-util build --all --jobs "$(nproc || printf '%s\n' 1)"
|
||||
|
||||
# Since our subtopologies have EXCLUDE_FROM_ALL, we need to explicitly build them
|
||||
fprime-util build --target Svc_Subtopologies --jobs "$(nproc || printf '%s\n' 1)"
|
||||
echo CPPCHECK_OPTS=--project="$GITHUB_WORKSPACE/build-fprime-automatic-native/compile_commands.json" >> $GITHUB_ENV
|
||||
|
||||
- name: Run cppcheck
|
||||
|
||||
@ -82,8 +82,8 @@ int main(int argc, char* argv[]) {
|
||||
}
|
||||
// Object for communicating state to the reference topology
|
||||
Ref::TopologyState inputs;
|
||||
inputs.comCcsds.hostname = hostname;
|
||||
inputs.comCcsds.port = port_number;
|
||||
inputs.hostname = hostname;
|
||||
inputs.port = port_number;
|
||||
|
||||
// Setup program shutdown via Ctrl-C
|
||||
signal(SIGINT, signalHandler);
|
||||
|
||||
@ -9,10 +9,10 @@ telemetry packets RefPackets {
|
||||
FileHandling.fileDownlink.PacketsSent
|
||||
FileHandling.fileManager.CommandsExecuted
|
||||
|
||||
ComCcsds.cmdSeq.CS_LoadCommands
|
||||
ComCcsds.cmdSeq.CS_CancelCommands
|
||||
ComCcsds.cmdSeq.CS_CommandsExecuted
|
||||
ComCcsds.cmdSeq.CS_SequencesCompleted
|
||||
Ref.cmdSeq.CS_LoadCommands
|
||||
Ref.cmdSeq.CS_CancelCommands
|
||||
Ref.cmdSeq.CS_CommandsExecuted
|
||||
Ref.cmdSeq.CS_SequencesCompleted
|
||||
ComCcsds.comQueue.comQueueDepth
|
||||
ComCcsds.comQueue.buffQueueDepth
|
||||
ComCcsds.commsBufferManager.TotalBuffs
|
||||
@ -32,7 +32,7 @@ telemetry packets RefPackets {
|
||||
FileHandling.fileDownlink.Warnings
|
||||
FileHandling.fileManager.Errors
|
||||
|
||||
ComCcsds.cmdSeq.CS_Errors
|
||||
Ref.cmdSeq.CS_Errors
|
||||
ComCcsds.commsBufferManager.NoBuffs
|
||||
ComCcsds.commsBufferManager.EmptyBuffs
|
||||
|
||||
|
||||
@ -8,20 +8,19 @@
|
||||
// ALL RIGHTS RESERVED. United States Government Sponsorship
|
||||
// acknowledged.
|
||||
// ======================================================================
|
||||
|
||||
// Provides access to autocoded functions
|
||||
#include <Ref/Top/RefTopologyAc.hpp>
|
||||
|
||||
// Necessary project-specified types
|
||||
#include <Os/Console.hpp>
|
||||
#include <Fw/Types/MallocAllocator.hpp>
|
||||
|
||||
// Used for 1Hz synthetic cycling
|
||||
#include <Os/Mutex.hpp>
|
||||
|
||||
// Allows easy reference to objects in FPP/autocoder required namespaces
|
||||
using namespace Ref;
|
||||
|
||||
// Instantiate a system logger that will handle Fw::Logger::log calls
|
||||
Os::Console logger;
|
||||
// Instantiate a malloc allocator for cmdSeq buffer allocation
|
||||
Fw::MallocAllocator mallocator;
|
||||
|
||||
// The reference topology divides the incoming clock signal (1Hz) into sub-signals: 1Hz, 1/2Hz, and 1/4Hz and
|
||||
// zero offset for all the dividers
|
||||
@ -33,6 +32,10 @@ U32 rateGroup1Context[Svc::ActiveRateGroup::CONNECTION_COUNT_MAX] = {};
|
||||
U32 rateGroup2Context[Svc::ActiveRateGroup::CONNECTION_COUNT_MAX] = {};
|
||||
U32 rateGroup3Context[Svc::ActiveRateGroup::CONNECTION_COUNT_MAX] = {};
|
||||
|
||||
enum TopologyConstants {
|
||||
COMM_PRIORITY = 100,
|
||||
};
|
||||
|
||||
/**
|
||||
* \brief configure/setup components in project-specific way
|
||||
*
|
||||
@ -48,6 +51,9 @@ void configureTopology() {
|
||||
rateGroup1Comp.configure(rateGroup1Context, FW_NUM_ARRAY_ELEMENTS(rateGroup1Context));
|
||||
rateGroup2Comp.configure(rateGroup2Context, FW_NUM_ARRAY_ELEMENTS(rateGroup2Context));
|
||||
rateGroup3Comp.configure(rateGroup3Context, FW_NUM_ARRAY_ELEMENTS(rateGroup3Context));
|
||||
|
||||
// Command sequencer needs to allocate memory to hold contents of command sequences
|
||||
cmdSeq.allocateBuffer(0, mallocator, 5 * 1024);
|
||||
}
|
||||
|
||||
// Public functions for use in main program are namespaced with deployment name Ref
|
||||
@ -63,12 +69,20 @@ void setupTopology(const TopologyState& state) {
|
||||
regCommands();
|
||||
// Autocoded configuration. Function provided by autocoder.
|
||||
configComponents(state);
|
||||
if (state.hostname != nullptr && state.port != 0) {
|
||||
comDriver.configure(state.hostname, state.port);
|
||||
}
|
||||
// Project-specific component configuration. Function provided above. May be inlined, if desired.
|
||||
configureTopology();
|
||||
// Autocoded parameter loading. Function provided by autocoder.
|
||||
loadParameters();
|
||||
// Autocoded task kick-off (active components). Function provided by autocoder.
|
||||
startTasks(state);
|
||||
//Initialize socket client communication if and only if there is a valid specification
|
||||
if (state.hostname != nullptr && state.port != 0) {
|
||||
Os::TaskString name("ReceiveTask");
|
||||
comDriver.start(name, COMM_PRIORITY, Default::STACK_SIZE);
|
||||
}
|
||||
}
|
||||
|
||||
void startRateGroups(Fw::TimeInterval interval) {
|
||||
@ -88,5 +102,12 @@ void teardownTopology(const TopologyState& state) {
|
||||
stopTasks(state);
|
||||
freeThreads(state);
|
||||
tearDownComponents(state);
|
||||
|
||||
//Stop the comDriver component, free thread
|
||||
comDriver.stop();
|
||||
(void)comDriver.join();
|
||||
|
||||
// Resource deallocation
|
||||
cmdSeq.deallocateBuffer(mallocator);
|
||||
}
|
||||
} // namespace Ref
|
||||
|
||||
@ -21,10 +21,15 @@
|
||||
#include "Svc/Subtopologies/FileHandling/PingEntries.hpp"
|
||||
|
||||
// SubtopologyTopologyDefs includes
|
||||
#include "Svc/Subtopologies/CdhCore/SubtopologyTopologyDefs.hpp"
|
||||
#include "Svc/Subtopologies/ComCcsds/SubtopologyTopologyDefs.hpp"
|
||||
#include "Svc/Subtopologies/DataProducts/SubtopologyTopologyDefs.hpp"
|
||||
#include "Svc/Subtopologies/FileHandling/SubtopologyTopologyDefs.hpp"
|
||||
|
||||
//ComCcsds Enum Includes
|
||||
#include "Svc/Subtopologies/ComCcsds/Ports_ComPacketQueueEnumAc.hpp"
|
||||
#include "Svc/Subtopologies/ComCcsds/Ports_ComBufferQueueEnumAc.hpp"
|
||||
|
||||
/**
|
||||
* \brief required ping constants
|
||||
*
|
||||
@ -50,6 +55,7 @@ namespace PingEntries {
|
||||
namespace Ref_rateGroup1Comp {enum { WARN = 3, FATAL = 5 };}
|
||||
namespace Ref_rateGroup2Comp {enum { WARN = 3, FATAL = 5 };}
|
||||
namespace Ref_rateGroup3Comp {enum { WARN = 3, FATAL = 5 };}
|
||||
namespace Ref_cmdSeq {enum { WARN = 3, FATAL = 5 };}
|
||||
} // namespace PingEntries
|
||||
|
||||
// Definitions are placed within a namespace named after the deployment
|
||||
@ -64,7 +70,12 @@ namespace Ref {
|
||||
* fields, which are derived by command line inputs.
|
||||
*/
|
||||
struct TopologyState {
|
||||
ComCcsds::SubtopologyState comCcsds; //!< Subtopology state for ComCcsds
|
||||
const char* hostname; //!< Hostname for TCP communication
|
||||
U16 port; //!< Port for TCP communication
|
||||
CdhCore::SubtopologyState cdhCore; //!< Subtopology state for CdhCore
|
||||
ComCcsds::SubtopologyState comCcsds; //!< Subtopology state for ComCcsds
|
||||
DataProducts::SubtopologyState dataProducts; //!< Subtopology state for DataProducts
|
||||
FileHandling::SubtopologyState fileHandling; //!< Subtopology state for FileHandling
|
||||
};
|
||||
|
||||
namespace PingEntries = ::PingEntries;
|
||||
|
||||
@ -1,5 +1,18 @@
|
||||
module Ref {
|
||||
|
||||
# ----------------------------------------------------------------------
|
||||
# Base ID Convention
|
||||
# ----------------------------------------------------------------------
|
||||
#
|
||||
# All Base IDs follow the 8-digit hex format: 0xDSSCCxxx
|
||||
#
|
||||
# Where:
|
||||
# D = Deployment digit (1-F)
|
||||
# SS = Subtopology digits (00 for main topology, 01-FF)
|
||||
# CC = Component digits (00-FF)
|
||||
# xxx = Reserved for internal component items (events, commands, telemetry)
|
||||
#
|
||||
|
||||
# ----------------------------------------------------------------------
|
||||
# Defaults
|
||||
# ----------------------------------------------------------------------
|
||||
@ -13,67 +26,74 @@ module Ref {
|
||||
# Active component instances
|
||||
# ----------------------------------------------------------------------
|
||||
|
||||
instance blockDrv: Ref.BlockDriver base id 0x01000000 \
|
||||
instance blockDrv: Ref.BlockDriver base id 0x10000000 \
|
||||
queue size Default.QUEUE_SIZE \
|
||||
stack size Default.STACK_SIZE \
|
||||
priority 140
|
||||
|
||||
instance rateGroup1Comp: Svc.ActiveRateGroup base id 0x01010000 \
|
||||
instance rateGroup1Comp: Svc.ActiveRateGroup base id 0x10001000 \
|
||||
queue size Default.QUEUE_SIZE \
|
||||
stack size Default.STACK_SIZE \
|
||||
priority 120
|
||||
|
||||
instance rateGroup2Comp: Svc.ActiveRateGroup base id 0x01020000 \
|
||||
instance rateGroup2Comp: Svc.ActiveRateGroup base id 0x10002000 \
|
||||
queue size Default.QUEUE_SIZE \
|
||||
stack size Default.STACK_SIZE \
|
||||
priority 119
|
||||
|
||||
instance rateGroup3Comp: Svc.ActiveRateGroup base id 0x01030000 \
|
||||
instance rateGroup3Comp: Svc.ActiveRateGroup base id 0x10003000 \
|
||||
queue size Default.QUEUE_SIZE \
|
||||
stack size Default.STACK_SIZE \
|
||||
priority 118
|
||||
|
||||
instance pingRcvr: Ref.PingReceiver base id 0x01040000 \
|
||||
instance pingRcvr: Ref.PingReceiver base id 0x10004000 \
|
||||
queue size Default.QUEUE_SIZE \
|
||||
stack size Default.STACK_SIZE \
|
||||
priority 100
|
||||
|
||||
instance typeDemo: Ref.TypeDemo base id 0x01050000
|
||||
instance typeDemo: Ref.TypeDemo base id 0x10005000
|
||||
|
||||
instance cmdSeq: Svc.CmdSequencer base id 0x10006000 \
|
||||
queue size Default.QUEUE_SIZE \
|
||||
stack size Default.STACK_SIZE \
|
||||
priority 97
|
||||
|
||||
# ----------------------------------------------------------------------
|
||||
# Queued component instances
|
||||
# ----------------------------------------------------------------------
|
||||
|
||||
instance sendBuffComp: Ref.SendBuff base id 0x01060000 \
|
||||
instance sendBuffComp: Ref.SendBuff base id 0x10010000 \
|
||||
queue size Default.QUEUE_SIZE
|
||||
|
||||
instance SG1: Ref.SignalGen base id 0x01070000 \
|
||||
instance SG1: Ref.SignalGen base id 0x10011000 \
|
||||
queue size Default.QUEUE_SIZE
|
||||
|
||||
instance SG2: Ref.SignalGen base id 0x01080000 \
|
||||
instance SG2: Ref.SignalGen base id 0x10012000 \
|
||||
queue size Default.QUEUE_SIZE
|
||||
|
||||
instance SG3: Ref.SignalGen base id 0x01090000 \
|
||||
instance SG3: Ref.SignalGen base id 0x10013000 \
|
||||
queue size Default.QUEUE_SIZE
|
||||
|
||||
instance SG4: Ref.SignalGen base id 0x010A0000 \
|
||||
instance SG4: Ref.SignalGen base id 0x10014000 \
|
||||
queue size Default.QUEUE_SIZE
|
||||
|
||||
instance SG5: Ref.SignalGen base id 0x010B0000 \
|
||||
instance SG5: Ref.SignalGen base id 0x10015000 \
|
||||
queue size Default.QUEUE_SIZE
|
||||
|
||||
# ----------------------------------------------------------------------
|
||||
# Passive component instances
|
||||
# ----------------------------------------------------------------------
|
||||
|
||||
instance posixTime: Svc.PosixTime base id 0x010C0000
|
||||
instance posixTime: Svc.PosixTime base id 0x10020000
|
||||
|
||||
instance rateGroupDriverComp: Svc.RateGroupDriver base id 0x010D0000
|
||||
instance rateGroupDriverComp: Svc.RateGroupDriver base id 0x10021000
|
||||
|
||||
instance recvBuffComp: Ref.RecvBuff base id 0x010E0000
|
||||
instance recvBuffComp: Ref.RecvBuff base id 0x10022000
|
||||
|
||||
instance systemResources: Svc.SystemResources base id 0x010F0000
|
||||
instance systemResources: Svc.SystemResources base id 0x10023000
|
||||
|
||||
instance linuxTimer: Svc.LinuxTimer base id 0x01100000
|
||||
instance linuxTimer: Svc.LinuxTimer base id 0x10024000
|
||||
|
||||
instance comDriver: Drv.TcpClient base id 0x10025000
|
||||
|
||||
}
|
||||
|
||||
@ -42,6 +42,8 @@ module Ref {
|
||||
instance typeDemo
|
||||
instance systemResources
|
||||
instance linuxTimer
|
||||
instance comDriver
|
||||
instance cmdSeq
|
||||
|
||||
# ----------------------------------------------------------------------
|
||||
# Pattern graph specifiers
|
||||
@ -87,7 +89,7 @@ module Ref {
|
||||
|
||||
# Rate group 2
|
||||
rateGroupDriverComp.CycleOut[Ports_RateGroups.rateGroup2] -> rateGroup2Comp.CycleIn
|
||||
rateGroup2Comp.RateGroupMemberOut[0] -> ComCcsds.cmdSeq.schedIn
|
||||
rateGroup2Comp.RateGroupMemberOut[0] -> cmdSeq.schedIn
|
||||
rateGroup2Comp.RateGroupMemberOut[1] -> sendBuffComp.SchedIn
|
||||
rateGroup2Comp.RateGroupMemberOut[2] -> SG3.schedIn
|
||||
rateGroup2Comp.RateGroupMemberOut[3] -> SG4.schedIn
|
||||
@ -103,6 +105,21 @@ module Ref {
|
||||
rateGroup3Comp.RateGroupMemberOut[6] -> DataProducts.dpMgr.schedIn
|
||||
}
|
||||
|
||||
connections Communications {
|
||||
# ComDriver buffer allocations
|
||||
comDriver.allocate -> ComCcsds.commsBufferManager.bufferGetCallee
|
||||
comDriver.deallocate -> ComCcsds.commsBufferManager.bufferSendIn
|
||||
|
||||
# ComDriver <-> ComStub (Uplink)
|
||||
comDriver.$recv -> ComCcsds.comStub.drvReceiveIn
|
||||
ComCcsds.comStub.drvReceiveReturnOut -> comDriver.recvReturnIn
|
||||
|
||||
# ComStub <-> ComDriver (Downlink)
|
||||
ComCcsds.comStub.drvSendOut -> comDriver.$send
|
||||
comDriver.sendReturnOut -> ComCcsds.comStub.drvSendReturnIn
|
||||
comDriver.ready -> ComCcsds.comStub.drvConnected
|
||||
}
|
||||
|
||||
connections Ref {
|
||||
sendBuffComp.Data -> blockDrv.BufferIn
|
||||
blockDrv.BufferOut -> recvBuffComp.Data
|
||||
@ -126,14 +143,14 @@ module Ref {
|
||||
# Router <-> CmdDispatcher
|
||||
ComCcsds.fprimeRouter.commandOut -> CdhCore.cmdDisp.seqCmdBuff
|
||||
CdhCore.cmdDisp.seqCmdStatus -> ComCcsds.fprimeRouter.cmdResponseIn
|
||||
ComCcsds.cmdSeq.comCmdOut -> CdhCore.cmdDisp.seqCmdBuff
|
||||
CdhCore.cmdDisp.seqCmdStatus -> ComCcsds.cmdSeq.cmdResponseIn
|
||||
cmdSeq.comCmdOut -> CdhCore.cmdDisp.seqCmdBuff
|
||||
CdhCore.cmdDisp.seqCmdStatus -> cmdSeq.cmdResponseIn
|
||||
}
|
||||
|
||||
connections ComCcsds_FileHandling {
|
||||
# File Downlink <-> ComQueue
|
||||
FileHandling.fileDownlink.bufferSendOut -> ComCcsds.comQueue.bufferQueueIn[FileHandling.Ports_ComBufferQueue.FILE_DOWNLINK]
|
||||
ComCcsds.comQueue.bufferReturnOut[FileHandling.Ports_ComBufferQueue.FILE_DOWNLINK] -> FileHandling.fileDownlink.bufferReturn
|
||||
FileHandling.fileDownlink.bufferSendOut -> ComCcsds.comQueue.bufferQueueIn[ComCcsds.Ports_ComBufferQueue.FILE]
|
||||
ComCcsds.comQueue.bufferReturnOut[ComCcsds.Ports_ComBufferQueue.FILE] -> FileHandling.fileDownlink.bufferReturn
|
||||
|
||||
# Router <-> FileUplink
|
||||
ComCcsds.fprimeRouter.fileOut -> FileHandling.fileUplink.bufferSendIn
|
||||
|
||||
@ -285,5 +285,5 @@ def test_seqgen(fprime_test_api):
|
||||
== 0
|
||||
), "Failed to run fprime-seqgen"
|
||||
fprime_test_api.send_and_assert_command(
|
||||
"ComCcsds.cmdSeq.CS_RUN", args=["/tmp/ref_test_int.bin", "BLOCK"], max_delay=5
|
||||
"Ref.cmdSeq.CS_RUN", args=["/tmp/ref_test_int.bin", "BLOCK"], max_delay=5
|
||||
)
|
||||
|
||||
@ -4,3 +4,19 @@ add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ComFprime/")
|
||||
add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/FileHandling/")
|
||||
add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/DataProducts/")
|
||||
add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ComLoggerTee/")
|
||||
|
||||
add_custom_target(
|
||||
Svc_Subtopologies
|
||||
DEPENDS
|
||||
Svc_Subtopologies_CdhCore
|
||||
Svc_Subtopologies_CdhCore_CdhCoreConfig
|
||||
Svc_Subtopologies_ComCcsds
|
||||
Svc_Subtopologies_ComCcsds_ComCcsdsConfig
|
||||
Svc_Subtopologies_ComFprime
|
||||
Svc_Subtopologies_ComFprime_ComFprimeConfig
|
||||
Svc_Subtopologies_FileHandling
|
||||
Svc_Subtopologies_FileHandling_FileHandlingConfig
|
||||
Svc_Subtopologies_DataProducts
|
||||
Svc_Subtopologies_DataProducts_DataProductsConfig
|
||||
Svc_Subtopologies_ComLoggerTee
|
||||
)
|
||||
@ -1,9 +1,11 @@
|
||||
add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/CdhCoreConfig/")
|
||||
|
||||
register_fprime_module(
|
||||
EXCLUDE_FROM_ALL
|
||||
AUTOCODER_INPUTS
|
||||
"${CMAKE_CURRENT_LIST_DIR}/CdhCore.fpp"
|
||||
HEADERS
|
||||
"${CMAKE_CURRENT_LIST_DIR}/SubtopologyTopologyDefs.hpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/PingEntries.hpp"
|
||||
INTERFACE
|
||||
DEPENDS
|
||||
|
||||
@ -2,12 +2,12 @@ module CdhCore {
|
||||
# ----------------------------------------------------------------------
|
||||
# Active Components
|
||||
# ----------------------------------------------------------------------
|
||||
instance cmdDisp: Svc.CommandDispatcher base id CdhCoreConfig.BASE_ID + 0x0100 \
|
||||
instance cmdDisp: Svc.CommandDispatcher base id CdhCoreConfig.BASE_ID + 0x00000 \
|
||||
queue size CdhCoreConfig.QueueSizes.cmdDisp \
|
||||
stack size CdhCoreConfig.StackSizes.cmdDisp \
|
||||
priority CdhCoreConfig.Priorities.cmdDisp
|
||||
|
||||
instance events: Svc.EventManager base id CdhCoreConfig.BASE_ID + 0x0200 \
|
||||
instance events: Svc.EventManager base id CdhCoreConfig.BASE_ID + 0x001000 \
|
||||
queue size CdhCoreConfig.QueueSizes.events \
|
||||
stack size CdhCoreConfig.StackSizes.events \
|
||||
priority CdhCoreConfig.Priorities.events
|
||||
@ -15,7 +15,7 @@ module CdhCore {
|
||||
# ----------------------------------------------------------------------
|
||||
# Queued Components
|
||||
# ----------------------------------------------------------------------
|
||||
instance $health: Svc.Health base id CdhCoreConfig.BASE_ID + 0x0300 \
|
||||
instance $health: Svc.Health base id CdhCoreConfig.BASE_ID + 0x002000 \
|
||||
queue size CdhCoreConfig.QueueSizes.$health \
|
||||
{
|
||||
phase Fpp.ToCpp.Phases.configConstants """
|
||||
@ -36,7 +36,7 @@ module CdhCore {
|
||||
# ----------------------------------------------------------------------
|
||||
# Passive Components
|
||||
# ----------------------------------------------------------------------
|
||||
instance version: Svc.Version base id CdhCoreConfig.BASE_ID + 0x0400 \
|
||||
instance version: Svc.Version base id CdhCoreConfig.BASE_ID + 0x003000 \
|
||||
{
|
||||
phase Fpp.ToCpp.Phases.configComponents """
|
||||
// Startup TLM and Config verbosity for Versions
|
||||
@ -44,9 +44,9 @@ module CdhCore {
|
||||
"""
|
||||
}
|
||||
|
||||
instance textLogger: Svc.PassiveTextLogger base id CdhCoreConfig.BASE_ID + 0x0500
|
||||
instance textLogger: Svc.PassiveTextLogger base id CdhCoreConfig.BASE_ID + 0x004000
|
||||
|
||||
instance fatalAdapter: Svc.AssertFatalAdapter base id CdhCoreConfig.BASE_ID + 0x0600
|
||||
instance fatalAdapter: Svc.AssertFatalAdapter base id CdhCoreConfig.BASE_ID + 0x005000
|
||||
|
||||
topology Subtopology {
|
||||
#Active Components
|
||||
|
||||
@ -1,4 +1,5 @@
|
||||
register_fprime_config(
|
||||
EXCLUDE_FROM_ALL
|
||||
AUTOCODER_INPUTS
|
||||
"${CMAKE_CURRENT_LIST_DIR}/CdhCoreConfig.fpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/CdhCoreFatalHandlerConfig.fpp"
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
module CdhCoreConfig {
|
||||
#Base ID for the CdhCore Subtopology, all components are offsets from this base ID
|
||||
constant BASE_ID = 0x10100000
|
||||
constant BASE_ID = 0x01000000
|
||||
|
||||
module QueueSizes {
|
||||
constant cmdDisp = 10
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
module CdhCore {
|
||||
|
||||
# Update this as a custom fatal handler if needed
|
||||
instance fatalHandler: Svc.FatalHandler base id CdhCoreConfig.BASE_ID + 0x0800
|
||||
instance fatalHandler: Svc.FatalHandler base id CdhCoreConfig.BASE_ID + 0x07000
|
||||
|
||||
}
|
||||
|
||||
@ -1,12 +1,12 @@
|
||||
module CdhCore{
|
||||
|
||||
instance tlmSend: Svc.TlmChan base id CdhCoreConfig.BASE_ID + 0x0700 \
|
||||
instance tlmSend: Svc.TlmChan base id CdhCoreConfig.BASE_ID + 0x06000 \
|
||||
queue size CdhCoreConfig.QueueSizes.tlmSend \
|
||||
stack size CdhCoreConfig.StackSizes.tlmSend \
|
||||
priority CdhCoreConfig.Priorities.tlmSend \
|
||||
|
||||
# Uncomment the following block and comment the above block to use TlmPacketizer instead of TlmChan
|
||||
#instance tlmSend: Svc.TlmPacketizer base id CdhCoreConfig.BASE_ID + 0x0700 \
|
||||
#instance tlmSend: Svc.TlmPacketizer base id CdhCoreConfig.BASE_ID + 0x06000 \
|
||||
# queue size CdhCoreConfig.QueueSizes.tlmSend \
|
||||
# stack size CdhCoreConfig.StackSizes.tlmSend \
|
||||
# priority CdhCoreConfig.Priorities.tlmSend \
|
||||
|
||||
17
Svc/Subtopologies/CdhCore/SubtopologyTopologyDefs.hpp
Normal file
17
Svc/Subtopologies/CdhCore/SubtopologyTopologyDefs.hpp
Normal file
@ -0,0 +1,17 @@
|
||||
#ifndef CDHCORESUBTOPOLOGY_DEFS_HPP
|
||||
#define CDHCORESUBTOPOLOGY_DEFS_HPP
|
||||
|
||||
#include "Svc/Subtopologies/CdhCore/CdhCoreConfig/FppConstantsAc.hpp"
|
||||
|
||||
namespace CdhCore {
|
||||
// State for topology construction
|
||||
struct SubtopologyState {
|
||||
// Empty - no external state needed for CdhCore subtopology
|
||||
};
|
||||
|
||||
struct TopologyState {
|
||||
SubtopologyState cdhCore;
|
||||
};
|
||||
}
|
||||
|
||||
#endif
|
||||
@ -1,8 +1,8 @@
|
||||
restrict_platforms(Posix SOCKETS)
|
||||
|
||||
add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ComCcsdsConfig/")
|
||||
|
||||
register_fprime_module(
|
||||
EXCLUDE_FROM_ALL
|
||||
AUTOCODER_INPUTS
|
||||
"${CMAKE_CURRENT_LIST_DIR}/ComCcsds.fpp"
|
||||
HEADERS
|
||||
|
||||
@ -3,39 +3,36 @@ module ComCcsds {
|
||||
# ComPacket Queue enum for queue types
|
||||
enum Ports_ComPacketQueue {
|
||||
EVENTS,
|
||||
TELEMETRY,
|
||||
FILE_QUEUE
|
||||
TELEMETRY
|
||||
}
|
||||
|
||||
enum Ports_ComBufferQueue {
|
||||
FILE
|
||||
}
|
||||
|
||||
# ----------------------------------------------------------------------
|
||||
# Active Components
|
||||
# ----------------------------------------------------------------------
|
||||
instance comQueue: Svc.ComQueue base id ComCcsdsConfig.BASE_ID + 0x0100 \
|
||||
instance comQueue: Svc.ComQueue base id ComCcsdsConfig.BASE_ID + 0x00000 \
|
||||
queue size ComCcsdsConfig.QueueSizes.comQueue \
|
||||
stack size ComCcsdsConfig.StackSizes.comQueue \
|
||||
priority ComCcsdsConfig.Priorities.comQueue \
|
||||
{
|
||||
phase Fpp.ToCpp.Phases.configConstants """
|
||||
enum {
|
||||
EVENTS,
|
||||
TELEMETRY,
|
||||
FILE_QUEUE
|
||||
};
|
||||
"""
|
||||
phase Fpp.ToCpp.Phases.configComponents """
|
||||
using namespace ComCcsds;
|
||||
Svc::ComQueue::QueueConfigurationTable configurationTable;
|
||||
|
||||
// Events (highest-priority)
|
||||
configurationTable.entries[ConfigConstants::ComCcsds_comQueue::EVENTS].depth = ComCcsdsConfig::QueueDepths::events;
|
||||
configurationTable.entries[ConfigConstants::ComCcsds_comQueue::EVENTS].priority = ComCcsdsConfig::QueuePriorities::events;
|
||||
configurationTable.entries[Ports_ComPacketQueue::EVENTS].depth = ComCcsdsConfig::QueueDepths::events;
|
||||
configurationTable.entries[Ports_ComPacketQueue::EVENTS].priority = ComCcsdsConfig::QueuePriorities::events;
|
||||
|
||||
// Telemetry
|
||||
configurationTable.entries[ConfigConstants::ComCcsds_comQueue::TELEMETRY].depth = ComCcsdsConfig::QueueDepths::tlm;
|
||||
configurationTable.entries[ConfigConstants::ComCcsds_comQueue::TELEMETRY].priority = ComCcsdsConfig::QueuePriorities::tlm;
|
||||
configurationTable.entries[Ports_ComPacketQueue::TELEMETRY].depth = ComCcsdsConfig::QueueDepths::tlm;
|
||||
configurationTable.entries[Ports_ComPacketQueue::TELEMETRY].priority = ComCcsdsConfig::QueuePriorities::tlm;
|
||||
|
||||
// File Downlink Queue
|
||||
configurationTable.entries[ConfigConstants::ComCcsds_comQueue::FILE_QUEUE].depth = ComCcsdsConfig::QueueDepths::file;
|
||||
configurationTable.entries[ConfigConstants::ComCcsds_comQueue::FILE_QUEUE].priority = ComCcsdsConfig::QueuePriorities::file;
|
||||
// File Downlink Queue (buffer queue using NUM_CONSTANTS offset)
|
||||
configurationTable.entries[Ports_ComPacketQueue::NUM_CONSTANTS + Ports_ComBufferQueue::FILE].depth = ComCcsdsConfig::QueueDepths::file;
|
||||
configurationTable.entries[Ports_ComPacketQueue::NUM_CONSTANTS + Ports_ComBufferQueue::FILE].priority = ComCcsdsConfig::QueuePriorities::file;
|
||||
|
||||
// Allocation identifier is 0 as the MallocAllocator discards it
|
||||
ComCcsds::comQueue.configure(configurationTable, 0, ComCcsds::Allocation::memAllocator);
|
||||
@ -45,24 +42,10 @@ module ComCcsds {
|
||||
"""
|
||||
}
|
||||
|
||||
instance cmdSeq: Svc.CmdSequencer base id ComCcsdsConfig.BASE_ID + 0x0200 \
|
||||
queue size ComCcsdsConfig.QueueSizes.cmdSeq \
|
||||
stack size ComCcsdsConfig.StackSizes.cmdSeq \
|
||||
priority ComCcsdsConfig.Priorities.cmdSeq \
|
||||
{
|
||||
phase Fpp.ToCpp.Phases.configComponents """
|
||||
ComCcsds::cmdSeq.allocateBuffer(0, ComCcsds::Allocation::memAllocator, ComCcsdsConfig::BuffMgr::cmdSeqBuffSize);
|
||||
"""
|
||||
|
||||
phase Fpp.ToCpp.Phases.tearDownComponents """
|
||||
ComCcsds::cmdSeq.deallocateBuffer(ComCcsds::Allocation::memAllocator);
|
||||
"""
|
||||
}
|
||||
|
||||
# ----------------------------------------------------------------------
|
||||
# Passive Components
|
||||
# ----------------------------------------------------------------------
|
||||
instance frameAccumulator: Svc.FrameAccumulator base id ComCcsdsConfig.BASE_ID + 0x0500 \
|
||||
instance frameAccumulator: Svc.FrameAccumulator base id ComCcsdsConfig.BASE_ID + 0x01000 \
|
||||
{
|
||||
|
||||
phase Fpp.ToCpp.Phases.configObjects """
|
||||
@ -82,7 +65,7 @@ module ComCcsds {
|
||||
"""
|
||||
}
|
||||
|
||||
instance commsBufferManager: Svc.BufferManager base id ComCcsdsConfig.BASE_ID + 0x0600 \
|
||||
instance commsBufferManager: Svc.BufferManager base id ComCcsdsConfig.BASE_ID + 0x02000 \
|
||||
{
|
||||
phase Fpp.ToCpp.Phases.configObjects """
|
||||
Svc::BufferManager::BufferBins bins;
|
||||
@ -107,31 +90,29 @@ module ComCcsds {
|
||||
"""
|
||||
}
|
||||
|
||||
instance fprimeRouter: Svc.FprimeRouter base id ComCcsdsConfig.BASE_ID + 0x0700 \
|
||||
instance fprimeRouter: Svc.FprimeRouter base id ComCcsdsConfig.BASE_ID + 0x03000 \
|
||||
|
||||
instance comStub: Svc.ComStub base id ComCcsdsConfig.BASE_ID + 0x0800 \
|
||||
instance comStub: Svc.ComStub base id ComCcsdsConfig.BASE_ID + 0x04000 \
|
||||
|
||||
instance tcDeframer: Svc.Ccsds.TcDeframer base id ComCcsdsConfig.BASE_ID + 0x0900 \
|
||||
instance tcDeframer: Svc.Ccsds.TcDeframer base id ComCcsdsConfig.BASE_ID + 0x05000 \
|
||||
|
||||
instance spacePacketDeframer: Svc.Ccsds.SpacePacketDeframer base id ComCcsdsConfig.BASE_ID + 0x0A00 \
|
||||
instance spacePacketDeframer: Svc.Ccsds.SpacePacketDeframer base id ComCcsdsConfig.BASE_ID + 0x06000 \
|
||||
|
||||
instance tmFramer: Svc.Ccsds.TmFramer base id ComCcsdsConfig.BASE_ID + 0x0B00 \
|
||||
instance tmFramer: Svc.Ccsds.TmFramer base id ComCcsdsConfig.BASE_ID + 0x07000 \
|
||||
|
||||
instance spacePacketFramer: Svc.Ccsds.SpacePacketFramer base id ComCcsdsConfig.BASE_ID + 0x0C00 \
|
||||
instance spacePacketFramer: Svc.Ccsds.SpacePacketFramer base id ComCcsdsConfig.BASE_ID + 0x08000 \
|
||||
|
||||
instance apidManager: Svc.Ccsds.ApidManager base id ComCcsdsConfig.BASE_ID + 0x0D00 \
|
||||
instance apidManager: Svc.Ccsds.ApidManager base id ComCcsdsConfig.BASE_ID + 0x09000 \
|
||||
|
||||
topology Subtopology {
|
||||
# Active Components
|
||||
instance comQueue
|
||||
instance cmdSeq
|
||||
|
||||
# Passive Components
|
||||
instance commsBufferManager
|
||||
instance frameAccumulator
|
||||
instance fprimeRouter
|
||||
instance comStub
|
||||
instance comDriver
|
||||
instance tcDeframer
|
||||
instance spacePacketDeframer
|
||||
instance tmFramer
|
||||
@ -154,10 +135,6 @@ module ComCcsds {
|
||||
# Framer <-> ComStub
|
||||
tmFramer.dataOut -> comStub.dataIn
|
||||
comStub.dataReturnOut -> tmFramer.dataReturnIn
|
||||
# ComStub <-> ComDriver
|
||||
comStub.drvSendOut -> comDriver.$send
|
||||
comDriver.sendReturnOut -> comStub.drvSendReturnIn
|
||||
comDriver.ready -> comStub.drvConnected
|
||||
# ComStatus
|
||||
comStub.comStatusOut -> tmFramer.comStatusIn
|
||||
tmFramer.comStatusOut -> spacePacketFramer.comStatusIn
|
||||
@ -165,12 +142,6 @@ module ComCcsds {
|
||||
}
|
||||
|
||||
connections Uplink {
|
||||
# ComDriver buffer allocations
|
||||
comDriver.allocate -> commsBufferManager.bufferGetCallee
|
||||
comDriver.deallocate -> commsBufferManager.bufferSendIn
|
||||
# ComDriver <-> ComStub
|
||||
comDriver.$recv -> comStub.drvReceiveIn
|
||||
comStub.drvReceiveReturnOut -> comDriver.recvReturnIn
|
||||
# ComStub <-> FrameAccumulator
|
||||
comStub.dataOut -> frameAccumulator.dataIn
|
||||
frameAccumulator.dataReturnOut -> comStub.dataReturnIn
|
||||
|
||||
@ -1,11 +1,11 @@
|
||||
register_fprime_config(
|
||||
EXCLUDE_FROM_ALL
|
||||
SOURCES
|
||||
"${CMAKE_CURRENT_LIST_DIR}/ComCcsdsSubtopologyConfig.cpp"
|
||||
HEADERS
|
||||
"${CMAKE_CURRENT_LIST_DIR}/ComCcsdsSubtopologyConfig.hpp"
|
||||
AUTOCODER_INPUTS
|
||||
"${CMAKE_CURRENT_LIST_DIR}/ComCcsdsConfig.fpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/ComCcsdsComDriverConfig.fpp"
|
||||
DEPENDS
|
||||
Fw_Types
|
||||
)
|
||||
|
||||
@ -1,28 +0,0 @@
|
||||
module ComCcsds {
|
||||
# Communications driver. May be swapped out with other comm drivers like UART in this file
|
||||
# to use another driver in the Comms Subtopology
|
||||
instance comDriver: Drv.TcpClient base id ComCcsdsConfig.BASE_ID + 0x0B00 \
|
||||
{
|
||||
phase Fpp.ToCpp.Phases.configComponents """
|
||||
if (state.comCcsds.hostname != nullptr && state.comCcsds.port != 0) {
|
||||
ComCcsds::comDriver.configure(state.comCcsds.hostname, state.comCcsds.port);
|
||||
}
|
||||
"""
|
||||
|
||||
phase Fpp.ToCpp.Phases.startTasks """
|
||||
// Initialize socket client communication if and only if there is a valid specification
|
||||
if (state.comCcsds.hostname != nullptr && state.comCcsds.port != 0) {
|
||||
Os::TaskString name("ReceiveTask");
|
||||
ComCcsds::comDriver.start(name, ComCcsdsConfig::Priorities::comDriver, ComCcsdsConfig::StackSizes::comDriver);
|
||||
}
|
||||
"""
|
||||
|
||||
phase Fpp.ToCpp.Phases.stopTasks """
|
||||
ComCcsds::comDriver.stop();
|
||||
"""
|
||||
|
||||
phase Fpp.ToCpp.Phases.freeThreads """
|
||||
(void)ComCcsds::comDriver.join();
|
||||
"""
|
||||
}
|
||||
}
|
||||
@ -1,22 +1,17 @@
|
||||
module ComCcsdsConfig {
|
||||
#Base ID for the ComCcsds Subtopology, all components are offsets from this base ID
|
||||
constant BASE_ID = 0x10300000
|
||||
constant BASE_ID = 0x02000000
|
||||
|
||||
module QueueSizes {
|
||||
constant comQueue = 50
|
||||
constant cmdSeq = 10
|
||||
}
|
||||
|
||||
module StackSizes {
|
||||
constant comQueue = 64 * 1024
|
||||
constant cmdSeq = 64 * 1024
|
||||
constant comDriver = 100
|
||||
}
|
||||
|
||||
module Priorities {
|
||||
constant comQueue = 101
|
||||
constant cmdSeq = 100
|
||||
constant comDriver = 100
|
||||
}
|
||||
|
||||
# Queue configuration constants
|
||||
@ -34,7 +29,6 @@ module ComCcsdsConfig {
|
||||
|
||||
# Buffer management constants
|
||||
module BuffMgr {
|
||||
constant cmdSeqBuffSize = 5 * 1024
|
||||
constant frameAccumulatorSize = 2048
|
||||
constant commsBuffSize = 2048
|
||||
constant commsFileBuffSize = 3000
|
||||
|
||||
@ -3,7 +3,7 @@
|
||||
#define COMCCSDS_PINGENTRIES_HPP
|
||||
|
||||
namespace PingEntries {
|
||||
namespace ComCcsds_cmdSeq {enum { WARN = 3, FATAL = 5 };}
|
||||
// No ping-enabled components in ComCcsds subtopology
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
@ -9,8 +9,7 @@
|
||||
|
||||
namespace ComCcsds {
|
||||
struct SubtopologyState {
|
||||
const char* hostname;
|
||||
U16 port;
|
||||
// Empty - no external state needed for ComCcsds subtopology
|
||||
};
|
||||
|
||||
struct TopologyState {
|
||||
|
||||
@ -1,8 +1,8 @@
|
||||
restrict_platforms(Posix SOCKETS)
|
||||
|
||||
add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ComFprimeConfig/")
|
||||
|
||||
register_fprime_module(
|
||||
EXCLUDE_FROM_ALL
|
||||
AUTOCODER_INPUTS
|
||||
"${CMAKE_CURRENT_LIST_DIR}/ComFprime.fpp"
|
||||
HEADERS
|
||||
|
||||
@ -3,35 +3,33 @@ module ComFprime {
|
||||
enum Ports_ComPacketQueue {
|
||||
EVENTS,
|
||||
TELEMETRY,
|
||||
FILE_QUEUE
|
||||
};
|
||||
|
||||
enum Ports_ComBufferQueue {
|
||||
FILE
|
||||
};
|
||||
|
||||
# ----------------------------------------------------------------------
|
||||
# Active Components
|
||||
# ----------------------------------------------------------------------
|
||||
instance comQueue: Svc.ComQueue base id ComFprimeConfig.BASE_ID + 0x0100 \
|
||||
instance comQueue: Svc.ComQueue base id ComFprimeConfig.BASE_ID + 0x00000 \
|
||||
queue size ComFprimeConfig.QueueSizes.comQueue \
|
||||
stack size ComFprimeConfig.StackSizes.comQueue \
|
||||
priority ComFprimeConfig.Priorities.comQueue \
|
||||
{
|
||||
phase Fpp.ToCpp.Phases.configConstants """
|
||||
enum{
|
||||
EVENTS,
|
||||
TELEMETRY,
|
||||
FILE_QUEUE
|
||||
};
|
||||
"""
|
||||
phase Fpp.ToCpp.Phases.configComponents """
|
||||
using namespace ComFprime;
|
||||
Svc::ComQueue::QueueConfigurationTable configurationTable;
|
||||
|
||||
// Events (highest-priority)
|
||||
configurationTable.entries[ConfigConstants::ComFprime_comQueue::EVENTS].depth = ComFprimeConfig::QueueDepths::events;
|
||||
configurationTable.entries[ConfigConstants::ComFprime_comQueue::EVENTS].priority = ComFprimeConfig::QueuePriorities::events;
|
||||
configurationTable.entries[Ports_ComPacketQueue::EVENTS].depth = ComFprimeConfig::QueueDepths::events;
|
||||
configurationTable.entries[Ports_ComPacketQueue::EVENTS].priority = ComFprimeConfig::QueuePriorities::events;
|
||||
// Telemetry
|
||||
configurationTable.entries[ConfigConstants::ComFprime_comQueue::TELEMETRY].depth = ComFprimeConfig::QueueDepths::tlm;
|
||||
configurationTable.entries[ConfigConstants::ComFprime_comQueue::TELEMETRY].priority = ComFprimeConfig::QueuePriorities::tlm;
|
||||
configurationTable.entries[Ports_ComPacketQueue::TELEMETRY].depth = ComFprimeConfig::QueueDepths::tlm;
|
||||
configurationTable.entries[Ports_ComPacketQueue::TELEMETRY].priority = ComFprimeConfig::QueuePriorities::tlm;
|
||||
// File Downlink Queue
|
||||
configurationTable.entries[ConfigConstants::ComFprime_comQueue::FILE_QUEUE].depth = ComFprimeConfig::QueueDepths::file;
|
||||
configurationTable.entries[ConfigConstants::ComFprime_comQueue::FILE_QUEUE].priority = ComFprimeConfig::QueuePriorities::file;
|
||||
configurationTable.entries[Ports_ComPacketQueue::NUM_CONSTANTS + Ports_ComBufferQueue::FILE].depth = ComFprimeConfig::QueueDepths::file;
|
||||
configurationTable.entries[Ports_ComPacketQueue::NUM_CONSTANTS + Ports_ComBufferQueue::FILE].priority = ComFprimeConfig::QueuePriorities::file;
|
||||
// Allocation identifier is 0 as the MallocAllocator discards it
|
||||
ComFprime::comQueue.configure(configurationTable, 0, ComFprime::Allocation::memAllocator);
|
||||
"""
|
||||
@ -40,24 +38,10 @@ module ComFprime {
|
||||
"""
|
||||
}
|
||||
|
||||
instance cmdSeq: Svc.CmdSequencer base id ComFprimeConfig.BASE_ID + 0x0200 \
|
||||
queue size ComFprimeConfig.QueueSizes.cmdSeq \
|
||||
stack size ComFprimeConfig.StackSizes.cmdSeq \
|
||||
priority ComFprimeConfig.Priorities.cmdSeq \
|
||||
{
|
||||
phase Fpp.ToCpp.Phases.configComponents """
|
||||
ComFprime::cmdSeq.allocateBuffer(0, ComFprime::Allocation::memAllocator, ComFprimeConfig::BuffMgr::cmdSeqBuffSize);
|
||||
"""
|
||||
|
||||
phase Fpp.ToCpp.Phases.tearDownComponents """
|
||||
ComFprime::cmdSeq.deallocateBuffer(ComFprime::Allocation::memAllocator);
|
||||
"""
|
||||
}
|
||||
|
||||
# ----------------------------------------------------------------------
|
||||
# Passive Components
|
||||
# ----------------------------------------------------------------------
|
||||
instance frameAccumulator: Svc.FrameAccumulator base id ComFprimeConfig.BASE_ID + 0x0500 \
|
||||
instance frameAccumulator: Svc.FrameAccumulator base id ComFprimeConfig.BASE_ID + 0x01000 \
|
||||
{
|
||||
phase Fpp.ToCpp.Phases.configObjects """
|
||||
Svc::FrameDetectors::FprimeFrameDetector frameDetector;
|
||||
@ -77,7 +61,7 @@ module ComFprime {
|
||||
"""
|
||||
}
|
||||
|
||||
instance commsBufferManager: Svc.BufferManager base id ComFprimeConfig.BASE_ID + 0x0600 \
|
||||
instance commsBufferManager: Svc.BufferManager base id ComFprimeConfig.BASE_ID + 0x02000 \
|
||||
{
|
||||
phase Fpp.ToCpp.Phases.configObjects """
|
||||
Svc::BufferManager::BufferBins bins;
|
||||
@ -102,18 +86,17 @@ module ComFprime {
|
||||
"""
|
||||
}
|
||||
|
||||
instance deframer: Svc.FprimeDeframer base id ComFprimeConfig.BASE_ID + 0x0700 \
|
||||
instance deframer: Svc.FprimeDeframer base id ComFprimeConfig.BASE_ID + 0x03000 \
|
||||
|
||||
instance fprimeFramer: Svc.FprimeFramer base id ComFprimeConfig.BASE_ID + 0x0800 \
|
||||
instance fprimeFramer: Svc.FprimeFramer base id ComFprimeConfig.BASE_ID + 0x04000 \
|
||||
|
||||
instance fprimeRouter: Svc.FprimeRouter base id ComFprimeConfig.BASE_ID + 0x0900 \
|
||||
instance fprimeRouter: Svc.FprimeRouter base id ComFprimeConfig.BASE_ID + 0x05000 \
|
||||
|
||||
instance comStub: Svc.ComStub base id ComFprimeConfig.BASE_ID + 0x0A00 \
|
||||
instance comStub: Svc.ComStub base id ComFprimeConfig.BASE_ID + 0x06000 \
|
||||
|
||||
topology Subtopology {
|
||||
# Active Components
|
||||
instance comQueue
|
||||
instance cmdSeq
|
||||
|
||||
# Passive Components
|
||||
instance commsBufferManager
|
||||
@ -122,7 +105,6 @@ module ComFprime {
|
||||
instance fprimeFramer
|
||||
instance fprimeRouter
|
||||
instance comStub
|
||||
instance comDriver
|
||||
|
||||
|
||||
connections Downlink {
|
||||
@ -136,22 +118,12 @@ module ComFprime {
|
||||
# Framer <-> ComStub
|
||||
fprimeFramer.dataOut -> comStub.dataIn
|
||||
comStub.dataReturnOut -> fprimeFramer.dataReturnIn
|
||||
# ComStub <-> ComDriver
|
||||
comStub.drvSendOut -> comDriver.$send
|
||||
comDriver.sendReturnOut -> comStub.drvSendReturnIn
|
||||
comDriver.ready -> comStub.drvConnected
|
||||
# ComStatus
|
||||
comStub.comStatusOut -> fprimeFramer.comStatusIn
|
||||
fprimeFramer.comStatusOut -> comQueue.comStatusIn
|
||||
}
|
||||
|
||||
connections Uplink {
|
||||
# ComDriver buffer allocations
|
||||
comDriver.allocate -> commsBufferManager.bufferGetCallee
|
||||
comDriver.deallocate -> commsBufferManager.bufferSendIn
|
||||
# ComDriver <-> ComStub
|
||||
comDriver.$recv -> comStub.drvReceiveIn
|
||||
comStub.drvReceiveReturnOut -> comDriver.recvReturnIn
|
||||
# ComStub <-> FrameAccumulator
|
||||
comStub.dataOut -> frameAccumulator.dataIn
|
||||
frameAccumulator.dataReturnOut -> comStub.dataReturnIn
|
||||
|
||||
@ -1,9 +1,11 @@
|
||||
register_fprime_config(
|
||||
EXCLUDE_FROM_ALL
|
||||
SOURCES
|
||||
"${CMAKE_CURRENT_LIST_DIR}/ComFprimeSubtopologyConfig.cpp"
|
||||
HEADERS
|
||||
"${CMAKE_CURRENT_LIST_DIR}/ComFprimeSubtopologyConfig.hpp"
|
||||
AUTOCODER_INPUTS
|
||||
"${CMAKE_CURRENT_LIST_DIR}/ComFprimeConfig.fpp"
|
||||
"${CMAKE_CURRENT_LIST_DIR}/ComFprimeComDriverConfig.fpp"
|
||||
DEPENDS
|
||||
Fw_Types
|
||||
)
|
||||
|
||||
@ -1,28 +0,0 @@
|
||||
module ComFprime {
|
||||
# Communications driver. May be swapped out with other comm drivers like UART in this file
|
||||
# to use another driver in the Comms Subtopology
|
||||
instance comDriver: Drv.TcpClient base id ComFprimeConfig.BASE_ID + 0x0B00 \
|
||||
{
|
||||
phase Fpp.ToCpp.Phases.configComponents """
|
||||
if (state.comFprime.hostname != nullptr && state.comFprime.port != 0) {
|
||||
ComFprime::comDriver.configure(state.comFprime.hostname, state.comFprime.port);
|
||||
}
|
||||
"""
|
||||
|
||||
phase Fpp.ToCpp.Phases.startTasks """
|
||||
// Initialize socket client communication if and only if there is a valid specification
|
||||
if (state.comFprime.hostname != nullptr && state.comFprime.port != 0) {
|
||||
Os::TaskString name("ReceiveTask");
|
||||
ComFprime::comDriver.start(name, ComFprimeConfig::Priorities::comDriver, ComFprimeConfig::StackSizes::comDriver);
|
||||
}
|
||||
"""
|
||||
|
||||
phase Fpp.ToCpp.Phases.stopTasks """
|
||||
ComFprime::comDriver.stop();
|
||||
"""
|
||||
|
||||
phase Fpp.ToCpp.Phases.freeThreads """
|
||||
(void)ComFprime::comDriver.join();
|
||||
"""
|
||||
}
|
||||
}
|
||||
@ -1,22 +1,17 @@
|
||||
module ComFprimeConfig {
|
||||
#Base ID for the ComFprime Subtopology, all components are offsets from this base ID
|
||||
constant BASE_ID = 0x10200000
|
||||
constant BASE_ID = 0x03000000
|
||||
|
||||
module QueueSizes {
|
||||
constant comQueue = 50
|
||||
constant cmdSeq = 10
|
||||
}
|
||||
|
||||
module StackSizes {
|
||||
constant comQueue = 64 * 1024
|
||||
constant cmdSeq = 64 * 1024
|
||||
constant comDriver = 100
|
||||
}
|
||||
|
||||
module Priorities {
|
||||
constant comQueue = 101
|
||||
constant cmdSeq = 100
|
||||
constant comDriver = 100
|
||||
}
|
||||
|
||||
# Queue configuration constants
|
||||
@ -34,7 +29,6 @@ module ComFprimeConfig {
|
||||
|
||||
# Buffer management constants
|
||||
module BuffMgr {
|
||||
constant cmdSeqBuffSize = 5 * 1024
|
||||
constant frameAccumulatorSize = 2048
|
||||
constant commsBuffSize = 2048
|
||||
constant commsFileBuffSize = 3000
|
||||
|
||||
@ -2,7 +2,7 @@
|
||||
#define COMFPRIME_PINGENTRIES_HPP
|
||||
|
||||
namespace PingEntries {
|
||||
namespace ComFprime_cmdSeq {enum { WARN = 3, FATAL = 5 };}
|
||||
// No ping-enabled components in ComFprime subtopology
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
@ -9,12 +9,12 @@
|
||||
|
||||
namespace ComFprime {
|
||||
struct SubtopologyState {
|
||||
const char* hostname;
|
||||
U16 port;
|
||||
// Empty - no external state needed for ComFprime subtopology
|
||||
};
|
||||
|
||||
struct TopologyState {
|
||||
SubtopologyState comFprime;
|
||||
};
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
@ -1,6 +1,7 @@
|
||||
add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/ComLoggerTeeConfig")
|
||||
|
||||
register_fprime_module(
|
||||
EXCLUDE_FROM_ALL
|
||||
AUTOCODER_INPUTS
|
||||
${CMAKE_CURRENT_LIST_DIR}/ComLoggerTee.fpp
|
||||
DEPENDS
|
||||
|
||||
@ -1,4 +1,5 @@
|
||||
register_fprime_config(
|
||||
EXCLUDE_FROM_ALL
|
||||
AUTOCODER_INPUTS
|
||||
${CMAKE_CURRENT_LIST_DIR}/ComLoggerTeeConfig.fpp
|
||||
INTERFACE
|
||||
|
||||
@ -1,6 +1,7 @@
|
||||
add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/DataProductsConfig/")
|
||||
|
||||
register_fprime_module(
|
||||
EXCLUDE_FROM_ALL
|
||||
AUTOCODER_INPUTS
|
||||
"${CMAKE_CURRENT_LIST_DIR}/DataProducts.fpp"
|
||||
HEADERS
|
||||
|
||||
@ -4,7 +4,7 @@ module DataProducts{
|
||||
# Active Components
|
||||
# ----------------------------------------------------------------------
|
||||
|
||||
instance dpCat: Svc.DpCatalog base id DataProductsConfig.BASE_ID + 0x0100 \
|
||||
instance dpCat: Svc.DpCatalog base id DataProductsConfig.BASE_ID + 0x00000 \
|
||||
queue size DataProductsConfig.QueueSizes.dpCat \
|
||||
stack size DataProductsConfig.StackSizes.dpCat \
|
||||
priority DataProductsConfig.Priorities.dpCat \
|
||||
@ -17,12 +17,12 @@ module DataProducts{
|
||||
"""
|
||||
}
|
||||
|
||||
instance dpMgr: Svc.DpManager base id DataProductsConfig.BASE_ID + 0x0200 \
|
||||
instance dpMgr: Svc.DpManager base id DataProductsConfig.BASE_ID + 0x01000 \
|
||||
queue size DataProductsConfig.QueueSizes.dpMgr \
|
||||
stack size DataProductsConfig.StackSizes.dpMgr \
|
||||
priority DataProductsConfig.Priorities.dpMgr
|
||||
|
||||
instance dpWriter: Svc.DpWriter base id DataProductsConfig.BASE_ID + 0x0300 \
|
||||
instance dpWriter: Svc.DpWriter base id DataProductsConfig.BASE_ID + 0x02000 \
|
||||
queue size DataProductsConfig.QueueSizes.dpWriter \
|
||||
stack size DataProductsConfig.StackSizes.dpWriter \
|
||||
priority DataProductsConfig.Priorities.dpWriter \
|
||||
@ -36,7 +36,7 @@ module DataProducts{
|
||||
# Passive Components
|
||||
# ----------------------------------------------------------------------
|
||||
|
||||
instance dpBufferManager: Svc.BufferManager base id DataProductsConfig.BASE_ID + 0x0400 \
|
||||
instance dpBufferManager: Svc.BufferManager base id DataProductsConfig.BASE_ID + 0x03000 \
|
||||
{
|
||||
phase Fpp.ToCpp.Phases.configObjects """
|
||||
Svc::BufferManager::BufferBins bins;
|
||||
|
||||
@ -1,4 +1,5 @@
|
||||
register_fprime_config(
|
||||
EXCLUDE_FROM_ALL
|
||||
SOURCES
|
||||
"${CMAKE_CURRENT_LIST_DIR}/DataProductsSubtopologyConfig.cpp"
|
||||
HEADERS
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
module DataProductsConfig {
|
||||
#Base ID for the DataProducts Subtopology, all components are offsets from this base ID
|
||||
constant BASE_ID = 0x10400000
|
||||
constant BASE_ID = 0x04000000
|
||||
|
||||
module QueueSizes {
|
||||
constant dpCat = 10
|
||||
|
||||
@ -9,7 +9,12 @@
|
||||
|
||||
namespace DataProducts {
|
||||
// State for topology construction
|
||||
struct SubtopologyState {
|
||||
// Empty - no external state needed for DataProducts subtopology
|
||||
};
|
||||
|
||||
struct TopologyState {
|
||||
SubtopologyState dataProducts;
|
||||
};
|
||||
}
|
||||
|
||||
|
||||
@ -1,6 +1,7 @@
|
||||
add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/FileHandlingConfig/")
|
||||
|
||||
register_fprime_module(
|
||||
EXCLUDE_FROM_ALL
|
||||
AUTOCODER_INPUTS
|
||||
"${CMAKE_CURRENT_LIST_DIR}/FileHandling.fpp"
|
||||
HEADERS
|
||||
|
||||
@ -1,18 +1,14 @@
|
||||
module FileHandling {
|
||||
|
||||
enum Ports_ComBufferQueue {
|
||||
FILE_DOWNLINK
|
||||
}
|
||||
|
||||
# ----------------------------------------------------------------------
|
||||
# Active Components
|
||||
# ----------------------------------------------------------------------
|
||||
instance fileUplink: Svc.FileUplink base id FileHandlingConfig.BASE_ID + 0x0100 \
|
||||
instance fileUplink: Svc.FileUplink base id FileHandlingConfig.BASE_ID + 0x00000 \
|
||||
queue size FileHandlingConfig.QueueSizes.fileUplink \
|
||||
stack size FileHandlingConfig.StackSizes.fileUplink \
|
||||
priority FileHandlingConfig.Priorities.fileUplink
|
||||
|
||||
instance fileDownlink: Svc.FileDownlink base id FileHandlingConfig.BASE_ID + 0x0200 \
|
||||
instance fileDownlink: Svc.FileDownlink base id FileHandlingConfig.BASE_ID + 0x01000 \
|
||||
queue size FileHandlingConfig.QueueSizes.fileDownlink \
|
||||
stack size FileHandlingConfig.StackSizes.fileDownlink \
|
||||
priority FileHandlingConfig.Priorities.fileDownlink \
|
||||
@ -27,12 +23,12 @@ module FileHandling {
|
||||
"""
|
||||
}
|
||||
|
||||
instance fileManager: Svc.FileManager base id FileHandlingConfig.BASE_ID + 0x0300 \
|
||||
instance fileManager: Svc.FileManager base id FileHandlingConfig.BASE_ID + 0x02000 \
|
||||
queue size FileHandlingConfig.QueueSizes.fileManager \
|
||||
stack size FileHandlingConfig.StackSizes.fileManager \
|
||||
priority FileHandlingConfig.Priorities.fileManager
|
||||
|
||||
instance prmDb: Svc.PrmDb base id FileHandlingConfig.BASE_ID + 0x0400 \
|
||||
instance prmDb: Svc.PrmDb base id FileHandlingConfig.BASE_ID + 0x03000 \
|
||||
queue size FileHandlingConfig.QueueSizes.prmDb \
|
||||
stack size FileHandlingConfig.StackSizes.prmDb \
|
||||
priority FileHandlingConfig.Priorities.prmDb \
|
||||
|
||||
@ -1,4 +1,5 @@
|
||||
register_fprime_config(
|
||||
EXCLUDE_FROM_ALL
|
||||
AUTOCODER_INPUTS
|
||||
"${CMAKE_CURRENT_LIST_DIR}/FileHandlingConfig.fpp"
|
||||
INTERFACE
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
module FileHandlingConfig {
|
||||
#Base ID for the FileHandling Subtopology, all components are offsets from this base ID
|
||||
constant BASE_ID = 0x10600000
|
||||
constant BASE_ID = 0x05000000
|
||||
|
||||
module QueueSizes {
|
||||
constant fileUplink = 10
|
||||
|
||||
@ -2,9 +2,15 @@
|
||||
#define FILEHANDLINGSUBTOPOLOGY_DEFS_HPP
|
||||
|
||||
#include "Svc/Subtopologies/FileHandling/FileHandlingConfig/FppConstantsAc.hpp"
|
||||
|
||||
namespace FileHandling {
|
||||
// State for topology construction
|
||||
struct SubtopologyState {
|
||||
// Empty - no external state needed for FileHandling subtopology
|
||||
};
|
||||
|
||||
struct TopologyState {
|
||||
SubtopologyState fileHandling;
|
||||
};
|
||||
}
|
||||
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user