diff --git a/.gitignore b/.gitignore index e91004ae0..27608dc86 100644 --- a/.gitignore +++ b/.gitignore @@ -6,3 +6,4 @@ build/** .project venv *.class +*__pycache__ diff --git a/Makefile b/Makefile index 381f06c78..02485011f 100644 --- a/Makefile +++ b/Makefile @@ -62,12 +62,23 @@ help:: @echo ' hosted on the generic quad-X airframe with the ' @echo ' Aerotenna uLanding landing radar system. ' @echo ' uLanding landing radar system. ' + @echo ' obc-all : This will build flight software for both the ' + @echo ' Performance Processing Domain (PPD) and the ' + @echo ' Critical Processing Domain (CPD) of the ' + @echo ' Windhover On-Board Computer (OBC), as well as the ' + @echo ' associated ground products. ' @echo ' obc/ppd : This will build flight software for the ' @echo ' Performance Processing Domain (PPD) of the ' @echo ' Windhover On-Board Computer (OBC). ' @echo ' obc/cpd : This will build flight software for the ' - @echo ' Critical Processing Domain (PPD) of the Windhover ' + @echo ' Critical Processing Domain (CPD) of the Windhover ' @echo ' Windhover On-Board Computer (OBC). ' + @echo ' obc-sitl : This will build a SITL versions of both the PPD ' + @echo ' and CPD flight software. ' + @echo ' obc/ppd/sitl : This will build a SITL version of the PPD flight ' + @echo ' software. ' + @echo ' obc/cpd/sitl : This will build a SITL version of the CPD flight ' + @echo ' software. ' @echo ' clean : This will clean all build flight software build ' @echo ' targets. This includes the Commander workspace, ' @echo ' if one was generated. ' @@ -96,6 +107,7 @@ help:: @echo ' docs-sphinx : Generate the Sphinx documentation from the ' @echo ' reference build. ' + .PHONY: help Makefile docs obc @@ -122,33 +134,26 @@ $(GENERIC_TARGET_NAMES):: -DCMAKE_ECLIPSE_GENERATE_SOURCE_PROJECT=TRUE CMAKE_BUILD_TYPE=Debug $(ROOT_DIR); \ $(MAKE) --no-print-directory); \ fi \ - done; + done; -obc:: - @echo 'Building 'OBC'.' - @idx=1; \ - for name in $(GENERIC_TARGET_NAMES); do \ - if [ "$$name" == "$@" ] ; then \ - break; \ - fi; \ - ((idx++)); \ - done; \ - TARGET_PATH=$$(echo ${GENERIC_TARGET_PATHS} | cut -d " " -f $$idx); \ - echo "Generating complete design/configuration definition file, 'wh_defs.yaml'"; \ - if [ -f "$(CONFIG_DIR)/$$TARGET_PATH/wh_config.yaml" ]; then \ - mkdir -p build/$$TARGET_PATH/target; \ - python3 core/base/tools/config/wh_defgen.py $(CONFIG_DIR)/$$TARGET_PATH/ build/$$TARGET_PATH/target/wh_defs.yaml; \ - fi; \ - for buildtype in $(BUILD_TYPES); do \ - if [ -d "$(CONFIG_DIR)/$$TARGET_PATH/$$buildtype" ]; then \ - mkdir -p build/$$TARGET_PATH/$$buildtype; \ - (cd build/$$TARGET_PATH/$$buildtype; \ - cmake -DBUILDNAME:STRING=$$TARGET_PATH -DBUILDTYPE:STRING=$$buildtype -G"Eclipse CDT4 - Unix Makefiles" \ - -DCMAKE_ECLIPSE_GENERATE_SOURCE_PROJECT=TRUE CMAKE_BUILD_TYPE=Debug $(ROOT_DIR); \ - $(MAKE) --no-print-directory); \ - fi \ - done; +obc-all:: obc/ppd obc/cpd + @echo 'Generating ground products.' + @make -C build/obc/ppd/target ground-tools + @make -C build/obc/cpd/target ground-tools + @echo 'Done' + +workspace:: + rm build/obc/commander_workspace/Displays/Resources/definitions.yaml + python3 core/base/tools/config/yaml_path_merger.py --yaml_output build/obc/commander_workspace/Displays/Resources/definitions.yaml --yaml_input build/obc/cpd/target/wh_defs.yaml --yaml_path /modules/cpd + python3 core/base/tools/config/yaml_path_merger.py --yaml_output build/obc/commander_workspace/Displays/Resources/definitions.yaml --yaml_input build/obc/ppd/target/wh_defs.yaml --yaml_path /modules/ppd + + +obc-sitl:: obc/ppd/sitl obc/cpd/sitl + @echo 'Generating ground products.' + @make -C build/obc/ppd/sitl/target ground-tools + @make -C build/obc/cpd/sitl/target ground-tools + @echo 'Done' docs-doxygen: diff --git a/apps/pq_lib/fsw/public_inc/pq_platform_cfg.h b/apps/pq_lib/fsw/public_inc/pq_platform_cfg.h index 0266ba638..e30811675 100644 --- a/apps/pq_lib/fsw/public_inc/pq_platform_cfg.h +++ b/apps/pq_lib/fsw/public_inc/pq_platform_cfg.h @@ -100,6 +100,10 @@ extern "C" { #define PQ_EVENT_ID_OFFSET (100) + +#define PQ_DEFAULT_QUEUE_MSG_LIMIT (1) +#define PQ_DEFAULT_QUEUE_IDX (4) + #ifdef __cplusplus } #endif diff --git a/apps/pq_lib/fsw/public_inc/pq_structs.h b/apps/pq_lib/fsw/public_inc/pq_structs.h index 18eca5888..9ec6cddc0 100644 --- a/apps/pq_lib/fsw/public_inc/pq_structs.h +++ b/apps/pq_lib/fsw/public_inc/pq_structs.h @@ -72,7 +72,6 @@ typedef enum } PQ_PriorityQueueType_t; - /** \brief Definition for a single priority queue entry. */ typedef struct { @@ -274,7 +273,7 @@ CompileTimeAssert((PQ_CHANNEL_STATE_COUNT <= 0xff), PQ_ChannelState_t_less_than_ /** \pqtbl PQ Configuration Table * - * \brief Definition for a TO Configuration table + * \brief Definition for a PQ Configuration table */ typedef struct { @@ -319,8 +318,7 @@ typedef struct } PQ_ChannelTbl_t; - -/** \brief Definition for a single TO dump table entry */ +/** \brief Definition for a single PQ dump table entry */ typedef struct { /** @@ -437,7 +435,7 @@ typedef struct uint32 SentMsgCount; /** \totlm Queued Channel Telemetry - \brief Count of telemetry messages queued on the TO channel's Priority Queues. + \brief Count of telemetry messages queued on the PQ channel's Priority Queues. Counter begins at zero with app initialization and rolls over. */ uint32 QueuedMsgCount; @@ -507,7 +505,7 @@ typedef struct } PQ_ChannelMemoryInfo_t; /** -** \brief TO application housekeeping data +** \brief PQ housekeeping data */ typedef struct { @@ -520,16 +518,16 @@ typedef struct \totlmmnemonic PQ_STORSENT \brief Count of telemetry messages sent out the channel interface. Counter begins at zero with app initialization and rolls over. - Index of array is equivalent to the relevant TO channel index. */ + Index of array is equivalent to the relevant PQ channel index. */ uint32 uiSentMsgCountChannel; /** \totlm Queued Channel Telemetry \totlmmnemonic PQ_RDOQUEUED \totlmmnemonic PQ_SNKLQUEUED \totlmmnemonic PQ_STORQUEUED - \brief Count of telemetry messages queued on the TO channel's Priority Queues. + \brief Count of telemetry messages queued on the PQ channel's Priority Queues. Counter begins at zero with app initialization and rolls over. - Index of array is equivalent to the relevant TO channel index. */ + Index of array is equivalent to the relevant PQ channel index. */ uint32 uiQueuedMsgCountChannel; /** \totlm Dropped Channel Telemetry @@ -538,7 +536,7 @@ typedef struct \totlmmnemonic PQ_STORDROP \brief Count of telemetry messages rejected, and not passed into the channel's Priority Queues. Counter begins at zero with app initialization and rolls over. - Index of array is equivalent to the relevant TO channel index. */ + Index of array is equivalent to the relevant PQ channel index. */ uint32 uiDropMsgCountChannel; /** \totlm Failed Channel Telemetry @@ -548,7 +546,7 @@ typedef struct \brief Count of telemetry messages failed on interface write after being pulled from the output queue, and lost. Counter begins at zero with app initialization and rolls over. - Index of array is equivalent to the relevant TO channel index. */ + Index of array is equivalent to the relevant PQ channel index. */ uint32 uiFailedMsgCountChannel; /** \totlm Channel Bytes Sent @@ -557,7 +555,7 @@ typedef struct \totlmmnemonic PQ_STORB \brief The number of bytes sent out the channel's interface Counter begins at zero with app initialization and rolls over. - Index of array is equivalent to the relevant TO channel index. */ + Index of array is equivalent to the relevant PQ channel index. */ uint32 uiBytesSentChannel; /** \totlmmnemonic PQ_CMDACPTCNT @@ -588,6 +586,8 @@ typedef struct \brief Memory information per channel. */ PQ_ChannelMemoryInfo_t ChannelMemInfo; + PQ_OutputQueue_t OutputQueue; + } PQ_HkTlm_t; diff --git a/apps/pq_lib/fsw/src/pq_channel.c b/apps/pq_lib/fsw/src/pq_channel.c index 4698e3fb9..154e119e8 100644 --- a/apps/pq_lib/fsw/src/pq_channel.c +++ b/apps/pq_lib/fsw/src/pq_channel.c @@ -52,7 +52,7 @@ ** Local Structure Declarations *************************************************************************/ -uint32 PQ_MemPoolDefSize[PQ_MAX_MEMPOOL_BLK_SIZES] = +uint32 PQ_MemPoolDefSize[PQ_MAX_MEMPOOL_BLK_SIZES] = { PQ_MAX_BLOCK_SIZE, PQ_MEM_BLOCK_SIZE_07, @@ -405,4 +405,9 @@ void PQ_Channel_CopyStats(PQ_HkTlm_t *HkTlm, PQ_ChannelData_t *Channel) //(void) OS_MutSemTake(TO_AppData.MutexID); HkTlm->SentBytes = Channel->OutputQueue.SentBytes; //(void) OS_MutSemGive(TO_AppData.MutexID); + HkTlm->OutputQueue.OSALQueueID = Channel->OutputQueue.OSALQueueID; + HkTlm->OutputQueue.SentBytes = Channel->OutputQueue.SentBytes; + HkTlm->OutputQueue.SentCount = Channel->OutputQueue.SentCount; + HkTlm->OutputQueue.CurrentlyQueuedCnt = Channel->OutputQueue.CurrentlyQueuedCnt; + HkTlm->OutputQueue.HighwaterMark = Channel->OutputQueue.HighwaterMark; } diff --git a/apps/pq_lib/fsw/src/pq_classifier.c b/apps/pq_lib/fsw/src/pq_classifier.c index 342b80002..223314d69 100644 --- a/apps/pq_lib/fsw/src/pq_classifier.c +++ b/apps/pq_lib/fsw/src/pq_classifier.c @@ -79,19 +79,35 @@ void PQ_Classifier_Run(PQ_ChannelData_t *Channel, CFE_SB_MsgPtr_t DataMsgPtr) } /* Get the first Message Flow object. If this returns null, the - * Message ID is not in the table at all so we shouldn't have - * received this message. Raise an event. + * Message ID is not in the table.. */ msgFlow = PQ_MessageFlow_GetObject(Channel, DataMsgID, &msgFlowIndex); if (NULL == msgFlow) { - (void) CFE_EVS_SendEvent(PQ_MF_MSG_ID_ERR_EID, - CFE_EVS_ERROR, - "Classifier Recvd invalid msgId (0x%04X) or message flow was removed on channel (%u)", - (unsigned short)DataMsgID, - (unsigned short)Channel->channelIdx); - Channel->DropMsgCount++; - goto end_of_function; + osalbool retVal = FALSE; + + /* Add the unknown message to the default pq. */ + retVal = PQ_MessageFlow_Add(Channel, + DataMsgID, + PQ_DEFAULT_QUEUE_MSG_LIMIT, + PQ_DEFAULT_QUEUE_IDX); + if(retVal != TRUE) + { + Channel->DropMsgCount++; + goto end_of_function; + } + + msgFlow = PQ_MessageFlow_GetObject(Channel, DataMsgID, &msgFlowIndex); + if (NULL == msgFlow) + { + (void) CFE_EVS_SendEvent(PQ_MF_MSG_ID_ERR_EID, + CFE_EVS_ERROR, + "Classifier failed to get message flow object for msgId (0x%04X) on channel (%u)", + (unsigned short)DataMsgID, + (unsigned short)Channel->channelIdx); + Channel->DropMsgCount++; + goto end_of_function; + } } /* Get the Priority Queue assigned to this Message Flow. */ diff --git a/apps/sbn/CMakeLists.txt b/apps/sbn/CMakeLists.txt deleted file mode 100644 index 445a7c1b5..000000000 --- a/apps/sbn/CMakeLists.txt +++ /dev/null @@ -1,18 +0,0 @@ -cmake_minimum_required(VERSION 2.6.4) -project(SBN_APP C) - -# workaround until these definitions are exposed by cfe_sb -include_directories(${CFECORE_SOURCE_DIR}/src/sb) - -include_directories(fsw/platform_inc) - -aux_source_directory(fsw/src APP_SRC_FILES) -aux_source_directory(fsw/tables APP_SRC_FILES) - -# Create the app module -add_cfe_app(sbn ${APP_SRC_FILES}) - -if (COMMAND add_cfe_tables) - aux_source_directory(fsw/tables APP_TBL_FILES) - add_cfe_tables(sbn ${APP_TBL_FILES}) -endif(COMMAND add_cfe_tables) diff --git a/apps/sbn/fsw/for_build/Makefile b/apps/sbn/fsw/for_build/Makefile deleted file mode 100644 index 70f7d89e5..000000000 --- a/apps/sbn/fsw/for_build/Makefile +++ /dev/null @@ -1,114 +0,0 @@ -############################################################################### -# File: CFS Application Makefile -# -# $Id: Makefile 1.5 2009/07/09 11:41:19EDT rmcgraw Exp $ -# -# $Log: Makefile $ -# Revision 1.5 2009/07/09 11:41:19EDT rmcgraw -# DCR8291:1 Changed CFE_MISSION_INC to CFS_MISSION_INC and added log if needed -# -############################################################################### -# -# Subsystem produced by this makefile. -# -APPTARGET = sbn - -# -# Entry Point for task -# -ENTRY_PT = SBN_AppMain - -# -# Object files required to build subsystem. -# -OBJS = sbn_app.o -OBJS += sbn_netif.o -OBJS += sbn_loader.o -OBJS += sbn_cmds.o -OBJS += sbn_subs.o -# -# Source files required to build subsystem; used to generate dependencies. -# As long as there are no assembly files this can be automated. -# -SOURCES = $(OBJS:.o=.c) - -## -## EXEDIR is defined here, just in case it needs to be different for a custom -## build -## -EXEDIR=../exe - -## -## Certain OSs and Application Loaders require the following option for -## Shared libraries. Currently only needed for vxWorks 5.5 and RTEMS. -## For each shared library that this app depends on, you need to have an -## entry like the following: -## -R../tst_lib/tst_lib.elf -## -SHARED_LIB_LINK = - -######################################################################## -# Should not have to change below this line, except for customized -# Mission and cFE directory structures -######################################################################## - -# -# Set build type to CFE_APP. This allows us to -# define different compiler flags for the cFE Core and Apps. -# -BUILD_TYPE = CFE_APP - -## -## Include all necessary cFE make rules -## Any of these can be copied to a local file and -## changed if needed. -## -## -## cfe-config.mak contains PSP and OS selection -## -include ../cfe/cfe-config.mak -## -## debug-opts.mak contains debug switches -## -include ../cfe/debug-opts.mak -## -## compiler-opts.mak contains compiler definitions and switches/defines -## -include $(CFE_PSP_SRC)/$(PSP)/make/compiler-opts.mak - -## -## Setup the include path for this subsystem -## The OS specific includes are in the build-rules.make file -## -## If this subsystem needs include files from another app, add the path here. -## -INCLUDE_PATH = \ --I$(OSAL_SRC)/inc \ --I$(CFE_CORE_SRC)/inc \ --I$(CFE_CORE_SRC)/sb \ --I$(CFE_PSP_SRC)/inc \ --I$(CFE_PSP_SRC)/$(PSP)/inc \ --I$(CFS_APP_SRC)/inc \ --I$(CFS_APP_SRC)/$(APPTARGET)/fsw/src \ --I$(CFS_MISSION_INC) \ --I../cfe/inc \ --I../inc - -## -## Define the VPATH make variable. -## This can be modified to include source from another directory. -## If there is no corresponding app in the cfs-apps directory, then this can be discarded, or -## if the mission chooses to put the src in another directory such as "src", then that can be -## added here as well. -## -VPATH = $(CFS_APP_SRC)/$(APPTARGET)/fsw/src - -## -## Include the common make rules for building a cFE Application -## -include $(CFE_CORE_SRC)/make/app-rules.mak - -install: - $(CP) $(APPTARGET).$(APP_EXT) $(EXEDIR) - $(CP) $(CFS_APP_SRC)/$(APPTARGET)/fsw/src/SbnPeerData.dat $(EXEDIR) - $(CP) $(CFS_APP_SRC)/$(APPTARGET)/fsw/src/SbnModuleData.dat $(EXEDIR) diff --git a/apps/sbn/fsw/src/sbn_app.c b/apps/sbn/fsw/src/sbn_app.c index 563865598..c65bda260 100644 --- a/apps/sbn/fsw/src/sbn_app.c +++ b/apps/sbn/fsw/src/sbn_app.c @@ -1051,7 +1051,7 @@ int SBN_InitInterfaces(void) /* create a pipe name string similar to SBN_0_CPU2_Pipe */ snprintf(PipeName, OS_MAX_API_NAME, "SBN_%d_%s_Pipe", NetIdx, Peer->Name); - int Status = CFE_SB_CreatePipe(&(Peer->Pipe), 2, PipeName); + int Status = CFE_SB_CreatePipe(&(Peer->Pipe), SBN_PEER_PIPE_DEPTH, PipeName); if(Status != CFE_SUCCESS) { @@ -1271,9 +1271,9 @@ static int WaitForSBStartup(void) /** \brief SBN Main Routine */ void SBN_AppMain(void) { - int Status = CFE_SUCCESS; - uint32 RunStatus = CFE_ES_APP_RUN, - AppID = 0; + int Status = CFE_SUCCESS; + uint32 RunStatus = CFE_ES_APP_RUN; + uint32 AppID = 0; Status = CFE_ES_RegisterApp(); if(Status != CFE_SUCCESS) @@ -1446,12 +1446,18 @@ void SBN_AppMain(void) /* Wait for event from SB saying it is initialized OR a response from SB to the above messages. TRUE means it needs to re-send subscription requests */ - if(WaitForSBStartup()) SBN_SendSubsRequests(); + if(WaitForSBStartup()) + { + SBN_SendSubsRequests(); + } - if(Status != CFE_SUCCESS) RunStatus = CFE_ES_APP_ERROR; +end_of_function: /* Loop Forever */ - while(CFE_ES_RunLoop(&RunStatus)) WaitForWakeup(SBN_MAIN_LOOP_DELAY); + while(CFE_ES_RunLoop(&RunStatus)) + { + WaitForWakeup(SBN_MAIN_LOOP_DELAY); + } int NetIdx = 0; for(NetIdx = 0; NetIdx < SBN.NetCnt; NetIdx++) @@ -1461,8 +1467,6 @@ void SBN_AppMain(void) }/* end for */ /* SBN_UnloadModules(); */ - -end_of_function: CFE_ES_ExitApp(RunStatus); }/* end SBN_AppMain */ diff --git a/apps/sbn/fsw/src/sbn_cmds.c b/apps/sbn/fsw/src/sbn_cmds.c index a130f0de1..92f9662da 100644 --- a/apps/sbn/fsw/src/sbn_cmds.c +++ b/apps/sbn/fsw/src/sbn_cmds.c @@ -342,7 +342,7 @@ static void HKCmd(CFE_SB_MsgPtr_t MsgPtr) return; }/* end if */ - CFE_EVS_SendEvent(SBN_CMD_EID, CFE_EVS_INFORMATION, "hk command"); + //CFE_EVS_SendEvent(SBN_CMD_EID, CFE_EVS_INFORMATION, "hk command"); uint8 HKBuf[SBN_HK_LEN]; Pack_t Pack; @@ -376,7 +376,7 @@ static void HKCmd(CFE_SB_MsgPtr_t MsgPtr) CFE_EVS_SendEvent(SBN_PEER_EID, CFE_EVS_ERROR, "network #%d not configured", NetIdx); - return SBN_ERROR; + return; }/* end if */ /* Note: StatusPacket currently unused. */ diff --git a/apps/sbn/fsw/src/sbn_loader.c b/apps/sbn/fsw/src/sbn_loader.c index 25639903a..71b943121 100644 --- a/apps/sbn/fsw/src/sbn_loader.c +++ b/apps/sbn/fsw/src/sbn_loader.c @@ -91,11 +91,6 @@ int32 SBN_ReadModuleFile(void) #else /* ! CFE_ES_CONFLOADER */ -//#include "sbn_interfaces.h" - -extern SBN_IfOps_t SBN_Mbox_Ops; - - /** * \brief Reads a file describing the interface modules that must be loaded. * @@ -241,9 +236,7 @@ int32 SBN_ParseModuleEntry(char *FileEntry, uint32 LineNum) OS_printf("SBN found symbol %s (%08x) in %s (%s)\n", StructName, StructAddr, ModuleName, ModuleFile); - /* TODO */ - //SBN.IfOps[ProtocolID] = (SBN_IfOps_t *)StructAddr; - SBN.IfOps[ProtocolID] = (SBN_IfOps_t *)&SBN_Mbox_Ops; + SBN.IfOps[ProtocolID] = (SBN_IfOps_t *)StructAddr; SBN.ModuleIDs[ProtocolID] = ModuleID; return SBN_SUCCESS; diff --git a/apps/sbn/fsw/src/sbn_msg.h b/apps/sbn/fsw/src/sbn_msg.h index 97b6a74b4..8bcd76569 100644 --- a/apps/sbn/fsw/src/sbn_msg.h +++ b/apps/sbn/fsw/src/sbn_msg.h @@ -49,6 +49,22 @@ */ #define SBN_HKNET_LEN (CFE_SB_TLM_HDR_SIZE + sizeof(uint8) * 2 + sizeof(char) * SBN_MAX_NET_NAME_LEN + sizeof(uint8) + sizeof(uint16)) + +/** +** \brief No Arguments Command +** +** \par +** For command details see #SBN_NOOP_CC, #SBN_RESET_CC +** +*/ +typedef struct +{ + /** \brief message header */ + uint8 ucCmdHeader[CFE_SB_CMD_HDR_SIZE]; + +} SBN_NoArgCmd_t; + + /** * @brief Module status response packet structure */ diff --git a/apps/sbn/fsw/src/sbn_subs.c b/apps/sbn/fsw/src/sbn_subs.c index e7c9bd880..e03bee886 100644 --- a/apps/sbn/fsw/src/sbn_subs.c +++ b/apps/sbn/fsw/src/sbn_subs.c @@ -52,28 +52,6 @@ void SBN_SendSubsRequests(void) CFE_SB_SendMsg((CFE_SB_MsgPtr_t) &SBCmdMsg); }/* end SBN_SendSubsRequests */ -/** - * \brief Sends a local subscription over the wire to a peer. - * - * @param[in] SubType Whether this is a subscription or unsubscription. - * @param[in] MsgID The CCSDS message ID being (un)subscribed. - * @param[in] QoS The CCSDS quality of service being (un)subscribed. - * @param[in] Peer The Peer interface - */ -//static void SendLocalSubToPeer(int SubType, CFE_SB_MsgId_t MsgID, - //CFE_SB_Qos_t QoS, SBN_PeerInterface_t *Peer) -//{ - //uint8 Buf[SBN_PACKED_SUB_SZ]; - //Pack_t Pack; - //Pack_Init(&Pack, &Buf, SBN_PACKED_SUB_SZ, 0); - //Pack_Data(&Pack, SBN_IDENT, SBN_IDENT_LEN); - //Pack_UInt16(&Pack, 1); - - //Pack_MsgID(&Pack, MsgID); - //Pack_Data(&Pack, &QoS, sizeof(QoS)); /* 2 uint8's */ - - //SBN_SendNetMsg(SubType, Pack.BufUsed, Buf, Peer); -//}/* end SendLocalSubToPeer */ /** * \brief Sends a local subscription over the wire to a peer. @@ -106,30 +84,6 @@ static void SendLocalSubToPeer(int SubType, CFE_SB_MsgId_t MsgID, SBN_SendNetMsg(SubType, sizeof(Packet), &Packet, Peer); }/* end SendLocalSubToPeer */ -/** - * \brief Sends all local subscriptions over the wire to a peer. - * - * @param[in] Peer The peer interface. - */ -//void SBN_SendLocalSubsToPeer(SBN_PeerInterface_t *Peer) -//{ - //uint8 Buf[SBN_PACKED_SUB_SZ]; - //Pack_t Pack; - //Pack_Init(&Pack, &Buf, SBN_PACKED_SUB_SZ, 0); - //Pack_Data(&Pack, SBN_IDENT, SBN_IDENT_LEN); - //Pack_UInt16(&Pack, SBN.SubCnt); - - //int i = 0; - //for(i = 0; i < SBN.SubCnt; i++) - //{ - //Pack_MsgID(&Pack, SBN.Subs[i].MsgID); - ///* 2 uint8's */ - //Pack_Data(&Pack, &SBN.Subs[i].QoS, sizeof(SBN.Subs[i].QoS)); - //}/* end for */ - - //SBN_SendNetMsg(SBN_SUBSCRIBE_MSG, Pack.BufUsed, Buf, Peer); -//}/* end SBN_SendLocalSubsToPeer */ - /** * \brief Sends all local subscriptions over the wire to a peer. @@ -459,44 +413,6 @@ static void ProcessSubFromPeer(SBN_PeerInterface_t *Peer, CFE_SB_MsgId_t MsgID, }/* end if */ }/* ProcessSubFromPeer */ -/** - * \brief Process a subscription message from a peer. - * - * @param[in] PeerIdx The peer index (in SBN.Peer) - * @param[in] Msg The subscription SBN message. - */ -//void SBN_ProcessSubsFromPeer(SBN_PeerInterface_t *Peer, void *Msg) -//{ - //Unpack_t Unpack; - //char VersionHash[SBN_IDENT_LEN]; - - //Unpack_Init(&Unpack, Msg, CFE_SB_MAX_SB_MSG_SIZE); - - //Unpack_Data(&Unpack, VersionHash, SBN_IDENT_LEN); - - //if(strncmp(VersionHash, SBN_IDENT, SBN_IDENT_LEN)) - //{ - //CFE_EVS_SendEvent(SBN_PROTO_EID, CFE_EVS_ERROR, - //"version number mismatch with peer CpuID %lu", - //Peer->ProcessorID); - //} - - //uint16 SubCnt; - //Unpack_UInt16(&Unpack, &SubCnt); - - //int SubIdx = 0; - //for(SubIdx = 0; SubIdx < SubCnt; SubIdx++) - //{ - //CFE_SB_MsgId_t MsgID; - //Unpack_MsgID(&Unpack, &MsgID); - //CFE_SB_Qos_t QoS; - //Unpack_Data(&Unpack, &QoS, sizeof(QoS)); - - //ProcessSubFromPeer(Peer, MsgID, QoS); - //}/* end for */ -//}/* SBN_ProcessSubsFromPeer */ - - /** * \brief Process a subscription message from a peer. * @@ -553,13 +469,8 @@ void SBN_ProcessSubsFromPeer(SBN_PeerInterface_t *Peer, void *Msg) } } - - - - }/* SBN_ProcessSubsFromPeer */ - static void ProcessUnsubFromPeer(SBN_PeerInterface_t *Peer, CFE_SB_MsgId_t MsgID) { @@ -599,96 +510,6 @@ static void ProcessUnsubFromPeer(SBN_PeerInterface_t *Peer, }/* end if */ }/* end ProcessUnsubFromPeer */ -///** - //* \brief Process an unsubscription message from a peer. - //* - //* @param[in] PeerIdx The peer index (in SBN.Peer) - //* @param[in] Msg The unsubscription SBN message. - //*/ -//void SBN_ProcessUnsubsFromPeer(SBN_PeerInterface_t *Peer, void *Msg) -//{ - //Unpack_t Unpack; - - //Unpack_Init(&Unpack, Msg, CFE_SB_MAX_SB_MSG_SIZE); - - //char VersionHash[SBN_IDENT_LEN]; - - //Unpack_Data(&Unpack, VersionHash, SBN_IDENT_LEN); - - //if(strncmp(VersionHash, SBN_IDENT, SBN_IDENT_LEN)) - //{ - //CFE_EVS_SendEvent(SBN_PROTO_EID, CFE_EVS_ERROR, - //"version number mismatch with peer CpuID %lu", - //Peer->ProcessorID); - //} - - //uint16 SubCnt; - //Unpack_UInt16(&Unpack, &SubCnt); - - //int SubIdx = 0; - //for(SubIdx = 0; SubIdx < SubCnt; SubIdx++) - //{ - //CFE_SB_MsgId_t MsgID; - //Unpack_MsgID(&Unpack, &MsgID); - //CFE_SB_Qos_t QoS; - //Unpack_Data(&Unpack, &QoS, sizeof(QoS)); - - //int idx, RemappedFlag = 0; - - //if(OS_MutSemTake(SBN.RemapMutex) != OS_SUCCESS) - //{ - //CFE_EVS_SendEvent(SBN_REMAP_EID, CFE_EVS_ERROR, - //"unable to take mutex"); - //continue; - //}/* end if */ - - ///** If there's a filter, ignore this unsub. */ - //for(idx = 0; RemappedFlag == 0 && idx < SBN.RemapTbl->EntryCnt; idx++) - //{ - //if(SBN.RemapTbl->Entries[idx].ProcessorID - //== Peer->ProcessorID - //&& SBN.RemapTbl->Entries[idx].FromMID == MsgID - //&& SBN.RemapTbl->Entries[idx].ToMID == 0x0000) - //{ - //RemappedFlag = 1; - //}/* end if */ - //}/* end for */ - - ///***** - //* If there's a remap that would generate that - //* MID, I need to unsubscribe locally to the "from". Usually this will - //* only be one "from" but it's possible that multiple "from"s map to - //* the same "to". - //*/ - //for(idx = 0; idx < SBN.RemapTbl->EntryCnt; idx++) - //{ - //if(SBN.RemapTbl->Entries[idx].ProcessorID - //== Peer->ProcessorID - //&& SBN.RemapTbl->Entries[idx].ToMID == MsgID) - //{ - ///* Unsubscribe from each "ToMID" match. */ - //ProcessUnsubFromPeer(Peer, - //SBN.RemapTbl->Entries[idx].FromMID); - - //RemappedFlag = 1; - //}/* end if */ - //}/* end for */ - - ///* if there's no remap ID's, unsubscribe from the original MID. */ - //if(!RemappedFlag) - //{ - //ProcessUnsubFromPeer(Peer, MsgID); - //}/* end if */ - - //if(OS_MutSemGive(SBN.RemapMutex) != OS_SUCCESS) - //{ - //CFE_EVS_SendEvent(SBN_REMAP_EID, CFE_EVS_ERROR, - //"unable to give mutex"); - //}/* end if */ - //}/* end for */ -//}/* end SBN_ProcessUnsubFromPeer */ - - /** * \brief Process an unsubscription message from a peer. * @@ -777,7 +598,6 @@ void SBN_ProcessUnsubsFromPeer(SBN_PeerInterface_t *Peer, void *Msg) }/* end for */ }/* end SBN_ProcessUnsubFromPeer */ - /** * When SBN starts, it queries for all existing subscriptions. This method * processes those subscriptions. diff --git a/apps/sbn/modules/mbox/fsw/for_build/CMakeLists.txt b/apps/sbn/modules/mbox/fsw/for_build/CMakeLists.txt deleted file mode 100644 index b1e475797..000000000 --- a/apps/sbn/modules/mbox/fsw/for_build/CMakeLists.txt +++ /dev/null @@ -1,46 +0,0 @@ - ############################################################################# - # - # Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. - # - # Redistribution and use in source and binary forms, with or without - # modification, are permitted provided that the following conditions - # are met: - # - # 1. Redistributions of source code must retain the above copyright - # notice, this list of conditions and the following disclaimer. - # 2. Redistributions in binary form must reproduce the above copyright - # notice, this list of conditions and the following disclaimer in - # the documentation and/or other materials provided with the - # distribution. - # 3. Neither the name Windhover Labs nor the names of its contributors - # may be used to endorse or promote products derived from this software - # without specific prior written permission. - # - # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - # OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - # AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - # POSSIBILITY OF SUCH DAMAGE. - # - ############################################################################# - -buildliner_add_app_def(sbn_mbox - FILE sbn_mbox - SOURCES - ${CMAKE_CURRENT_SOURCE_DIR}/../src/sbn_mailbox_if.c - ${CMAKE_CURRENT_SOURCE_DIR}/../src/sbn_mailbox_if.h - ${CMAKE_CURRENT_SOURCE_DIR}/../src/mailbox_parser.c - ${CMAKE_CURRENT_SOURCE_DIR}/../src/mailbox_parser.h - - INCLUDES - ${CMAKE_CURRENT_SOURCE_DIR}/../src/ - ${CMAKE_CURRENT_SOURCE_DIR}/../../../../fsw/src/ -) - diff --git a/apps/sbn/modules/mbox/fsw/src/mailbox_parser.c b/apps/sbn/modules/mbox/fsw/src/mailbox_parser.c deleted file mode 100644 index 42444fe75..000000000 --- a/apps/sbn/modules/mbox/fsw/src/mailbox_parser.c +++ /dev/null @@ -1,66 +0,0 @@ -#include "sbn_mailbox_if.h" -#include "mailbox_parser.h" - -unsigned int ParseMessage(Mailbox_Parser_Handle_t *Handle, unsigned int Input, unsigned int* Buffer, unsigned int *BufferSize) -{ - unsigned int sizeInWords = (*BufferSize+3)/4; - - switch(Handle->State) - { - /* Fallthru */ - case MPS_MESSAGE_COMPLETE: - case MPS_WAITING_FOR_CADU: - { - if(Input == MAILBOX_MSG_CADU) - { - Handle->InputBufferCursor = 0; - Handle->CurrentChecksum = 0; - Handle->State = MPS_WAITING_FOR_SIZE; - } - else - { - Handle->State = MPS_WAITING_FOR_CADU; - } - break; - } - - case MPS_WAITING_FOR_SIZE: - { - Handle->FullMessageSize = Input; - Handle->State = MPS_PARSING_MESSAGE; - break; - } - - case MPS_PARSING_MESSAGE: - { - if(Handle->InputBufferCursor < sizeInWords) - { - Buffer[Handle->InputBufferCursor] = Input; - } - Handle->CurrentChecksum += Input; - Handle->InputBufferCursor++; - if(Handle->InputBufferCursor >= Handle->FullMessageSize) - { - Handle->State = MPS_WAITING_FOR_CHECKSUM; - } - break; - } - - case MPS_WAITING_FOR_CHECKSUM: - { - if(Input != Handle->CurrentChecksum) - { - /* Checkum mismatch. */ - Handle->State = MPS_WAITING_FOR_CADU; - } - else - { - *BufferSize = Handle->InputBufferCursor*4; - Handle->State = MPS_MESSAGE_COMPLETE; - } - break; - } - } - - return Handle->State; -} diff --git a/apps/sbn/modules/mbox/fsw/src/mailbox_parser.h b/apps/sbn/modules/mbox/fsw/src/mailbox_parser.h deleted file mode 100644 index ebaaf6701..000000000 --- a/apps/sbn/modules/mbox/fsw/src/mailbox_parser.h +++ /dev/null @@ -1,27 +0,0 @@ -#ifndef MAILBOX_PARSER_H -#define MAILBOX_PARSER_H - -#define MAILBOX_MSG_CADU (0x01020304) - -typedef enum -{ - MPS_WAITING_FOR_CADU, - MPS_WAITING_FOR_SIZE, - MPS_PARSING_MESSAGE, - MPS_WAITING_FOR_CHECKSUM, - MPS_MESSAGE_COMPLETE, - MPS_BUFFER_OVERFLOW -} Mailbox_Parser_State_t; - -typedef struct -{ - Mailbox_Parser_State_t State; - unsigned int CurrentChecksum; - unsigned int InputBufferCursor; - unsigned int FullMessageSize; -} Mailbox_Parser_Handle_t; - - -unsigned int ParseMessage(Mailbox_Parser_Handle_t *Handle, unsigned int Input, unsigned int* Buffer, unsigned int *BufferSize); - -#endif diff --git a/apps/sbn/modules/mbox/fsw/src/sbn_mailbox_if.c b/apps/sbn/modules/mbox/fsw/src/sbn_mailbox_if.c deleted file mode 100644 index f9d16153f..000000000 --- a/apps/sbn/modules/mbox/fsw/src/sbn_mailbox_if.c +++ /dev/null @@ -1,418 +0,0 @@ -#include "sbn_mailbox_if.h" -#include "sbn_interfaces.h" -#include "sbn_platform_cfg.h" -#include "stdbool.h" - -extern PQ_ChannelTbl_t PQ_BackupConfigTbl; - -SBN_Mailbox_Data_t SBN_Mailbox_Data; - -void SBN_PQ_Output_Task(void); -void SBN_PQ_ChannelHandler(PQ_ChannelData_t *Channel); - - -/* Blocking write */ -int MailboxWrite(XMbox *instance, const unsigned int *buffer, unsigned int size) -{ - int Status = 0; - unsigned int BytesSent = 0; - unsigned int TotalBytesSent = 0; - unsigned int RequestedBytes = size * 4; - - while(1) - { - XMbox_Write(instance, buffer[TotalBytesSent], RequestedBytes, &BytesSent); - RequestedBytes = RequestedBytes - BytesSent; - TotalBytesSent = TotalBytesSent + BytesSent; - if(TotalBytesSent < RequestedBytes) - { - /* Sleep */ - OS_TaskDelay(SBN_MAILBOX_BLOCKING_DELAY); - } - else - { - break; - } - } - - Status = TotalBytesSent; - -end_of_function: - return Status; -} - - -int MailboxRead(XMbox *instance, unsigned int *buffer, unsigned int size) -{ - int Status = 0; - unsigned int BytesRecvd = 0; - - Status = XMbox_Read(instance, buffer, size, &BytesRecvd); - - if(Status == XST_NO_DATA) - { - Status = 0; - goto end_of_function; - } - - if(Status == XST_SUCCESS) - { - Status = BytesRecvd; - } - else - { - printf("XMbox_Read Failed %u.\r\n", Status); - } - -end_of_function: - return Status; -} - - -static int InitNet(SBN_NetInterface_t *Net) -{ - int Status = SBN_SUCCESS; - - memset(&SBN_Mailbox_Data, 0x0, sizeof(SBN_Mailbox_Data)); - - SBN_Mailbox_Data.HkTlm.ChannelMaxMem = PQ_NUM_BYTES_IN_MEM_POOL; - - SBN_Mailbox_Data.MboxConfigPtr = XMbox_LookupConfig(XPAR_SED_MBOX_MAILBOX_CPD_TO_SED_IF_1_DEVICE_ID); - if (SBN_Mailbox_Data.MboxConfigPtr == (XMbox_Config *)NULL) - { - printf ("XMbox_LookupConfig Failed.\r\n"); - Status = SBN_ERROR; - goto end_of_function; - } - - Status = XMbox_CfgInitialize(&SBN_Mailbox_Data.Mbox, - SBN_Mailbox_Data.MboxConfigPtr, - SBN_Mailbox_Data.MboxConfigPtr->BaseAddress); - if (Status != XST_SUCCESS) - { - printf ("XMbox_CfgInitialize Failed.\r\n"); - Status = SBN_ERROR; - goto end_of_function; - } - - - /* Initialize PQ channel. */ - Status = PQ_Channel_Init(SBN_PQ_CHANNEL_NUMBER, &SBN_Mailbox_Data.Channel); - if (Status != CFE_SUCCESS) - { - /* TODO update to event. */ - OS_printf("PQ_Channel_Init failed%u\n", Status); - Status = SBN_ERROR; - goto end_of_function; - } - - /* Open PQ channel. */ - Status = PQ_Channel_OpenChannel( - &SBN_Mailbox_Data.Channel, - SBN_PQ_CHANNEL_NAME, - SBN_PQ_CONFIG_TABLENAME, - SBN_PQ_CONFIG_TABLE_FILENAME, - &PQ_BackupConfigTbl, - SBN_PQ_DUMP_TABLENAME, - SBN_PQ_CF_SEM_INIT_VALUE, - SBN_PQ_CF_THROTTLE_SEM_NAME); - - if (Status != CFE_SUCCESS) - { - /* TODO update to event. */ - OS_printf("PQ_Channel_OpenChannel failed %u\n", Status); - Status = SBN_ERROR; - goto end_of_function; - } - - /* Create send task. */ - SBN_Mailbox_Data.SendTask = SBN_PQ_Output_Task; - Status = CFE_ES_CreateChildTask( - &SBN_Mailbox_Data.ChildTaskID, - SBN_PQ_SEND_TASK_NAME, - SBN_Mailbox_Data.SendTask, - 0, - SBN_PQ_SEND_TASK_STACK_SIZE, - SBN_PQ_SEND_TASK_PRIORITY, - SBN_PQ_SEND_TASK_FLAGS); - if (Status != CFE_SUCCESS) - { - /* TODO update to event. */ - printf("CFE_ES_CreateChildTask failed%u\n", Status); - Status = SBN_ERROR; - goto end_of_function; - } - -end_of_function: - return Status; -} - - -static int InitPeer(SBN_PeerInterface_t *Peer) -{ - - return SBN_SUCCESS; -} - - -static int LoadNet(const char **Row, int FieldCnt, SBN_NetInterface_t *Net) -{ - return SBN_SUCCESS; -} - - -static int LoadPeer(const char **Row, int FieldCnt, SBN_PeerInterface_t *Peer) -{ - return SBN_SUCCESS; -} - - -static int PollPeer(SBN_PeerInterface_t *Peer) -{ - return SBN_SUCCESS; -} - - -int SBN_MailboxRecv(void *instance, const unsigned int *buffer, unsigned int size) -{ - -} - - -void SBN_PQ_Output_Task(void) -{ - CFE_ES_RegisterChildTask(); - - SBN_PQ_ChannelHandler(&SBN_Mailbox_Data.Channel); - - CFE_ES_ExitChildTask(); -} - - -void SBN_PQ_ChannelHandler(PQ_ChannelData_t *Channel) -{ - int32 iStatus = CFE_SUCCESS; - uint32 msgSize = 0; - char *buffer; - - SBN_Mailbox_Data.TaskContinueFlag = TRUE; - - while(SBN_Mailbox_Data.TaskContinueFlag) - { - if(PQ_Channel_State(Channel) == PQ_CHANNEL_OPENED) - { - PQ_OutputQueue_t *chQueue = &Channel->OutputQueue; - - iStatus = OS_QueueGet( - chQueue->OSALQueueID, - &buffer, sizeof(buffer), &msgSize, SBN_PQ_CHANNEL_GET_TIMEOUT); - - if(iStatus == OS_SUCCESS) - { - uint16 actualMessageSize = CFE_SB_GetTotalMsgLength((CFE_SB_MsgPtr_t)buffer); - CFE_SB_MsgId_t MsgID = CFE_SB_GetMsgId((CFE_SB_MsgPtr_t)buffer); - SBN_MsgType_t MsgType; - size_t BufSz = actualMessageSize + SBN_PACKED_HDR_SZ; - /* TODO fix this. */ - uint8 Buf[BufSz]; - unsigned int SizeInBytes = 0; - unsigned int SizeInWords = 0; - unsigned int Checksum = 0; - unsigned int i = 0; - - if(MsgID == SBN_SUB_MID || MsgID == SBN_ALLSUB_MID) - { - MsgType = SBN_SUBSCRIBE_MSG; - } - else if (MsgID == SBN_UNSUB_MID) - { - MsgType = SBN_UN_SUBSCRIBE_MSG; - } - else - { - MsgType = SBN_APP_MSG; - } - - SBN_PackMsg(&Buf, actualMessageSize, MsgType, CFE_PSP_GetProcessorId(), buffer); - - SizeInBytes = BufSz; - /* Ensure word boundary */ - SizeInBytes = (BufSz + (MAILBOX_WORD_SIZE - (BufSz % MAILBOX_WORD_SIZE))); - SizeInWords = SizeInBytes / MAILBOX_WORD_SIZE; - - //printf("BufSz %u\n", BufSz); - //printf("SizeInBytes %u\n", SizeInBytes); - //printf("SizeInWords %u\n", SizeInWords); - - if(SizeInWords + MAILBOX_HEADER_SIZE_WORDS > MAILBOX_MAX_BUFFER_SIZE_WORDS) - { - /* TODO update to event. */ - OS_printf("SBN_MailboxSend Send size too large %u bytes, %u words.\n", SizeInBytes, SizeInWords); - continue; - } - - /* Set CADU. */ - SBN_Mailbox_Data.OutputBuffer[0] = MAILBOX_MSG_CADU; - /* Set size of the payload in words. */ - SBN_Mailbox_Data.OutputBuffer[1] = SizeInWords; - /* Copy the payload. */ - memcpy(&SBN_Mailbox_Data.OutputBuffer[2], &Buf[0], BufSz); - - Checksum = 0; - /* Checksum Calculation */ - for(i = 0; i < SizeInWords - 1; ++i) - { - Checksum += SBN_Mailbox_Data.OutputBuffer[i + 2]; - } - /* Set the checksum. */ - SBN_Mailbox_Data.OutputBuffer[SizeInWords + 2] = Checksum; - - /* Blocking write. */ - (void) MailboxWrite(&SBN_Mailbox_Data.Mbox, &SBN_Mailbox_Data.OutputBuffer[0], SizeInWords + MAILBOX_HEADER_SIZE_WORDS); - - iStatus = CFE_ES_PutPoolBuf(Channel->MemPoolHandle, (uint32 *)buffer); - if(iStatus < 0) - { - (void) CFE_EVS_SendEvent(PQ_PUT_POOL_ERR_EID, CFE_EVS_ERROR, - "PutPoolBuf: error=0x%08lx", - (unsigned long)iStatus); - } - else - { - //OS_MutSemTake(TO_AppData.MutexID); - Channel->MemInUse -= iStatus; - //OS_MutSemGive(TO_AppData.MutexID); - - PQ_Channel_LockByRef(Channel); - chQueue->CurrentlyQueuedCnt--; - chQueue->SentCount++; - PQ_Channel_UnlockByRef(Channel); - } - - } - else if(iStatus == OS_QUEUE_TIMEOUT) - { - /* Do nothing. Just loop back around and check the guard. */ - } - else - { - CFE_EVS_SendEvent(PQ_OSQUEUE_GET_ERROR_EID, CFE_EVS_ERROR, - "Send task failed to pop message from queue. (%i).", (int)iStatus); - } - } - } -} - - -static int Send(SBN_PeerInterface_t *Peer, SBN_MsgType_t MsgType, - SBN_MsgSz_t MsgSz, void *Payload) -{ - unsigned int TotalSize = MsgSz + SBN_PACKED_HDR_SZ; - int Status = SBN_SUCCESS; - - if(TotalSize > MAILBOX_MAX_BUFFER_SIZE_BYTES) - { - /* TODO update to event. */ - OS_printf("SBN_MailboxSend Send size too large %u bytes.\n", TotalSize); - Status = SBN_ERROR; - goto end_of_function; - } - - printf("MsgSz into queue %u\n", MsgSz); - /* Push message onto the PQ */ - PQ_Channel_ProcessTelemetry(&SBN_Mailbox_Data.Channel, Payload); - -end_of_function: - return Status; -} - - -static int Recv(SBN_NetInterface_t *Net, SBN_MsgType_t *MsgTypePtr, - SBN_MsgSz_t *MsgSzPtr, SBN_CpuID_t *CpuIDPtr, void *Payload) -{ - int SizeRead = 0; - unsigned int i = 0; - int ReturnValue = SBN_IF_EMPTY; - - SizeRead = MailboxRead(&SBN_Mailbox_Data.Mbox, - &SBN_Mailbox_Data.InputBuffer[0], - sizeof(SBN_Mailbox_Data.InputBuffer)); - if(SizeRead > 0) - { - for(i = 0; i < SizeRead; ++i) - { - unsigned int Size = MAILBOX_MAX_BUFFER_SIZE_BYTES; - unsigned int Status = ParseMessage(&SBN_Mailbox_Data.Parser, - SBN_Mailbox_Data.InputBuffer[i], - &SBN_Mailbox_Data.ParserBuffer[0], - &Size); - if(Status == MPS_MESSAGE_COMPLETE) - { - if (SBN_UnpackMsg(&SBN_Mailbox_Data.ParserBuffer[0], MsgSzPtr, MsgTypePtr, CpuIDPtr, Payload) == false) - { - OS_printf("Unpack failed.\n"); - ReturnValue = SBN_ERROR; - goto end_of_function; - } - ReturnValue = SBN_SUCCESS; - } - } - } - -#ifdef SBN_RECV_TASK - (void) OS_TaskDelay(MAILBOX_SBN_TASK_DELAY_MSEC); -#endif - -end_of_function: - return ReturnValue; -} - - -static int ReportModuleStatus(SBN_ModuleStatusPacket_t *Packet) -{ - PQ_Channel_CopyStats(&SBN_Mailbox_Data.HkTlm, &SBN_Mailbox_Data.Channel); - - CFE_SB_InitMsg(&SBN_Mailbox_Data.HkTlm, SBN_MODULE_HK_MID, - sizeof(SBN_Mailbox_Data.HkTlm), FALSE); - CFE_SB_TimeStampMsg((CFE_SB_Msg_t *) &SBN_Mailbox_Data.HkTlm); - CFE_SB_SendMsg((CFE_SB_Msg_t *) &SBN_Mailbox_Data.HkTlm); - - return SBN_SUCCESS; -} - - -static int ResetPeer(SBN_PeerInterface_t *Peer) -{ - return SBN_NOT_IMPLEMENTED; -} - - -static int UnloadNet(SBN_NetInterface_t *Net) -{ - return SBN_NOT_IMPLEMENTED; -} - - -static int UnloadPeer(SBN_PeerInterface_t *Peer) -{ - return SBN_NOT_IMPLEMENTED; -} - - -SBN_IfOps_t SBN_Mbox_Ops = -{ - LoadNet, - LoadPeer, - InitNet, - InitPeer, - PollPeer, - Send, - NULL, - Recv, - ReportModuleStatus, - ResetPeer, - UnloadNet, - UnloadPeer -}; - - diff --git a/apps/sbn/modules/mbox/fsw/src/sbn_mailbox_if.h b/apps/sbn/modules/mbox/fsw/src/sbn_mailbox_if.h deleted file mode 100644 index c011677c1..000000000 --- a/apps/sbn/modules/mbox/fsw/src/sbn_mailbox_if.h +++ /dev/null @@ -1,59 +0,0 @@ -#ifndef SBN_MAILBOX_IF_H -#define SBN_MAILBOX_IF_H - -#include "mailbox_parser.h" -#include "xmbox.h" -#include "pq_includes.h" - - -#define MAILBOX_HEADER_SIZE_BYTES (12) -#define MAILBOX_WORD_SIZE (4) -#define MAILBOX_HEADER_SIZE_WORDS (MAILBOX_HEADER_SIZE_BYTES/MAILBOX_WORD_SIZE) -#define MAILBOX_MAX_BUFFER_SIZE_BYTES (1500) -#define MAILBOX_MAX_BUFFER_SIZE_WORDS (MAILBOX_MAX_BUFFER_SIZE_BYTES/MAILBOX_WORD_SIZE) -#define MAILBOX_SBN_HEADER_SIZE_WORDS (2) -#define MAILBOX_SBN_TASK_DELAY_MSEC (1) - -#define SBN_MAILBOX_BLOCKING_DELAY (1) - -/* PQ specific */ -#define SBN_PQ_CHANNEL_NAME ("MBOX") -#define SBN_PQ_CHANNEL_NUMBER (0) -#define SBN_PQ_CONFIG_TABLENAME ("CFG") -#define SBN_PQ_DUMP_TABLENAME ("DMP") -#define SBN_PQ_CONFIG_TABLE_FILENAME ("/cf/apps/pq_cfg.tbl") -#define SBN_PQ_CF_THROTTLE_SEM_NAME ("PQ_CF_CH0_SEM") -#define SBN_PQ_CF_SEM_INIT_VALUE (1) - -/* Send task specific */ -#define SBN_PQ_SEND_TASK_NAME ("PQ_OUTCH_0") -#define SBN_PQ_SEND_TASK_STACK_SIZE (131072) -#define SBN_PQ_SEND_TASK_PRIORITY (50) -#define SBN_PQ_SEND_TASK_FLAGS (OS_ENABLE_CORE_0) -#define SBN_PQ_CHANNEL_GET_TIMEOUT (500) - - -typedef struct -{ - XMbox Mbox; - XMbox_Config *MboxConfigPtr; - unsigned int OutputBuffer[1500/sizeof(unsigned int)] __attribute__ ((aligned(4))); - unsigned int InputBuffer[1500/sizeof(unsigned int)] __attribute__ ((aligned(4))); - unsigned int ParserBuffer[1500/sizeof(unsigned int)]; - unsigned int PackedBuffer[1500/sizeof(unsigned int)]; - Mailbox_Parser_Handle_t Parser; - /* PQ specific. */ - PQ_ChannelData_t Channel; - PQ_HkTlm_t HkTlm; - /* Send task specific. */ - uint32 ChildTaskID; - CFE_ES_ChildTaskMainFuncPtr_t SendTask; - boolean TaskContinueFlag; -} SBN_Mailbox_Data_t; - - -int MailboxWrite(XMbox *instance, const unsigned int *buffer, unsigned int size); -int MailboxRead(XMbox *instance, unsigned int *buffer, unsigned int size); - - -#endif diff --git a/apps/sbn/modules/udp_pq/CMakeLists.txt b/apps/sbn/modules/udp_pq/CMakeLists.txt deleted file mode 100644 index 891fb6902..000000000 --- a/apps/sbn/modules/udp_pq/CMakeLists.txt +++ /dev/null @@ -1,13 +0,0 @@ -cmake_minimum_required(VERSION 2.6.4) -project(SBN_UDP C) - -if(NOT(IS_DIRECTORY ${SBN_APP_SOURCE_DIR})) - message(FATAL_ERROR "SBN_APP_SOURCE_DIR not defined, is sbn in the target list before this module?") -endif() - -include_directories(${SBN_APP_SOURCE_DIR}/fsw/platform_inc) - -aux_source_directory(fsw/src LIB_SRC_FILES) - -# Create the app module -add_cfe_app(sbn_udp ${LIB_SRC_FILES}) diff --git a/apps/sbn/modules/udp_pq/app.cfg b/apps/sbn/modules/udp_pq/app.cfg deleted file mode 100644 index 53d0c50f3..000000000 --- a/apps/sbn/modules/udp_pq/app.cfg +++ /dev/null @@ -1,12 +0,0 @@ -SHOULD_START=0 -APP_NAME=udp -APP_ABBREV=UDP -OBJ_TYPE=CFE_APP -APP_PATH=/cf/apps/udp.so -ENTRY_PT=UDP_AppMain -CFE_NAME=UDP_APP -PRIORITY=15 -STACK_SIZE=4096 -LOAD_ADDR=0x0 -EXCEPT_ACT=0 - diff --git a/apps/sbn/modules/udp_pq/fsw/for_build/CMakeLists.txt b/apps/sbn/modules/udp_pq/fsw/for_build/CMakeLists.txt deleted file mode 100644 index acbb9d7a5..000000000 --- a/apps/sbn/modules/udp_pq/fsw/for_build/CMakeLists.txt +++ /dev/null @@ -1,48 +0,0 @@ - ############################################################################# - # - # Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. - # - # Redistribution and use in source and binary forms, with or without - # modification, are permitted provided that the following conditions - # are met: - # - # 1. Redistributions of source code must retain the above copyright - # notice, this list of conditions and the following disclaimer. - # 2. Redistributions in binary form must reproduce the above copyright - # notice, this list of conditions and the following disclaimer in - # the documentation and/or other materials provided with the - # distribution. - # 3. Neither the name Windhover Labs nor the names of its contributors - # may be used to endorse or promote products derived from this software - # without specific prior written permission. - # - # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - # OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - # AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - # POSSIBILITY OF SUCH DAMAGE. - # - ############################################################################# - -buildliner_add_app_def(sbn_udp - FILE sbn_udp - SOURCES - ${CMAKE_CURRENT_SOURCE_DIR}/../src/sbn_udp_if.c - ${CMAKE_CURRENT_SOURCE_DIR}/../src/sbn_udp_if.h - ${CMAKE_CURRENT_SOURCE_DIR}/../src/mailbox_parser.c - ${CMAKE_CURRENT_SOURCE_DIR}/../src/mailbox_parser.h - ${CMAKE_CURRENT_SOURCE_DIR}/../src/sbn_udp_events.h - ${CMAKE_CURRENT_SOURCE_DIR}/../src/sbn_udp_if_struct.h - - INCLUDES - ${CMAKE_CURRENT_SOURCE_DIR}/../src/ - ${CMAKE_CURRENT_SOURCE_DIR}/../../../../fsw/src/ -) - diff --git a/apps/sbn/modules/udp_pq/fsw/for_build/Makefile b/apps/sbn/modules/udp_pq/fsw/for_build/Makefile deleted file mode 100644 index 0db7c9fcb..000000000 --- a/apps/sbn/modules/udp_pq/fsw/for_build/Makefile +++ /dev/null @@ -1,111 +0,0 @@ -############################################################################### -# File: UDP Application Makefile -# -############################################################################### -# -# Subsystem produced by this makefile. -# -export APPTARGET = sbn_udp - -# -# Entry Point for task -# -ENTRY_PT = SBN_UDP_AppMain - -# -# Object files required to build subsystem. -# -OBJS = sbn_udp_if.o - -# -# Source files required to build subsystem; used to generate dependencies. -# As long as there are no assembly files this can be automated. -# -SOURCES = $(OBJS:.o=.c) - - -## -## Specify extra C Flags needed to build this subsystem -## -LOCAL_COPTS = -g -fPIC - - -## -## EXEDIR is defined here, just in case it needs to be different for a custom -## build -## -EXEDIR=../exe - -## -## Certain OSs and Application Loaders require the following option for -## Shared libraries. Currently only needed for vxWorks 5.5 and RTEMS. -## For each shared library that this app depends on, you need to have an -## entry like the following: -## -R../tst_lib/tst_lib.elf -## -## For builds under cygwin when you need the cfs_lib.dll linked in -## set this variables as follows: -## -## SHARED_LIB_LINK =../cfs_lib/cfs_lib.dll -## -SHARED_LIB_LINK = - -######################################################################## -# Should not have to change below this line, except for customized -# Mission and cFE directory structures -######################################################################## - -# -# Set build type to CFE_APP. This allows us to -# define different compiler flags for the cFE Core and Apps. -# -BUILD_TYPE = CFE_APP - -## -## Include all necessary cFE make rules -## Any of these can be copied to a local file and -## changed if needed. -## -## -## cfe-config.mak contains PSP and OS selection -## -include ../cfe/cfe-config.mak -## -## debug-opts.mak contains debug switches -## -include ../cfe/debug-opts.mak -## -## compiler-opts.mak contains compiler definitions and switches/defines -## -include $(CFE_PSP_SRC)/$(PSP)/make/compiler-opts.mak - -## -## Setup the include path for this subsystem -## The OS specific includes are in the build-rules.make file -## -## If this subsystem needs include files from another app, add the path here. -## -INCLUDE_PATH = \ --I$(OSAL_SRC)/inc \ --I$(CFE_CORE_SRC)/inc \ --I$(CFE_PSP_SRC)/inc \ --I$(CFE_PSP_SRC)/$(PSP)/inc \ --I$(CFS_APP_SRC)/inc \ --I$(CFS_APP_SRC)/$(APPTARGET)/fsw/src \ --I$(CFS_MISSION_INC) \ --I../cfe/inc \ --I../inc - -## -## Define the VPATH make variable. -## This can be modified to include source from another directory. -## If there is no corresponding app in the cfs-apps directory, then this can be discarded, or -## if the mission chooses to put the src in another directory such as src, then that can be -## added here as well. -## -VPATH = $(CFS_APP_SRC)/$(APPTARGET)/fsw/src - -## -## Include the common make rules for building a cFE Application -## -include $(CFE_CORE_SRC)/make/app-rules.mak diff --git a/apps/sbn/modules/udp_pq/fsw/src/mailbox_parser.c b/apps/sbn/modules/udp_pq/fsw/src/mailbox_parser.c deleted file mode 100644 index 2345c128e..000000000 --- a/apps/sbn/modules/udp_pq/fsw/src/mailbox_parser.c +++ /dev/null @@ -1,69 +0,0 @@ -#include "mailbox_parser.h" - - -unsigned int ParseMessage(Mailbox_Parser_Handle_t *Handle, unsigned int Input, unsigned int* Buffer, unsigned int *BufferSize) -{ - unsigned int sizeInWords = (*BufferSize+3)/4; - - switch(Handle->State) - { - /* Fallthru */ - case MPS_MESSAGE_COMPLETE: - case MPS_WAITING_FOR_CADU: - { - if(Input == MAILBOX_MSG_CADU) - { - printf("got CADU\n"); - Handle->InputBufferCursor = 0; - Handle->CurrentChecksum = 0; - Handle->State = MPS_WAITING_FOR_SIZE; - } - else - { - Handle->State = MPS_WAITING_FOR_CADU; - } - break; - } - - case MPS_WAITING_FOR_SIZE: - { - printf("got size %u\n", Input); - Handle->FullMessageSize = Input; - Handle->State = MPS_PARSING_MESSAGE; - break; - } - - case MPS_PARSING_MESSAGE: - { - if(Handle->InputBufferCursor < sizeInWords) - { - Buffer[Handle->InputBufferCursor] = Input; - } - Handle->CurrentChecksum += Input; - Handle->InputBufferCursor++; - if(Handle->InputBufferCursor >= Handle->FullMessageSize) - { - Handle->State = MPS_WAITING_FOR_CHECKSUM; - } - break; - } - - case MPS_WAITING_FOR_CHECKSUM: - { - if(Input != Handle->CurrentChecksum) - { - printf("checksum mismatch Input %x current %x\n", Input, Handle->CurrentChecksum); - /* Checkum mismatch. */ - Handle->State = MPS_WAITING_FOR_CADU; - } - else - { - *BufferSize = Handle->InputBufferCursor*4; - Handle->State = MPS_MESSAGE_COMPLETE; - } - break; - } - } - - return Handle->State; -} diff --git a/apps/sbn/modules/udp_pq/fsw/src/mailbox_parser.h b/apps/sbn/modules/udp_pq/fsw/src/mailbox_parser.h deleted file mode 100644 index ebaaf6701..000000000 --- a/apps/sbn/modules/udp_pq/fsw/src/mailbox_parser.h +++ /dev/null @@ -1,27 +0,0 @@ -#ifndef MAILBOX_PARSER_H -#define MAILBOX_PARSER_H - -#define MAILBOX_MSG_CADU (0x01020304) - -typedef enum -{ - MPS_WAITING_FOR_CADU, - MPS_WAITING_FOR_SIZE, - MPS_PARSING_MESSAGE, - MPS_WAITING_FOR_CHECKSUM, - MPS_MESSAGE_COMPLETE, - MPS_BUFFER_OVERFLOW -} Mailbox_Parser_State_t; - -typedef struct -{ - Mailbox_Parser_State_t State; - unsigned int CurrentChecksum; - unsigned int InputBufferCursor; - unsigned int FullMessageSize; -} Mailbox_Parser_Handle_t; - - -unsigned int ParseMessage(Mailbox_Parser_Handle_t *Handle, unsigned int Input, unsigned int* Buffer, unsigned int *BufferSize); - -#endif diff --git a/apps/sbn/modules/udp_pq/fsw/src/sbn_udp_events.h b/apps/sbn/modules/udp_pq/fsw/src/sbn_udp_events.h deleted file mode 100644 index 6137eb371..000000000 --- a/apps/sbn/modules/udp_pq/fsw/src/sbn_udp_events.h +++ /dev/null @@ -1,10 +0,0 @@ -#ifndef _sbn_udp_events_h -#define _sbn_udp_events_h - -#include "sbn_events.h" - -#define SBN_UDP_SOCK_EID SBN_UDP_FIRST_EID + 1 /* skip 0th */ -#define SBN_UDP_CONFIG_EID SBN_UDP_FIRST_EID + 2 -#define SBN_UDP_DEBUG_EID SBN_UDP_FIRST_EID + 3 - -#endif /* _sbn_udp_events_h */ diff --git a/apps/sbn/modules/udp_pq/fsw/src/sbn_udp_if.c b/apps/sbn/modules/udp_pq/fsw/src/sbn_udp_if.c deleted file mode 100644 index 9f97d37e8..000000000 --- a/apps/sbn/modules/udp_pq/fsw/src/sbn_udp_if.c +++ /dev/null @@ -1,575 +0,0 @@ -#include "sbn_udp_if_struct.h" -#include "sbn_udp_if.h" -#include "sbn_udp_events.h" -#include "cfe.h" -#include -#include -#include "pq_includes.h" -#include "msg_ids.h" -#include "pq_events.h" -#include "mailbox_parser.h" - -/* at some point this will be replaced by the OSAL network interface */ -#ifdef _VXWORKS_OS_ -#include "selectLib.h" -#else -#include -#endif - - -#define MAILBOX_HEADER_SIZE_BYTES (12) -#define MAILBOX_WORD_SIZE (4) -#define MAILBOX_HEADER_SIZE_WORDS (MAILBOX_HEADER_SIZE_BYTES/MAILBOX_WORD_SIZE) -#define MAILBOX_MAX_BUFFER_SIZE_BYTES (1500) -#define MAILBOX_MAX_BUFFER_SIZE_WORDS (MAILBOX_MAX_BUFFER_SIZE_BYTES/MAILBOX_WORD_SIZE) -#define MAILBOX_SBN_HEADER_SIZE_WORDS (2) -#define MAILBOX_SBN_TASK_DELAY_MSEC (1) - - -void SBN_PQ_Output_Task(void); -void SBN_PQ_ChannelHandler(PQ_ChannelData_t *Channel); - -int SBN_UDP_Send_Direct(SBN_PeerInterface_t *Peer, SBN_MsgType_t MsgType, - SBN_MsgSz_t MsgSz, void *Payload); - -extern PQ_ChannelTbl_t PQ_BackupConfigTbl; - -/* TODO add to global data struct. */ -PQ_ChannelData_t Channel; -PQ_HkTlm_t HkTlm; -struct sockaddr_in s_addr; -int Socket; -/* Mailbox specific */ -unsigned int OutputBuffer[1500/sizeof(unsigned int)] __attribute__ ((aligned(4))); -unsigned int InputBuffer[1500/sizeof(unsigned int)] __attribute__ ((aligned(4))); -unsigned int ParserBuffer[1500/sizeof(unsigned int)]; -Mailbox_Parser_Handle_t Parser; - - -int SBN_UDP_LoadNet(const char **Row, int FieldCnt, - SBN_NetInterface_t *Net) -{ - char *ValidatePtr = NULL; - SBN_UDP_Net_t *NetData = (SBN_UDP_Net_t *)Net->ModulePvt; - - if(FieldCnt < SBN_UDP_ITEMS_PER_FILE_LINE) - { - CFE_EVS_SendEvent(SBN_UDP_CONFIG_EID, CFE_EVS_ERROR, - "invalid host entry (expected %d items, found %d)", - SBN_UDP_ITEMS_PER_FILE_LINE, FieldCnt); - return SBN_ERROR; - }/* end if */ - - strncpy(NetData->Host, Row[0], sizeof(NetData->Host)); - NetData->Port = strtol(Row[1], &ValidatePtr, 0); - if(!ValidatePtr || ValidatePtr == Row[1]) - { - CFE_EVS_SendEvent(SBN_UDP_CONFIG_EID, CFE_EVS_ERROR, - "invalid port"); - }/* end if */ - - return SBN_SUCCESS; -}/* end SBN_UDP_LoadNet */ - -int SBN_UDP_LoadPeer(const char **Row, int FieldCnt, - SBN_PeerInterface_t *Peer) -{ - char *ValidatePtr = NULL; - SBN_UDP_Peer_t *PeerData = (SBN_UDP_Peer_t *)Peer->ModulePvt; - - if(FieldCnt < SBN_UDP_ITEMS_PER_FILE_LINE) - { - CFE_EVS_SendEvent(SBN_UDP_CONFIG_EID, CFE_EVS_ERROR, - "invalid peer entry (expected %d items, found %d)", - SBN_UDP_ITEMS_PER_FILE_LINE, FieldCnt); - return SBN_ERROR; - }/* end if */ - - strncpy(PeerData->Host, Row[0], sizeof(PeerData->Host)); - PeerData->Port = strtol(Row[1], &ValidatePtr, 0); - if(!ValidatePtr || ValidatePtr == Row[1]) - { - CFE_EVS_SendEvent(SBN_UDP_CONFIG_EID, CFE_EVS_ERROR, - "invalid port"); - }/* end if */ - - return SBN_SUCCESS; -}/* end SBN_UDP_LoadHost */ - -/** - * Initializes an UDP host. - * - * @param Interface data structure containing the file entry - * @return SBN_SUCCESS on success, error code otherwise - */ -int SBN_UDP_InitNet(SBN_NetInterface_t *Net) -{ - int32 iStatus = 0; - SBN_UDP_Net_t *NetData = (SBN_UDP_Net_t *)Net->ModulePvt; - - CFE_EVS_SendEvent(SBN_UDP_SOCK_EID, CFE_EVS_DEBUG, - "creating socket (%s:%d)", NetData->Host, NetData->Port); - - if((NetData->Socket - = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP)) < 0) - { - CFE_EVS_SendEvent(SBN_UDP_SOCK_EID, CFE_EVS_ERROR, - "socket call failed (errno=%d)", errno); - return SBN_ERROR; - }/* end if */ - - iStatus = PQ_Channel_Init(0, &Channel); - if (iStatus != CFE_SUCCESS) - { - /* TODO update to event. */ - printf("PQ_Channel_Init failed%u\n", iStatus); - return SBN_ERROR; - } - - iStatus = PQ_Channel_OpenChannel( - &Channel, - PQ_UDP_CHANNEL_NAME, - PQ_UDP_CONFIG_TABLENAME, - PQ_UDP_CONFIG_TABLE_FILENAME, - &PQ_BackupConfigTbl, - PQ_UDP_DUMP_TABLENAME, - 1, - PQ_UDP_CF_THROTTLE_SEM_NAME); - - if (iStatus != CFE_SUCCESS) - { - /* TODO update to event. */ - printf("PQ_Channel_OpenChannel failed %u\n", iStatus); - return SBN_ERROR; - } - - static struct sockaddr_in my_addr; - - my_addr.sin_addr.s_addr = inet_addr(NetData->Host); - my_addr.sin_family = AF_INET; - my_addr.sin_port = htons(NetData->Port); - - if(bind(NetData->Socket, (struct sockaddr *) &my_addr, - sizeof(my_addr)) < 0) - { - CFE_EVS_SendEvent(SBN_UDP_SOCK_EID, CFE_EVS_ERROR, - "bind call failed (%s:%d Socket=%d errno=%d)", - NetData->Host, NetData->Port, NetData->Socket, errno); - return SBN_ERROR; - }/* end if */ - else - { - /* TODO update to event. */ - printf("SBN bound %s:%d\n", NetData->Host, NetData->Port); - } - - char TaskName[OS_MAX_API_NAME]; - snprintf(TaskName, OS_MAX_API_NAME, "PQ_OUTCH_%u", 0); - uint32 ChildTaskID = 0; - CFE_ES_ChildTaskMainFuncPtr_t ListenerTask = SBN_PQ_Output_Task; - - /* Create a child task here. */ - iStatus = CFE_ES_CreateChildTask( - &ChildTaskID, - (const char *)TaskName, - ListenerTask, - 0, - 131072, - 50, - OS_ENABLE_CORE_0); - if (iStatus != CFE_SUCCESS) - { - /* TODO update to event. */ - printf("CFE_ES_CreateChildTask failed%u\n", iStatus); - return SBN_ERROR; - } - - memset(&Parser, 0x0, sizeof(Parser)); - - return SBN_SUCCESS; -}/* end SBN_UDP_InitNet */ - -/** - * Initializes an UDP host or peer data struct depending on the - * CPU name. - * - * @param Interface data structure containing the file entry - * @return SBN_SUCCESS on success, error code otherwise - */ -int SBN_UDP_InitPeer(SBN_PeerInterface_t *Peer) -{ - return SBN_SUCCESS; -}/* end SBN_UDP_InitPeer */ - -int SBN_UDP_PollPeer(SBN_PeerInterface_t *Peer) -{ - //OS_time_t CurrentTime; - //OS_GetLocalTime(&CurrentTime); - - //SBN_UDP_Peer_t *PeerData = (SBN_UDP_Peer_t *)Peer->ModulePvt; - - //if(PeerData->ConnectedFlag) - //{ - //if(CurrentTime.seconds - Peer->LastRecv.seconds - //> SBN_UDP_PEER_TIMEOUT) - //{ - //CFE_EVS_SendEvent(SBN_UDP_DEBUG_EID, CFE_EVS_INFORMATION, - //"CPU %d disconnected", Peer->ProcessorID); - //PeerData->ConnectedFlag = FALSE; - //return 0; - //}/* end if */ - - //if(CurrentTime.seconds - Peer->LastSend.seconds - //> SBN_UDP_PEER_HEARTBEAT) - //{ - //return SBN_UDP_Send_Direct(Peer, SBN_UDP_HEARTBEAT_MSG, 0, NULL); - //}/* end if */ - //} - //else - //{ - //if(CurrentTime.seconds - Peer->LastSend.seconds - //> SBN_UDP_ANNOUNCE_TIMEOUT) - //{ - //return SBN_UDP_Send_Direct(Peer, SBN_UDP_ANNOUNCE_MSG, 0, NULL); - //}/* end if */ - //}/* end if */ - return SBN_SUCCESS; -}/* end SBN_UDP_PollPeer */ - -int SBN_UDP_Send(SBN_PeerInterface_t *Peer, SBN_MsgType_t MsgType, - SBN_MsgSz_t MsgSz, void *Payload) -{ - //SBN_UDP_Send_Direct(Peer, MsgType, MsgSz, Payload); - //return SBN_SUCCESS; - - printf("MsgSz into queue %u\n", MsgSz); - /* Push message onto the PQ */ - PQ_Channel_ProcessTelemetry(&Channel, Payload); - - //size_t BufSz = MsgSz + SBN_PACKED_HDR_SZ; - //uint8 Buf[BufSz]; - - SBN_UDP_Peer_t *PeerData = (SBN_UDP_Peer_t *)Peer->ModulePvt; - SBN_NetInterface_t *Net = Peer->Net; - SBN_UDP_Net_t *NetData = (SBN_UDP_Net_t *)Net->ModulePvt; - - //SBN_PackMsg(&Buf, MsgSz, MsgType, CFE_PSP_GetProcessorId(), Payload); - - /* TODO Save off this information for now. */ - memset(&s_addr, 0, sizeof(s_addr)); - s_addr.sin_family = AF_INET; - s_addr.sin_addr.s_addr = inet_addr(PeerData->Host); - s_addr.sin_port = htons(PeerData->Port); - Socket = NetData->Socket; - - //sendto(NetData->Socket, &Buf, BufSz, 0, (struct sockaddr *) &s_addr, - //sizeof(s_addr)); - - return SBN_SUCCESS; -}/* end SBN_UDP_Send */ - - -/* Note that this Recv function is indescriminate, packets will be received - * from all peers but that's ok, I just inject them into the SB and all is - * good! - */ -int SBN_UDP_Recv(SBN_NetInterface_t *Net, SBN_MsgType_t *MsgTypePtr, - SBN_MsgSz_t *MsgSzPtr, SBN_CpuID_t *CpuIDPtr, - void *Payload) -{ - uint8 RecvBuf[SBN_MAX_PACKED_MSG_SZ]; - - SBN_UDP_Net_t *NetData = (SBN_UDP_Net_t *)Net->ModulePvt; - boolean MessageComplete = FALSE; - -#ifndef SBN_RECV_TASK - - /* task-based peer connections block on reads, otherwise use select */ - - fd_set ReadFDs; - struct timeval Timeout; - - FD_ZERO(&ReadFDs); - FD_SET(NetData->Socket, &ReadFDs); - - memset(&Timeout, 0, sizeof(Timeout)); - - if(select(FD_SETSIZE, &ReadFDs, NULL, NULL, &Timeout) == 0) - { - /* nothing to receive */ - return SBN_IF_EMPTY; - }/* end if */ - -#endif /* !SBN_RECV_TASK */ - - int Received = recv(NetData->Socket, (char *)&RecvBuf, - CFE_SB_MAX_SB_MSG_SIZE, 0); - - if(Received < 0) - { - return SBN_ERROR; - }/* end if */ - - /* each UDP packet is a full SBN message */ - - /******************************************************************/ - printf("Received %u\n", Received); - memcpy(&InputBuffer[0], &RecvBuf[0], Received); - - /* TODO this can't handle two messages in a buffer. */ - if(Received > 0) - { - int i = 0; - /* Add check for word length. */ - for(i = 0; i < Received/4; ++i) - { - unsigned int Size = MAILBOX_MAX_BUFFER_SIZE_BYTES; - unsigned int Status = ParseMessage(&Parser, - InputBuffer[i], - &ParserBuffer[0], - &Size); - if(Status == MPS_MESSAGE_COMPLETE) - { - printf("message complete.\n"); - MessageComplete = TRUE; - if (SBN_UnpackMsg(&ParserBuffer[0], MsgSzPtr, MsgTypePtr, CpuIDPtr, Payload) == FALSE) - { - OS_printf("Unpack failed.\n"); - return SBN_ERROR; - } - } - } - } - /******************************************************************/ - - if(MessageComplete == FALSE) - { - return SBN_IF_EMPTY; - } - - //if(SBN_UnpackMsg(&RecvBuf[8], MsgSzPtr, MsgTypePtr, CpuIDPtr, Payload) - //== FALSE) - //{ - //return SBN_ERROR; - //}/* end if */ - - //if(SBN_UnpackMsg(&RecvBuf, MsgSzPtr, MsgTypePtr, CpuIDPtr, Payload) - //== FALSE) - //{ - //return SBN_ERROR; - //}/* end if */ - - CFE_SB_MsgId_t MsgID = CFE_SB_GetMsgId((CFE_SB_MsgPtr_t)Payload); - printf("Received %u CPUID %u, %x\n", Received, *CpuIDPtr, MsgID); - - SBN_PeerInterface_t *Peer = SBN_GetPeer(Net, *CpuIDPtr); - if(Peer == NULL) - { - return SBN_ERROR; - } - - SBN_UDP_Peer_t *PeerData = (SBN_UDP_Peer_t *)Peer->ModulePvt; - - if(!PeerData->ConnectedFlag) - { - CFE_EVS_SendEvent(SBN_UDP_DEBUG_EID, CFE_EVS_INFORMATION, - "CPU %d connected", *CpuIDPtr); - - PeerData->ConnectedFlag = TRUE; - - SBN_SendLocalSubsToPeer(Peer); - } - - return SBN_SUCCESS; -}/* end SBN_UDP_Recv */ - - -int SBN_UDP_ReportModuleStatus(SBN_ModuleStatusPacket_t *Packet) -{ - PQ_Channel_CopyStats(&HkTlm, &Channel); - - CFE_SB_InitMsg(&HkTlm, SBN_MODULE_HK_MID, - sizeof(HkTlm), FALSE); - CFE_SB_TimeStampMsg((CFE_SB_Msg_t *) &HkTlm); - CFE_SB_SendMsg((CFE_SB_Msg_t *) &HkTlm); - - return SBN_SUCCESS; -}/* end SBN_UDP_ReportModuleStatus */ - - -int SBN_UDP_ResetPeer(SBN_PeerInterface_t *Peer) -{ - return SBN_NOT_IMPLEMENTED; -}/* end SBN_UDP_ResetPeer */ - - -int SBN_UDP_UnloadNet(SBN_NetInterface_t *Net) -{ - SBN_UDP_Net_t *NetData = (SBN_UDP_Net_t *)Net->ModulePvt; - - close(NetData->Socket); - - int PeerIdx = 0; - for(PeerIdx = 0; PeerIdx < Net->PeerCnt; PeerIdx++) - { - SBN_UDP_UnloadPeer(&Net->Peers[PeerIdx]); - }/* end if */ - - return SBN_SUCCESS; -}/* end SBN_UDP_UnloadNet */ - -int SBN_UDP_UnloadPeer(SBN_PeerInterface_t *Peer) -{ - return SBN_SUCCESS; -}/* end SBN_UDP_UnloadPeer */ - - -void SBN_PQ_Output_Task(void) -{ - CFE_ES_RegisterChildTask(); - - SBN_PQ_ChannelHandler(&Channel); - - CFE_ES_ExitChildTask(); -} - - -/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ -/* */ -/* Channel Handler */ -/* */ -/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ -void SBN_PQ_ChannelHandler(PQ_ChannelData_t *Channel) -{ - int32 iStatus = CFE_SUCCESS; - uint32 msgSize = 0; - char *buffer; - - /* TODO add flag */ - while(1) - { - if(PQ_Channel_State(Channel) == PQ_CHANNEL_OPENED) - { - PQ_OutputQueue_t *chQueue = &Channel->OutputQueue; - - iStatus = OS_QueueGet( - chQueue->OSALQueueID, - &buffer, sizeof(buffer), &msgSize, 500); - - if(iStatus == OS_SUCCESS) - { - uint16 actualMessageSize = CFE_SB_GetTotalMsgLength((CFE_SB_MsgPtr_t)buffer); - CFE_SB_MsgId_t MsgID = CFE_SB_GetMsgId((CFE_SB_MsgPtr_t)buffer); - SBN_MsgType_t MsgType; - size_t BufSz = actualMessageSize + SBN_PACKED_HDR_SZ; - uint8 Buf[BufSz]; - int status = 0; - uint32 outputWord = 0; - - if(MsgID == SBN_SUB_MID || MsgID == SBN_ALLSUB_MID) - { - MsgType = SBN_SUBSCRIBE_MSG; - } - else if (MsgID == SBN_UNSUB_MID) - { - MsgType = SBN_UN_SUBSCRIBE_MSG; - } - else - { - MsgType = SBN_APP_MSG; - } - - SBN_PackMsg(&Buf, actualMessageSize, MsgType, CFE_PSP_GetProcessorId(), buffer); - - /* Mailbox specific */ - /******************************************************/ - unsigned int SizeInBytes = 0; - unsigned int SizeInWords = 0; - unsigned int Checksum = 0; - unsigned int i = 0; - - SizeInBytes = BufSz; - /* Ensure word boundary */ - SizeInBytes = (BufSz + (MAILBOX_WORD_SIZE - (BufSz % MAILBOX_WORD_SIZE))); - SizeInWords = SizeInBytes / MAILBOX_WORD_SIZE; - - //printf("BufSz %u\n", BufSz); - //printf("SizeInBytes %u\n", SizeInBytes); - //printf("SizeInWords %u\n", SizeInWords); - - if(SizeInWords + MAILBOX_HEADER_SIZE_WORDS > MAILBOX_MAX_BUFFER_SIZE_WORDS) - { - /* TODO update to event. */ - OS_printf("SBN_MailboxSend Send size too large %u bytes, %u words.\n", SizeInBytes, SizeInWords); - continue; - } - - /* Set CADU. */ - OutputBuffer[0] = MAILBOX_MSG_CADU; - /* Set size of the payload in words. */ - OutputBuffer[1] = SizeInWords; - /* Copy the payload. */ - memcpy(&OutputBuffer[2], &Buf[0], BufSz); - - Checksum = 0; - /* Checksum Calculation */ - for(i = 0; i < SizeInWords - 1; ++i) - { - Checksum += OutputBuffer[i + 2]; - } - /* Set the checksum. */ - OutputBuffer[SizeInWords + 2] = Checksum; - - /* Send payload size plus mailbox header size. */ - status = sendto(Socket, (const char*)&OutputBuffer[0], SizeInBytes + MAILBOX_HEADER_SIZE_BYTES, 0, (struct sockaddr *) &s_addr, - sizeof(s_addr)); - if (status < 0) - { - /* TODO */ - printf("sendto failed errno %d\n", errno); - iStatus = -1; - } - /******************************************************/ - printf("sent %u\n", SizeInBytes + MAILBOX_HEADER_SIZE_BYTES); - //status = sendto(Socket, (const char*)Buf, BufSz, 0, (struct sockaddr *) &s_addr, - //sizeof(s_addr)); - //if (status < 0) - //{ - ///* TODO */ - //printf("sendto failed errno %d\n", errno); - //iStatus = -1; - //} - - iStatus = CFE_ES_PutPoolBuf(Channel->MemPoolHandle, (uint32 *)buffer); - if(iStatus < 0) - { - (void) CFE_EVS_SendEvent(PQ_PUT_POOL_ERR_EID, CFE_EVS_ERROR, - "PutPoolBuf: error=0x%08lx", - (unsigned long)iStatus); - } - else - { - //OS_MutSemTake(TO_AppData.MutexID); - Channel->MemInUse -= iStatus; - //OS_MutSemGive(TO_AppData.MutexID); - - PQ_Channel_LockByRef(Channel); - chQueue->CurrentlyQueuedCnt--; - chQueue->SentCount++; - PQ_Channel_UnlockByRef(Channel); - } - - } - else if(iStatus == OS_QUEUE_TIMEOUT) - { - /* Do nothing. Just loop back around and check the guard. */ - } - else - { - CFE_EVS_SendEvent(PQ_OSQUEUE_GET_ERROR_EID, CFE_EVS_ERROR, - "Listener failed to pop message from queue. (%i).", (int)iStatus); - } - } - } -} - diff --git a/apps/sbn/modules/udp_pq/fsw/src/sbn_udp_if.h b/apps/sbn/modules/udp_pq/fsw/src/sbn_udp_if.h deleted file mode 100644 index ba3b7b17b..000000000 --- a/apps/sbn/modules/udp_pq/fsw/src/sbn_udp_if.h +++ /dev/null @@ -1,65 +0,0 @@ -#ifndef _sbn_udp_if_h_ -#define _sbn_udp_if_h_ - -#include "sbn_constants.h" -#include "sbn_interfaces.h" -#include "cfe.h" -/* network includes */ -#include -#include -#include -#include -#include -#include -#include - -/** - * UDP-specific message types. - */ -#define SBN_UDP_HEARTBEAT_MSG 0xA0 -#define SBN_UDP_ANNOUNCE_MSG 0xA1 - -int SBN_UDP_LoadNet(const char **Row, int FieldCount, - SBN_NetInterface_t *Net); - -int SBN_UDP_LoadPeer(const char **Row, int FieldCount, - SBN_PeerInterface_t *Peer); - -int SBN_UDP_InitNet(SBN_NetInterface_t *NetInterface); - -int SBN_UDP_InitPeer(SBN_PeerInterface_t *PeerInterface); - -int SBN_UDP_PollPeer(SBN_PeerInterface_t *PeerInterface); - -int SBN_UDP_Send(SBN_PeerInterface_t *Peer, SBN_MsgType_t MsgType, - SBN_MsgSz_t MsgSz, void *Payload); - -int SBN_UDP_Recv(SBN_NetInterface_t *Net, SBN_MsgType_t *MsgTypePtr, - SBN_MsgSz_t *MsgSzPtr, SBN_CpuID_t *CpuIDPtr, - void *PayloadBuffer); - -int SBN_UDP_ReportModuleStatus(SBN_ModuleStatusPacket_t *Packet); - -int SBN_UDP_ResetPeer(SBN_PeerInterface_t *PeerInterface); - -int SBN_UDP_UnloadNet(SBN_NetInterface_t *NetInterface); - -int SBN_UDP_UnloadPeer(SBN_PeerInterface_t *PeerInterface); - -SBN_IfOps_t SBN_UDP_Ops = -{ - SBN_UDP_LoadNet, - SBN_UDP_LoadPeer, - SBN_UDP_InitNet, - SBN_UDP_InitPeer, - SBN_UDP_PollPeer, - SBN_UDP_Send, - NULL, - SBN_UDP_Recv, - SBN_UDP_ReportModuleStatus, - SBN_UDP_ResetPeer, - SBN_UDP_UnloadNet, - SBN_UDP_UnloadPeer -}; - -#endif /* _sbn_udp_if_h_ */ diff --git a/apps/sbn/modules/udp_pq/fsw/src/sbn_udp_if_struct.h b/apps/sbn/modules/udp_pq/fsw/src/sbn_udp_if_struct.h deleted file mode 100644 index 6ee08b879..000000000 --- a/apps/sbn/modules/udp_pq/fsw/src/sbn_udp_if_struct.h +++ /dev/null @@ -1,48 +0,0 @@ -#ifndef _sbn_udp_if_struct_h_ -#define _sbn_udp_if_struct_h_ - -#include "sbn_constants.h" -#include "sbn_interfaces.h" -#include "sbn_platform_cfg.h" -#include "cfe.h" - -#define SBN_UDP_ITEMS_PER_FILE_LINE 2 - -/** - * \brief Number of seconds since last I've sent the peer a message when - * I send an empty heartbeat message. - */ -#define SBN_UDP_PEER_HEARTBEAT 5 - -/** - * \brief Number of seconds since I've last heard from the peer when I consider - * the peer connection to be dropped. - */ -#define SBN_UDP_PEER_TIMEOUT 10 - -/** - * \brief If we're not connected, send peer occasional messages to wake - * them up and tell them "I'm here". - */ -#define SBN_UDP_ANNOUNCE_TIMEOUT 10 - -typedef struct -{ - char Host[16]; - int Port; - - /** - * \brief TRUE if "connected" (I've sent subs, I have received messages - * in less than - * data). - */ - boolean ConnectedFlag; -} SBN_UDP_Peer_t; - -typedef struct -{ - char Host[16]; - int Port, Socket; -} SBN_UDP_Net_t; - -#endif /* _sbn_udp_if_struct_h_ */ diff --git a/apps/sbn/modules/uio_mbox/fsw/for_build/CMakeLists.txt b/apps/sbn/modules/uio_mbox/fsw/for_build/CMakeLists.txt deleted file mode 100644 index 46be0dfbc..000000000 --- a/apps/sbn/modules/uio_mbox/fsw/for_build/CMakeLists.txt +++ /dev/null @@ -1,47 +0,0 @@ - ############################################################################# - # - # Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. - # - # Redistribution and use in source and binary forms, with or without - # modification, are permitted provided that the following conditions - # are met: - # - # 1. Redistributions of source code must retain the above copyright - # notice, this list of conditions and the following disclaimer. - # 2. Redistributions in binary form must reproduce the above copyright - # notice, this list of conditions and the following disclaimer in - # the documentation and/or other materials provided with the - # distribution. - # 3. Neither the name Windhover Labs nor the names of its contributors - # may be used to endorse or promote products derived from this software - # without specific prior written permission. - # - # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - # OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - # AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - # POSSIBILITY OF SUCH DAMAGE. - # - ############################################################################# - -buildliner_add_app_def(sbn_uio_mbox - FILE sbn_uio_mbox - SOURCES - ${CMAKE_CURRENT_SOURCE_DIR}/../src/sbn_uio_mailbox_if.c - ${CMAKE_CURRENT_SOURCE_DIR}/../src/sbn_uio_mailbox_if.h - ${CMAKE_CURRENT_SOURCE_DIR}/../src/mailbox_map.h - ${CMAKE_CURRENT_SOURCE_DIR}/../src/mailbox_parser.c - ${CMAKE_CURRENT_SOURCE_DIR}/../src/mailbox_parser.h - - INCLUDES - ${CMAKE_CURRENT_SOURCE_DIR}/../src/ - ${CMAKE_CURRENT_SOURCE_DIR}/../../../../fsw/src/ -) - diff --git a/apps/sbn/modules/uio_mbox/fsw/src/mailbox_map.h b/apps/sbn/modules/uio_mbox/fsw/src/mailbox_map.h deleted file mode 100644 index f722aba86..000000000 --- a/apps/sbn/modules/uio_mbox/fsw/src/mailbox_map.h +++ /dev/null @@ -1,47 +0,0 @@ -#ifndef MAILBOX_MAP_H -#define MAILBOX_MAP_H - -/* Mailbox Registers */ -/* Table 2-5 Mailbox v2.1 Product Guide */ -#define MAILBOX_WRITE_REG (0x0) -#define MAILBOX_RESERVED_0_REG (0x4) -#define MAILBOX_READ_REG (0x8) -#define MAILBOX_RESERVED_1_REG (0xC) -#define MAILBOX_STATUS_REG (0x10) -#define MAILBOX_ERROR_REG (0x14) -#define MAILBOX_SEND_INT_REG (0x18) -#define MAILBOX_RECV_INT_REG (0x1C) -#define MAILBOX_INT_STATUS_REG (0x20) -#define MAILBOX_INT_ENABLE_REG (0x24) -#define MAILBOX_INT_PENDING_REG (0x28) -#define MAILBOX_CONTROL_REG (0x2C) -#define MAILBOX_RESERVED_2_REG (0x30) -#define MAILBOX_RESERVED_3_REG (0x34) -#define MAILBOX_RESERVED_4_REG (0x38) -#define MAILBOX_RESERVED_5_REG (0x3C) - -/* Status bits */ -/* Table 2-11 Mailbox v2.1 Product Guide */ -#define MAILBOX_STATUS_FIFO_EMPTY_BIT (0x1) -#define MAILBOX_STATUS_FIFO_FULL_BIT (0x2) -#define MAILBOX_STATUS_FIFO_RTA_BIT (0x4) -#define MAILBOX_STATUS_FIFO_STA_BIT (0x8) - -/* Error bits */ -/* Table 2-13 Mailbox v2.1 Product Guide */ -#define MAILBOX_ERROR_FULL_BIT (0x1) -#define MAILBOX_ERROR_EMPTY_BIT (0x2) - -/* Interrupt bits */ -/* Table 2-14 - 2-23 Mailbox v2.1 Product Guide */ -#define MAILBOX_INT_STA_BIT (0x1) -#define MAILBOX_INT_RTA_BIT (0x2) -#define MAILBOX_INT_ERROR_BIT (0x4) - -/* Control bits */ -/* Table 2-24 Mailbox v2.1 Product Guide */ -#define MAILBOX_CONTROL_RESET_SEND_FIFO_BIT (0x1) -#define MAILBOX_CONTROL_RESET_RECV_FIFO_BIT (0x2) - - -#endif /* MAILBOX_MAP_H */ diff --git a/apps/sbn/modules/uio_mbox/fsw/src/mailbox_parser.c b/apps/sbn/modules/uio_mbox/fsw/src/mailbox_parser.c deleted file mode 100644 index e5ad9d4bd..000000000 --- a/apps/sbn/modules/uio_mbox/fsw/src/mailbox_parser.c +++ /dev/null @@ -1,67 +0,0 @@ -#include "sbn_uio_mailbox_if.h" -#include "mailbox_parser.h" - - -unsigned int ParseMessage(Mailbox_Parser_Handle_t *Handle, unsigned int Input, unsigned int* Buffer, unsigned int *BufferSize) -{ - unsigned int sizeInWords = (*BufferSize+3)/4; - - switch(Handle->State) - { - /* Fallthru */ - case MPS_MESSAGE_COMPLETE: - case MPS_WAITING_FOR_CADU: - { - if(Input == MAILBOX_MSG_CADU) - { - Handle->InputBufferCursor = 0; - Handle->CurrentChecksum = 0; - Handle->State = MPS_WAITING_FOR_SIZE; - } - else - { - Handle->State = MPS_WAITING_FOR_CADU; - } - break; - } - - case MPS_WAITING_FOR_SIZE: - { - Handle->FullMessageSize = Input; - Handle->State = MPS_PARSING_MESSAGE; - break; - } - - case MPS_PARSING_MESSAGE: - { - if(Handle->InputBufferCursor < sizeInWords) - { - Buffer[Handle->InputBufferCursor] = Input; - } - Handle->CurrentChecksum += Input; - Handle->InputBufferCursor++; - if(Handle->InputBufferCursor >= Handle->FullMessageSize) - { - Handle->State = MPS_WAITING_FOR_CHECKSUM; - } - break; - } - - case MPS_WAITING_FOR_CHECKSUM: - { - if(Input != Handle->CurrentChecksum) - { - /* Checkum mismatch. */ - Handle->State = MPS_WAITING_FOR_CADU; - } - else - { - *BufferSize = Handle->InputBufferCursor*4; - Handle->State = MPS_MESSAGE_COMPLETE; - } - break; - } - } - - return Handle->State; -} diff --git a/apps/sbn/modules/uio_mbox/fsw/src/mailbox_parser.h b/apps/sbn/modules/uio_mbox/fsw/src/mailbox_parser.h deleted file mode 100644 index ebaaf6701..000000000 --- a/apps/sbn/modules/uio_mbox/fsw/src/mailbox_parser.h +++ /dev/null @@ -1,27 +0,0 @@ -#ifndef MAILBOX_PARSER_H -#define MAILBOX_PARSER_H - -#define MAILBOX_MSG_CADU (0x01020304) - -typedef enum -{ - MPS_WAITING_FOR_CADU, - MPS_WAITING_FOR_SIZE, - MPS_PARSING_MESSAGE, - MPS_WAITING_FOR_CHECKSUM, - MPS_MESSAGE_COMPLETE, - MPS_BUFFER_OVERFLOW -} Mailbox_Parser_State_t; - -typedef struct -{ - Mailbox_Parser_State_t State; - unsigned int CurrentChecksum; - unsigned int InputBufferCursor; - unsigned int FullMessageSize; -} Mailbox_Parser_Handle_t; - - -unsigned int ParseMessage(Mailbox_Parser_Handle_t *Handle, unsigned int Input, unsigned int* Buffer, unsigned int *BufferSize); - -#endif diff --git a/apps/sbn/modules/uio_mbox/fsw/src/sbn_uio_mailbox_if.c b/apps/sbn/modules/uio_mbox/fsw/src/sbn_uio_mailbox_if.c deleted file mode 100644 index 3b3b41e39..000000000 --- a/apps/sbn/modules/uio_mbox/fsw/src/sbn_uio_mailbox_if.c +++ /dev/null @@ -1,473 +0,0 @@ -#include "mailbox_map.h" -#include "sbn_uio_mailbox_if.h" -#include -#include -#include -#include -#include -#include -#include -#include "sbn_interfaces.h" -#include "sbn_platform_cfg.h" -#include "msg_ids.h" -#include "pq_events.h" - -extern PQ_ChannelTbl_t PQ_BackupConfigTbl; - -SBN_UIO_Mailbox_Data_t SBN_UIO_Mailbox_Data; - -void SBN_PQ_Output_Task(void); -void SBN_PQ_ChannelHandler(PQ_ChannelData_t *Channel); - -static void uio_write(void *timer_base, unsigned int offset, unsigned int value) -{ - *((volatile unsigned *)(timer_base + offset)) = value; -} - - -static unsigned int uio_read(void *timer_base, unsigned int offset) -{ - return *((volatile unsigned *)(timer_base + offset)); -} - - -void *InitDevice(const char *path) -{ - int fd = 0; - void *mailbox_ptr = 0; - - fd = open(path, O_RDWR); - if (fd < 1) - { - /* TODO remove after debug. */ - OS_printf("Invalid UIO device file:%s.\n", path); - goto end_of_function; - } - - mailbox_ptr = mmap(NULL, MAILBOX_SIZE, PROT_READ|PROT_WRITE, MAP_SHARED, fd, 0); - if (mailbox_ptr == MAP_FAILED) - { - /* TODO remove after debug. */ - OS_printf("Mmap call failure. errno %d\n", errno); - goto end_of_function; - } - - close(fd); - -end_of_function: - return mailbox_ptr; -} - - -bool MailboxFull(void *instance) -{ - unsigned int reg = 0; - reg = uio_read(instance, MAILBOX_STATUS_REG); - return reg & MAILBOX_STATUS_FIFO_FULL_BIT; -} - - -bool MailboxEmpty(void *instance) -{ - unsigned int reg = 0; - reg = uio_read(instance, MAILBOX_STATUS_REG); - return reg & MAILBOX_STATUS_FIFO_EMPTY_BIT; -} - - -bool MailboxFullError(void *instance) -{ - unsigned int reg = 0; - reg = uio_read(instance, MAILBOX_ERROR_REG); - return reg & MAILBOX_ERROR_FULL_BIT; -} - - -bool MailboxEmptyError(void *instance) -{ - unsigned int reg = 0; - reg = uio_read(instance, MAILBOX_ERROR_REG); - return reg & MAILBOX_ERROR_EMPTY_BIT; -} - - -/* Blocking write */ -int MailboxWrite(void *instance, const unsigned int *buffer, unsigned int size) -{ - int status = size; - bool isFull = false; - unsigned int i = 0; - - for(i = 0; i < size; ++i) - { - while(MailboxFull(instance)) - { - OS_TaskDelay(SBN_MAILBOX_BLOCKING_DELAY); - } - uio_write(instance, MAILBOX_WRITE_REG, *buffer++); - } - -end_of_function: - return status; -} - -/* Non-blocking read */ -int MailboxRead(void *instance, unsigned int *buffer, unsigned int size) -{ - int status = 0; - bool isEmpty = false; - unsigned int i = 0; - - isEmpty = MailboxEmpty(instance); - if(isEmpty == true) - { - goto end_of_function; - } - - for(i = 0; i < size; ++i) - { - *buffer++ = uio_read(instance, MAILBOX_READ_REG); - status = size; - isEmpty = MailboxEmpty(instance); - if(isEmpty == true) - { - goto end_of_function; - } - } - -end_of_function: - return status; -} - - -void SBN_PQ_Output_Task(void) -{ - CFE_ES_RegisterChildTask(); - - SBN_PQ_ChannelHandler(&SBN_UIO_Mailbox_Data.Channel); - - CFE_ES_ExitChildTask(); -} - - -void SBN_PQ_ChannelHandler(PQ_ChannelData_t *Channel) -{ - int32 iStatus = CFE_SUCCESS; - uint32 msgSize = 0; - char *buffer; - - SBN_UIO_Mailbox_Data.TaskContinueFlag = TRUE; - - while(SBN_UIO_Mailbox_Data.TaskContinueFlag) - { - if(PQ_Channel_State(Channel) == PQ_CHANNEL_OPENED) - { - PQ_OutputQueue_t *chQueue = &Channel->OutputQueue; - - iStatus = OS_QueueGet( - chQueue->OSALQueueID, - &buffer, sizeof(buffer), &msgSize, SBN_PQ_CHANNEL_GET_TIMEOUT); - - if(iStatus == OS_SUCCESS) - { - uint16 actualMessageSize = CFE_SB_GetTotalMsgLength((CFE_SB_MsgPtr_t)buffer); - CFE_SB_MsgId_t MsgID = CFE_SB_GetMsgId((CFE_SB_MsgPtr_t)buffer); - SBN_MsgType_t MsgType; - size_t BufSz = actualMessageSize + SBN_PACKED_HDR_SZ; - /* TODO fix this. */ - uint8 Buf[BufSz]; - unsigned int SizeInBytes = 0; - unsigned int SizeInWords = 0; - unsigned int Checksum = 0; - unsigned int i = 0; - - if(MsgID == SBN_SUB_MID || MsgID == SBN_ALLSUB_MID) - { - MsgType = SBN_SUBSCRIBE_MSG; - } - else if (MsgID == SBN_UNSUB_MID) - { - MsgType = SBN_UN_SUBSCRIBE_MSG; - } - else - { - MsgType = SBN_APP_MSG; - } - - SBN_PackMsg(&Buf, actualMessageSize, MsgType, CFE_PSP_GetProcessorId(), buffer); - - SizeInBytes = BufSz; - /* Ensure word boundary */ - SizeInBytes = (BufSz + (MAILBOX_WORD_SIZE - (BufSz % MAILBOX_WORD_SIZE))); - SizeInWords = SizeInBytes / MAILBOX_WORD_SIZE; - - //printf("BufSz %u\n", BufSz); - //printf("SizeInBytes %u\n", SizeInBytes); - //printf("SizeInWords %u\n", SizeInWords); - - if(SizeInWords + MAILBOX_HEADER_SIZE_WORDS > MAILBOX_MAX_BUFFER_SIZE_WORDS) - { - /* TODO update to event. */ - OS_printf("SBN_MailboxSend Send size too large %u bytes, %u words.\n", SizeInBytes, SizeInWords); - continue; - } - - /* Set CADU. */ - SBN_UIO_Mailbox_Data.OutputBuffer[0] = MAILBOX_MSG_CADU; - /* Set size of the payload in words. */ - SBN_UIO_Mailbox_Data.OutputBuffer[1] = SizeInWords; - /* Copy the payload. */ - memcpy(&SBN_UIO_Mailbox_Data.OutputBuffer[2], &Buf[0], BufSz); - - Checksum = 0; - /* Checksum Calculation */ - for(i = 0; i < SizeInWords - 1; ++i) - { - Checksum += SBN_UIO_Mailbox_Data.OutputBuffer[i + 2]; - } - /* Set the checksum. */ - SBN_UIO_Mailbox_Data.OutputBuffer[SizeInWords + 2] = Checksum; - - /* Blocking write. */ - (void) MailboxWrite(SBN_UIO_Mailbox_Data.Instance, &SBN_UIO_Mailbox_Data.OutputBuffer[0], SizeInWords + MAILBOX_HEADER_SIZE_WORDS); - - iStatus = CFE_ES_PutPoolBuf(Channel->MemPoolHandle, (uint32 *)buffer); - if(iStatus < 0) - { - (void) CFE_EVS_SendEvent(PQ_PUT_POOL_ERR_EID, CFE_EVS_ERROR, - "PutPoolBuf: error=0x%08lx", - (unsigned long)iStatus); - } - else - { - //OS_MutSemTake(TO_AppData.MutexID); - Channel->MemInUse -= iStatus; - //OS_MutSemGive(TO_AppData.MutexID); - - PQ_Channel_LockByRef(Channel); - chQueue->CurrentlyQueuedCnt--; - chQueue->SentCount++; - PQ_Channel_UnlockByRef(Channel); - } - - } - else if(iStatus == OS_QUEUE_TIMEOUT) - { - /* Do nothing. Just loop back around and check the guard. */ - } - else - { - CFE_EVS_SendEvent(PQ_OSQUEUE_GET_ERROR_EID, CFE_EVS_ERROR, - "Send task failed to pop message from queue. (%i).", (int)iStatus); - } - } - } -} - - -static int InitNet(SBN_NetInterface_t *Net) -{ - int Status = SBN_SUCCESS; - - memset(&SBN_UIO_Mailbox_Data, 0x0, sizeof(SBN_UIO_Mailbox_Data)); - - SBN_UIO_Mailbox_Data.HkTlm.ChannelMaxMem = PQ_NUM_BYTES_IN_MEM_POOL; - - SBN_UIO_Mailbox_Data.Instance = InitDevice(MAILBOX_UIO_PATH); - if(SBN_UIO_Mailbox_Data.Instance == NULL) - { - /* TODO update to event. */ - OS_printf("SBN_UIO_Mailbox InitDevice Instance Null.\n"); - Status = SBN_ERROR; - goto end_of_function; - } - - /* Initialize PQ channel. */ - Status = PQ_Channel_Init(SBN_PQ_CHANNEL_NUMBER, &SBN_UIO_Mailbox_Data.Channel); - if (Status != CFE_SUCCESS) - { - /* TODO update to event. */ - OS_printf("PQ_Channel_Init failed%u\n", Status); - Status = SBN_ERROR; - goto end_of_function; - } - - /* Open PQ channel. */ - Status = PQ_Channel_OpenChannel( - &SBN_UIO_Mailbox_Data.Channel, - SBN_PQ_CHANNEL_NAME, - SBN_PQ_CONFIG_TABLENAME, - SBN_PQ_CONFIG_TABLE_FILENAME, - &PQ_BackupConfigTbl, - SBN_PQ_DUMP_TABLENAME, - SBN_PQ_CF_SEM_INIT_VALUE, - SBN_PQ_CF_THROTTLE_SEM_NAME); - - if (Status != CFE_SUCCESS) - { - /* TODO update to event. */ - OS_printf("PQ_Channel_OpenChannel failed %u\n", Status); - Status = SBN_ERROR; - goto end_of_function; - } - - /* Create send task. */ - SBN_UIO_Mailbox_Data.SendTask = SBN_PQ_Output_Task; - Status = CFE_ES_CreateChildTask( - &SBN_UIO_Mailbox_Data.ChildTaskID, - SBN_PQ_SEND_TASK_NAME, - SBN_UIO_Mailbox_Data.SendTask, - 0, - SBN_PQ_SEND_TASK_STACK_SIZE, - SBN_PQ_SEND_TASK_PRIORITY, - SBN_PQ_SEND_TASK_FLAGS); - if (Status != CFE_SUCCESS) - { - /* TODO update to event. */ - printf("CFE_ES_CreateChildTask failed%u\n", Status); - Status = SBN_ERROR; - goto end_of_function; - } - -end_of_function: - return Status; -} - - -static int InitPeer(SBN_PeerInterface_t *Peer) -{ - - return SBN_SUCCESS; -} - - -static int LoadNet(const char **Row, int FieldCnt, SBN_NetInterface_t *Net) -{ - return SBN_SUCCESS; -} - - -static int LoadPeer(const char **Row, int FieldCnt, SBN_PeerInterface_t *Peer) -{ - return SBN_SUCCESS; -} - - -static int PollPeer(SBN_PeerInterface_t *Peer) -{ - return SBN_SUCCESS; -} - - -static int Send(SBN_PeerInterface_t *Peer, SBN_MsgType_t MsgType, - SBN_MsgSz_t MsgSz, void *Payload) -{ - unsigned int TotalSize = MsgSz + SBN_PACKED_HDR_SZ; - int Status = SBN_SUCCESS; - - if(TotalSize > MAILBOX_MAX_BUFFER_SIZE_BYTES) - { - /* TODO update to event. */ - OS_printf("SBN_MailboxSend Send size too large %u bytes.\n", TotalSize); - Status = SBN_ERROR; - goto end_of_function; - } - - printf("MsgSz into queue %u\n", MsgSz); - /* Push message onto the PQ */ - PQ_Channel_ProcessTelemetry(&SBN_UIO_Mailbox_Data.Channel, Payload); - -end_of_function: - return Status; -} - - -static int Recv(SBN_NetInterface_t *Net, SBN_MsgType_t *MsgTypePtr, - SBN_MsgSz_t *MsgSzPtr, SBN_CpuID_t *CpuIDPtr, void *Payload) -{ - int SizeRead = 0; - unsigned int i = 0; - int ReturnValue = SBN_IF_EMPTY; - - SizeRead = MailboxRead(SBN_UIO_Mailbox_Data.Instance, - &SBN_UIO_Mailbox_Data.InputBuffer[0], - MAILBOX_MAX_BUFFER_SIZE_WORDS); - if(SizeRead > 0) - { - for(i = 0; i < SizeRead; ++i) - { - unsigned int Size = MAILBOX_MAX_BUFFER_SIZE_BYTES; - unsigned int Status = ParseMessage(&SBN_UIO_Mailbox_Data.Parser, - SBN_UIO_Mailbox_Data.InputBuffer[i], - &SBN_UIO_Mailbox_Data.ParserBuffer[0], - &Size); - if(Status == MPS_MESSAGE_COMPLETE) - { - if (SBN_UnpackMsg(&SBN_UIO_Mailbox_Data.ParserBuffer[0], MsgSzPtr, MsgTypePtr, CpuIDPtr, Payload) == false) - { - OS_printf("Unpack failed.\n"); - ReturnValue = SBN_ERROR; - goto end_of_function; - } - ReturnValue = SBN_SUCCESS; - } - } - } - -#ifdef SBN_RECV_TASK - (void) OS_TaskDelay(MAILBOX_SBN_TASK_DELAY_MSEC); -#endif - -end_of_function: - return ReturnValue; -} - - -static int ReportModuleStatus(SBN_ModuleStatusPacket_t *Packet) -{ - PQ_Channel_CopyStats(&SBN_UIO_Mailbox_Data.HkTlm, &SBN_UIO_Mailbox_Data.Channel); - - CFE_SB_InitMsg(&SBN_UIO_Mailbox_Data.HkTlm, SBN_MODULE_HK_MID, - sizeof(SBN_UIO_Mailbox_Data.HkTlm), FALSE); - CFE_SB_TimeStampMsg((CFE_SB_Msg_t *) &SBN_UIO_Mailbox_Data.HkTlm); - CFE_SB_SendMsg((CFE_SB_Msg_t *) &SBN_UIO_Mailbox_Data.HkTlm); - - return SBN_SUCCESS; -} - - -static int ResetPeer(SBN_PeerInterface_t *Peer) -{ - return SBN_NOT_IMPLEMENTED; -} - - -static int UnloadNet(SBN_NetInterface_t *Net) -{ - return SBN_NOT_IMPLEMENTED; -} - - -static int UnloadPeer(SBN_PeerInterface_t *Peer) -{ - return SBN_NOT_IMPLEMENTED; -} - - -SBN_IfOps_t SBN_UIO_Mbox_Ops = -{ - LoadNet, - LoadPeer, - InitNet, - InitPeer, - PollPeer, - Send, - NULL, - Recv, - ReportModuleStatus, - ResetPeer, - UnloadNet, - UnloadPeer -}; - - diff --git a/apps/sbn/modules/uio_mbox/fsw/src/sbn_uio_mailbox_if.h b/apps/sbn/modules/uio_mbox/fsw/src/sbn_uio_mailbox_if.h deleted file mode 100644 index 220cd3287..000000000 --- a/apps/sbn/modules/uio_mbox/fsw/src/sbn_uio_mailbox_if.h +++ /dev/null @@ -1,78 +0,0 @@ -#ifndef SBN_UIO_MAILBOX_IF_H -#define SBN_UIO_MAILBOX_IF_H - -#include -#include "mailbox_parser.h" -#include "pq_includes.h" -#include "cfe.h" - -/* Mailbox specific */ -#define MAILBOX_SIZE (0x10000) -#define MAILBOX_UIO_PATH "/dev/uio0" -#define MAILBOX_HEADER_SIZE_BYTES (12) -#define MAILBOX_WORD_SIZE (4) -#define MAILBOX_HEADER_SIZE_WORDS (MAILBOX_HEADER_SIZE_BYTES/MAILBOX_WORD_SIZE) -#define MAILBOX_MAX_BUFFER_SIZE_BYTES (1500) -#define MAILBOX_MAX_BUFFER_SIZE_WORDS (MAILBOX_MAX_BUFFER_SIZE_BYTES/MAILBOX_WORD_SIZE) -#define MAILBOX_SBN_HEADER_SIZE_WORDS (2) -#define MAILBOX_SBN_TASK_DELAY_MSEC (1) - -#define SBN_MAILBOX_BLOCKING_DELAY (1) - -/* PQ specific */ -#define SBN_PQ_CHANNEL_NAME ("MBOX") -#define SBN_PQ_CHANNEL_NUMBER (0) -#define SBN_PQ_CONFIG_TABLENAME ("CFG") -#define SBN_PQ_DUMP_TABLENAME ("DMP") -#define SBN_PQ_CONFIG_TABLE_FILENAME ("/cf/apps/pq_cfg.tbl") -#define SBN_PQ_CF_THROTTLE_SEM_NAME ("PQ_CF_CH0_SEM") -#define SBN_PQ_CF_SEM_INIT_VALUE (1) - -/* Send task specific */ -#define SBN_PQ_SEND_TASK_NAME ("PQ_OUTCH_0") -#define SBN_PQ_SEND_TASK_STACK_SIZE (131072) -#define SBN_PQ_SEND_TASK_PRIORITY (50) -#define SBN_PQ_SEND_TASK_FLAGS (OS_ENABLE_CORE_0) -#define SBN_PQ_CHANNEL_GET_TIMEOUT (500) - - -typedef struct -{ - void *Instance; - unsigned int OutputBuffer[1500/sizeof(unsigned int)] __attribute__ ((aligned(4))); - unsigned int InputBuffer[1500/sizeof(unsigned int)] __attribute__ ((aligned(4))); - unsigned int ParserBuffer[1500/sizeof(unsigned int)]; - unsigned int PackedBuffer[1500/sizeof(unsigned int)]; - Mailbox_Parser_Handle_t Parser; - /* PQ specific. */ - PQ_ChannelData_t Channel; - PQ_HkTlm_t HkTlm; - /* Send task specific. */ - uint32 ChildTaskID; - CFE_ES_ChildTaskMainFuncPtr_t SendTask; - boolean TaskContinueFlag; -} SBN_UIO_Mailbox_Data_t; - - -/* Write to shared memory. */ -static void uio_write(void *base, unsigned int offset, unsigned int value); -/* Read from shared memory. */ -static unsigned int uio_read(void *base, unsigned int offset); -/* Open and memory map uio. */ -void *InitDevice(const char *path); -/* Check if mailbox is full. */ -bool MailboxFull(void *instance); -/* Check if mailbox is empty. */ -bool MailboxEmpty(void *instance); -/* Check for full error. */ -bool MailboxFullError(void *instance); -/* Check for empty error. */ -bool MailboxEmptyError(void *instance); -/* Write to mailbox. */ -int MailboxWrite(void *instance, const unsigned int *buffer, unsigned int size); -/* Read from mailbox. */ -int MailboxRead(void *instance, unsigned int *buffer, unsigned int size); - - - -#endif diff --git a/apps/sbn/wh_design.yaml b/apps/sbn/wh_design.yaml index 12d5b4072..fec624b77 100644 --- a/apps/sbn/wh_design.yaml +++ b/apps/sbn/wh_design.yaml @@ -1,2 +1,127 @@ short_name: sbn long_name: Software Bus Network + events: + SBN_SB_EID: + id: 1 + SBN_INIT_EID: + id: 2 + SBN_MSG_EID: + id: 3 + SBN_FILE_EID: + id: 4 + SBN_PEER_EID: + id: 5 + SBN_PROTO_EID: + id: 6 + SBN_CMD_EID: + id: 7 + SBN_SUB_EID: + id: 8 + SBN_REMAP_EID: + id: 9 + SBN_PEERTASK_EID: + id: 10 + SBN_DEBUG_EID: + id: 11 + PQ_INIT_APP_ERR_EID: + id: 101 + PQ_INIT_CONFIG_ERR_EID: + id: 102 + PQ_CONFIG_ADDR_ERR_EID: + id: 103 + PQ_CONFIG_MANAGE_ERR_EID: + id: 104 + PQ_CONFIG_TABLE_ERR_EID: + id: 105 + PQ_MSG_DROP_FROM_FLOW_DBG_EID: + id: 106 + PQ_CR_POOL_ERR_EID: + id: 107 + PQ_MSG_FLOW_INFO_EID: + id: 108 + PQ_MSG_FLOW_INFO_ERR_EID: + id: 109 + PQ_MSG_FLOW_MISSING_TBL_ERR_EID: + id: 110 + PQ_PQUEUE_INFO_EID: + id: 111 + PQ_PQUEUE_INFO_ERR_EID: + id: 112 + PQ_OUT_CH_INFO_EID: + id: 113 + PQ_OUT_CH_INFO_ERR_EID: + id: 114 + PQ_CMD_ADD_MSG_FLOW_ERR_EID: + id: 115 + PQ_CMD_REMOVE_MSG_FLOW_ERR_EID: + id: 116 + PQ_PQUEUE_MISSING_TBL_ERR_EID: + id: 117 + PQ_PQUEUE_CREATE_ERR_EID: + id: 118 + PQ_PQUEUE_TEARDOWN_ERR_EID: + id: 119 + PQ_CONFIG_TABLE_NULL_PTR_EID: + id: 120 + PQ_CONFIG_TABLE_PQUEUE_STATE_ERR_EID: + id: 121 + PQ_CONFIG_TABLE_PQUEUE_QTYPE_ERR_EID: + id: 122 + PQ_CONFIG_TABLE_PQUEUE_MSG_LIMIT_ERR_EID: + id: 123 + PQ_CONFIG_TABLE_NO_PQUEUES_ERR_EID: + id: 124 + PQ_CONFIG_TABLE_SHDR_ABSENT_EID: + id: 125 + PQ_CONFIG_TABLE_CCSDS_VER_INVALID_EID: + id: 126 + PQ_CONFIG_TABLE_MSG_FLOW_MSG_LIMIT_ERR_EID: + id: 127 + PQ_CONFIG_TABLE_MSG_FLOW_PQ_ID_ERR_EID: + id: 128 + PQ_CONFIG_TABLE_NO_MSG_FLOW_INF_EID: + id: 129 + PQ_PUT_POOL_ERR_EID: + id: 130 + PQ_CHANNEL_TEARDOWN_ERR_EID: + id: 131 + PQ_CHANNEL_LOCK_MUTEX_ERR_EID: + id: 132 + PQ_CHANNEL_UNLOCK_MUTEX_ERR_EID: + id: 133 + PQ_CONFIG_PROCESS_CONFIG_TBL_ERR_EID: + id: 134 + PQ_OSQUEUE_PUT_ERROR_EID: + id: 135 + PQ_OSQUEUE_GET_ERROR_EID: + id: 136 + PQ_BACKUP_TABLE_INF_EID: + id: 137 + PQ_TLM_MSG_LEN_ERR_EID: + id: 138 + PQ_MF_MSG_ID_ERR_EID: + id: 139 + PQ_BACKUP_TABLE_ERR_EID: + id: 140 + PQ_NULL_POINTER_ERR_EID: + id: 141 + telemetry: + SBN_MODULE_HK_TLM_MID: + msgID: + struct: PQ_HkTlm_t + commands: + SBN_CMD_MID: + msgID: + commands: + Noop: + cc: 0 + struct: SBN_NoArgCmd_t + Reset: + cc: 1 + struct: SBN_NoArgCmd_t + SendHK: + cc: 10 + struct: SBN_NoArgCmd_t + Wakeup: + cc: 100 + struct: SBN_NoArgCmd_t diff --git a/apps/sch/fsw/for_build/CMakeLists.txt b/apps/sch/fsw/for_build/CMakeLists.txt index fd7f760e0..dd57239a6 100644 --- a/apps/sch/fsw/for_build/CMakeLists.txt +++ b/apps/sch/fsw/for_build/CMakeLists.txt @@ -48,6 +48,8 @@ buildliner_add_app_def(sch ${CMAKE_CURRENT_SOURCE_DIR}/../src/sch_verify.h ${CMAKE_CURRENT_SOURCE_DIR}/../src/sch_version.h ${CMAKE_CURRENT_SOURCE_DIR}/../public_inc/sch_api.h + ${CMAKE_CURRENT_SOURCE_DIR}/../src/sch_symbols.c + INCLUDES ${CMAKE_CURRENT_SOURCE_DIR}/../src/ diff --git a/apps/sch/fsw/src/sch_msg.h b/apps/sch/fsw/src/sch_msg.h index 8f5fb2591..919ac9412 100644 --- a/apps/sch/fsw/src/sch_msg.h +++ b/apps/sch/fsw/src/sch_msg.h @@ -35,6 +35,7 @@ #include "common_types.h" #include "sch_msgdefs.h" +#include "cfe.h" /************************************************************************* ** diff --git a/apps/sch/fsw/src/sch_symbols.c b/apps/sch/fsw/src/sch_symbols.c new file mode 100644 index 000000000..bf61b1d8b --- /dev/null +++ b/apps/sch/fsw/src/sch_symbols.c @@ -0,0 +1,4 @@ +#include "sch_msg.h" + +// Add symbols that are not instantiated in flight software for juicer to parse. +SCH_NoArgsCmd_t SCH_NoArgCmd; diff --git a/apps/sch/wh_design.yaml b/apps/sch/wh_design.yaml index 85aebde1a..444fb196b 100644 --- a/apps/sch/wh_design.yaml +++ b/apps/sch/wh_design.yaml @@ -1 +1 @@ - short_name: sch long_name: Scheduler events: SCH_INITSTATS_INF_EID: id: 1 SCH_APP_EXIT_EID: id: 2 SCH_CR_PIPE_ERR_EID: id: 3 SCH_SUB_HK_REQ_ERR_EID: id: 4 SCH_SUB_GND_CMD_ERR_EID: id: 5 SCH_SDT_REG_ERR_EID: id: 7 SCH_MDT_REG_ERR_EID: id: 8 SCH_SDT_LOAD_ERR_EID: id: 9 SCH_MDT_LOAD_ERR_EID: id: 10 SCH_ACQ_PTR_ERR_EID: id: 11 SCH_MINOR_FRAME_TIMER_CREATE_ERR_EID: id: 12 SCH_MINOR_FRAME_TIMER_ACC_WARN_EID: id: 13 SCH_MAJOR_FRAME_SUB_ERR_EID: id: 14 SCH_SEM_CREATE_ERR_EID: id: 15 SCH_SAME_SLOT_EID: id: 16 SCH_SKIPPED_SLOTS_EID: id: 17 SCH_MULTI_SLOTS_EID: id: 18 SCH_CORRUPTION_EID: id: 19 SCH_PACKET_SEND_EID: id: 20 SCH_NOISY_MAJOR_FRAME_ERR_EID: id: 21 SCH_SCHEDULE_TBL_ERR_EID: id: 30 SCH_SCHEDULE_TABLE_EID: id: 31 SCH_MESSAGE_TBL_ERR_EID: id: 32 SCH_MESSAGE_TABLE_EID: id: 33 SCH_NOOP_CMD_EID: id: 40 SCH_RESET_CMD_EID: id: 41 SCH_ENABLE_CMD_EID: id: 42 SCH_DISABLE_CMD_EID: id: 43 SCH_ENA_GRP_CMD_EID: id: 44 SCH_DIS_GRP_CMD_EID: id: 45 SCH_ENA_SYNC_CMD_EID: id: 46 SCH_SEND_DIAG_CMD_EID: id: 47 SCH_ENABLE_CMD_ARG_ERR_EI: id: 50 SCH_ENABLE_CMD_ENTRY_ERR_EID: id: 51 SCH_DISABLE_CMD_ARG_ERR_EID: id: 52 SCH_DISABLE_CMD_ENTRY_ERR_EID: id: 53 SCH_ENA_GRP_CMD_ERR_EID: id: 54 SCH_ENA_GRP_NOT_FOUND_ERR_EID: id: 55 SCH_DIS_GRP_CMD_ERR_EID: id: 56 SCH_DIS_GRP_NOT_FOUND_ERR_EID: id: 57 SCH_CC_ERR_EID: id: 58 SCH_MD_ERR_EID: id: 59 SCH_CMD_LEN_ERR_EID: id: 60 SCH_DEADLINE_REG_ERR_EID: id: 61 SCH_SLOT_DEADLINE_FULL_ERR_EID: id: 62 SCH_SUB_ACTIVITY_DONE_REQ_ERR_EID: id: 63 SCH_UNEXPECTED_ACT_DONE_ERR_EID: id: 64 SCH_MUTEX_CREATE_ERR_EID: id: 65 SCH_AD_CHILD_TASK_CREATE_ERR_EID: id: 66 SCH_AD_RCVD_UNEXPECTED_MSG_ERR_EID: id: 67 msg_def_overrides: - parent: SCH_HkPacket_t member: SyncToMET type: enumeration enumerations: NONE: 0 MINOR: 1 PENDING: 2 MINOR_AND_PENDING: 3 MAJOR: 4 MAJOR_AND_MINOR: 5 MAJOR_AND_PENDING: 6 FULLY_SYNCED: 7 - parent: SCH_HkPacket_t member: MajorFrameSource type: enumeration enumerations: NONE: 0 CFE_TIME: 1 MINOR_FRAME_TIMER: 2 telemetry: SCH_ACTIVITY_DONE_MID: msgID: struct: SCH_ActivityDoneMsg_t SCH_DIAG_TLM_MID: msgID: struct: SCH_DiagPacket_t SCH_HK_TLM_MID: msgID: struct: SCH_HkPacket_t commands: SCH_CMD_MID: msgID: commands: Noop: cc: 0 struct: CFE_SB_CmdHdr_t Reset: cc: 1 struct: CFE_SB_CmdHdr_t Enable: cc: 2 struct: SCH_EntryCmd_t Disable: cc: 3 struct: SCH_EntryCmd_t EnableGroup: cc: 4 struct: SCH_GroupCmd_t DisableGroup: cc: 5 struct: SCH_GroupCmd_t EnableSync: cc: 6 struct: CFE_SB_CmdHdr_t SendDiag: cc: 7 struct: CFE_SB_CmdHdr_t SCH_SEND_HK_MID: msgID: commands: SendHK: cc: 0 struct: CFE_SB_CmdHdr_t perfids: SCH_APPMAIN_PERF_ID: id: config: SCH_PIPE_DEPTH: name: SCH_PIPE_DEPTH value: 12 SCH_TOTAL_SLOTS: name: SCH_TOTAL_SLOTS value: 100 SCH_ENTRIES_PER_SLOT: name: SCH_ENTRIES_PER_SLOT value: 5 SCH_MAX_MESSAGES: name: SCH_MAX_MESSAGES value: 128 SCH_MDT_MIN_MSG_ID: name: SCH_MDT_MIN_MSG_ID value: 0 SCH_MDT_MAX_MSG_ID: name: SCH_MDT_MAX_MSG_ID value: CFE_SB_HIGHEST_VALID_MSGID SCH_MAX_MSG_WORDS: name: SCH_MAX_MSG_WORDS value: 64 SCH_MAX_LAG_COUNT: name: SCH_MAX_LAG_COUNT value: (SCH_TOTAL_SLOTS / 2) SCH_MAX_SLOTS_PER_WAKEUP: name: SCH_MAX_SLOTS_PER_WAKEUP value: 5 SCH_MICROS_PER_MAJOR_FRAME: name: SCH_MICROS_PER_MAJOR_FRAME value: 1000000 SCH_SYNC_SLOT_DRIFT_WINDOW: name: SCH_SYNC_SLOT_DRIFT_WINDOW value: 5000 SCH_STARTUP_SYNC_TIMEOUT: name: SCH_STARTUP_SYNC_TIMEOUT value: 50000 SCH_STARTUP_PERIOD: name: SCH_STARTUP_PERIOD value: (5*SCH_MICROS_PER_MAJOR_FRAME) SCH_MAX_NOISY_MAJORF: name: SCH_MAX_NOISY_MAJORF value: 2 SCH_LIB_PRESENCE: name: SCH_LIB_PRESENCE value: 1 SCH_LIB_DIS_CTR: name: SCH_LIB_DIS_CTR value: 0 SCH_SCHEDULE_FILENAME: name: SCH_SCHEDULE_FILENAME value: /cf/apps/sch_def_schtbl.tbl SCH_MESSAGE_FILENAME: name: SCH_MESSAGE_FILENAME value: /cf/apps/sch_def_msgtbl.tbl SCH_MISSION_REV: name: SCH_MISSION_REV value: 0 SCH_AD_PIPE_DEPTH: name: SCH_AD_PIPE_DEPTH value: 3 SCH_AD_CHILD_TASK_PRIORITY: name: SCH_AD_CHILD_TASK_PRIORITY value: 10 SCH_DEADLINES_PER_SLOT: name: SCH_DEADLINES_PER_SLOT value: 5 SCH_AD_CHILD_TASK_FLAGS: name: SCH_AD_CHILD_TASK_FLAGS value: OS_ENABLE_CORE_0 \ No newline at end of file + short_name: sch long_name: Scheduler events: SCH_INITSTATS_INF_EID: id: 1 SCH_APP_EXIT_EID: id: 2 SCH_CR_PIPE_ERR_EID: id: 3 SCH_SUB_HK_REQ_ERR_EID: id: 4 SCH_SUB_GND_CMD_ERR_EID: id: 5 SCH_SDT_REG_ERR_EID: id: 7 SCH_MDT_REG_ERR_EID: id: 8 SCH_SDT_LOAD_ERR_EID: id: 9 SCH_MDT_LOAD_ERR_EID: id: 10 SCH_ACQ_PTR_ERR_EID: id: 11 SCH_MINOR_FRAME_TIMER_CREATE_ERR_EID: id: 12 SCH_MINOR_FRAME_TIMER_ACC_WARN_EID: id: 13 SCH_MAJOR_FRAME_SUB_ERR_EID: id: 14 SCH_SEM_CREATE_ERR_EID: id: 15 SCH_SAME_SLOT_EID: id: 16 SCH_SKIPPED_SLOTS_EID: id: 17 SCH_MULTI_SLOTS_EID: id: 18 SCH_CORRUPTION_EID: id: 19 SCH_PACKET_SEND_EID: id: 20 SCH_NOISY_MAJOR_FRAME_ERR_EID: id: 21 SCH_SCHEDULE_TBL_ERR_EID: id: 30 SCH_SCHEDULE_TABLE_EID: id: 31 SCH_MESSAGE_TBL_ERR_EID: id: 32 SCH_MESSAGE_TABLE_EID: id: 33 SCH_NOOP_CMD_EID: id: 40 SCH_RESET_CMD_EID: id: 41 SCH_ENABLE_CMD_EID: id: 42 SCH_DISABLE_CMD_EID: id: 43 SCH_ENA_GRP_CMD_EID: id: 44 SCH_DIS_GRP_CMD_EID: id: 45 SCH_ENA_SYNC_CMD_EID: id: 46 SCH_SEND_DIAG_CMD_EID: id: 47 SCH_ENABLE_CMD_ARG_ERR_EI: id: 50 SCH_ENABLE_CMD_ENTRY_ERR_EID: id: 51 SCH_DISABLE_CMD_ARG_ERR_EID: id: 52 SCH_DISABLE_CMD_ENTRY_ERR_EID: id: 53 SCH_ENA_GRP_CMD_ERR_EID: id: 54 SCH_ENA_GRP_NOT_FOUND_ERR_EID: id: 55 SCH_DIS_GRP_CMD_ERR_EID: id: 56 SCH_DIS_GRP_NOT_FOUND_ERR_EID: id: 57 SCH_CC_ERR_EID: id: 58 SCH_MD_ERR_EID: id: 59 SCH_CMD_LEN_ERR_EID: id: 60 SCH_DEADLINE_REG_ERR_EID: id: 61 SCH_SLOT_DEADLINE_FULL_ERR_EID: id: 62 SCH_SUB_ACTIVITY_DONE_REQ_ERR_EID: id: 63 SCH_UNEXPECTED_ACT_DONE_ERR_EID: id: 64 SCH_MUTEX_CREATE_ERR_EID: id: 65 SCH_AD_CHILD_TASK_CREATE_ERR_EID: id: 66 SCH_AD_RCVD_UNEXPECTED_MSG_ERR_EID: id: 67 msg_def_overrides: - parent: SCH_HkPacket_t member: SyncToMET type: enumeration enumerations: NONE: 0 MINOR: 1 PENDING: 2 MINOR_AND_PENDING: 3 MAJOR: 4 MAJOR_AND_MINOR: 5 MAJOR_AND_PENDING: 6 FULLY_SYNCED: 7 - parent: SCH_HkPacket_t member: MajorFrameSource type: enumeration enumerations: NONE: 0 CFE_TIME: 1 MINOR_FRAME_TIMER: 2 telemetry: SCH_ACTIVITY_DONE_MID: msgID: struct: SCH_ActivityDoneMsg_t SCH_DIAG_TLM_MID: msgID: struct: SCH_DiagPacket_t SCH_HK_TLM_MID: msgID: struct: SCH_HkPacket_t commands: SCH_CMD_MID: msgID: commands: Noop: cc: 0 struct: SCH_NoArgsCmd_t Reset: cc: 1 struct: SCH_NoArgsCmd_t Enable: cc: 2 struct: SCH_EntryCmd_t Disable: cc: 3 struct: SCH_EntryCmd_t EnableGroup: cc: 4 struct: SCH_GroupCmd_t DisableGroup: cc: 5 struct: SCH_GroupCmd_t EnableSync: cc: 6 struct: SCH_NoArgsCmd_t SendDiag: cc: 7 struct: SCH_NoArgsCmd_t SCH_SEND_HK_MID: msgID: commands: SendHK: cc: 0 struct: CFE_SB_CmdHdr_t perfids: SCH_APPMAIN_PERF_ID: id: config: SCH_PIPE_DEPTH: name: SCH_PIPE_DEPTH value: 12 SCH_TOTAL_SLOTS: name: SCH_TOTAL_SLOTS value: 100 SCH_ENTRIES_PER_SLOT: name: SCH_ENTRIES_PER_SLOT value: 5 SCH_MAX_MESSAGES: name: SCH_MAX_MESSAGES value: 128 SCH_MDT_MIN_MSG_ID: name: SCH_MDT_MIN_MSG_ID value: 0 SCH_MDT_MAX_MSG_ID: name: SCH_MDT_MAX_MSG_ID value: CFE_SB_HIGHEST_VALID_MSGID SCH_MAX_MSG_WORDS: name: SCH_MAX_MSG_WORDS value: 64 SCH_MAX_LAG_COUNT: name: SCH_MAX_LAG_COUNT value: (SCH_TOTAL_SLOTS / 2) SCH_MAX_SLOTS_PER_WAKEUP: name: SCH_MAX_SLOTS_PER_WAKEUP value: 5 SCH_MICROS_PER_MAJOR_FRAME: name: SCH_MICROS_PER_MAJOR_FRAME value: 1000000 SCH_SYNC_SLOT_DRIFT_WINDOW: name: SCH_SYNC_SLOT_DRIFT_WINDOW value: 5000 SCH_STARTUP_SYNC_TIMEOUT: name: SCH_STARTUP_SYNC_TIMEOUT value: 50000 SCH_STARTUP_PERIOD: name: SCH_STARTUP_PERIOD value: (5*SCH_MICROS_PER_MAJOR_FRAME) SCH_MAX_NOISY_MAJORF: name: SCH_MAX_NOISY_MAJORF value: 2 SCH_LIB_PRESENCE: name: SCH_LIB_PRESENCE value: 1 SCH_LIB_DIS_CTR: name: SCH_LIB_DIS_CTR value: 0 SCH_SCHEDULE_FILENAME: name: SCH_SCHEDULE_FILENAME value: /cf/apps/sch_def_schtbl.tbl SCH_MESSAGE_FILENAME: name: SCH_MESSAGE_FILENAME value: /cf/apps/sch_def_msgtbl.tbl SCH_MISSION_REV: name: SCH_MISSION_REV value: 0 SCH_AD_PIPE_DEPTH: name: SCH_AD_PIPE_DEPTH value: 3 SCH_AD_CHILD_TASK_PRIORITY: name: SCH_AD_CHILD_TASK_PRIORITY value: 10 SCH_DEADLINES_PER_SLOT: name: SCH_DEADLINES_PER_SLOT value: 5 SCH_AD_CHILD_TASK_FLAGS: name: SCH_AD_CHILD_TASK_FLAGS value: OS_ENABLE_CORE_0 \ No newline at end of file diff --git a/apps/to/wh_design.yaml b/apps/to/wh_design.yaml index 9946d2a29..dc2e259da 100644 --- a/apps/to/wh_design.yaml +++ b/apps/to/wh_design.yaml @@ -96,6 +96,9 @@ enumerations: FIFO: 0 SINGLE: 1 + - parent: TO_EnableChannelCmd_t + member: DestinationAddress + type: string telemetry: TO_DATA_TYPE_MID: msgID: diff --git a/config/bebop2/sitl/wh_config.yaml b/config/bebop2/sitl/wh_config.yaml index a56e670a8..b284515bb 100644 --- a/config/bebop2/sitl/wh_config.yaml +++ b/config/bebop2/sitl/wh_config.yaml @@ -6,4 +6,4 @@ core: definition: ${PROJECT_SOURCE_DIR}/core/psp/fsw/pc-linux-wh/wh_design.yaml modules: - sch: \ No newline at end of file + sch: {} \ No newline at end of file diff --git a/config/obc/cpd/target/apps/amc/CMakeLists.txt b/config/obc/cpd/apps/amc/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/amc/CMakeLists.txt rename to config/obc/cpd/apps/amc/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/amc/amc_custom.cpp b/config/obc/cpd/apps/amc/amc_custom.cpp similarity index 100% rename from config/obc/cpd/target/apps/amc/amc_custom.cpp rename to config/obc/cpd/apps/amc/amc_custom.cpp diff --git a/config/obc/cpd/target/apps/amc/tables/amc_mixercfg.c b/config/obc/cpd/apps/amc/tables/amc_mixercfg.c similarity index 100% rename from config/obc/cpd/target/apps/amc/tables/amc_mixercfg.c rename to config/obc/cpd/apps/amc/tables/amc_mixercfg.c diff --git a/config/obc/cpd/target/apps/amc/tables/amc_pwmcfg.c b/config/obc/cpd/apps/amc/tables/amc_pwmcfg.c similarity index 100% rename from config/obc/cpd/target/apps/amc/tables/amc_pwmcfg.c rename to config/obc/cpd/apps/amc/tables/amc_pwmcfg.c diff --git a/config/obc/cpd/target/apps/bat/CMakeLists.txt b/config/obc/cpd/apps/bat/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/bat/CMakeLists.txt rename to config/obc/cpd/apps/bat/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/bat/bat_custom.cpp b/config/obc/cpd/apps/bat/bat_custom.cpp similarity index 100% rename from config/obc/cpd/target/apps/bat/bat_custom.cpp rename to config/obc/cpd/apps/bat/bat_custom.cpp diff --git a/config/obc/cpd/target/apps/bat/tables/bat_config.c b/config/obc/cpd/apps/bat/tables/bat_config.c similarity index 100% rename from config/obc/cpd/target/apps/bat/tables/bat_config.c rename to config/obc/cpd/apps/bat/tables/bat_config.c diff --git a/config/obc/cpd/target/apps/cf/CMakeLists.txt b/config/obc/cpd/apps/cf/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/cf/CMakeLists.txt rename to config/obc/cpd/apps/cf/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/cf/tables/cf_cfgtable.c b/config/obc/cpd/apps/cf/tables/cf_cfgtable.c similarity index 100% rename from config/obc/cpd/target/apps/cf/tables/cf_cfgtable.c rename to config/obc/cpd/apps/cf/tables/cf_cfgtable.c diff --git a/config/obc/cpd/target/apps/ci/CMakeLists.txt b/config/obc/cpd/apps/ci/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/ci/CMakeLists.txt rename to config/obc/cpd/apps/ci/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/ci/ci_custom.c b/config/obc/cpd/apps/ci/ci_custom.c similarity index 100% rename from config/obc/cpd/target/apps/ci/ci_custom.c rename to config/obc/cpd/apps/ci/ci_custom.c diff --git a/config/obc/cpd/target/apps/ci/tables/ci_config.c b/config/obc/cpd/apps/ci/tables/ci_config.c similarity index 100% rename from config/obc/cpd/target/apps/ci/tables/ci_config.c rename to config/obc/cpd/apps/ci/tables/ci_config.c diff --git a/config/obc/cpd/target/apps/ci/unit_test/ci-custom.supp b/config/obc/cpd/apps/ci/unit_test/ci-custom.supp similarity index 100% rename from config/obc/cpd/target/apps/ci/unit_test/ci-custom.supp rename to config/obc/cpd/apps/ci/unit_test/ci-custom.supp diff --git a/config/obc/cpd/target/apps/ci/unit_test/ci_custom_test.c b/config/obc/cpd/apps/ci/unit_test/ci_custom_test.c similarity index 100% rename from config/obc/cpd/target/apps/ci/unit_test/ci_custom_test.c rename to config/obc/cpd/apps/ci/unit_test/ci_custom_test.c diff --git a/config/obc/cpd/target/apps/ci/unit_test/ci_custom_test.h b/config/obc/cpd/apps/ci/unit_test/ci_custom_test.h similarity index 100% rename from config/obc/cpd/target/apps/ci/unit_test/ci_custom_test.h rename to config/obc/cpd/apps/ci/unit_test/ci_custom_test.h diff --git a/config/obc/cpd/target/apps/ci/unit_test/ci_mock_os_calls.c b/config/obc/cpd/apps/ci/unit_test/ci_mock_os_calls.c similarity index 100% rename from config/obc/cpd/target/apps/ci/unit_test/ci_mock_os_calls.c rename to config/obc/cpd/apps/ci/unit_test/ci_mock_os_calls.c diff --git a/config/obc/cpd/target/apps/ci/unit_test/ci_mock_os_calls.h b/config/obc/cpd/apps/ci/unit_test/ci_mock_os_calls.h similarity index 100% rename from config/obc/cpd/target/apps/ci/unit_test/ci_mock_os_calls.h rename to config/obc/cpd/apps/ci/unit_test/ci_mock_os_calls.h diff --git a/config/obc/cpd/target/apps/ci/unit_test/ci_test_utils.c b/config/obc/cpd/apps/ci/unit_test/ci_test_utils.c similarity index 100% rename from config/obc/cpd/target/apps/ci/unit_test/ci_test_utils.c rename to config/obc/cpd/apps/ci/unit_test/ci_test_utils.c diff --git a/config/obc/cpd/target/apps/ci/unit_test/ci_test_utils.h b/config/obc/cpd/apps/ci/unit_test/ci_test_utils.h similarity index 100% rename from config/obc/cpd/target/apps/ci/unit_test/ci_test_utils.h rename to config/obc/cpd/apps/ci/unit_test/ci_test_utils.h diff --git a/config/obc/cpd/target/apps/ci/unit_test/ci_testrunner.c b/config/obc/cpd/apps/ci/unit_test/ci_testrunner.c similarity index 100% rename from config/obc/cpd/target/apps/ci/unit_test/ci_testrunner.c rename to config/obc/cpd/apps/ci/unit_test/ci_testrunner.c diff --git a/config/obc/cpd/target/apps/gps/CMakeLists.txt b/config/obc/cpd/apps/gps/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/gps/CMakeLists.txt rename to config/obc/cpd/apps/gps/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/gps/src/gps_custom.c b/config/obc/cpd/apps/gps/src/gps_custom.c similarity index 100% rename from config/obc/cpd/target/apps/gps/src/gps_custom.c rename to config/obc/cpd/apps/gps/src/gps_custom.c diff --git a/config/obc/cpd/target/apps/gps/tables/gps_config.c b/config/obc/cpd/apps/gps/tables/gps_config.c similarity index 100% rename from config/obc/cpd/target/apps/gps/tables/gps_config.c rename to config/obc/cpd/apps/gps/tables/gps_config.c diff --git a/config/obc/cpd/target/apps/hmc5883/CMakeLists.txt b/config/obc/cpd/apps/hmc5883/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/hmc5883/CMakeLists.txt rename to config/obc/cpd/apps/hmc5883/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/hmc5883/src/hmc5883_custom.c b/config/obc/cpd/apps/hmc5883/src/hmc5883_custom.c similarity index 100% rename from config/obc/cpd/target/apps/hmc5883/src/hmc5883_custom.c rename to config/obc/cpd/apps/hmc5883/src/hmc5883_custom.c diff --git a/config/obc/cpd/target/apps/hmc5883/tables/hmc5883_config.c b/config/obc/cpd/apps/hmc5883/tables/hmc5883_config.c similarity index 100% rename from config/obc/cpd/target/apps/hmc5883/tables/hmc5883_config.c rename to config/obc/cpd/apps/hmc5883/tables/hmc5883_config.c diff --git a/config/obc/cpd/target/apps/hmc5883/tables/hmc5883_config_default.c b/config/obc/cpd/apps/hmc5883/tables/hmc5883_config_default.c similarity index 100% rename from config/obc/cpd/target/apps/hmc5883/tables/hmc5883_config_default.c rename to config/obc/cpd/apps/hmc5883/tables/hmc5883_config_default.c diff --git a/config/obc/cpd/target/apps/hmc5883/tables/hmc5883_config_dev_ocpoc.c b/config/obc/cpd/apps/hmc5883/tables/hmc5883_config_dev_ocpoc.c similarity index 100% rename from config/obc/cpd/target/apps/hmc5883/tables/hmc5883_config_dev_ocpoc.c rename to config/obc/cpd/apps/hmc5883/tables/hmc5883_config_dev_ocpoc.c diff --git a/config/obc/cpd/target/apps/ld/CMakeLists.txt b/config/obc/cpd/apps/ld/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/ld/CMakeLists.txt rename to config/obc/cpd/apps/ld/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/ld/tables/ld_config.c b/config/obc/cpd/apps/ld/tables/ld_config.c similarity index 100% rename from config/obc/cpd/target/apps/ld/tables/ld_config.c rename to config/obc/cpd/apps/ld/tables/ld_config.c diff --git a/config/obc/cpd/target/apps/lgc/CMakeLists.txt b/config/obc/cpd/apps/lgc/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/lgc/CMakeLists.txt rename to config/obc/cpd/apps/lgc/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/lgc/lgc_custom.cpp b/config/obc/cpd/apps/lgc/lgc_custom.cpp similarity index 100% rename from config/obc/cpd/target/apps/lgc/lgc_custom.cpp rename to config/obc/cpd/apps/lgc/lgc_custom.cpp diff --git a/config/obc/cpd/target/apps/lgc/tables/lgc_config.c b/config/obc/cpd/apps/lgc/tables/lgc_config.c similarity index 100% rename from config/obc/cpd/target/apps/lgc/tables/lgc_config.c rename to config/obc/cpd/apps/lgc/tables/lgc_config.c diff --git a/config/obc/cpd/target/apps/mac/CMakeLists.txt b/config/obc/cpd/apps/mac/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/mac/CMakeLists.txt rename to config/obc/cpd/apps/mac/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/mac/tables/mac_param.c b/config/obc/cpd/apps/mac/tables/mac_param.c similarity index 100% rename from config/obc/cpd/target/apps/mac/tables/mac_param.c rename to config/obc/cpd/apps/mac/tables/mac_param.c diff --git a/config/obc/cpd/target/apps/mpc/CMakeLists.txt b/config/obc/cpd/apps/mpc/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/mpc/CMakeLists.txt rename to config/obc/cpd/apps/mpc/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/mpc/tables/mpc_config.c b/config/obc/cpd/apps/mpc/tables/mpc_config.c similarity index 100% rename from config/obc/cpd/target/apps/mpc/tables/mpc_config.c rename to config/obc/cpd/apps/mpc/tables/mpc_config.c diff --git a/config/obc/cpd/target/apps/mpu9250/CMakeLists.txt b/config/obc/cpd/apps/mpu9250/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/mpu9250/CMakeLists.txt rename to config/obc/cpd/apps/mpu9250/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/mpu9250/src/mpu9250_custom.c b/config/obc/cpd/apps/mpu9250/src/mpu9250_custom.c similarity index 100% rename from config/obc/cpd/target/apps/mpu9250/src/mpu9250_custom.c rename to config/obc/cpd/apps/mpu9250/src/mpu9250_custom.c diff --git a/config/obc/cpd/target/apps/mpu9250/tables/mpu9250_config.c b/config/obc/cpd/apps/mpu9250/tables/mpu9250_config.c similarity index 100% rename from config/obc/cpd/target/apps/mpu9250/tables/mpu9250_config.c rename to config/obc/cpd/apps/mpu9250/tables/mpu9250_config.c diff --git a/config/obc/cpd/target/apps/mpu9250/tables/mpu9250_config_default.c b/config/obc/cpd/apps/mpu9250/tables/mpu9250_config_default.c similarity index 100% rename from config/obc/cpd/target/apps/mpu9250/tables/mpu9250_config_default.c rename to config/obc/cpd/apps/mpu9250/tables/mpu9250_config_default.c diff --git a/config/obc/cpd/target/apps/mpu9250/tables/mpu9250_config_dev_ocpoc.c b/config/obc/cpd/apps/mpu9250/tables/mpu9250_config_dev_ocpoc.c similarity index 100% rename from config/obc/cpd/target/apps/mpu9250/tables/mpu9250_config_dev_ocpoc.c rename to config/obc/cpd/apps/mpu9250/tables/mpu9250_config_dev_ocpoc.c diff --git a/config/obc/cpd/target/apps/ms5611/CMakeLists.txt b/config/obc/cpd/apps/ms5611/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/ms5611/CMakeLists.txt rename to config/obc/cpd/apps/ms5611/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/ms5611/src/CMakeLists.txt b/config/obc/cpd/apps/ms5611/src/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/ms5611/src/CMakeLists.txt rename to config/obc/cpd/apps/ms5611/src/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/ms5611/src/ms5611_custom.c b/config/obc/cpd/apps/ms5611/src/ms5611_custom.c similarity index 100% rename from config/obc/cpd/target/apps/ms5611/src/ms5611_custom.c rename to config/obc/cpd/apps/ms5611/src/ms5611_custom.c diff --git a/config/obc/cpd/target/apps/ms5611/tables/ms5611_config.c b/config/obc/cpd/apps/ms5611/tables/ms5611_config.c similarity index 100% rename from config/obc/cpd/target/apps/ms5611/tables/ms5611_config.c rename to config/obc/cpd/apps/ms5611/tables/ms5611_config.c diff --git a/config/obc/cpd/target/apps/nav/CMakeLists.txt b/config/obc/cpd/apps/nav/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/nav/CMakeLists.txt rename to config/obc/cpd/apps/nav/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/nav/tables/nav_config.c b/config/obc/cpd/apps/nav/tables/nav_config.c similarity index 100% rename from config/obc/cpd/target/apps/nav/tables/nav_config.c rename to config/obc/cpd/apps/nav/tables/nav_config.c diff --git a/config/obc/cpd/target/apps/pe/CMakeLists.txt b/config/obc/cpd/apps/pe/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/pe/CMakeLists.txt rename to config/obc/cpd/apps/pe/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/pe/tables/pe_config.c b/config/obc/cpd/apps/pe/tables/pe_config.c similarity index 100% rename from config/obc/cpd/target/apps/pe/tables/pe_config.c rename to config/obc/cpd/apps/pe/tables/pe_config.c diff --git a/config/obc/cpd/target/apps/pq_lib/CMakeLists.txt b/config/obc/cpd/apps/pq_lib/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/pq_lib/CMakeLists.txt rename to config/obc/cpd/apps/pq_lib/CMakeLists.txt diff --git a/config/obc/sitl/target/apps/pq_lib/tables/pq_backup_cfg.c b/config/obc/cpd/apps/pq_lib/tables/pq_backup_cfg.c similarity index 93% rename from config/obc/sitl/target/apps/pq_lib/tables/pq_backup_cfg.c rename to config/obc/cpd/apps/pq_lib/tables/pq_backup_cfg.c index 0c6e3234e..d08dc1aee 100644 --- a/config/obc/sitl/target/apps/pq_lib/tables/pq_backup_cfg.c +++ b/config/obc/cpd/apps/pq_lib/tables/pq_backup_cfg.c @@ -14,7 +14,8 @@ #define PQ_PQUEUE_HIGH_OPS_RSRVD_IDX 1 #define PQ_PQUEUE_HIGH_IDX 2 #define PQ_PQUEUE_MEDIUM_IDX 3 -#define PQ_PQUEUE_LOW_IDX 4 +#define PQ_PQUEUE_DEFAULT_IDX 4 +#define PQ_PQUEUE_LOW_IDX 5 /** ** \brief Default TO config table data @@ -62,6 +63,8 @@ PQ_ChannelTbl_t PQ_BackupConfigTbl = {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO}, /* PQ_PQUEUE_MEDIUM_IDX */ {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO}, + /* PQ_PQUEUE_DEFAULT_IDX */ + {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO}, /* PQ_PQUEUE_LOW_IDX */ {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO} } diff --git a/config/obc/ppd/target/apps/pq_lib/tables/pq_cfg.c b/config/obc/cpd/apps/pq_lib/tables/pq_cfg.c similarity index 98% rename from config/obc/ppd/target/apps/pq_lib/tables/pq_cfg.c rename to config/obc/cpd/apps/pq_lib/tables/pq_cfg.c index 989c7f90f..461098674 100644 --- a/config/obc/ppd/target/apps/pq_lib/tables/pq_cfg.c +++ b/config/obc/cpd/apps/pq_lib/tables/pq_cfg.c @@ -33,7 +33,8 @@ static CFE_TBL_FileDef_t CFE_TBL_FileDef OS_USED = #define PQ_PQUEUE_HIGH_OPS_RSRVD_IDX 1 #define PQ_PQUEUE_HIGH_IDX 2 #define PQ_PQUEUE_MEDIUM_IDX 3 -#define PQ_PQUEUE_LOW_IDX 4 +#define PQ_PQUEUE_DEFAULT_IDX 4 +#define PQ_PQUEUE_LOW_IDX 5 /** ** \brief Default TO config table data @@ -207,6 +208,8 @@ PQ_ChannelTbl_t PQ_ConfigTbl = {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO}, /* PQ_PQUEUE_MEDIUM_IDX */ {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO}, + /* PQ_PQUEUE_DEFAULT_IDX */ + {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO}, /* PQ_PQUEUE_LOW_IDX */ {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO} } diff --git a/config/obc/cpd/target/apps/prm/CMakeLists.txt b/config/obc/cpd/apps/prm/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/prm/CMakeLists.txt rename to config/obc/cpd/apps/prm/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/prm/tables/prm_config.c b/config/obc/cpd/apps/prm/tables/prm_config.c similarity index 100% rename from config/obc/cpd/target/apps/prm/tables/prm_config.c rename to config/obc/cpd/apps/prm/tables/prm_config.c diff --git a/config/obc/cpd/target/apps/qae/CMakeLists.txt b/config/obc/cpd/apps/qae/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/qae/CMakeLists.txt rename to config/obc/cpd/apps/qae/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/qae/tables/qae_config.c b/config/obc/cpd/apps/qae/tables/qae_config.c similarity index 100% rename from config/obc/cpd/target/apps/qae/tables/qae_config.c rename to config/obc/cpd/apps/qae/tables/qae_config.c diff --git a/config/obc/cpd/target/apps/rcin/CMakeLists.txt b/config/obc/cpd/apps/rcin/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/rcin/CMakeLists.txt rename to config/obc/cpd/apps/rcin/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/rcin/src/CMakeLists.txt b/config/obc/cpd/apps/rcin/src/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/rcin/src/CMakeLists.txt rename to config/obc/cpd/apps/rcin/src/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/rcin/src/rcin_custom.c b/config/obc/cpd/apps/rcin/src/rcin_custom.c similarity index 100% rename from config/obc/cpd/target/apps/rcin/src/rcin_custom.c rename to config/obc/cpd/apps/rcin/src/rcin_custom.c diff --git a/config/obc/cpd/target/apps/rgbled/CMakeLists.txt b/config/obc/cpd/apps/rgbled/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/rgbled/CMakeLists.txt rename to config/obc/cpd/apps/rgbled/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/rgbled/src/CMakeLists.txt b/config/obc/cpd/apps/rgbled/src/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/rgbled/src/CMakeLists.txt rename to config/obc/cpd/apps/rgbled/src/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/rgbled/src/rgbled_custom.c b/config/obc/cpd/apps/rgbled/src/rgbled_custom.c similarity index 100% rename from config/obc/cpd/target/apps/rgbled/src/rgbled_custom.c rename to config/obc/cpd/apps/rgbled/src/rgbled_custom.c diff --git a/config/obc/cpd/target/apps/rgbled/src/rgbled_driver.h b/config/obc/cpd/apps/rgbled/src/rgbled_driver.h similarity index 100% rename from config/obc/cpd/target/apps/rgbled/src/rgbled_driver.h rename to config/obc/cpd/apps/rgbled/src/rgbled_driver.h diff --git a/config/obc/cpd/target/apps/sbn/CMakeLists.txt b/config/obc/cpd/apps/sbn/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/sbn/CMakeLists.txt rename to config/obc/cpd/apps/sbn/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/sbn/src/sbn_remap_tbl.c b/config/obc/cpd/apps/sbn/src/sbn_remap_tbl.c similarity index 100% rename from config/obc/cpd/target/apps/sbn/src/sbn_remap_tbl.c rename to config/obc/cpd/apps/sbn/src/sbn_remap_tbl.c diff --git a/config/obc/cpd/target/apps/sbn/tables/mbox/SbnModuleData.dat b/config/obc/cpd/apps/sbn/tables/mbox/SbnModuleData.dat similarity index 100% rename from config/obc/cpd/target/apps/sbn/tables/mbox/SbnModuleData.dat rename to config/obc/cpd/apps/sbn/tables/mbox/SbnModuleData.dat diff --git a/config/obc/cpd/target/apps/sbn/tables/mbox/SbnPeerData.dat b/config/obc/cpd/apps/sbn/tables/mbox/SbnPeerData.dat similarity index 100% rename from config/obc/cpd/target/apps/sbn/tables/mbox/SbnPeerData.dat rename to config/obc/cpd/apps/sbn/tables/mbox/SbnPeerData.dat diff --git a/config/obc/cpd/target/apps/sch/CMakeLists.txt b/config/obc/cpd/apps/sch/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/sch/CMakeLists.txt rename to config/obc/cpd/apps/sch/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/sch/sch_custom_rt.c b/config/obc/cpd/apps/sch/sch_custom_rt.c similarity index 100% rename from config/obc/cpd/target/apps/sch/sch_custom_rt.c rename to config/obc/cpd/apps/sch/sch_custom_rt.c diff --git a/config/obc/cpd/target/apps/sch/tables/sch_def_msgtbl.c b/config/obc/cpd/apps/sch/tables/sch_def_msgtbl.c similarity index 98% rename from config/obc/cpd/target/apps/sch/tables/sch_def_msgtbl.c rename to config/obc/cpd/apps/sch/tables/sch_def_msgtbl.c index cdfe776cb..8f35dabec 100644 --- a/config/obc/cpd/target/apps/sch/tables/sch_def_msgtbl.c +++ b/config/obc/cpd/apps/sch/tables/sch_def_msgtbl.c @@ -236,9 +236,11 @@ SCH_MessageEntry_t SCH_DefaultMessageTable[SCH_MAX_MESSAGES] = /* Command ID #97 */ { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, /* Command ID #98 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, + /* SBN Wakeup command code. */ + { { SCH_FIX_HEADER(SBN_CMD_MID, 0xC000, 0x0001), 0x6400 } }, /* Command ID #99 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, + /* SBN Send HK command code. */ + { { SCH_FIX_HEADER(SBN_CMD_MID, 0xC000, 0x0001), 0x0A00 } }, /* Command ID #100 */ { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, /* Command ID #101 */ diff --git a/config/obc/cpd/target/apps/sch/tables/sch_def_schtbl.c b/config/obc/cpd/apps/sch/tables/sch_def_schtbl.c similarity index 93% rename from config/obc/cpd/target/apps/sch/tables/sch_def_schtbl.c rename to config/obc/cpd/apps/sch/tables/sch_def_schtbl.c index 11bbaef5c..7b09ba1bf 100644 --- a/config/obc/cpd/target/apps/sch/tables/sch_def_schtbl.c +++ b/config/obc/cpd/apps/sch/tables/sch_def_schtbl.c @@ -187,6 +187,9 @@ VC_PROCESS_CMDS_MIDX 1Hz, 12 #define PRM_SEND_HK_MIDX 96 #define PRM_WAKEUP_MIDX 97 +#define SBN_WAKEUP_MIDX 98 +#define SBN_SEND_HK_MIDX 99 + #define QAE_SEND_HK_MIDX 102 #define QAE_WAKEUP_MIDX 103 #define LD_SEND_HK_MIDX 104 @@ -230,7 +233,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -242,7 +245,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -263,7 +266,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -276,11 +279,11 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_SEND_HK_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -297,7 +300,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -311,7 +314,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_SEND_HK_MIDX, SCH_GROUP_NONE }, @@ -378,7 +381,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -400,7 +403,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -412,7 +415,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -429,7 +432,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -446,7 +449,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -463,7 +466,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -481,7 +484,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -497,7 +500,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -514,7 +517,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -531,7 +534,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -548,7 +551,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -570,7 +573,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CFE_ES_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -582,7 +585,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -599,7 +602,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -616,7 +619,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -633,7 +636,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -651,7 +654,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CFE_EVS_SEND_HK_MIDX, SCH_GROUP_NONE }, @@ -667,7 +670,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -684,7 +687,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -701,7 +704,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -718,7 +721,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -740,7 +743,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CFE_SB_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -752,7 +755,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -769,7 +772,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -786,7 +789,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -803,7 +806,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -821,10 +824,10 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CFE_TIME_SEND_HK_MIDX, SCH_GROUP_NONE }, + { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -837,7 +840,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -854,7 +857,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -871,7 +874,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -888,7 +891,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -911,7 +914,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CFE_TIME_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, /* slot #41*/ @@ -922,7 +925,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -939,7 +942,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -957,7 +960,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -974,7 +977,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -992,7 +995,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CFE_TBL_SEND_HK_MIDX, SCH_GROUP_NONE }, @@ -1008,7 +1011,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1025,7 +1028,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1042,7 +1045,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1059,7 +1062,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1080,7 +1083,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -1093,7 +1096,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1110,7 +1113,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1127,7 +1130,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1144,7 +1147,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1162,7 +1165,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, GPS_READ_SENSOR_MIDX, SCH_GROUP_NONE }, @@ -1178,7 +1181,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1195,7 +1198,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1212,7 +1215,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1229,7 +1232,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1251,7 +1254,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CF_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -1263,7 +1266,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1280,7 +1283,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1297,7 +1300,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1314,7 +1317,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1332,7 +1335,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -1348,7 +1351,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1365,7 +1368,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1382,7 +1385,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1399,7 +1402,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1421,7 +1424,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CI_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -1433,7 +1436,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1450,7 +1453,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1467,7 +1470,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1484,7 +1487,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1502,7 +1505,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CS_SEND_HK_MIDX, SCH_GROUP_NONE }, @@ -1518,7 +1521,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1535,7 +1538,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1552,7 +1555,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1569,7 +1572,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1591,7 +1594,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, DS_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -1603,7 +1606,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1620,7 +1623,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1637,7 +1640,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1654,7 +1657,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1672,7 +1675,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, EA_SEND_HK_MIDX, SCH_GROUP_NONE }, @@ -1688,7 +1691,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1705,7 +1708,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1722,7 +1725,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1739,7 +1742,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1761,7 +1764,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -1773,7 +1776,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1790,7 +1793,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1807,7 +1810,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1824,7 +1827,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1842,7 +1845,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, @@ -1858,7 +1861,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1875,7 +1878,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1892,7 +1895,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1909,7 +1912,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1931,7 +1934,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, EA_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -1943,7 +1946,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1960,7 +1963,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1977,7 +1980,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1994,7 +1997,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2012,7 +2015,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, GPS_READ_SENSOR_MIDX, SCH_GROUP_NONE }, @@ -2028,7 +2031,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2045,7 +2048,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2062,7 +2065,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2079,7 +2082,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2101,7 +2104,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, GPS_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -2113,7 +2116,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2130,7 +2133,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2147,7 +2150,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2164,7 +2167,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2182,7 +2185,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -2198,7 +2201,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2215,7 +2218,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2232,7 +2235,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2249,7 +2252,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2271,7 +2274,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -2283,7 +2286,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2300,7 +2303,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2317,7 +2320,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2334,7 +2337,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2352,7 +2355,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HS_SEND_HK_MIDX, SCH_GROUP_NONE }, @@ -2368,7 +2371,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2385,7 +2388,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2402,7 +2405,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2419,7 +2422,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2441,7 +2444,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -2453,7 +2456,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2470,7 +2473,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2487,7 +2490,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2504,7 +2507,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2522,7 +2525,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, FM_SEND_HK_MIDX, SCH_GROUP_NONE }, @@ -2538,7 +2541,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2555,7 +2558,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2572,7 +2575,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2589,7 +2592,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2612,7 +2615,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LC_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, /* slot #141*/ @@ -2623,7 +2626,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2640,7 +2643,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2657,7 +2660,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2674,7 +2677,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, @@ -2692,7 +2695,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_SEND_HK_MIDX, SCH_GROUP_NONE }, @@ -2708,7 +2711,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2725,7 +2728,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2781,7 +2784,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MD_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -2793,7 +2796,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2810,7 +2813,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2827,7 +2830,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2844,7 +2847,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2862,7 +2865,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MD_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -2878,7 +2881,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2895,7 +2898,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2912,7 +2915,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2929,7 +2932,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2951,7 +2954,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MM_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -2963,7 +2966,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2980,7 +2983,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2997,7 +3000,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3014,7 +3017,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3032,7 +3035,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -3048,7 +3051,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3065,7 +3068,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3082,7 +3085,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3099,7 +3102,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3121,7 +3124,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -3133,7 +3136,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3150,7 +3153,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3167,7 +3170,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3184,7 +3187,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3202,7 +3205,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_SEND_HK_MIDX, SCH_GROUP_NONE }, @@ -3218,7 +3221,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3235,7 +3238,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3252,7 +3255,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3270,7 +3273,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LGC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, @@ -3291,7 +3294,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -3303,7 +3306,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3320,7 +3323,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3337,7 +3340,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3354,7 +3357,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3372,7 +3375,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -3388,7 +3391,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3405,7 +3408,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3422,7 +3425,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3439,7 +3442,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3462,7 +3465,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, /* slot #191*/ @@ -3473,7 +3476,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3490,7 +3493,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3507,7 +3510,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3524,7 +3527,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3542,7 +3545,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, @@ -3558,7 +3561,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3575,7 +3578,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3592,7 +3595,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3609,7 +3612,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3630,7 +3633,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -3643,7 +3646,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3660,7 +3663,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3677,7 +3680,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3694,7 +3697,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3712,7 +3715,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, GPS_READ_SENSOR_MIDX, SCH_GROUP_NONE }, @@ -3728,7 +3731,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3745,7 +3748,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3762,7 +3765,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3779,7 +3782,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3800,7 +3803,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -3813,7 +3816,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3830,7 +3833,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3847,7 +3850,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3864,7 +3867,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3882,7 +3885,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -3898,7 +3901,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3915,7 +3918,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3932,7 +3935,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3949,7 +3952,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3971,7 +3974,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RGBLED_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -3983,7 +3986,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4000,7 +4003,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4017,7 +4020,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4034,7 +4037,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4052,7 +4055,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SC_1HZ_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -4068,7 +4071,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4086,7 +4089,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LGC_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, @@ -4102,7 +4105,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4119,7 +4122,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4141,7 +4144,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SC_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -4153,7 +4156,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4170,7 +4173,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4187,7 +4190,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4204,7 +4207,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4222,7 +4225,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SCH_SEND_HK_MIDX, SCH_GROUP_NONE }, @@ -4238,7 +4241,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4255,7 +4258,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4272,7 +4275,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4289,7 +4292,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4312,7 +4315,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, TO_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, /* slot #241*/ @@ -4323,7 +4326,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4340,7 +4343,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4357,7 +4360,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4374,7 +4377,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4392,7 +4395,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_SEND_HK_MIDX, SCH_GROUP_NONE }, @@ -4408,7 +4411,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4425,7 +4428,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4442,7 +4445,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4459,7 +4462,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, diff --git a/config/obc/cpd/target/apps/sch/unit_test/sch_custom_test.c b/config/obc/cpd/apps/sch/unit_test/sch_custom_test.c similarity index 100% rename from config/obc/cpd/target/apps/sch/unit_test/sch_custom_test.c rename to config/obc/cpd/apps/sch/unit_test/sch_custom_test.c diff --git a/config/obc/cpd/target/apps/sch/unit_test/sch_custom_test.h b/config/obc/cpd/apps/sch/unit_test/sch_custom_test.h similarity index 100% rename from config/obc/cpd/target/apps/sch/unit_test/sch_custom_test.h rename to config/obc/cpd/apps/sch/unit_test/sch_custom_test.h diff --git a/config/obc/cpd/target/apps/sch/unit_test/sch_test_utils.c b/config/obc/cpd/apps/sch/unit_test/sch_test_utils.c similarity index 100% rename from config/obc/cpd/target/apps/sch/unit_test/sch_test_utils.c rename to config/obc/cpd/apps/sch/unit_test/sch_test_utils.c diff --git a/config/obc/cpd/target/apps/sch/unit_test/sch_test_utils.h b/config/obc/cpd/apps/sch/unit_test/sch_test_utils.h similarity index 100% rename from config/obc/cpd/target/apps/sch/unit_test/sch_test_utils.h rename to config/obc/cpd/apps/sch/unit_test/sch_test_utils.h diff --git a/config/obc/cpd/target/apps/sch/unit_test/sch_testrunner.c b/config/obc/cpd/apps/sch/unit_test/sch_testrunner.c similarity index 100% rename from config/obc/cpd/target/apps/sch/unit_test/sch_testrunner.c rename to config/obc/cpd/apps/sch/unit_test/sch_testrunner.c diff --git a/config/obc/cpd/target/apps/sens/CMakeLists.txt b/config/obc/cpd/apps/sens/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/sens/CMakeLists.txt rename to config/obc/cpd/apps/sens/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/sens/tables/sens_config.c b/config/obc/cpd/apps/sens/tables/sens_config.c similarity index 100% rename from config/obc/cpd/target/apps/sens/tables/sens_config.c rename to config/obc/cpd/apps/sens/tables/sens_config.c diff --git a/config/obc/cpd/target/apps/to/CMakeLists.txt b/config/obc/cpd/apps/to/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/to/CMakeLists.txt rename to config/obc/cpd/apps/to/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/to/tables/to_backup_cfg.c b/config/obc/cpd/apps/to/tables/to_backup_cfg.c similarity index 100% rename from config/obc/cpd/target/apps/to/tables/to_backup_cfg.c rename to config/obc/cpd/apps/to/tables/to_backup_cfg.c diff --git a/config/obc/cpd/target/apps/to/tables/to_udp_cfg.c b/config/obc/cpd/apps/to/tables/to_udp_cfg.c similarity index 100% rename from config/obc/cpd/target/apps/to/tables/to_udp_cfg.c rename to config/obc/cpd/apps/to/tables/to_udp_cfg.c diff --git a/config/obc/cpd/target/apps/to/to_custom.c b/config/obc/cpd/apps/to/to_custom.c similarity index 100% rename from config/obc/cpd/target/apps/to/to_custom.c rename to config/obc/cpd/apps/to/to_custom.c diff --git a/config/obc/cpd/target/apps/to/to_custom_udp.h b/config/obc/cpd/apps/to/to_custom_udp.h similarity index 100% rename from config/obc/cpd/target/apps/to/to_custom_udp.h rename to config/obc/cpd/apps/to/to_custom_udp.h diff --git a/config/obc/cpd/target/apps/to/unit_test/to_app_custom_test.c b/config/obc/cpd/apps/to/unit_test/to_app_custom_test.c similarity index 100% rename from config/obc/cpd/target/apps/to/unit_test/to_app_custom_test.c rename to config/obc/cpd/apps/to/unit_test/to_app_custom_test.c diff --git a/config/obc/cpd/target/apps/to/unit_test/to_app_custom_test.h b/config/obc/cpd/apps/to/unit_test/to_app_custom_test.h similarity index 100% rename from config/obc/cpd/target/apps/to/unit_test/to_app_custom_test.h rename to config/obc/cpd/apps/to/unit_test/to_app_custom_test.h diff --git a/config/obc/cpd/target/apps/to/unit_test/to_app_stubs.c b/config/obc/cpd/apps/to/unit_test/to_app_stubs.c similarity index 100% rename from config/obc/cpd/target/apps/to/unit_test/to_app_stubs.c rename to config/obc/cpd/apps/to/unit_test/to_app_stubs.c diff --git a/config/obc/cpd/target/apps/to/unit_test/to_app_stubs.h b/config/obc/cpd/apps/to/unit_test/to_app_stubs.h similarity index 100% rename from config/obc/cpd/target/apps/to/unit_test/to_app_stubs.h rename to config/obc/cpd/apps/to/unit_test/to_app_stubs.h diff --git a/config/obc/cpd/target/apps/to/unit_test/to_custom_test_utils.c b/config/obc/cpd/apps/to/unit_test/to_custom_test_utils.c similarity index 100% rename from config/obc/cpd/target/apps/to/unit_test/to_custom_test_utils.c rename to config/obc/cpd/apps/to/unit_test/to_custom_test_utils.c diff --git a/config/obc/cpd/target/apps/to/unit_test/to_custom_test_utils.h b/config/obc/cpd/apps/to/unit_test/to_custom_test_utils.h similarity index 100% rename from config/obc/cpd/target/apps/to/unit_test/to_custom_test_utils.h rename to config/obc/cpd/apps/to/unit_test/to_custom_test_utils.h diff --git a/config/obc/cpd/target/apps/to/unit_test/to_custom_testrunner.c b/config/obc/cpd/apps/to/unit_test/to_custom_testrunner.c similarity index 100% rename from config/obc/cpd/target/apps/to/unit_test/to_custom_testrunner.c rename to config/obc/cpd/apps/to/unit_test/to_custom_testrunner.c diff --git a/config/obc/cpd/target/apps/to/unit_test/to_platform_stubs.c b/config/obc/cpd/apps/to/unit_test/to_platform_stubs.c similarity index 100% rename from config/obc/cpd/target/apps/to/unit_test/to_platform_stubs.c rename to config/obc/cpd/apps/to/unit_test/to_platform_stubs.c diff --git a/config/obc/cpd/target/apps/to/unit_test/to_platform_stubs.h b/config/obc/cpd/apps/to/unit_test/to_platform_stubs.h similarity index 100% rename from config/obc/cpd/target/apps/to/unit_test/to_platform_stubs.h rename to config/obc/cpd/apps/to/unit_test/to_platform_stubs.h diff --git a/config/obc/cpd/target/apps/to/user_doxy.in b/config/obc/cpd/apps/to/user_doxy.in similarity index 100% rename from config/obc/cpd/target/apps/to/user_doxy.in rename to config/obc/cpd/apps/to/user_doxy.in diff --git a/config/obc/cpd/target/apps/ulr/CMakeLists.txt b/config/obc/cpd/apps/ulr/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/ulr/CMakeLists.txt rename to config/obc/cpd/apps/ulr/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/ulr/tables/ulr_config.c b/config/obc/cpd/apps/ulr/tables/ulr_config.c similarity index 100% rename from config/obc/cpd/target/apps/ulr/tables/ulr_config.c rename to config/obc/cpd/apps/ulr/tables/ulr_config.c diff --git a/config/obc/cpd/target/apps/ulr/ulr_custom.cpp b/config/obc/cpd/apps/ulr/ulr_custom.cpp similarity index 100% rename from config/obc/cpd/target/apps/ulr/ulr_custom.cpp rename to config/obc/cpd/apps/ulr/ulr_custom.cpp diff --git a/config/obc/cpd/target/apps/vm/CMakeLists.txt b/config/obc/cpd/apps/vm/CMakeLists.txt similarity index 100% rename from config/obc/cpd/target/apps/vm/CMakeLists.txt rename to config/obc/cpd/apps/vm/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/vm/tables/vm_config.c b/config/obc/cpd/apps/vm/tables/vm_config.c similarity index 100% rename from config/obc/cpd/target/apps/vm/tables/vm_config.c rename to config/obc/cpd/apps/vm/tables/vm_config.c diff --git a/config/obc/cpd/inc/sed_platform_cfg.h b/config/obc/cpd/inc/sed_platform_cfg.h new file mode 100644 index 000000000..bcbd3475b --- /dev/null +++ b/config/obc/cpd/inc/sed_platform_cfg.h @@ -0,0 +1,136 @@ +#ifndef SED_PLATFORM_CFG_H +#define SED_PLATFORM_CFG_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "math.h" + +/* +** SED Platform Configuration Parameter Definitions +*/ + +/** \brief Mission specific version number for SED application +** +** \par Description: +** An application version number consists of four parts: +** major version number, minor version number, revision +** number and mission specific revision number. The mission +** specific revision number is defined here and the other +** parts are defined in "sed_version.h". +** +** \par Limits: +** Must be defined as a numeric value that is greater than +** or equal to zero. +*/ +#define SED_MISSION_REV (0) + +/** \brief Pipe depth for the Scheduler pipe +** +** \par Limits: +** minimum of 1, max of CFE_SB_MAX_PIPE_DEPTH. +*/ +#define SED_SCH_PIPE_DEPTH (2) + +/** \brief Pipe name for the Scheduler pipe +** +** \par Limits: +** Note, this name must fit in OS_MAX_API_NAME. +*/ +#define SED_SCH_PIPE_NAME ("SED_SCH_PIPE") + +/** \brief The SB pend behavior type for the Scheduler pipe. +** +** \par Limits: +** One of: CFE_SB_POLL, CFE_SB_PEND_FOREVER, or the +** number of milliseconds to wait for a new message (recommended). +** Note, using CFE_SB_PEND_FOREVER may cause an unresponsive +** application if no messages arrive on this pipe. +*/ +#define SED_SCH_PIPE_PEND_TIME (2000) + +/** \brief Pipe depth for the params pipe +** +** \par Limits: +** minimum of 1, max of CFE_SB_MAX_PIPE_DEPTH. +*/ +#define SED_PARAM_PIPE_DEPTH (4) + +/** \brief Pipe name for the params pipe +** +** \par Limits: +** Note, this name must fit in OS_MAX_API_NAME. +*/ +#define SED_PARAM_PIPE_NAME ("SED_PARAM_PIPE") + +/** \brief The number of WAKEUP messages to reserve on the Scheduler pipe. +** +** \par Limits: +** minimum of 1, max limited to CFE_SB_MAX_PIPE_DEPTH-1. Note the +** SED_MEASURE_MID_MAX_MSG_COUNT and SED_SEND_HK_MID_MAX_MSG_COUNT +** must be less than SED_SCH_PIPE_DEPTH. +*/ +#define SED_MEASURE_MID_MAX_MSG_COUNT (1) + +/** \brief The number of SEND_HK messages to reserve on the Scheduler pipe. +** +** \par Limits: +** minimum of 1, max of CFE_SB_MAX_PIPE_DEPTH. Note the +** SED_MEASURE_MID_MAX_MSG_COUNT and SED_SEND_HK_MID_MAX_MSG_COUNT +** must be less than SED_SCH_PIPE_DEPTH. +*/ +#define SED_SEND_HK_MID_MAX_MSG_COUNT (1) + +/** \brief Pipe depth for the command pipe +** +** \par Limits: +** minimum of 1, max of CFE_SB_MAX_PIPE_DEPTH. +*/ +#define SED_CMD_PIPE_DEPTH (4) + +/** \brief Pipe name for the Scheduler pipe +** +** \par Limits: +** Note, this name must fit in OS_MAX_API_NAME. +*/ +#define SED_CMD_PIPE_NAME ("SED_CMD_PIPE") + +/** \brief Pipe depth for the data pipe +** +** \par Limits: +** minimum of 1, max of CFE_SB_MAX_PIPE_DEPTH. +*/ +#define SED_DATA_PIPE_DEPTH (4) + +/** \brief Pipe name for the Scheduler pipe +** +** \par Limits: +** Note, this name must fit in OS_MAX_API_NAME. +*/ +#define SED_DATA_PIPE_NAME ("SED_DATA_PIPE") + +/** \brief The config table default filename +** +** \par Limits: +** The length of each string, including the NULL terminator cannot exceed +** the #OS_MAX_PATH_LEN value. +*/ +#define SED_CONFIG_TABLE_FILENAME ("/ram/apps/sed_config.tbl") + +/** \brief The timeout value, in milliseconds, to wait for ES application startup sync. +** +** \par Limits: +** This parameter must be at least 1000 (ms). +*/ +#define SED_STARTUP_TIMEOUT_MSEC (1000) + +#ifdef __cplusplus +} +#endif + +#endif /* SED_PLATFORM_CFG_H */ + +/************************/ +/* End of File Comment */ +/************************/ diff --git a/config/obc/sitl/gdbinit b/config/obc/cpd/sitl/gdbinit similarity index 100% rename from config/obc/sitl/gdbinit rename to config/obc/cpd/sitl/gdbinit diff --git a/config/obc/cpd/sitl/host/CMakeLists.txt b/config/obc/cpd/sitl/host/CMakeLists.txt new file mode 100644 index 000000000..02af9dd76 --- /dev/null +++ b/config/obc/cpd/sitl/host/CMakeLists.txt @@ -0,0 +1,11 @@ +include(../set-vars.cmake) + +# Put host specific functions here. This allows us to build things like elf2cfetbl which are built using the host +# toolchain, not the cross toolchain. +buildliner_build_cfe_host_tools( + PSP ${PSP} + OSAL ${OSAL} + CONFIG + ${CMAKE_CURRENT_SOURCE_DIR}/../../inc + ${PROJECT_SOURCE_DIR}/config/shared/inc +) \ No newline at end of file diff --git a/config/obc/sitl/perf_id_list b/config/obc/cpd/sitl/perf_id_list similarity index 100% rename from config/obc/sitl/perf_id_list rename to config/obc/cpd/sitl/perf_id_list diff --git a/config/obc/sitl/set-vars.cmake b/config/obc/cpd/sitl/set-vars.cmake similarity index 100% rename from config/obc/sitl/set-vars.cmake rename to config/obc/cpd/sitl/set-vars.cmake diff --git a/config/obc/cpd/sitl/target/CMakeLists.txt b/config/obc/cpd/sitl/target/CMakeLists.txt new file mode 100644 index 000000000..4212aa5ad --- /dev/null +++ b/config/obc/cpd/sitl/target/CMakeLists.txt @@ -0,0 +1,129 @@ +include(../set-vars.cmake) + +buildliner_initialize( + PSP ${PSP} + OSAL ${OSAL} + CPU_ID CPD + CORE_TOOLS ${CMAKE_CURRENT_SOURCE_DIR}/tools + CONFIG + ${CMAKE_CURRENT_SOURCE_DIR}/../../inc + ${PROJECT_SOURCE_DIR}/config/shared/inc + FILESYS + /cf/apps + /cf/download + /cf/log + /cf/upload + /ram + STARTUP_SCRIPT + ${CMAKE_CURRENT_SOURCE_DIR}/../../cfe_es_startup.scr + + COMMANDER_WORKSPACE + ${CMAKE_BINARY_DIR}/../../../sitl_commander_workspace +) + +buildliner_add_app( + cfs_lib + DEFINITION ${PROJECT_SOURCE_DIR}/apps/cfs_lib/fsw/for_build +) + +buildliner_add_app( + mbp_lib + DEFINITION ${PROJECT_SOURCE_DIR}/../private/apps/mbp_lib/fsw/for_build +) + +buildliner_add_app( + px4lib + DEFINITION ${PROJECT_SOURCE_DIR}/apps/px4lib/fsw/for_build +) + +buildliner_add_app( + pq_lib + DEFINITION ${PROJECT_SOURCE_DIR}/apps/pq_lib/fsw/for_build + # TODO move this table build to sbn module? + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../../apps/pq_lib +) + +buildliner_add_app( + prmlib + DEFINITION ${PROJECT_SOURCE_DIR}/apps/prmlib/fsw/for_build + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../../apps/prm +) + +buildliner_add_app( + sch + DEFINITION ${PROJECT_SOURCE_DIR}/apps/sch/fsw/for_build + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../../apps/sch + CONFIG_SOURCES + ${CMAKE_CURRENT_SOURCE_DIR}/../../apps/sch/sch_custom_rt.c +) + +buildliner_add_app( + cf + DEFINITION ${PROJECT_SOURCE_DIR}/apps/cf/fsw/for_build + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../../apps/cf +) + +buildliner_add_app( + cs + DEFINITION ${PROJECT_SOURCE_DIR}/apps/cs/fsw/for_build + CONFIG ${PROJECT_SOURCE_DIR}/config/shared/apps/cs +) + +buildliner_add_app( + fm + DEFINITION ${PROJECT_SOURCE_DIR}/apps/fm/fsw/for_build + CONFIG ${PROJECT_SOURCE_DIR}/config/shared/apps/fm +) + +buildliner_add_app( + hk + DEFINITION ${PROJECT_SOURCE_DIR}/apps/hk/fsw/for_build + CONFIG ${PROJECT_SOURCE_DIR}/config/shared/apps/hk +) + +buildliner_add_app( + hs + DEFINITION ${PROJECT_SOURCE_DIR}/apps/hs/fsw/for_build + CONFIG ${PROJECT_SOURCE_DIR}/config/shared/apps/hs + CONFIG_SOURCES + ${PROJECT_SOURCE_DIR}/config/shared/apps/hs/hs_custom.c +) + +buildliner_add_app( + lc + DEFINITION ${PROJECT_SOURCE_DIR}/apps/lc/fsw/for_build + CONFIG ${PROJECT_SOURCE_DIR}/config/shared/apps/lc + CONFIG_SOURCES + ${PROJECT_SOURCE_DIR}/config/shared/apps/lc/src/lc_custom.c +) + +buildliner_add_app( + md + DEFINITION ${PROJECT_SOURCE_DIR}/apps/md/fsw/for_build + CONFIG ${PROJECT_SOURCE_DIR}/config/shared/apps/md +) + +buildliner_add_app( + mm + DEFINITION ${PROJECT_SOURCE_DIR}/apps/mm/fsw/for_build +) + +buildliner_add_app( + sc + DEFINITION ${PROJECT_SOURCE_DIR}/apps/sc/fsw/for_build + CONFIG ${PROJECT_SOURCE_DIR}/config/shared/apps/sc +) + +buildliner_add_app( + sbn + DEFINITION ${PROJECT_SOURCE_DIR}/apps/sbn/fsw/for_build + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../../apps/sbn + CONFIG_SOURCES + ${CMAKE_CURRENT_SOURCE_DIR}/../../apps/sbn/src/sbn_remap_tbl.c +) + +buildliner_add_app( + sbn_udp + DEFINITION ${PROJECT_SOURCE_DIR}/apps/sbn/modules/udp/fsw/for_build +) + diff --git a/config/obc/sitl/target/gdbinit b/config/obc/cpd/sitl/target/gdbinit similarity index 100% rename from config/obc/sitl/target/gdbinit rename to config/obc/cpd/sitl/target/gdbinit diff --git a/config/obc/cpd/sitl/wh_config.yaml b/config/obc/cpd/sitl/wh_config.yaml new file mode 100644 index 000000000..d2daf9c79 --- /dev/null +++ b/config/obc/cpd/sitl/wh_config.yaml @@ -0,0 +1,9 @@ +--- +config_base: ${PROJECT_SOURCE_DIR} +modules: + core: + modules: + osal: + definition: ${PROJECT_SOURCE_DIR}/core/osal/fsw/posix-fast/wh_design.yaml + psp: + definition: ${PROJECT_SOURCE_DIR}/core/psp/fsw/pc-linux/wh_design.yaml diff --git a/config/obc/cpd/target/CMakeLists.txt b/config/obc/cpd/target/CMakeLists.txt index ec2a0c829..ed864e7e3 100644 --- a/config/obc/cpd/target/CMakeLists.txt +++ b/config/obc/cpd/target/CMakeLists.txt @@ -2,6 +2,7 @@ include(../set-vars.cmake) buildliner_initialize( EMBED_SYMTAB + CPU_ID CPD PSP ${PSP} OSAL ${OSAL} CORE_TOOLS ${CMAKE_CURRENT_SOURCE_DIR}/tools @@ -17,6 +18,9 @@ buildliner_initialize( /ram STARTUP_SCRIPT ${CMAKE_CURRENT_SOURCE_DIR}/cfe_es_startup.scr + + COMMANDER_WORKSPACE + ${CMAKE_BINARY_DIR}/../../commander_workspace ) @@ -27,33 +31,46 @@ buildliner_add_app( ) buildliner_add_app( - px4lib + mbp_lib EMBEDDED - DEFINITION ${PROJECT_SOURCE_DIR}/apps/px4lib/fsw/for_build + DEFINITION ${PROJECT_SOURCE_DIR}/../private/apps/mbp_lib/fsw/for_build ) buildliner_add_app( - prmlib + pq_lib EMBEDDED - DEFINITION ${PROJECT_SOURCE_DIR}/apps/prmlib/fsw/for_build - CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/apps/prm + DEFINITION ${PROJECT_SOURCE_DIR}/apps/pq_lib/fsw/for_build + # TODO move this table build to sbn module? + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../apps/pq_lib ) buildliner_add_app( - pq_lib + px4lib EMBEDDED - DEFINITION ${PROJECT_SOURCE_DIR}/apps/pq_lib/fsw/for_build - # TODO move this table build to sbn module? - CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/apps/pq_lib + DEFINITION ${PROJECT_SOURCE_DIR}/apps/px4lib/fsw/for_build +) + +buildliner_add_app( + sed + EMBEDDED + DEFINITION ${PROJECT_SOURCE_DIR}/../private/apps/sed/fsw/for_build + CONFIG ${PROJECT_SOURCE_DIR}/config/shared/apps/sed ) +#buildliner_add_app( +# prmlib +# EMBEDDED +# DEFINITION ${PROJECT_SOURCE_DIR}/apps/prmlib/fsw/for_build +# CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/apps/prm +#) + buildliner_add_app( sch EMBEDDED DEFINITION ${PROJECT_SOURCE_DIR}/apps/sch/fsw/for_build - CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/apps/sch + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../apps/sch CONFIG_SOURCES - ${CMAKE_CURRENT_SOURCE_DIR}/apps/sch/sch_custom_rt.c + ${CMAKE_CURRENT_SOURCE_DIR}/../apps/sch/sch_custom_rt.c ) # This is temporarily removed until we can remove the OS dependency @@ -123,17 +140,17 @@ buildliner_add_app( sbn EMBEDDED DEFINITION ${PROJECT_SOURCE_DIR}/apps/sbn/fsw/for_build - CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/apps/sbn + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../apps/sbn CONFIG_SOURCES - ${CMAKE_CURRENT_SOURCE_DIR}/apps/sbn/src/sbn_remap_tbl.c + ${CMAKE_CURRENT_SOURCE_DIR}/../apps/sbn/src/sbn_remap_tbl.c ) buildliner_add_app( sbn_mbox EMBEDDED - DEFINITION ${PROJECT_SOURCE_DIR}/apps/sbn/modules/mbox/fsw/for_build + DEFINITION ${PROJECT_SOURCE_DIR}/../private/apps/sbn_mbox/fsw/for_build CONFIG_SOURCES - ${CMAKE_CURRENT_SOURCE_DIR}/apps/pq_lib/tables/pq_backup_cfg.c + ${CMAKE_CURRENT_SOURCE_DIR}/../apps/pq_lib/tables/pq_backup_cfg.c ) # This is temporarily removed until we can remove the OS dependency @@ -145,18 +162,17 @@ buildliner_add_app( # CONFIG_SOURCES # ${CMAKE_CURRENT_SOURCE_DIR}/apps/ci/ci_custom.c #) -# -## This is temporarily removed until we can remove the OS dependency -## in ci, i.e. "arpa/inet.h" + #buildliner_add_app( -# to -# DEFINITION ${PROJECT_SOURCE_DIR}/apps/to/fsw/for_build -# CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/apps/to -# CONFIG_SOURCES -# ${CMAKE_CURRENT_SOURCE_DIR}/apps/to/tables/to_backup_cfg.c -# ${CMAKE_CURRENT_SOURCE_DIR}/apps/to/to_custom.c + #to + #EMBEDDED + #DEFINITION ${PROJECT_SOURCE_DIR}/apps/to/fsw/for_build + #CONFIG ${PROJECT_SOURCE_DIR}/../private/config/obc/cpd/apps/to + #CONFIG_SOURCES + #${PROJECT_SOURCE_DIR}/../private/config/obc/cpd/apps/to/tables/to_backup_cfg.c + #${PROJECT_SOURCE_DIR}/../private/config/obc/cpd/apps/to/to_custom.c #) -# + # ## This is temporarily removed until we can geet px4lib back in #buildliner_add_app( diff --git a/config/obc/cpd/target/apps/pq_lib/tables/pq_cfg.c b/config/obc/cpd/target/apps/pq_lib/tables/pq_cfg.c deleted file mode 100644 index 989c7f90f..000000000 --- a/config/obc/cpd/target/apps/pq_lib/tables/pq_cfg.c +++ /dev/null @@ -1,218 +0,0 @@ -/************************************************************************ - ** Includes - *************************************************************************/ -#include "cfe_tbl_filedef.h" -#include "pq_structs.h" -#include "msg_ids.h" - -/** - ** \brief The cFE TO config table definition. - ** - ** Content format: ObjName[64], TblName[38], Desc[32], TgtFileName[20], ObjSize - ** ObjName - variable name of config table, e.g., PQ_ConfigDefTbl[] - ** TblName - app's table name, e.g., TO.CONFIG_TBL, where TO is the same app name - ** used in cfe_es_startup.scr, and PQ_defConfigTbl is the same table - ** name passed in to CFE_TBL_Register() - ** Desc - description of table in string format - ** TgtFileName[20] - table file name, compiled as .tbl file extension - ** ObjSize - size of the entire table - ** - */ -static CFE_TBL_FileDef_t CFE_TBL_FileDef OS_USED = -{ - "PQ_ConfigTbl", "SBN.CFG", "PQ table", - "pq_cfg.tbl", (sizeof(PQ_ChannelTbl_t)) -}; - - -/************************************************************************ - ** Defines - *************************************************************************/ - -#define PQ_PQUEUE_SINGLE_PASS_IDX 0 -#define PQ_PQUEUE_HIGH_OPS_RSRVD_IDX 1 -#define PQ_PQUEUE_HIGH_IDX 2 -#define PQ_PQUEUE_MEDIUM_IDX 3 -#define PQ_PQUEUE_LOW_IDX 4 - -/** - ** \brief Default TO config table data - */ -PQ_ChannelTbl_t PQ_ConfigTbl = -{ - /* Table ID */ - 1, - { - /* Message Flows */ - /* Ground Queues */ - {SBN_SUB_MID, 64, PQ_PQUEUE_MEDIUM_IDX}, - {SBN_UNSUB_MID, 64, PQ_PQUEUE_MEDIUM_IDX}, - {SBN_ALLSUB_MID, 1, PQ_PQUEUE_HIGH_IDX}, - {AMC_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {MAC_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {MPC_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {ULR_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {RGBLED_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {GPS_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {SENS_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {LD_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {NAV_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {RCIN_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {VM_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {BAT_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {PE_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {AK8963_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {AK8963_DIAG_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {MS5611_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {MS5611_DIAG_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {MPU6050_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {MPU6050_DIAG_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {EA_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {VC_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {GPS_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CFE_ES_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CFE_EVS_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CFE_SB_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CFE_TBL_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CFE_TIME_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CFE_TIME_DIAG_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CFE_EVS_EVENT_MSG_MID, 32, PQ_PQUEUE_LOW_IDX}, - {CFE_SB_STATS_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CFE_ES_APP_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CFE_TBL_REG_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CFE_ES_SHELL_TLM_MID, 32, PQ_PQUEUE_LOW_IDX}, - {CFE_ES_MEMSTATS_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CF_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CF_TRANS_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CF_CONFIG_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CF_SPACE_TO_GND_PDU_MID, 32, PQ_PQUEUE_LOW_IDX}, - {CS_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {DS_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {DS_DIAG_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {FM_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {FM_FILE_INFO_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {FM_DIR_LIST_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {FM_OPEN_FILES_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {FM_FREE_SPACE_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {HK_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {HS_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {LC_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {MD_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {MM_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {SCH_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {SCH_DIAG_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {QAE_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {MPC_DIAG_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {LD_DIAG_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {PRM_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {VM_CONFIG_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - -// {PX4_ACTUATOR_ARMED_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_ACTUATOR_CONTROLS_0_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_ACTUATOR_CONTROLS_1_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_ACTUATOR_CONTROLS_2_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_ACTUATOR_CONTROLS_3_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_ACTUATOR_DIRECT_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_ACTUATOR_OUTPUTS_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_ADC_REPORT_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_AIRSPEED_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_ATT_POS_MOCAP_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_BATTERY_STATUS_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_CAMERA_TRIGGER_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_COMMANDER_STATE_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_CONTROL_STATE_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_CPULOAD_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_DEBUG_KEY_VALUE_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_DIFFERENTIAL_PRESSURE_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_DISTANCE_SENSOR_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_FW_POS_CTRL_STATUS_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_FW_VIRTUAL_ATTITUDE_SETPOINT_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_FW_VIRTUAL_RATES_SETPOINT_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_EKF2_INNOVATIONS_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_EKF2_REPLAY_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_ESC_REPORT_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_ESC_STATUS_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_ESTIMATOR_STATUS_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_FENCE_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_FENCE_VERTEX_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_FILTERED_BOTTOM_FLOW_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_FOLLOW_TARGET_MID, 1, PQ_PQUEUE_LOW_IDX}, - {PX4_GEOFENCE_RESULT_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_GPS_DUMP_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_GPS_INJECT_DATA_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_HIL_SENSOR_MID, 1, PQ_PQUEUE_LOW_IDX}, - {PX4_HOME_POSITION_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_INPUT_RC_MID, 1, PQ_PQUEUE_LOW_IDX}, - {PX4_LED_CONTROL_MID, 1, PQ_PQUEUE_LOW_IDX}, - {PX4_LOG_MESSAGE_MID, 1, PQ_PQUEUE_LOW_IDX}, - {PX4_MANUAL_CONTROL_SETPOINT_MID, 1, PQ_PQUEUE_LOW_IDX}, - {PX4_MAVLINK_LOG_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_MC_ATT_CTRL_STATUS_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_MC_VIRTUAL_ATTITUDE_SETPOINT_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_MC_VIRTUAL_RATES_SETPOINT_MID, 1, PQ_PQUEUE_LOW_IDX}, - {PX4_MISSION_MID, 1, PQ_PQUEUE_LOW_IDX}, - {PX4_MISSION_RESULT_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_MULTIROTOR_MOTOR_LIMITS_MID, 1, PQ_PQUEUE_LOW_IDX}, - {PX4_OFFBOARD_CONTROL_MODE_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_OPTICAL_FLOW_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_OUTPUT_PWM_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_PARAMETER_UPDATE_MID, 1, PQ_PQUEUE_LOW_IDX}, - {PX4_POSITION_SETPOINT_TRIPLET_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_PWM_INPUT_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_QSHELL_REQ_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_RC_CHANNELS_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_RC_PARAMETER_MAP_MID, 1, PQ_PQUEUE_LOW_IDX}, - {PX4_SAFETY_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_SATELLITE_INFO_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_SENSOR_ACCEL_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_SENSOR_BARO_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_SENSOR_COMBINED_MID, 1, PQ_PQUEUE_LOW_IDX}, - {PX4_SENSOR_CORRECTION_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_SENSOR_GYRO_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_SENSOR_MAG_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_SERVORAIL_STATUS_MID, 1, PQ_PQUEUE_LOW_IDX}, - {PX4_SUBSYSTEM_INFO_MID, 1, PQ_PQUEUE_LOW_IDX}, - {PX4_SYSTEM_POWER_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_TECS_STATUS_MID, 1, PQ_PQUEUE_LOW_IDX}, - {PX4_TELEMETRY_STATUS_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_TEST_MOTOR_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_TIME_OFFSET_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_TRANSPONDER_REPORT_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_UAVCAN_PARAMETER_REQUEST_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_UAVCAN_PARAMETER_VALUE_MID, 1, PQ_PQUEUE_LOW_IDX}, - {PX4_VEHICLE_ATTITUDE_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_VEHICLE_ATTITUDE_SETPOINT_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_VEHICLE_COMMAND_ACK_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_VEHICLE_COMMAND_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_VEHICLE_CONTROL_MODE_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_VEHICLE_FORCE_SETPOINT_MID, 1, PQ_PQUEUE_LOW_IDX}, - {PX4_VEHICLE_GLOBAL_POSITION_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_VEHICLE_GLOBAL_VELOCITY_SETPOINT_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_VEHICLE_GPS_POSITION_MID, 1, PQ_PQUEUE_LOW_IDX}, - {PX4_VEHICLE_LAND_DETECTED_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_VEHICLE_LOCAL_POSITION_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_VEHICLE_LOCAL_POSITION_SETPOINT_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_VEHICLE_RATES_SETPOINT_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_VEHICLE_STATUS_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_VISION_POSITION_ESTIMATE_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_VTOL_VEHICLE_STATUS_MID, 1, PQ_PQUEUE_LOW_IDX}, -// {PX4_WIND_ESTIMATE_MID, 1, PQ_PQUEUE_LOW_IDX} - },{ - /* Priority Queues */ - /* PQ_PQUEUE_SINGLE_PASS_IDX */ - {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_SINGLE}, - /* PQ_PQUEUE_HIGH_OPS_RSRVD_IDX */ - {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO}, - /* PQ_PQUEUE_HIGH_IDX */ - {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO}, - /* PQ_PQUEUE_MEDIUM_IDX */ - {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO}, - /* PQ_PQUEUE_LOW_IDX */ - {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO} - } -}; - - -/************************/ -/* End of File Comment */ -/************************/ diff --git a/config/obc/cpd/target/cfe_es_startup.scr b/config/obc/cpd/target/cfe_es_startup.scr index ca46a102f..05afa3fc9 100644 --- a/config/obc/cpd/target/cfe_es_startup.scr +++ b/config/obc/cpd/target/cfe_es_startup.scr @@ -1,6 +1,8 @@ CFE_LIB, /embedded/CFS_LIB.so, CFS_LibInit, CFS_LIB, 0, 0, 0x0, 0, 2; +CFE_LIB, /embedded/MBP_LIB.so, MBP_LibInit, MBP_LIB, 0, 0, 0x0, 0, 2; CFE_LIB, /embedded/PQ_LIB.so, PQ_LibInit, PQ_LIB, 0, 0, 0x0, 0, 2; CFE_APP, /embedded/SBN.so, SBN_AppMain, SBN, 37, 32768, 0x0, 0, 2; +CFE_APP, /embedded/SED.so, SED_AppMain, SED, 46, 327680, 0x0, 0, 2; CFE_APP, /embedded/SCH.so, SCH_AppMain, SCH, 34, 40960, 0x0, 0, 2; !CFE_LIB, /embedded/PRMLIB.so, PRMLIB_LibInit, PRMLIB, 0, 0, 0x0, 0, 2; CFE_LIB, /embedded/PX4LIB.so, PX4LIB_LibInit, PX4LIB, 0, 0, 0x0, 0, 2; diff --git a/config/obc/cpd/target/unit_test_wrapper b/config/obc/cpd/target/unit_test_wrapper deleted file mode 100755 index 1f8dde316..000000000 --- a/config/obc/cpd/target/unit_test_wrapper +++ /dev/null @@ -1,22 +0,0 @@ -#!/bin/bash -HOST_PATH=$1 -FULL_COMMAND=${*:2} -TARGET_DIR="/var/lib/jenkins/workspace/Airliner/OcPoC/Release_1.0.0" -TARGET_GCOV_PREFIX="${TARGET_DIR}" -TARGET_USER="root" -TARGET_ADDRESS="10.10.0.80" -HOST_DIR_DEPTH=$(find $1 -type d -printf '%d\n' | sort -n | tail -1) - -echo "*****************************" -echo "HOST_PATH = ${HOST_PATH}" -echo "FULL_COMMAND = ${FULL_COMMAND}" -echo "TARGET_DIR = ${TARGET_DIR}" -echo "TARGET_GCOV_PREFIX = ${TARGET_GCOV_PREFIX}" -echo "TARGET_USER = ${TARGET_USER}" -echo "TARGET_ADDRESS = ${TARGET_ADDRESS}" -echo "HOST_DIR_DEPTH = ${HOST_DIR_DEPTH}" -ssh ${TARGET_USER}@${TARGET_ADDRESS} "cd ${HOST_PATH}; ${FULL_COMMAND}" -RETURN_CODE=$? -echo "*****************************" - -exit ${RETURN_CODE} diff --git a/config/obc/cpd/target/unit_test_wrapper2 b/config/obc/cpd/target/unit_test_wrapper2 deleted file mode 100755 index f346e2eec..000000000 --- a/config/obc/cpd/target/unit_test_wrapper2 +++ /dev/null @@ -1,18 +0,0 @@ -#!/bin/bash -HOST_PATH=$1 -FULL_COMMAND=${*:2} -TARGET_DIR="/root/unit-test" -TARGET_GCOV_PREFIX="${TARGET_DIR}" -TARGET_USER="root" -TARGET_ADDRESS="192.168.1.150" -HOST_DIR_DEPTH=$(find $1 -type d -printf '%d\n' | sort -n | tail -1) - -ssh ${TARGET_USER}@${TARGET_ADDRESS} "mkdir -p ${TARGET_DIR}" || /bin/true -ssh ${TARGET_USER}@${TARGET_ADDRESS} "mkdir -p ${TARGET_GCOV_PREFIX}" || /bin/true -rsync -a -z ${HOST_PATH}/* ${TARGET_USER}@${TARGET_ADDRESS}:${TARGET_DIR}/ -ssh ${TARGET_USER}@${TARGET_ADDRESS} "cd ${TARGET_DIR}; GCOV_PREFIX=${TARGET_GCOV_PREFIX} GCOV_PREFIX_STRIP=${HOST_DIR_DEPTH} ${FULL_COMMAND}" -RETURN_CODE=$? -rsync -a -z ${TARGET_USER}@${TARGET_ADDRESS}:${TARGET_DIR}/* ${HOST_PATH}/ -ssh ${TARGET_USER}@${TARGET_ADDRESS} "rm -Rf ${TARGET_DIR}" || /bin/true - -exit ${RETURN_CODE} diff --git a/config/obc/cpd/wh_config.yaml b/config/obc/cpd/wh_config.yaml index 0359c05ad..683324c14 100644 --- a/config/obc/cpd/wh_config.yaml +++ b/config/obc/cpd/wh_config.yaml @@ -1,10 +1,905 @@ --- config_base: ${PROJECT_SOURCE_DIR} - +cpu_id: CPD modules: core: modules: osal: - definition: ${PROJECT_SOURCE_DIR}/core/osal/fsw/freertos/wh_design.yaml + definition: ${PROJECT_SOURCE_DIR}/../private/core/osal/freertos/wh_design.yaml psp: - definition: ${PROJECT_SOURCE_DIR}/core/psp/fsw/obc-cpd/wh_design.yaml \ No newline at end of file + definition: ${PROJECT_SOURCE_DIR}/../private/core/psp/obc-cpd/wh_design.yaml + cfe: + definition: ${PROJECT_SOURCE_DIR}/core/base/cfe/wh_design.yaml + modules: + cfe_es: + telemetry: + CFE_ES_HK_TLM_MID: + msgID: 0x0a0f + CFE_ES_APP_TLM_MID: + msgID: 0x0a17 + CFE_ES_MEMSTATS_TLM_MID: + msgID: 0x0a1c + CFE_ES_SHELL_TLM_MID: + msgID: 0x0a1b + commands: + CFE_ES_CMD_MID: + msgID: 0x1a04 + CFE_ES_SEND_HK_MID: + msgID: 0x1a05 + cfe_evs: + telemetry: + CFE_EVS_HK_TLM_MID: + msgID: 0x0a10 + CFE_EVS_EVENT_MSG_MID: + msgID: 0x0a15 + commands: + CFE_EVS_CMD_MID: + msgID: 0x1a00 + CFE_EVS_SEND_HK_MID: + msgID: 0x1a06 + cfe_sb: + telemetry: + CFE_SB_HK_TLM_MID: + msgID: 0x0a11 + CFE_SB_STATS_TLM_MID: + msgID: 0x0a16 + CFE_SB_ALLSUBS_TLM_MID: + msgID: 0x0a19 + CFE_SB_ONESUB_TLM_MID: + msgID: 0x0a1a + commands: + CFE_SB_CMD_MID: + msgID: 0x1a01 + CFE_SB_SEND_HK_MID: + msgID: 0x1a07 + cfe_tbl: + telemetry: + CFE_TBL_HK_TLM_MID: + msgID: 0x1a02 + CFE_TBL_REG_TLM_MID: + msgID: 0x0a18 + commands: + CFE_TBL_CMD_MID: + msgID: 0x1a02 + CFE_TBL_SEND_HK_MID: + msgID: 0x1a08 + cfe_time: + telemetry: + CFE_TIME_DIAG_TLM_MID: + msgID: 0x0a14 + CFE_TIME_HK_TLM_MID: + msgID: 0x0a13 + commands: + CFE_TIME_CMD_MID: + msgID: 0x1a03 + CFE_TIME_SEND_HK_MID: + msgID: 0x1a09 + CFE_TIME_DATA_CMD_MID: + msgID: 0x1a0c + CFE_TIME_TONE_CMD_MID: + msgID: 0x1a0a + CFE_TIME_FAKE_CMD_MID: + msgID: 0x1a0d + CFE_TIME_1HZ_CMD_MID: + msgID: 0x1a0b + CFE_TIME_SEND_CMD_MID: + msgID: 0x1a0e + + ci: + definition: ${PROJECT_SOURCE_DIR}/apps/ci/wh_design.yaml + telemetry: + CI_HK_TLM_MID: + msgID: 0x0a32 + commands: + CI_CMD_MID: + msgID: 0x1a34 + CI_PROCESS_TIMEOUTS_MID: + msgID: 0x1a35 + CI_SEND_HK_MID: + msgID: 0x1a36 + CI_WAKEUP_MID: + msgID: 0x1a37 + + cf: + definition: ${PROJECT_SOURCE_DIR}/apps/cf/wh_design.yaml + telemetry: + CF_CONFIG_TLM_MID: + msgID: 0x0a38 + CF_HK_TLM_MID: + msgID: 0x0a39 + CF_INCOMING_PDU_MID: + msgID: 0x0a3a + CF_TRANS_TLM_MID: + msgID: 0x0a3b + commands: + CF_CMD_MID: + msgID: 0x1a3c + CF_SEND_HK_MID: + msgID: 0x1a3d + CF_SPACE_TO_GND_PDU_MID: + msgID: 0x1a3e + CF_WAKE_UP_REQ_CMD_MID: + msgID: 0x1a3f + + cs: + definition: ${PROJECT_SOURCE_DIR}/apps/cs/wh_design.yaml + telemetry: + CS_HK_TLM_MID: + msgID: 0x0a50 + commands: + CS_CMD_MID: + msgID: 0x1a51 + CS_BACKGROUND_CYCLE_MID: + msgID: 0x1a52 + CS_SEND_HK_MID: + msgID: 0x1a53 + + ds: + definition: ${PROJECT_SOURCE_DIR}/apps/ds/wh_design.yaml + telemetry: + DS_DIAG_TLM_MID: + msgID: 0x0a54 + DS_HK_TLM_MID: + msgID: 0x0a55 + commands: + DS_CMD_MID: + msgID: 0x1a56 + DS_SEND_HK_MID: + msgID: 0x1a57 + + fm: + definition: ${PROJECT_SOURCE_DIR}/apps/fm/wh_design.yaml + telemetry: + FM_DIR_LIST_TLM_MID: + msgID: 0x0a58 + FM_FILE_INFO_TLM_MID: + msgID: 0x0a59 + FM_FREE_SPACE_TLM_MID: + msgID: 0x0a5a + FM_HK_TLM_MID: + msgID: 0x0a5b + FM_OPEN_FILES_TLM_MID: + msgID: 0x0a5c + commands: + FM_CMD_MID: + msgID: 0x1a5d + FM_SEND_HK_MID: + msgID: 0x1a5e + + hk: + definition: ${PROJECT_SOURCE_DIR}/apps/hk/wh_design.yaml + telemetry: + HK_COMBINED_PKT1_MID: + msgID: 0x0a64 + HK_COMBINED_PKT2_MID: + msgID: 0x0a65 + HK_COMBINED_PKT3_MID: + msgID: 0x0a66 + HK_COMBINED_PKT4_MID: + msgID: 0x0a67 + HK_COMBINED_PKT5_MID: + msgID: 0x0a68 + HK_COMBINED_PKT6_MID: + msgID: 0x0a69 + HK_COMBINED_PKT7_MID: + msgID: 0x0a6a + HK_COMBINED_PKT8_MID: + msgID: 0x0a6b + HK_COMBINED_PKT9_MID: + msgID: 0x0a6c + HK_COMBINED_PKT10_MID: + msgID: 0x0a6d + HK_HK_TLM_MID: + msgID: 0x0a6e + commands: + HK_CMD_MID: + msgID: 0x1a6f + HK_SEND_COMBINED_PKT_MID: + msgID: 0x1a70 + HK_SEND_HK_MID: + msgID: 0x1a71 + + hs: + definition: ${PROJECT_SOURCE_DIR}/apps/hs/wh_design.yaml + telemetry: + HS_HK_TLM_MID: + msgID: 0x0a78 + commands: + HS_CMD_MID: + msgID: 0x1a79 + HS_SEND_HK_MID: + msgID: 0x1a7a + HS_WAKEUP_MID: + msgID: 0x1a7b + + lc: + definition: ${PROJECT_SOURCE_DIR}/apps/lc/wh_design.yaml + telemetry: + LC_HK_TLM_MID: + msgID: 0x0a82 + commands: + LC_CMD_MID: + msgID: 0x1a83 + LC_SAMPLE_AP_MID: + msgID: 0x1a84 + LC_SEND_HK_MID: + msgID: 0x1a85 + + md: + definition: ${PROJECT_SOURCE_DIR}/apps/md/wh_design.yaml + telemetry: + MD_DWELL_PKT_MID_BASE: + msgID: 0x0a86 + MD_DWELL_PKT1_MID: + msgID: 0x0a86 + MD_DWELL_PKT2_MID: + msgID: 0x0a87 + MD_DWELL_PKT3_MID: + msgID: 0x0a88 + MD_DWELL_PKT4_MID: + msgID: 0x0a89 + MD_HK_TLM_MID: + msgID: 0x0a8b + commands: + MD_CMD_MID: + msgID: 0x1a8c + MD_SEND_HK_MID: + msgID: 0x1a8d + MD_WAKEUP_MID: + msgID: 0x1a8e + + mm: + definition: ${PROJECT_SOURCE_DIR}/apps/mm/wh_design.yaml + telemetry: + MM_HK_TLM_MID: + msgID: 0x0a8f + commands: + MM_CMD_MID: + msgID: 0x1a90 + MM_SEND_HK_MID: + msgID: 0x1a91 + + sc: + definition: ${PROJECT_SOURCE_DIR}/apps/sc/wh_design.yaml + telemetry: + SC_HK_TLM_MID: + msgID: 0x0a92 + commands: + SC_1HZ_WAKEUP_MID: + msgID: 0x1a93 + SC_CMD_MID: + msgID: 0x1a94 + SC_SEND_HK_MID: + msgID: 0x1a95 + + sch: + definition: ${PROJECT_SOURCE_DIR}/apps/sch/wh_design.yaml + telemetry: + SCH_ACTIVITY_DONE_MID: + msgID: 0x0a96 + SCH_DIAG_TLM_MID: + msgID: 0x0a97 + SCH_HK_TLM_MID: + msgID: 0x0a98 + commands: + SCH_CMD_MID: + msgID: 0x1a99 + SCH_SEND_HK_MID: + msgID: 0x1a9a + + to: + definition: ${PROJECT_SOURCE_DIR}/apps/to/wh_design.yaml + telemetry: + TO_DATA_TYPE_MID: + msgID: 0x0a9b + TO_DIAG_MSG_FLOW_MID: + msgID: 0x0a9c + TO_DIAG_TLM_MID: + msgID: 0x0a9d + TO_HK_TLM_MID: + msgID: 0x0a9e + commands: + TO_CMD_MID: + msgID: 0x1a9f + TO_SEND_HK_MID: + msgID: 0x1aa0 + TO_SEND_TLM_MID: + msgID: 0x1aa1 + + + px4lib: + definition: ${PROJECT_SOURCE_DIR}/apps/px4lib/wh_design.yaml + telemetry: + PX4_ACTUATOR_ARMED_MID: + msgID: 0x0aa2 + PX4_ACTUATOR_CONTROLS_0_MID: + msgID: 0x0aa3 + PX4_ACTUATOR_CONTROLS_1_MID: + msgID: 0x0aa4 + PX4_ACTUATOR_CONTROLS_2_MID: + msgID: 0x0aa5 + PX4_ACTUATOR_CONTROLS_3_MID: + msgID: 0x0aa6 + PX4_ACTUATOR_DIRECT_MID: + msgID: 0x0aa7 + PX4_ACTUATOR_OUTPUTS_MID: + msgID: 0x0aa8 + PX4_ADC_REPORT_MID: + msgID: 0x0aa9 + PX4_AIRSPEED_MID: + msgID: 0x0aaa + PX4_ATT_POS_MOCAP_MID: + msgID: 0x0aab + PX4_BATTERY_STATUS_MID: + msgID: 0x0aac + PX4_CAMERA_TRIGGER_MID: + msgID: 0x0aad + PX4_COMMANDER_STATE_MID: + msgID: 0x0aae + PX4_CONTROL_STATE_MID: + msgID: 0x0aaf + PX4_CPULOAD_MID: + msgID: 0x0ab0 + PX4_DEBUG_KEY_VALUE_MID: + msgID: 0x0ab1 + PX4_DIFFERENTIAL_PRESSURE_MID: + msgID: 0x0ab2 + PX4_DISTANCE_SENSOR_MID: + msgID: 0x0ab3 + PX4_FW_POS_CTRL_STATUS_MID: + msgID: 0x0ab4 + PX4_FW_VIRTUAL_ATTITUDE_SETPOINT_MID: + msgID: 0x0ab5 + PX4_FW_VIRTUAL_RATES_SETPOINT_MID: + msgID: 0x0ab6 + PX4_EKF2_INNOVATIONS_MID: + msgID: 0x0ab7 + PX4_EKF2_REPLAY_MID: + msgID: 0x0ab8 + PX4_ESC_REPORT_MID: + msgID: 0x0ab9 + PX4_ESC_STATUS_MID: + msgID: 0x0aba + PX4_ESTIMATOR_STATUS_MID: + msgID: 0x0abb + PX4_FENCE_MID: + msgID: 0x0abc + PX4_FENCE_VERTEX_MID: + msgID: 0x0abd + PX4_FILTERED_BOTTOM_FLOW_MID: + msgID: 0x0abe + PX4_FOLLOW_TARGET_MID: + msgID: 0x0abf + PX4_GEOFENCE_RESULT_MID: + msgID: 0x0ac0 + PX4_GPS_DUMP_MID: + msgID: 0x0ac1 + PX4_GPS_INJECT_DATA_MID: + msgID: 0x0ac2 + PX4_HIL_SENSOR_MID: + msgID: 0x0ac3 + PX4_HOME_POSITION_MID: + msgID: 0x0ac4 + PX4_INPUT_RC_MID: + msgID: 0x0ac5 + PX4_LED_CONTROL_MID: + msgID: 0x0ac6 + PX4_LOG_MESSAGE_MID: + msgID: 0x0ac7 + PX4_MANUAL_CONTROL_SETPOINT_MID: + msgID: 0x0ac8 + PX4_MAVLINK_LOG_MID: + msgID: 0x0ac9 + PX4_MC_ATT_CTRL_STATUS_MID: + msgID: 0x0aca + PX4_MC_VIRTUAL_ATTITUDE_SETPOINT_MID: + msgID: 0x0acb + PX4_MC_VIRTUAL_RATES_SETPOINT_MID: + msgID: 0x0acc + PX4_MISSION_MID: + msgID: 0x0acd + PX4_MISSION_RESULT_MID: + msgID: 0x0ace + PX4_MULTIROTOR_MOTOR_LIMITS_MID: + msgID: 0x0acf + PX4_OFFBOARD_CONTROL_MODE_MID: + msgID: 0x0ad0 + PX4_OPTICAL_FLOW_MID: + msgID: 0x0ad1 + PX4_OUTPUT_PWM_MID: + msgID: 0x0ad2 + PX4_PARAMETER_UPDATE_MID: + msgID: 0x0ad3 + PX4_POSITION_SETPOINT_MID: + msgID: 0x0ad4 + PX4_POSITION_SETPOINT_TRIPLET_MID: + msgID: 0x0ad5 + PX4_PWM_INPUT_MID: + msgID: 0x0ad6 + PX4_QSHELL_REQ_MID: + msgID: 0x0ad7 + PX4_RC_CHANNELS_MID: + msgID: 0x0ad8 + PX4_RC_PARAMETER_MAP_MID: + msgID: 0x0ad9 + PX4_SAFETY_MID: + msgID: 0x0ada + PX4_SATELLITE_INFO_MID: + msgID: 0x0adb + PX4_SENSOR_ACCEL_MID: + msgID: 0x0adc + PX4_SENSOR_BARO_MID: + msgID: 0x0add + PX4_SENSOR_COMBINED_MID: + msgID: 0x0ade + PX4_SENSOR_GYRO_MID: + msgID: 0x0adf + PX4_SENSOR_MAG_MID: + msgID: 0x0ae0 + PX4_SERVORAIL_STATUS_MID: + msgID: 0x0ae1 + PX4_SUBSYSTEM_INFO_MID: + msgID: 0x0ae2 + PX4_SYSTEM_POWER_MID: + msgID: 0x0ae3 + PX4_TECS_STATUS_MID: + msgID: 0x0ae4 + PX4_TELEMETRY_STATUS_MID: + msgID: 0x0ae5 + PX4_TEST_MOTOR_MID: + msgID: 0x0ae6 + PX4_TIME_OFFSET_MID: + msgID: 0x0ae7 + PX4_TRANSPONDER_REPORT_MID: + msgID: 0x0ae8 + PX4_UAVCAN_PARAMETER_REQUEST_MID: + msgID: 0x0ae9 + PX4_UAVCAN_PARAMETER_VALUE_MID: + msgID: 0x0aea + PX4_VEHICLE_ATTITUDE_MID: + msgID: 0x0aeb + PX4_VEHICLE_ATTITUDE_SETPOINT_MID: + msgID: 0x0aec + PX4_VEHICLE_COMMAND_ACK_MID: + msgID: 0x0aed + PX4_VEHICLE_COMMAND_MID: + msgID: 0x0aee + PX4_VEHICLE_CONTROL_MODE_MID: + msgID: 0x0aef + PX4_VEHICLE_FORCE_SETPOINT_MID: + msgID: 0x0af0 + PX4_VEHICLE_GLOBAL_POSITION_MID: + msgID: 0x0af1 + PX4_VEHICLE_GLOBAL_VELOCITY_SETPOINT_MID: + msgID: 0x0af2 + PX4_VEHICLE_GPS_POSITION_MID: + msgID: 0x0af3 + PX4_VEHICLE_LAND_DETECTED_MID: + msgID: 0x0af4 + PX4_VEHICLE_LOCAL_POSITION_MID: + msgID: 0x0af5 + PX4_VEHICLE_LOCAL_POSITION_SETPOINT_MID: + msgID: 0x0af6 + PX4_VEHICLE_RATES_SETPOINT_MID: + msgID: 0x0af7 + PX4_VEHICLE_STATUS_MID: + msgID: 0x0af8 + PX4_VISION_POSITION_ESTIMATE_MID: + msgID: 0x0af9 + PX4_VTOL_VEHICLE_STATUS_MID: + msgID: 0x0afa + PX4_WIND_ESTIMATE_MID: + msgID: 0x0afb + PX4_SENSOR_CORRECTION_MID: + msgID: 0x0afc + + ak8963: + definition: ${PROJECT_SOURCE_DIR}/apps/ak8963/wh_design.yaml + telemetry: + AK8963_DIAG_TLM_MID: + msgID: 0x0b13 + AK8963_HK_TLM_MID: + msgID: 0x0b14 + commands: + AK8963_CMD_MID: + msgID: 0x1b15 + AK8963_SEND_HK_MID: + msgID: 0x1b16 + AK8963_WAKEUP_MID: + msgID: 0x1b17 + + amc: + definition: ${PROJECT_SOURCE_DIR}/apps/amc/wh_design.yaml + telemetry: + AMC_HK_TLM_MID: + msgID: 0x0b18 + AMC_OUT_DATA_MID: + msgID: 0x0b19 + struct: AMC_BebopObservationMsg_t + commands: + AMC_CMD_MID: + msgID: 0x1b1a + AMC_SEND_HK_MID: + msgID: 0x1b1b + AMC_UPDATE_MOTORS_MID: + msgID: 0x1b1c + + bat: + definition: ${PROJECT_SOURCE_DIR}/apps/bat/wh_design.yaml + telemetry: + BAT_HK_TLM_MID: + msgID: 0x0b1f + commands: + BAT_CMD_MID: + msgID: 0x1b20 + BAT_SEND_HK_MID: + msgID: 0x1b21 + BAT_WAKEUP_MID: + msgID: 0x1b22 + + ea: + definition: ${PROJECT_SOURCE_DIR}/apps/ea/wh_design.yaml + telemetry: + EA_HK_TLM_MID: + msgID: 0x0b25 + commands: + EA_CMD_MID: + msgID: 0x1b26 + EA_SEND_HK_MID: + msgID: 0x1b27 + EA_WAKEUP_MID: + msgID: 0x1b28 + + gps: + definition: ${PROJECT_SOURCE_DIR}/apps/gps/wh_design.yaml + telemetry: + GPS_ACK_ACK_MID: + msgID: 0x0b2c + GPS_ACK_NAK_MID: + msgID: 0x0b2d + GPS_CFG_MSG_MID: + msgID: 0x0b2e + GPS_CFG_NAV5_MID: + msgID: 0x0b2f + GPS_CFG_PRT_MID: + msgID: 0x0b30 + GPS_CFG_RATE_MID: + msgID: 0x0b31 + GPS_CFG_SBAS_MID: + msgID: 0x0b32 + GPS_HK_TLM_MID: + msgID: 0x0b33 + GPS_MON_HW_MID: + msgID: 0x0b34 + GPS_NAV_DOP_MID: + msgID: 0x0b35 + GPS_NAV_NAVPVT_MID: + msgID: 0x0b36 + GPS_NAV_SVINFO_MID: + msgID: 0x0b37 + GPS_SEND_HK_MID: + msgID: 0x0b38 + GPS_HK_TLM_MID: + msgID: 0x0b39 + commands: + GPS_CMD_MID: + msgID: 0x1a3a + GPS_SEND_HK_MID: + msgID: 0x1a3b + GPS_READ_SENSOR_MID: + msgID: 0x1a3c + + hmc5883: + definition: ${PROJECT_SOURCE_DIR}/apps/hmc5883/wh_design.yaml + telemetry: + HMC5883_DIAG_TLM_MID: + msgID: 0x0b4a + HMC5883_HK_TLM_MID: + msgID: 0x0b4b + commands: + HMC5883_CMD_MID: + msgID: 0x1b4c + HMC5883_SEND_HK_MID: + msgID: 0x1b4d + HMC5883_WAKEUP_MID: + msgID: 0x1b4e + + ld: + definition: ${PROJECT_SOURCE_DIR}/apps/ld/wh_design.yaml + telemetry: + LD_DIAG_TLM_MID: + msgID: 0x0b4f + LD_HK_TLM_MID: + msgID: 0x0b50 + commands: + LD_CMD_MID: + msgID: 0x1b51 + LD_SEND_HK_MID: + msgID: 0x1b52 + LD_WAKEUP_MID: + msgID: 0x1b53 + + lgc: + definition: ${PROJECT_SOURCE_DIR}/apps/lgc/wh_design.yaml + telemetry: + LGC_HK_TLM_MID: + msgID: 0x0b56 + commands: + LGC_CMD_MID: + msgID: 0x1b57 + LGC_SEND_HK_MID: + msgID: 0x1b58 + LGC_WAKEUP_MID: + msgID: 0x1b59 + + mac: + definition: ${PROJECT_SOURCE_DIR}/apps/mac/wh_design.yaml + telemetry: + MAC_HK_TLM_MID: + msgID: 0x0b5c + commands: + MAC_CMD_MID: + msgID: 0x1b5d + MAC_RUN_CONTROLLER_MID: + msgID: 0x1b5e + MAC_SEND_HK_MID: + msgID: 0x1b5f + + mpc: + definition: ${PROJECT_SOURCE_DIR}/apps/mpc/wh_design.yaml + telemetry: + MPC_DIAG_TLM_MID: + msgID: 0x0b63 + MPC_HK_TLM_MID: + msgID: 0x0b64 + commands: + MPC_CMD_MID: + msgID: 0x1b65 + MPC_WAKEUP_MID: + msgID: 0x1b66 + MPC_SEND_HK_MID: + msgID: 0x1b67 + + mpu6050: + definition: ${PROJECT_SOURCE_DIR}/apps/mpu6050/wh_design.yaml + telemetry: + MPU6050_DIAG_TLM_MID: + msgID: 0x0b6a + MPU6050_HK_TLM_MID: + msgID: 0x0b6b + commands: + MPU6050_CMD_MID: + msgID: 0x1b6c + MPU6050_MEASURE_MID: + msgID: 0x1b6d + MPU6050_SEND_HK_MID: + msgID: 0x1b6e + + mpu9250: + definition: ${PROJECT_SOURCE_DIR}/apps/mpu9250/wh_design.yaml + telemetry: + MPU9250_DIAG_TLM_MID: + msgID: 0x0b71 + MPU9250_HK_TLM_MID: + msgID: 0x0b72 + commands: + MPU9250_CMD_MID: + msgID: 0x1b73 + MPU9250_MEASURE_MID: + msgID: 0x1b74 + MPU9250_SEND_HK_MID: + msgID: 0x1b75 + + ms5607: + definition: ${PROJECT_SOURCE_DIR}/apps/ms5607/wh_design.yaml + telemetry: + MS5607_DIAG_TLM_MID: + msgID: 0x0b78 + MS5607_HK_TLM_MID: + msgID: 0x0b79 + commands: + MS5607_CMD_MID: + msgID: 0x1b7a + MS5607_MEASURE_MID: + msgID: 0x1b7b + MS5607_SEND_HK_MID: + msgID: 0x1b7c + + ms5611: + definition: ${PROJECT_SOURCE_DIR}/apps/ms5611/wh_design.yaml + telemetry: + MS5611_DIAG_TLM_MID: + msgID: 0x0b7f + MS5611_HK_TLM_MID: + msgID: 0x0b80 + commands: + MS5611_CMD_MID: + msgID: 0x1b81 + MS5611_MEASURE_MID: + msgID: 0x1b82 + MS5611_SEND_HK_MID: + msgID: 0x1b83 + + nav: + definition: ${PROJECT_SOURCE_DIR}/apps/nav/wh_design.yaml + telemetry: + NAV_HK_TLM_MID: + msgID: 0x0b86 + commands: + NAV_CMD_MID: + msgID: 0x1b87 + NAV_SEND_HK_MID: + msgID: 0x1b88 + NAV_WAKEUP_MID: + msgID: 0x1b89 + +# prmlib: +# telemetry: +# PRMLIB_PARAM_UPDATED_MID: +# msgID: +# commands: +# PRM_CMD_MID: +# msgID: +# PRM_SEND_HK_MID: +# msgID: +# PRM_WAKEUP_MID: +# msgID: +# perfids: +# PARAMS_MAIN_TASK_PERF_ID: +# id: 90 +# definition: ${PROJECT_SOURCE_DIR}/apps/prmlib/wh_design.yaml + + pe: + definition: ${PROJECT_SOURCE_DIR}/apps/pe/wh_design.yaml + telemetry: + PE_HK_TLM_MID: + msgID: 0x0b8c + commands: + PE_CMD_MID: + msgID: 0x1b8d + PE_SEND_HK_MID: + msgID: 0x1b8e + PE_WAKEUP_MID: + msgID: 0x1b8f + + qae: + definition: ${PROJECT_SOURCE_DIR}/apps/qae/wh_design.yaml + telemetry: + QAE_HK_TLM_MID: + msgID: 0x0b9c + commands: + QAE_CMD_MID: + msgID: 0x1b9d + QAE_SEND_HK_MID: + msgID: 0x1b9e + QAE_WAKEUP_MID: + msgID: 0x1b9f + + rcin: + definition: ${PROJECT_SOURCE_DIR}/apps/rcin/wh_design.yaml + telemetry: + RCIN_HK_TLM_MID: + msgID: 0x0ba2 + commands: + RCIN_CMD_MID: + msgID: 0x1ba3 + RCIN_SEND_HK_MID: + msgID: 0x1ba4 + RCIN_WAKEUP_MID: + msgID: 0x1ba5 + + rgbled: + definition: ${PROJECT_SOURCE_DIR}/apps/rgbled/wh_design.yaml + telemetry: + RGBLED_HK_TLM_MID: + msgID: 0x0ba8 + commands: + RGBLED_CMD_MID: + msgID: 0x1ba9 + RGBLED_SEND_HK_MID: + msgID: 0x1baa + RGBLED_WAKEUP_MID: + msgID: 0x1bab + +# sbn: +# commands: +# SBN_WAKEUP_MID: +# msgID: +# definition: ${PROJECT_SOURCE_DIR}/apps/sbn/wh_design.yaml + + sens: + definition: ${PROJECT_SOURCE_DIR}/apps/sens/wh_design.yaml + telemetry: + SENS_HK_TLM_MID: + msgID: 0x0bb8 + commands: + SENS_CMD_MID: + msgID: 0x1bb9 + SENS_SEND_HK_MID: + msgID: 0x1bba + SENS_WAKEUP_MID: + msgID: 0x1bbb + + sim: + definition: ${PROJECT_SOURCE_DIR}/apps/sim/wh_design.yaml + telemetry: + SIM_HK_TLM_MID: + msgID: 0x0bbe + commands: + SIM_CMD_MID: + msgID: 0x1bbf + SIM_SEND_HK_MID: + msgID: 0x1bc0 + SIM_WAKEUP_MID: + msgID: 0x1bc1 + + sonar: + definition: ${PROJECT_SOURCE_DIR}/apps/sonar/wh_design.yaml + telemetry: + SONAR_OUT_DATA_MID: + msgID: 0x0bc4 + SONAR_HK_TLM_MID: + msgID: 0x0bc5 + commands: + SONAR_CMD_MID: + msgID: 0x1bc6 + SONAR_MEASURE_MID: + msgID: 0x1bc7 + SONAR_SEND_HK_MID: + msgID: 0x1bc8 + + ulr: + definition: ${PROJECT_SOURCE_DIR}/apps/ulr/wh_design.yaml + telemetry: + ULR_HK_TLM_MID: + msgID: 0x0bca + commands: + ULR_CMD_MID: + msgID: 0x1bcb + ULR_MEASURE_MID: + msgID: 0x1bcc + ULR_SEND_HK_MID: + msgID: 0x1bcd + + vc: + definition: ${PROJECT_SOURCE_DIR}/apps/vc/wh_design.yaml + telemetry: + VC_HK_TLM_MID: + msgID: 0x0bd0 + FLOW_FRAME_MID: + msgID: 0x0bd1 + commands: + VC_CMD_MID: + msgID: 0x1bd2 + VC_PROCESS_CMDS_MID: + msgID: 0x1bd3 + VC_SEND_HK_MID: + msgID: 0x1bd4 + + vm: + definition: ${PROJECT_SOURCE_DIR}/apps/vm/wh_design.yaml + telemetry: + VM_CONFIG_TLM_MID: + msgID: 0x0be0 + VM_HK_TLM_MID: + msgID: 0x0be1 + commands: + VM_CMD_MID: + msgID: 0x1be2 + VM_SEND_HK_MID: + msgID: 0x1be3 + VM_WAKEUP_MID: + msgID: 0x1be4 + + sbn: + definition: ${PROJECT_SOURCE_DIR}/apps/sbn/wh_design.yaml + telemetry: + SBN_TLM_MID: + msgID: 0x0bae + SBN_MODULE_HK_TLM_MID: + msgID: 0x0bb4 + commands: + SBN_CMD_MID: + msgID: 0x1baf + SBN_WAKEUP_MID: + msgID: 0x1bb0 diff --git a/config/obc/ppd/target/apps/cf/CMakeLists.txt b/config/obc/ppd/apps/cf/CMakeLists.txt similarity index 100% rename from config/obc/ppd/target/apps/cf/CMakeLists.txt rename to config/obc/ppd/apps/cf/CMakeLists.txt diff --git a/config/obc/ppd/target/apps/cf/tables/cf_cfgtable.c b/config/obc/ppd/apps/cf/tables/cf_cfgtable.c similarity index 100% rename from config/obc/ppd/target/apps/cf/tables/cf_cfgtable.c rename to config/obc/ppd/apps/cf/tables/cf_cfgtable.c diff --git a/config/obc/ppd/target/apps/ci/CMakeLists.txt b/config/obc/ppd/apps/ci/CMakeLists.txt similarity index 100% rename from config/obc/ppd/target/apps/ci/CMakeLists.txt rename to config/obc/ppd/apps/ci/CMakeLists.txt diff --git a/config/obc/ppd/target/apps/ci/ci_custom.c b/config/obc/ppd/apps/ci/ci_custom.c similarity index 100% rename from config/obc/ppd/target/apps/ci/ci_custom.c rename to config/obc/ppd/apps/ci/ci_custom.c diff --git a/config/obc/ppd/target/apps/ci/tables/ci_config.c b/config/obc/ppd/apps/ci/tables/ci_config.c similarity index 100% rename from config/obc/ppd/target/apps/ci/tables/ci_config.c rename to config/obc/ppd/apps/ci/tables/ci_config.c diff --git a/config/obc/ppd/target/apps/ci/unit_test/ci-custom.supp b/config/obc/ppd/apps/ci/unit_test/ci-custom.supp similarity index 100% rename from config/obc/ppd/target/apps/ci/unit_test/ci-custom.supp rename to config/obc/ppd/apps/ci/unit_test/ci-custom.supp diff --git a/config/obc/ppd/target/apps/ci/unit_test/ci_custom_test.c b/config/obc/ppd/apps/ci/unit_test/ci_custom_test.c similarity index 100% rename from config/obc/ppd/target/apps/ci/unit_test/ci_custom_test.c rename to config/obc/ppd/apps/ci/unit_test/ci_custom_test.c diff --git a/config/obc/ppd/target/apps/ci/unit_test/ci_custom_test.h b/config/obc/ppd/apps/ci/unit_test/ci_custom_test.h similarity index 100% rename from config/obc/ppd/target/apps/ci/unit_test/ci_custom_test.h rename to config/obc/ppd/apps/ci/unit_test/ci_custom_test.h diff --git a/config/obc/ppd/target/apps/ci/unit_test/ci_mock_os_calls.c b/config/obc/ppd/apps/ci/unit_test/ci_mock_os_calls.c similarity index 100% rename from config/obc/ppd/target/apps/ci/unit_test/ci_mock_os_calls.c rename to config/obc/ppd/apps/ci/unit_test/ci_mock_os_calls.c diff --git a/config/obc/ppd/target/apps/ci/unit_test/ci_mock_os_calls.h b/config/obc/ppd/apps/ci/unit_test/ci_mock_os_calls.h similarity index 100% rename from config/obc/ppd/target/apps/ci/unit_test/ci_mock_os_calls.h rename to config/obc/ppd/apps/ci/unit_test/ci_mock_os_calls.h diff --git a/config/obc/ppd/target/apps/ci/unit_test/ci_test_utils.c b/config/obc/ppd/apps/ci/unit_test/ci_test_utils.c similarity index 100% rename from config/obc/ppd/target/apps/ci/unit_test/ci_test_utils.c rename to config/obc/ppd/apps/ci/unit_test/ci_test_utils.c diff --git a/config/obc/ppd/target/apps/ci/unit_test/ci_test_utils.h b/config/obc/ppd/apps/ci/unit_test/ci_test_utils.h similarity index 100% rename from config/obc/ppd/target/apps/ci/unit_test/ci_test_utils.h rename to config/obc/ppd/apps/ci/unit_test/ci_test_utils.h diff --git a/config/obc/ppd/target/apps/ci/unit_test/ci_testrunner.c b/config/obc/ppd/apps/ci/unit_test/ci_testrunner.c similarity index 100% rename from config/obc/ppd/target/apps/ci/unit_test/ci_testrunner.c rename to config/obc/ppd/apps/ci/unit_test/ci_testrunner.c diff --git a/config/obc/ppd/target/apps/ds/CMakeLists.txt b/config/obc/ppd/apps/ds/CMakeLists.txt similarity index 100% rename from config/obc/ppd/target/apps/ds/CMakeLists.txt rename to config/obc/ppd/apps/ds/CMakeLists.txt diff --git a/config/obc/ppd/target/apps/ds/tables/ds_file_tbl.c b/config/obc/ppd/apps/ds/tables/ds_file_tbl.c similarity index 100% rename from config/obc/ppd/target/apps/ds/tables/ds_file_tbl.c rename to config/obc/ppd/apps/ds/tables/ds_file_tbl.c diff --git a/config/obc/ppd/target/apps/ds/tables/ds_filter_tbl.c b/config/obc/ppd/apps/ds/tables/ds_filter_tbl.c similarity index 100% rename from config/obc/ppd/target/apps/ds/tables/ds_filter_tbl.c rename to config/obc/ppd/apps/ds/tables/ds_filter_tbl.c diff --git a/config/obc/ppd/target/apps/ea/CMakeLists.txt b/config/obc/ppd/apps/ea/CMakeLists.txt similarity index 100% rename from config/obc/ppd/target/apps/ea/CMakeLists.txt rename to config/obc/ppd/apps/ea/CMakeLists.txt diff --git a/config/obc/ppd/target/apps/ea/ea-custom-ut.supp b/config/obc/ppd/apps/ea/ea-custom-ut.supp similarity index 100% rename from config/obc/ppd/target/apps/ea/ea-custom-ut.supp rename to config/obc/ppd/apps/ea/ea-custom-ut.supp diff --git a/config/obc/ppd/target/apps/ea/ea-perfmon-ut.supp b/config/obc/ppd/apps/ea/ea-perfmon-ut.supp similarity index 100% rename from config/obc/ppd/target/apps/ea/ea-perfmon-ut.supp rename to config/obc/ppd/apps/ea/ea-perfmon-ut.supp diff --git a/config/obc/ppd/target/apps/ea/src/ea_custom.c b/config/obc/ppd/apps/ea/src/ea_custom.c similarity index 100% rename from config/obc/ppd/target/apps/ea/src/ea_custom.c rename to config/obc/ppd/apps/ea/src/ea_custom.c diff --git a/config/obc/ppd/target/apps/ea/unit_test/ea-custom-ut.supp b/config/obc/ppd/apps/ea/unit_test/ea-custom-ut.supp similarity index 100% rename from config/obc/ppd/target/apps/ea/unit_test/ea-custom-ut.supp rename to config/obc/ppd/apps/ea/unit_test/ea-custom-ut.supp diff --git a/config/obc/ppd/target/apps/ea/unit_test/ea_custom_test.c b/config/obc/ppd/apps/ea/unit_test/ea_custom_test.c similarity index 100% rename from config/obc/ppd/target/apps/ea/unit_test/ea_custom_test.c rename to config/obc/ppd/apps/ea/unit_test/ea_custom_test.c diff --git a/config/obc/ppd/target/apps/ea/unit_test/ea_custom_test.h b/config/obc/ppd/apps/ea/unit_test/ea_custom_test.h similarity index 100% rename from config/obc/ppd/target/apps/ea/unit_test/ea_custom_test.h rename to config/obc/ppd/apps/ea/unit_test/ea_custom_test.h diff --git a/config/obc/ppd/target/apps/ea/unit_test/ea_mock_os_calls.c b/config/obc/ppd/apps/ea/unit_test/ea_mock_os_calls.c similarity index 100% rename from config/obc/ppd/target/apps/ea/unit_test/ea_mock_os_calls.c rename to config/obc/ppd/apps/ea/unit_test/ea_mock_os_calls.c diff --git a/config/obc/ppd/target/apps/ea/unit_test/ea_mock_os_calls.h b/config/obc/ppd/apps/ea/unit_test/ea_mock_os_calls.h similarity index 100% rename from config/obc/ppd/target/apps/ea/unit_test/ea_mock_os_calls.h rename to config/obc/ppd/apps/ea/unit_test/ea_mock_os_calls.h diff --git a/config/obc/ppd/target/apps/ea/unit_test/ea_perfmon_test.c b/config/obc/ppd/apps/ea/unit_test/ea_perfmon_test.c similarity index 100% rename from config/obc/ppd/target/apps/ea/unit_test/ea_perfmon_test.c rename to config/obc/ppd/apps/ea/unit_test/ea_perfmon_test.c diff --git a/config/obc/ppd/target/apps/ea/unit_test/ea_perfmon_test.h b/config/obc/ppd/apps/ea/unit_test/ea_perfmon_test.h similarity index 100% rename from config/obc/ppd/target/apps/ea/unit_test/ea_perfmon_test.h rename to config/obc/ppd/apps/ea/unit_test/ea_perfmon_test.h diff --git a/config/obc/ppd/target/apps/ea/unit_test/ea_perfmon_testrunner.c b/config/obc/ppd/apps/ea/unit_test/ea_perfmon_testrunner.c similarity index 100% rename from config/obc/ppd/target/apps/ea/unit_test/ea_perfmon_testrunner.c rename to config/obc/ppd/apps/ea/unit_test/ea_perfmon_testrunner.c diff --git a/config/obc/ppd/target/apps/ea/unit_test/ea_test_utils.c b/config/obc/ppd/apps/ea/unit_test/ea_test_utils.c similarity index 100% rename from config/obc/ppd/target/apps/ea/unit_test/ea_test_utils.c rename to config/obc/ppd/apps/ea/unit_test/ea_test_utils.c diff --git a/config/obc/ppd/target/apps/ea/unit_test/ea_test_utils.h b/config/obc/ppd/apps/ea/unit_test/ea_test_utils.h similarity index 100% rename from config/obc/ppd/target/apps/ea/unit_test/ea_test_utils.h rename to config/obc/ppd/apps/ea/unit_test/ea_test_utils.h diff --git a/config/obc/ppd/target/apps/ea/unit_test/ea_testrunner.c b/config/obc/ppd/apps/ea/unit_test/ea_testrunner.c similarity index 100% rename from config/obc/ppd/target/apps/ea/unit_test/ea_testrunner.c rename to config/obc/ppd/apps/ea/unit_test/ea_testrunner.c diff --git a/config/obc/ppd/target/apps/ea/unit_test/fib.py b/config/obc/ppd/apps/ea/unit_test/fib.py similarity index 100% rename from config/obc/ppd/target/apps/ea/unit_test/fib.py rename to config/obc/ppd/apps/ea/unit_test/fib.py diff --git a/config/obc/ppd/target/apps/ea/unit_test/noop.py b/config/obc/ppd/apps/ea/unit_test/noop.py similarity index 100% rename from config/obc/ppd/target/apps/ea/unit_test/noop.py rename to config/obc/ppd/apps/ea/unit_test/noop.py diff --git a/config/obc/ppd/target/apps/ea/unit_test/sleep.py b/config/obc/ppd/apps/ea/unit_test/sleep.py similarity index 100% rename from config/obc/ppd/target/apps/ea/unit_test/sleep.py rename to config/obc/ppd/apps/ea/unit_test/sleep.py diff --git a/config/obc/ppd/target/apps/pq_lib/CMakeLists.txt b/config/obc/ppd/apps/pq_lib/CMakeLists.txt similarity index 100% rename from config/obc/ppd/target/apps/pq_lib/CMakeLists.txt rename to config/obc/ppd/apps/pq_lib/CMakeLists.txt diff --git a/config/obc/cpd/target/apps/pq_lib/tables/pq_backup_cfg.c b/config/obc/ppd/apps/pq_lib/tables/pq_backup_cfg.c similarity index 89% rename from config/obc/cpd/target/apps/pq_lib/tables/pq_backup_cfg.c rename to config/obc/ppd/apps/pq_lib/tables/pq_backup_cfg.c index 0c6e3234e..5985cd4d7 100644 --- a/config/obc/cpd/target/apps/pq_lib/tables/pq_backup_cfg.c +++ b/config/obc/ppd/apps/pq_lib/tables/pq_backup_cfg.c @@ -14,7 +14,12 @@ #define PQ_PQUEUE_HIGH_OPS_RSRVD_IDX 1 #define PQ_PQUEUE_HIGH_IDX 2 #define PQ_PQUEUE_MEDIUM_IDX 3 -#define PQ_PQUEUE_LOW_IDX 4 +#define PQ_PQUEUE_DEFAULT_IDX 4 +#define PQ_PQUEUE_LOW_IDX 5 + +#define CPD_CPU_BASE (0x0200) +#define CFE_ES_CMD_MID_CPD (CPD_CPU_BASE + CFE_ES_CMD_MID) + /** ** \brief Default TO config table data @@ -29,6 +34,7 @@ PQ_ChannelTbl_t PQ_BackupConfigTbl = {SBN_SUB_MID, 64, PQ_PQUEUE_MEDIUM_IDX}, {SBN_UNSUB_MID, 64, PQ_PQUEUE_MEDIUM_IDX}, {SBN_ALLSUB_MID, 1, PQ_PQUEUE_HIGH_IDX}, + {CFE_ES_CMD_MID_CPD, 1, PQ_PQUEUE_HIGH_OPS_RSRVD_IDX}, {CFE_ES_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, {CFE_EVS_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, {CFE_SB_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, @@ -62,6 +68,8 @@ PQ_ChannelTbl_t PQ_BackupConfigTbl = {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO}, /* PQ_PQUEUE_MEDIUM_IDX */ {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO}, + /* PQ_PQUEUE_DEFAULT_IDX */ + {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO}, /* PQ_PQUEUE_LOW_IDX */ {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO} } diff --git a/config/obc/sitl/target/apps/pq_lib/tables/pq_cfg.c b/config/obc/ppd/apps/pq_lib/tables/pq_cfg.c similarity index 95% rename from config/obc/sitl/target/apps/pq_lib/tables/pq_cfg.c rename to config/obc/ppd/apps/pq_lib/tables/pq_cfg.c index f20daa3ea..3a8f349e2 100644 --- a/config/obc/sitl/target/apps/pq_lib/tables/pq_cfg.c +++ b/config/obc/ppd/apps/pq_lib/tables/pq_cfg.c @@ -33,7 +33,11 @@ static CFE_TBL_FileDef_t CFE_TBL_FileDef OS_USED = #define PQ_PQUEUE_HIGH_OPS_RSRVD_IDX 1 #define PQ_PQUEUE_HIGH_IDX 2 #define PQ_PQUEUE_MEDIUM_IDX 3 -#define PQ_PQUEUE_LOW_IDX 4 +#define PQ_PQUEUE_DEFAULT_IDX 4 +#define PQ_PQUEUE_LOW_IDX 5 + +#define CPD_CPU_BASE (0x0200) +#define CFE_ES_CMD_MID_CPD (CPD_CPU_BASE + CFE_ES_CMD_MID) /** ** \brief Default TO config table data @@ -47,7 +51,8 @@ PQ_ChannelTbl_t PQ_ConfigTbl = /* Ground Queues */ {SBN_SUB_MID, 64, PQ_PQUEUE_MEDIUM_IDX}, {SBN_UNSUB_MID, 64, PQ_PQUEUE_MEDIUM_IDX}, - {SBN_ALLSUB_MID, 1, PQ_PQUEUE_HIGH_IDX}, + {SBN_ALLSUB_MID, 1, PQ_PQUEUE_LOW_IDX}, + {CFE_ES_CMD_MID_CPD, 1, PQ_PQUEUE_HIGH_OPS_RSRVD_IDX}, {AMC_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, {MAC_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, {MPC_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, @@ -70,12 +75,11 @@ PQ_ChannelTbl_t PQ_ConfigTbl = {EA_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, {VC_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, {GPS_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {MAVLINK_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, {CFE_ES_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, {CFE_EVS_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, {CFE_SB_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, {CFE_TBL_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CFE_TIME_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, + {CFE_TIME_HK_TLM_MID, 1, PQ_PQUEUE_HIGH_IDX}, {CFE_TIME_DIAG_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, {CFE_EVS_EVENT_MSG_MID, 32, PQ_PQUEUE_LOW_IDX}, {CFE_SB_STATS_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, @@ -103,8 +107,6 @@ PQ_ChannelTbl_t PQ_ConfigTbl = {SCH_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, {SCH_DIAG_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, {QAE_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {FLOW_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {FLOW_DIAG_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, {MPC_DIAG_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, {LD_DIAG_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, {PRM_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, @@ -210,6 +212,8 @@ PQ_ChannelTbl_t PQ_ConfigTbl = {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO}, /* PQ_PQUEUE_MEDIUM_IDX */ {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO}, + /* PQ_PQUEUE_DEFAULT_IDX */ + {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO}, /* PQ_PQUEUE_LOW_IDX */ {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO} } diff --git a/config/obc/ppd/target/apps/prm/CMakeLists.txt b/config/obc/ppd/apps/prm/CMakeLists.txt similarity index 100% rename from config/obc/ppd/target/apps/prm/CMakeLists.txt rename to config/obc/ppd/apps/prm/CMakeLists.txt diff --git a/config/obc/ppd/target/apps/prm/tables/prm_config.c b/config/obc/ppd/apps/prm/tables/prm_config.c similarity index 100% rename from config/obc/ppd/target/apps/prm/tables/prm_config.c rename to config/obc/ppd/apps/prm/tables/prm_config.c diff --git a/config/obc/ppd/target/apps/sbn/CMakeLists.txt b/config/obc/ppd/apps/sbn/CMakeLists.txt similarity index 100% rename from config/obc/ppd/target/apps/sbn/CMakeLists.txt rename to config/obc/ppd/apps/sbn/CMakeLists.txt diff --git a/config/obc/ppd/target/apps/sbn/src/sbn_remap_tbl.c b/config/obc/ppd/apps/sbn/src/sbn_remap_tbl.c similarity index 100% rename from config/obc/ppd/target/apps/sbn/src/sbn_remap_tbl.c rename to config/obc/ppd/apps/sbn/src/sbn_remap_tbl.c diff --git a/config/obc/ppd/target/apps/sbn/tables/uio_mbox/SbnModuleData.dat b/config/obc/ppd/apps/sbn/tables/uio_mbox/SbnModuleData.dat similarity index 100% rename from config/obc/ppd/target/apps/sbn/tables/uio_mbox/SbnModuleData.dat rename to config/obc/ppd/apps/sbn/tables/uio_mbox/SbnModuleData.dat diff --git a/config/obc/ppd/target/apps/sbn/tables/uio_mbox/SbnPeerData.dat b/config/obc/ppd/apps/sbn/tables/uio_mbox/SbnPeerData.dat similarity index 100% rename from config/obc/ppd/target/apps/sbn/tables/uio_mbox/SbnPeerData.dat rename to config/obc/ppd/apps/sbn/tables/uio_mbox/SbnPeerData.dat diff --git a/config/obc/ppd/target/apps/sch/CMakeLists.txt b/config/obc/ppd/apps/sch/CMakeLists.txt similarity index 100% rename from config/obc/ppd/target/apps/sch/CMakeLists.txt rename to config/obc/ppd/apps/sch/CMakeLists.txt diff --git a/config/obc/ppd/target/apps/sch/sch_custom_rt.c b/config/obc/ppd/apps/sch/sch_custom_rt.c similarity index 100% rename from config/obc/ppd/target/apps/sch/sch_custom_rt.c rename to config/obc/ppd/apps/sch/sch_custom_rt.c diff --git a/config/obc/ppd/target/apps/sch/tables/sch_def_msgtbl.c b/config/obc/ppd/apps/sch/tables/sch_def_msgtbl.c similarity index 98% rename from config/obc/ppd/target/apps/sch/tables/sch_def_msgtbl.c rename to config/obc/ppd/apps/sch/tables/sch_def_msgtbl.c index cdfe776cb..8f35dabec 100644 --- a/config/obc/ppd/target/apps/sch/tables/sch_def_msgtbl.c +++ b/config/obc/ppd/apps/sch/tables/sch_def_msgtbl.c @@ -236,9 +236,11 @@ SCH_MessageEntry_t SCH_DefaultMessageTable[SCH_MAX_MESSAGES] = /* Command ID #97 */ { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, /* Command ID #98 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, + /* SBN Wakeup command code. */ + { { SCH_FIX_HEADER(SBN_CMD_MID, 0xC000, 0x0001), 0x6400 } }, /* Command ID #99 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, + /* SBN Send HK command code. */ + { { SCH_FIX_HEADER(SBN_CMD_MID, 0xC000, 0x0001), 0x0A00 } }, /* Command ID #100 */ { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, /* Command ID #101 */ diff --git a/config/obc/sitl/target/apps/sch/tables/sch_def_schtbl.c b/config/obc/ppd/apps/sch/tables/sch_def_schtbl.c similarity index 92% rename from config/obc/sitl/target/apps/sch/tables/sch_def_schtbl.c rename to config/obc/ppd/apps/sch/tables/sch_def_schtbl.c index ee85a6aa4..3deded9cd 100644 --- a/config/obc/sitl/target/apps/sch/tables/sch_def_schtbl.c +++ b/config/obc/ppd/apps/sch/tables/sch_def_schtbl.c @@ -57,8 +57,6 @@ extern "C" { #define CS_BACKGROUND_CYCLE_MIDX 39 #define SC_1HZ_WAKEUP_MIDX 40 #define SC_SEND_HK_MIDX 41 -#define FLOW_WAKEUP_MIDX 42 -#define FLOW_SEND_HK_MIDX 43 #define VC_SEND_HK_MIDX 45 #define VC_PROCESS_CMDS_MIDX 46 @@ -109,6 +107,9 @@ extern "C" { #define PRM_SEND_HK_MIDX 96 #define PRM_WAKEUP_MIDX 97 +#define SBN_WAKEUP_MIDX 98 +#define SBN_SEND_HK_MIDX 99 + #define QAE_SEND_HK_MIDX 102 #define QAE_WAKEUP_MIDX 103 #define LD_SEND_HK_MIDX 104 @@ -126,14 +127,12 @@ extern "C" { #define BAT_SEND_HK_MIDX 117 #define BAT_WAKEUP_MIDX 118 -#define MAVLINK_WAKEUP_MIDX 119 -#define MAVLINK_SEND_HK_MIDX 120 #define GPS_READ_SENSOR_MIDX 122 #define GPS_SEND_HK_MIDX 123 #define EA_WAKEUP_MIDX 125 -#define EA_PERFMON_MIDX 126 + #define EA_SEND_HK_MIDX 127 @@ -154,7 +153,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -166,7 +165,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -187,7 +186,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, FLOW_WAKEUP_MIDX, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -200,11 +199,11 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_SEND_HK_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -221,7 +220,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -235,7 +234,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_SEND_HK_MIDX, SCH_GROUP_NONE }, @@ -251,7 +250,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -268,7 +267,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -285,7 +284,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -302,7 +301,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -324,7 +323,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -336,7 +335,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -353,7 +352,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -370,7 +369,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -387,7 +386,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -405,7 +404,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -421,7 +420,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -438,7 +437,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -455,7 +454,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -472,7 +471,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -494,7 +493,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CFE_ES_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -506,7 +505,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -523,7 +522,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -540,7 +539,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -557,7 +556,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -575,7 +574,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CFE_EVS_SEND_HK_MIDX, SCH_GROUP_NONE }, @@ -591,7 +590,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -608,11 +607,11 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, FLOW_WAKEUP_MIDX, SCH_GROUP_NONE }, + { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -625,7 +624,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -642,7 +641,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -664,7 +663,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CFE_SB_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -676,7 +675,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -693,7 +692,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -710,7 +709,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -727,7 +726,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -745,10 +744,10 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CFE_TIME_SEND_HK_MIDX, SCH_GROUP_NONE }, + { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -761,7 +760,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -778,11 +777,11 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAVLINK_WAKEUP_MIDX, SCH_GROUP_NONE }, + { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -795,11 +794,11 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAVLINK_SEND_HK_MIDX, SCH_GROUP_NONE }, + { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -812,7 +811,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -835,7 +834,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CFE_TIME_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, /* slot #41*/ @@ -846,7 +845,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -863,7 +862,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -881,7 +880,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -898,7 +897,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -916,7 +915,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CFE_TBL_SEND_HK_MIDX, SCH_GROUP_NONE }, @@ -932,7 +931,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -949,7 +948,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -966,7 +965,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -983,7 +982,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1004,7 +1003,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -1017,7 +1016,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1034,11 +1033,11 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, FLOW_WAKEUP_MIDX, SCH_GROUP_NONE }, + { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -1051,11 +1050,11 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, FLOW_SEND_HK_MIDX, SCH_GROUP_NONE }, + { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -1068,7 +1067,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1086,7 +1085,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, GPS_READ_SENSOR_MIDX, SCH_GROUP_NONE }, @@ -1102,7 +1101,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1119,7 +1118,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1136,7 +1135,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1153,7 +1152,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1175,7 +1174,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CF_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -1187,7 +1186,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1204,7 +1203,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1221,7 +1220,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1238,7 +1237,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1256,7 +1255,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -1272,7 +1271,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1289,7 +1288,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1306,7 +1305,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1323,7 +1322,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1345,7 +1344,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CI_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -1357,7 +1356,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1374,7 +1373,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1391,7 +1390,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1408,7 +1407,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1426,7 +1425,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CS_SEND_HK_MIDX, SCH_GROUP_NONE }, @@ -1442,7 +1441,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1459,11 +1458,11 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, FLOW_WAKEUP_MIDX, SCH_GROUP_NONE }, + { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -1476,7 +1475,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1493,7 +1492,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1515,7 +1514,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, DS_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -1527,7 +1526,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1544,7 +1543,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1561,7 +1560,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1578,7 +1577,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1596,7 +1595,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, EA_SEND_HK_MIDX, SCH_GROUP_NONE }, @@ -1612,7 +1611,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1629,7 +1628,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1646,7 +1645,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1663,7 +1662,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1685,7 +1684,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, EA_PERFMON_MIDX, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -1697,7 +1696,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1714,7 +1713,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1731,7 +1730,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1748,7 +1747,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1766,7 +1765,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, @@ -1782,7 +1781,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1799,7 +1798,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1816,7 +1815,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1833,7 +1832,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1855,7 +1854,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, EA_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -1867,7 +1866,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1884,11 +1883,11 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, FLOW_WAKEUP_MIDX, SCH_GROUP_NONE }, + { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -1901,7 +1900,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1918,7 +1917,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1936,7 +1935,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, GPS_READ_SENSOR_MIDX, SCH_GROUP_NONE }, @@ -1952,7 +1951,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1969,7 +1968,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -1986,7 +1985,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2003,7 +2002,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2025,7 +2024,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, GPS_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -2037,7 +2036,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2054,7 +2053,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2071,7 +2070,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2088,7 +2087,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2106,7 +2105,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -2122,7 +2121,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2139,7 +2138,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2156,7 +2155,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2173,7 +2172,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2195,7 +2194,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -2207,7 +2206,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2224,7 +2223,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2241,7 +2240,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2258,7 +2257,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2276,7 +2275,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HS_SEND_HK_MIDX, SCH_GROUP_NONE }, @@ -2292,7 +2291,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2309,11 +2308,11 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, FLOW_WAKEUP_MIDX, SCH_GROUP_NONE }, + { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -2326,7 +2325,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2343,7 +2342,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2365,7 +2364,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -2377,7 +2376,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2394,7 +2393,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2411,7 +2410,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2428,7 +2427,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2446,7 +2445,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, FM_SEND_HK_MIDX, SCH_GROUP_NONE }, @@ -2462,7 +2461,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2479,7 +2478,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2496,7 +2495,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2513,7 +2512,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2536,7 +2535,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LC_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, /* slot #141*/ @@ -2547,7 +2546,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2564,7 +2563,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2581,7 +2580,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2598,7 +2597,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, @@ -2616,7 +2615,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_SEND_HK_MIDX, SCH_GROUP_NONE }, @@ -2632,7 +2631,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2649,7 +2648,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2666,7 +2665,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2683,7 +2682,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2705,7 +2704,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MD_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -2717,7 +2716,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2734,11 +2733,11 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, FLOW_WAKEUP_MIDX, SCH_GROUP_NONE }, + { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -2751,7 +2750,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2768,7 +2767,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2786,7 +2785,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MD_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -2802,7 +2801,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2819,7 +2818,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2836,7 +2835,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2853,7 +2852,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2875,7 +2874,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MM_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -2887,7 +2886,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2904,7 +2903,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2921,7 +2920,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2938,7 +2937,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2956,7 +2955,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -2972,7 +2971,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -2989,7 +2988,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3006,7 +3005,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3023,7 +3022,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3045,7 +3044,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -3057,7 +3056,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3074,7 +3073,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3091,7 +3090,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3108,7 +3107,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3126,7 +3125,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_SEND_HK_MIDX, SCH_GROUP_NONE }, @@ -3142,7 +3141,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3159,11 +3158,11 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, FLOW_WAKEUP_MIDX, SCH_GROUP_NONE }, + { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -3176,7 +3175,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3194,7 +3193,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LGC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, @@ -3215,7 +3214,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -3227,7 +3226,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3244,7 +3243,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3261,7 +3260,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3278,7 +3277,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3296,7 +3295,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -3312,7 +3311,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3329,7 +3328,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3346,7 +3345,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3364,7 +3363,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LC_SAMPLE_AP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, @@ -3386,7 +3385,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, /* slot #191*/ @@ -3397,7 +3396,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3414,7 +3413,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3431,7 +3430,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3448,7 +3447,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3466,7 +3465,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, @@ -3482,7 +3481,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3499,7 +3498,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3516,7 +3515,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3533,7 +3532,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3554,7 +3553,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -3567,7 +3566,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3584,11 +3583,11 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, FLOW_WAKEUP_MIDX, SCH_GROUP_NONE }, + { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -3601,7 +3600,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3618,7 +3617,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3636,7 +3635,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, GPS_READ_SENSOR_MIDX, SCH_GROUP_NONE }, @@ -3652,7 +3651,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3669,7 +3668,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3686,7 +3685,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3703,7 +3702,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3724,7 +3723,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -3737,7 +3736,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3754,7 +3753,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3771,7 +3770,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3788,7 +3787,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3806,7 +3805,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -3822,7 +3821,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3839,7 +3838,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3856,7 +3855,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3873,7 +3872,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3895,7 +3894,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RGBLED_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -3907,7 +3906,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3924,7 +3923,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3941,7 +3940,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3958,7 +3957,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -3976,7 +3975,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SC_1HZ_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -3992,7 +3991,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4010,10 +4009,10 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LGC_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, FLOW_WAKEUP_MIDX, SCH_GROUP_NONE }, + { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -4026,7 +4025,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4043,7 +4042,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4065,7 +4064,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SC_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, @@ -4077,7 +4076,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4094,7 +4093,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4111,7 +4110,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4128,7 +4127,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4146,7 +4145,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SCH_SEND_HK_MIDX, SCH_GROUP_NONE }, @@ -4162,7 +4161,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4179,7 +4178,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4196,7 +4195,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4213,7 +4212,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4236,7 +4235,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, TO_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, /* slot #241*/ @@ -4247,7 +4246,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4264,7 +4263,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4281,7 +4280,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4298,7 +4297,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4316,7 +4315,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_SEND_HK_MIDX, SCH_GROUP_NONE }, @@ -4332,7 +4331,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4349,7 +4348,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4366,7 +4365,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, @@ -4383,7 +4382,7 @@ SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, + { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SBN_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, diff --git a/config/obc/ppd/target/apps/sch/unit_test/sch_custom_test.c b/config/obc/ppd/apps/sch/unit_test/sch_custom_test.c similarity index 100% rename from config/obc/ppd/target/apps/sch/unit_test/sch_custom_test.c rename to config/obc/ppd/apps/sch/unit_test/sch_custom_test.c diff --git a/config/obc/ppd/target/apps/sch/unit_test/sch_custom_test.h b/config/obc/ppd/apps/sch/unit_test/sch_custom_test.h similarity index 100% rename from config/obc/ppd/target/apps/sch/unit_test/sch_custom_test.h rename to config/obc/ppd/apps/sch/unit_test/sch_custom_test.h diff --git a/config/obc/ppd/target/apps/sch/unit_test/sch_test_utils.c b/config/obc/ppd/apps/sch/unit_test/sch_test_utils.c similarity index 100% rename from config/obc/ppd/target/apps/sch/unit_test/sch_test_utils.c rename to config/obc/ppd/apps/sch/unit_test/sch_test_utils.c diff --git a/config/obc/ppd/target/apps/sch/unit_test/sch_test_utils.h b/config/obc/ppd/apps/sch/unit_test/sch_test_utils.h similarity index 100% rename from config/obc/ppd/target/apps/sch/unit_test/sch_test_utils.h rename to config/obc/ppd/apps/sch/unit_test/sch_test_utils.h diff --git a/config/obc/ppd/target/apps/sch/unit_test/sch_testrunner.c b/config/obc/ppd/apps/sch/unit_test/sch_testrunner.c similarity index 100% rename from config/obc/ppd/target/apps/sch/unit_test/sch_testrunner.c rename to config/obc/ppd/apps/sch/unit_test/sch_testrunner.c diff --git a/config/obc/ppd/target/apps/to/CMakeLists.txt b/config/obc/ppd/apps/to/CMakeLists.txt similarity index 100% rename from config/obc/ppd/target/apps/to/CMakeLists.txt rename to config/obc/ppd/apps/to/CMakeLists.txt diff --git a/config/obc/sitl/target/apps/to/tables/to_backup_cfg.c b/config/obc/ppd/apps/to/tables/to_backup_cfg.c similarity index 98% rename from config/obc/sitl/target/apps/to/tables/to_backup_cfg.c rename to config/obc/ppd/apps/to/tables/to_backup_cfg.c index dd007ca32..ee5c34438 100644 --- a/config/obc/sitl/target/apps/to/tables/to_backup_cfg.c +++ b/config/obc/ppd/apps/to/tables/to_backup_cfg.c @@ -29,6 +29,7 @@ TO_ChannelTbl_t TO_BackupConfigTbl = {TO_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, {TO_DATA_TYPE_MID, 1, TO_PQUEUE_HIGH_IDX}, {TO_DIAG_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, + {SBN_MODULE_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, {CFE_ES_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, {CFE_EVS_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, {CFE_SB_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, diff --git a/config/obc/ppd/target/apps/to/tables/to_udp_cfg.c b/config/obc/ppd/apps/to/tables/to_udp_cfg.c similarity index 97% rename from config/obc/ppd/target/apps/to/tables/to_udp_cfg.c rename to config/obc/ppd/apps/to/tables/to_udp_cfg.c index 75487c778..0d6b7bbb7 100644 --- a/config/obc/ppd/target/apps/to/tables/to_udp_cfg.c +++ b/config/obc/ppd/apps/to/tables/to_udp_cfg.c @@ -49,6 +49,9 @@ static CFE_TBL_FileDef_t CFE_TBL_FileDef OS_USED = #define CFE_TBL_REG_TLM_MID_CPD (CPD_CPU_BASE + CFE_TBL_REG_TLM_MID) #define CFE_ES_SHELL_TLM_MID_CPD (CPD_CPU_BASE + CFE_ES_SHELL_TLM_MID) #define CFE_ES_MEMSTATS_TLM_MID_CPD (CPD_CPU_BASE + CFE_ES_MEMSTATS_TLM_MID) +#define PX4_SENSOR_ACCEL_MID_CPD (CPD_CPU_BASE + PX4_SENSOR_ACCEL_MID) +#define PX4_SENSOR_GYRO_MID_CPD (CPD_CPU_BASE + PX4_SENSOR_GYRO_MID) + /** ** \brief Default TO config table data @@ -86,6 +89,7 @@ TO_ChannelTbl_t TO_ConfigTbl = {TO_DIAG_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, {TO_DIAG_MSG_FLOW_MID, 1, TO_PQUEUE_HIGH_IDX}, {GPS_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, + {SBN_MODULE_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, {CFE_ES_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, {CFE_EVS_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, {CFE_SB_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, @@ -99,7 +103,7 @@ TO_ChannelTbl_t TO_ConfigTbl = {CFE_SB_ONESUB_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, {CFE_ES_SHELL_TLM_MID, 32, TO_PQUEUE_MEDIUM_IDX}, {CFE_ES_MEMSTATS_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - /* CPD CFE Mids */ + /* CPD Mids */ {CFE_ES_HK_TLM_MID_CPD, 1, TO_PQUEUE_MEDIUM_IDX}, {CFE_EVS_HK_TLM_MID_CPD, 1, TO_PQUEUE_MEDIUM_IDX}, {CFE_SB_HK_TLM_MID_CPD, 1, TO_PQUEUE_MEDIUM_IDX}, @@ -112,6 +116,9 @@ TO_ChannelTbl_t TO_ConfigTbl = {CFE_TBL_REG_TLM_MID_CPD, 1, TO_PQUEUE_MEDIUM_IDX}, {CFE_ES_SHELL_TLM_MID_CPD, 32, TO_PQUEUE_MEDIUM_IDX}, {CFE_ES_MEMSTATS_TLM_MID_CPD, 1, TO_PQUEUE_MEDIUM_IDX}, + {PX4_SENSOR_ACCEL_MID_CPD, 1, TO_PQUEUE_LOW_IDX}, + {PX4_SENSOR_GYRO_MID_CPD, 1, TO_PQUEUE_LOW_IDX}, + /* End CPD Mids */ {CF_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, {CF_TRANS_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, {CF_CONFIG_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, diff --git a/config/obc/ppd/target/apps/to/to_custom.c b/config/obc/ppd/apps/to/to_custom.c similarity index 100% rename from config/obc/ppd/target/apps/to/to_custom.c rename to config/obc/ppd/apps/to/to_custom.c diff --git a/config/obc/ppd/target/apps/to/to_custom_udp.h b/config/obc/ppd/apps/to/to_custom_udp.h similarity index 100% rename from config/obc/ppd/target/apps/to/to_custom_udp.h rename to config/obc/ppd/apps/to/to_custom_udp.h diff --git a/config/obc/ppd/target/apps/to/unit_test/to_app_custom_test.c b/config/obc/ppd/apps/to/unit_test/to_app_custom_test.c similarity index 100% rename from config/obc/ppd/target/apps/to/unit_test/to_app_custom_test.c rename to config/obc/ppd/apps/to/unit_test/to_app_custom_test.c diff --git a/config/obc/ppd/target/apps/to/unit_test/to_app_custom_test.h b/config/obc/ppd/apps/to/unit_test/to_app_custom_test.h similarity index 100% rename from config/obc/ppd/target/apps/to/unit_test/to_app_custom_test.h rename to config/obc/ppd/apps/to/unit_test/to_app_custom_test.h diff --git a/config/obc/ppd/target/apps/to/unit_test/to_app_stubs.c b/config/obc/ppd/apps/to/unit_test/to_app_stubs.c similarity index 100% rename from config/obc/ppd/target/apps/to/unit_test/to_app_stubs.c rename to config/obc/ppd/apps/to/unit_test/to_app_stubs.c diff --git a/config/obc/ppd/target/apps/to/unit_test/to_app_stubs.h b/config/obc/ppd/apps/to/unit_test/to_app_stubs.h similarity index 100% rename from config/obc/ppd/target/apps/to/unit_test/to_app_stubs.h rename to config/obc/ppd/apps/to/unit_test/to_app_stubs.h diff --git a/config/obc/ppd/target/apps/to/unit_test/to_custom_test_utils.c b/config/obc/ppd/apps/to/unit_test/to_custom_test_utils.c similarity index 100% rename from config/obc/ppd/target/apps/to/unit_test/to_custom_test_utils.c rename to config/obc/ppd/apps/to/unit_test/to_custom_test_utils.c diff --git a/config/obc/ppd/target/apps/to/unit_test/to_custom_test_utils.h b/config/obc/ppd/apps/to/unit_test/to_custom_test_utils.h similarity index 100% rename from config/obc/ppd/target/apps/to/unit_test/to_custom_test_utils.h rename to config/obc/ppd/apps/to/unit_test/to_custom_test_utils.h diff --git a/config/obc/ppd/target/apps/to/unit_test/to_custom_testrunner.c b/config/obc/ppd/apps/to/unit_test/to_custom_testrunner.c similarity index 100% rename from config/obc/ppd/target/apps/to/unit_test/to_custom_testrunner.c rename to config/obc/ppd/apps/to/unit_test/to_custom_testrunner.c diff --git a/config/obc/ppd/target/apps/to/unit_test/to_platform_stubs.c b/config/obc/ppd/apps/to/unit_test/to_platform_stubs.c similarity index 100% rename from config/obc/ppd/target/apps/to/unit_test/to_platform_stubs.c rename to config/obc/ppd/apps/to/unit_test/to_platform_stubs.c diff --git a/config/obc/ppd/target/apps/to/unit_test/to_platform_stubs.h b/config/obc/ppd/apps/to/unit_test/to_platform_stubs.h similarity index 100% rename from config/obc/ppd/target/apps/to/unit_test/to_platform_stubs.h rename to config/obc/ppd/apps/to/unit_test/to_platform_stubs.h diff --git a/config/obc/ppd/target/apps/to/user_doxy.in b/config/obc/ppd/apps/to/user_doxy.in similarity index 100% rename from config/obc/ppd/target/apps/to/user_doxy.in rename to config/obc/ppd/apps/to/user_doxy.in diff --git a/config/obc/ppd/inc/sbn_platform_cfg.h b/config/obc/ppd/inc/sbn_platform_cfg.h new file mode 100644 index 000000000..79cdcf614 --- /dev/null +++ b/config/obc/ppd/inc/sbn_platform_cfg.h @@ -0,0 +1,145 @@ +/****************************************************************************** +** File: sbn_platform_cfg.h +** +** Copyright (c) 2004-2016, United States government as represented by the +** administrator of the National Aeronautics Space Administration. +** All rights reserved. This software(cFE) was created at NASA's Goddard +** Space Flight Center pursuant to government contracts. +** +** This software may be used only pursuant to a United States government +** sponsored project and the United States government may not be charged +** for use thereof. +** +** Purpose: +** This header file contains prototypes for private functions and type +** definitions for the Software Bus Network Application. +** +** Authors: J. Wilmot/GSFC Code582 +** R. McGraw/SSI +** C. Knight/ARC Code TI +******************************************************************************/ +#include "cfe.h" + +#ifndef _sbn_platform_cfg_h +#define _sbn_platform_cfg_h + +/** @brief Maximum number of networks allowed. */ +#define SBN_MAX_NETS 16 + +/** @brief Maximum number of peers per network allowed. */ +#define SBN_MAX_PEERS_PER_NET 32 + +/** @brief Maximum number of subscriptions allowed per peer allowed. */ +#define SBN_MAX_SUBS_PER_PEER 256 + +/** @brief Maximum length of the name field in the `SbnPeerData.dat` file. */ +#define SBN_MAX_PEER_NAME_LEN 32 + +/** @brief Maximum length of the network field in the `SbnPeerData.dat` file. */ +#define SBN_MAX_NET_NAME_LEN 16 + +/** + * @brief At most process this many SB messages per peer per wakeup. + * (To prevent starvation if a peer is babbling.) + */ +#define SBN_MAX_MSG_PER_WAKEUP 32 + +/** + * @brief In the polling configuration, how long (in milliseconds) to wait for + * a SCH wakeup message before SBN times out and processes. (Note, should + * really be significantly longer than the expected time between SCH wakeup + * messages.) + */ +#define SBN_MAIN_LOOP_DELAY 200 + +/** + * @brief If I haven't sent a message to a peer in this amount of time (in + * seconds), call the poll function of the API in case it needs to perform + * some connection maintenance. + */ +#define SBN_POLL_TIME 5 + +/** + * @brief For each peer, a pipe is created to receive messages that the peer has + * subscribed to. The pipe should be deep enough to handle all messages that + * will queue between wakeups. + */ +#define SBN_PEER_PIPE_DEPTH 64 + +/** + * @brief The maximum number of messages that will be queued for a particular + * message ID for a particular peer. + */ +#define SBN_DEFAULT_MSG_LIM 8 + +/** + * @brief The maximum number of subscription messages that will be queued + * between wakeups. + */ +#define SBN_SUB_PIPE_DEPTH 256 + +/** + * @brief The maximum number of subscription messages for a single message ID + * that will be queued between wakeups. (These are received when updates occur + * after SBN starts up.) + */ +#define SBN_MAX_ONESUB_PKTS_ON_PIPE 256 + +/** + * @brief The maximum number of subscription messages for all message IDs that + * will be queued between wakeups. (These are received on SBN startup.) + */ +#define SBN_MAX_ALLSUBS_PKTS_ON_PIPE 64 + +/** @brief The volatile memory location for the peer data file. */ +#define SBN_VOL_PEER_FILENAME "/ram/SbnPeerData.dat" + +/** @brief The non-volatile memory location for the peer data file. */ +#define SBN_NONVOL_PEER_FILENAME "/cf/apps/SbnPeerData.dat" + +/** + * @brief The maximum length of a line of configuration data in the peer data + * file. + */ +#define SBN_PEER_FILE_LINE_SZ 128 + +/** @brief The volatile memory location for the module data file. */ +#define SBN_VOL_MODULE_FILENAME "/ram/SbnModuleData.dat" + +/** @brief The non-volatile memory location for the module data file. */ +#define SBN_NONVOL_MODULE_FILENAME "/cf/apps/SbnModuleData.dat" + +/** + * @brief The maximum length of a line of configuration data in the peer data + * file. + */ +#define SBN_MODULE_FILE_LINE_SZ 128 + +/** @brief Maximum number of protocol modules. */ +#define SBN_MAX_INTERFACE_TYPES 8 + +/** + * @brief SBN modules can provide status messages for housekeeping requests, + * this is the maximum length those messages can be. + */ +#define SBN_MOD_STATUS_MSG_SZ 128 + +/** + * @brief Define this to use one task per peer pipe to send messages (each + * task blocks on read). Otherwise, pipes will be polled periodically. + */ +#undef SBN_SEND_TASK + +/** + * @brief Define this to use one task per peer to receive messages (each + * task blocks on read). Otherwise, another method (e.g. select) must be used + * to prevent blocking. + */ +#undef SBN_RECV_TASK + +/** + * @brief If defined, remapping is enabled at boot time. + */ +#define SBN_REMAP_ENABLED + +#endif /* _sbn_platform_cfg_h_ */ diff --git a/config/obc/ppd/inc/to_platform_cfg.h b/config/obc/ppd/inc/to_platform_cfg.h new file mode 100644 index 000000000..f102cd108 --- /dev/null +++ b/config/obc/ppd/inc/to_platform_cfg.h @@ -0,0 +1,281 @@ +#ifndef TO_PLATFORM_CFG_H +#define TO_PLATFORM_CFG_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "cfe_platform_cfg.h" + +/* +** Platform Configuration Parameter Definitions +*/ + + +/** \tocfg Child task flags +** +** \par Description: +** These are optional flags passed to the #CFE_ES_CreateChildTask +** function when creating the CFE child task. +** +*/ +#define TO_CUSTOM_CHILD_TASK_FLAGS (OS_ENABLE_CORE_0) + + +/** \tocfg Child task stack size +** +** \par Description: +** Child task stack size passed to the #CFE_ES_CreateChildTask +** function when creating the CFE child task. Stack size is in +** bytes. +** +*/ +#define TO_CUSTOM_TASK_STACK_SIZE (131072) + + +/** \tocfg Default telemetry destination IP address +** +** \par Description: +** Default IP address to send the telemetry stream to. This is default +** only and can be changed by command at runtime. +** +*/ +#define TO_UDP_CHANNEL_ADDRESS "192.168.2.20" + + +/** \tocfg Default telemetry destination UDP port +** +** \par Description: +** Default UDP port to send the telemetry stream to. This is default +** only and can be changed by command at runtime. +** +*/ +#define TO_UDP_CHANNEL_PORT (5011) + + +/** \tocfg Message Flow packet limit +** +** \par Description: +** This is the maximum number of message flow entries that can fit in +** a message flow diagnostic message. +** +*/ +#define TO_MSG_FLOW_PKT_LIMIT (200) + + +/** \tocfg Maximum message length +** +** \par Description: +** The maximum size that an output telemetry message can be. This is in +** bytes. If a message exceeds this size, it will be dropped by the +** classifier. +** +*/ +#define TO_MAX_MSG_LENGTH (32767) + +/** \tocfg The UDP channel's CF throttling semaphore name +** +** \par Limits: +** Two channels in CF must not have the same semaphore name. This must be unique +** compared to other channels' throttling semaphores. +*/ +#define TO_UDP_CF_THROTTLE_SEM_NAME "TO_CF_CH0_SEM" + + +/** \tocfg The UDP channel Name +*/ +#define TO_UDP_CHANNEL_NAME "UDP" + + + +/** \tocfg The UDP channel's default and maximum value for the CF + * throttling semaphore +** +** \par Limits: +** Must not be larger than the TO_DATA_PIPE_DEPTH +*/ +#define TO_UDP_CF_MAX_PDUS (4) + + +/** \tocfg Mission specific version number for TO application +** +** \par Description: +** An application version number consists of four parts: +** major version number, minor version number, revision +** number and mission specific revision number. The mission +** specific revision number is defined here and the other +** parts are defined in "to_version.h". +** +** \par Limits: +** Must be defined as a numeric value that is greater than +** or equal to zero. +*/ +#define TO_MISSION_REV (1) + +/** \tocfg Pipe depth for the Scheduler pipe +** +** \par Limits: +** minimum of 1, max of CFE_SB_MAX_PIPE_DEPTH. +*/ +#define TO_SCH_PIPE_DEPTH (2) + +/** \tocfg Pipe name for the Scheduler pipe +** +** \par Limits: +** Note, this name must fit in OS_MAX_API_NAME. +*/ +#define TO_SCH_PIPE_NAME ("TO_SCH_PIPE") + +/** \tocfg The SB pend behavior type for the Scheduler pipe. +** +** \par Limits: +** One of: CFE_SB_POLL, CFE_SB_PEND_FOREVER, or the +** number of milliseconds to wait for a new message (recommended). +** Note, using CFE_SB_PEND_FOREVER may cause an unresponsive +** application if no messages arrive on this pipe. +*/ +#define TO_SCH_PIPE_PEND_TIME (2000) + +/** \tocfg The number of WAKEUP messages to reserve on the Scheduler pipe. +** +** \par Limits: +** minimum of 1, max limited to CFE_SB_MAX_PIPE_DEPTH-1. Note the +** TO_SCH_PIPE_WAKEUP_RESERVED and TO_SCH_PIPE_SEND_HK_RESERVED +** must be less than TO_SCH_PIPE_DEPTH. +*/ +#define TO_SCH_PIPE_WAKEUP_RESERVED (1) + +/** \tocfg The number of SEND_HK messages to reserve on the Scheduler pipe. +** +** \par Limits: +** minimum of 1, max of CFE_SB_MAX_PIPE_DEPTH. Note the +** TO_SCH_PIPE_WAKEUP_RESERVED and TO_SCH_PIPE_SEND_HK_RESERVED +** must be less than TO_SCH_PIPE_DEPTH. +*/ +#define TO_SCH_PIPE_SEND_HK_RESERVED (1) + +/** \tocfg Pipe depth for the command pipe +** +** \par Limits: +** minimum of 1, max of CFE_SB_MAX_PIPE_DEPTH. +*/ +#define TO_CMD_PIPE_DEPTH (4) + +/** \tocfg Pipe name for the Scheduler pipe +** +** \par Limits: +** Note, this name must fit in OS_MAX_API_NAME. +*/ +#define TO_CMD_PIPE_NAME ("TO_CMD_PIPE") + +/** \tocfg Pipe depth for the data pipe +** +** \par Limits: +** minimum of 1, max of CFE_SB_MAX_PIPE_DEPTH. +*/ +#define TO_DATA_PIPE_DEPTH (CFE_SB_MAX_PIPE_DEPTH) + +/** \tocfg The config table default filename +** +** \par Limits: +** The length of each string, including the NULL terminator cannot exceed +** the #OS_MAX_PATH_LEN value. +*/ +#define TO_UDP_CONFIG_TABLE_FILENAME ("/cf/apps/to_udp_cfg.tbl") + + +#define TO_MAX_MEMPOOL_BLK_SIZES (8) + +/** +** \cfeescfg Define TO Memory Pool Block Sizes +** +** \par Description: +** TO Memory Pool Block Sizes +** +** \par Limits +** These sizes MUST be increasing and MUST be an integral multiple of 4. +** The number of block sizes defined cannot exceed +** #CFE_ES_MAX_MEMPOOL_BLOCK_SIZES +*/ +#define TO_MEM_BLOCK_SIZE_01 32 +#define TO_MEM_BLOCK_SIZE_02 64 +#define TO_MEM_BLOCK_SIZE_03 128 +#define TO_MEM_BLOCK_SIZE_04 256 +#define TO_MEM_BLOCK_SIZE_05 512 +#define TO_MEM_BLOCK_SIZE_06 2048 +#define TO_MEM_BLOCK_SIZE_07 8192 +#define TO_MAX_BLOCK_SIZE (TO_MEM_BLOCK_SIZE_07 + TO_MEM_BLOCK_SIZE_07) + +/** + * \tocfg Defines the table identification name used for table registration + * of the configuration table. + */ +#define TO_UDP_CONFIG_TABLENAME "UDP_CFG" + +/** + * \tocfg Defines the table identification name used for table registration + * of the dump table. + */ +#define TO_UDP_DUMP_TABLENAME "UDP_DMP" + +/** \tocfg The timeout value, in milliseconds, to wait for ES application startup sync. +** +** \par Limits: +** This parameter must be at least 1000 (ms). +*/ +#define TO_STARTUP_TIMEOUT_MSEC (1000) + +/** \tocfg Maximum number of messages to classify per processing frame. +*/ +#define TO_MAX_MSGS_OUT_PER_FRAME (100) + +/** \tocfg Maximum number of messages to classify per processing frame. +*/ + +/** \tocfg Maximum number configurable channels. + * +** \par Description: This is normally set to 1. +*/ +#define TO_MAX_CHANNELS (1) + +/** \tocfg Channel output queue depth. + * +** \par Description: This defines how many messages can be queued into the +** channel output queue by the scheduler. +*/ +#define TO_OUTPUT_QUEUE_DEPTH (20) + +/** \tocfg Development UDP channel task priority. + * +** \par Description: This defines the priority of the development UDP +** child task. +*/ +#define TO_UDP_CHANNEL_TASK_PRIORITY (119) + +/** +** \tocfg Number of bytes in the Message Memory Pool +** +** \par Description: +** The message memory pool contains the memory needed for the queued messages packets. +** The queued messages are dynamically allocated from this pool when the +** messages are received and queued, and deallocated when messages are transmitted +** or a new table is loaded. +** +** \par Limits +** The Telemetry Output app does not place a limit on this parameter, but there is +** an overhead cost in the memory pool. The value must be larger than what is +** needed. +*/ +#define TO_NUM_BYTES_IN_MEM_POOL (200 * TO_MAX_BLOCK_SIZE) + + +#ifdef __cplusplus +} +#endif + +#endif /* TO_PLATFORM_CFG_H */ + +/************************/ +/* End of File Comment */ +/************************/ + diff --git a/config/obc/ppd/sitl/gdbinit b/config/obc/ppd/sitl/gdbinit new file mode 100644 index 000000000..61b6b41a0 --- /dev/null +++ b/config/obc/ppd/sitl/gdbinit @@ -0,0 +1 @@ +handle SIG63 noprint nostop \ No newline at end of file diff --git a/config/obc/sitl/host/CMakeLists.txt b/config/obc/ppd/sitl/host/CMakeLists.txt similarity index 100% rename from config/obc/sitl/host/CMakeLists.txt rename to config/obc/ppd/sitl/host/CMakeLists.txt diff --git a/config/obc/sitl/inc/cfe_msgids.h b/config/obc/ppd/sitl/inc/cfe_msgids.h similarity index 100% rename from config/obc/sitl/inc/cfe_msgids.h rename to config/obc/ppd/sitl/inc/cfe_msgids.h diff --git a/config/obc/sitl/inc/cfe_platform_cfg.h b/config/obc/ppd/sitl/inc/cfe_platform_cfg.h similarity index 100% rename from config/obc/sitl/inc/cfe_platform_cfg.h rename to config/obc/ppd/sitl/inc/cfe_platform_cfg.h diff --git a/config/obc/ppd/sitl/perf_id_list b/config/obc/ppd/sitl/perf_id_list new file mode 100644 index 000000000..45f5dc865 --- /dev/null +++ b/config/obc/ppd/sitl/perf_id_list @@ -0,0 +1,77 @@ +MAC_MARKER_1_PERF_ID,0x00000064,0x00ff00,0.000000, +AE_MAIN_TASK_PERF_ID,0x0000004c,0x00ff00,0.000000, +AMC_MAIN_TASK_PERF_ID,0x00000043,0x00ff00,0.000000, +BAT_MAIN_TASK_PERF_ID,0x00000052,0x00ff00,0.000000, +CF_APPMAIN_PERF_ID,0x00000023,0x00ff00,0.000000, +CF_CYCLE_ENG_PERF_ID,0x0000002a,0x00ff00,0.000000, +CF_FCLOSE_PERF_ID,0x00000026,0x00ff00,0.000000, +CF_FILESIZE_PERF_ID,0x00000024,0x00ff00,0.000000, +CF_FOPEN_PERF_ID,0x00000025,0x00ff00,0.000000, +CF_FREAD_PERF_ID,0x00000027,0x00ff00,0.000000, +CF_FWRITE_PERF_ID,0x00000028,0x00ff00,0.000000, +CF_QDIRFILES_PERF_ID,0x0000002b,0x00ff00,0.000000, +CF_REDLIGHT_PERF_ID,0x00000029,0x00ff00,0.000000, +CFE_ES_MAIN_PERF_ID,0x00000001,0x00ff00,0.000000,Executive Services main execution loop +CFE_EVS_MAIN_PERF_ID,0x00000002,0x00ff00,0.000000,Event Services main execution loop +CFE_SB_MAIN_PERF_ID,0x00000004,0x00ff00,0.000000,Software Bus Services main execution loop +CFE_SB_MSG_LIM_PERF_ID,0x00000005,0x00ff00,0.000000,Software Bus Msg Limit errors +CFE_SB_PIPE_OFLOW_PERF_ID,0x0000001b,0x00ff00,0.000000,SOftware Bus Pipe Overflow Errors +CFE_TBL_MAIN_PERF_ID,0x00000003,0x00ff00,0.000000,Table Services main execution loop +CFE_TIME_LOCAL1HZISR_PERF_ID,0x00000008,0x00ff00,0.000000,1 Hz Local ISR +CFE_TIME_LOCAL1HZTASK_PERF_ID,0x0000000a,0x00ff00,0.000000,1 Hz Local Task +CFE_TIME_MAIN_PERF_ID,0x00000006,0x00ff00,0.000000,Time Services main execution loop +CFE_TIME_SENDMET_PERF_ID,0x00000009,0x00ff00,0.000000,Time ToneSendMET +CFE_TIME_TONE1HZISR_PERF_ID,0x00000007,0x00ff00,0.000000,1 Hz Tone ISR +CFE_TIME_TONE1HZTASK_PERF_ID,0x0000000b,0x00ff00,0.000000,1 Hz Tone Task +CI_MAIN_TASK_PERF_ID,0x00000021,0x00ff00,0.000000, +CI_SOCKET_RCV_PERF_ID,0x00000022,0x00ff00,0.000000, +CS_APPMAIN_PERF_ID,0x0000002c,0x00ff00,0.000000, +DS_APPMAIN_PERF_ID,0x0000002d,0x00ff00,0.000000, +EA_MAIN_TASK_PERF_ID,0x00000045,0x00ff00,0.000000, +FM_APPMAIN_PERF_ID,0x0000002e,0x00ff00,0.000000, +FM_CHILD_TASK_PERF_ID,0x0000002f,0x00ff00,0.000000, +HK_APPMAIN_PERF_ID,0x00000030,0x00ff00,0.000000, +HS_APPMAIN_PERF_ID,0x00000032,0x00ff00,0.000000, +HS_IDLETASK_PERF_ID,0x00000031,0x00ff00,0.000000, +LC_APPMAIN_PERF_ID,0x00000033,0x00ff00,0.000000, +LC_WDT_SEARCH_PERF_ID,0x00000034,0x00ff00,0.000000, +LD_MAIN_TASK_PERF_ID,0x0000004d,0x00ff00,0.000000, +MAC_MAIN_TASK_PERF_ID,0x00000044,0x00ff00,0.000000, +MD_APPMAIN_PERF_ID,0x00000035,0x00ff00,0.000000, +MM_APPMAIN_PERF_ID,0x00000036,0x00ff00,0.000000, +MM_EEPROM_FILELOAD_PERF_ID,0x00000039,0x00ff00,0.000000, +MM_EEPROM_FILL_PERF_ID,0x0000003a,0x00ff00,0.000000, +MM_EEPROM_POKE_PERF_ID,0x00000038,0x00ff00,0.000000, +MM_SEGBREAK_PERF_ID,0x00000037,0x00ff00,0.000000, +MPC_MAIN_TASK_PERF_ID,0x0000004e,0x00ff00,0.000000, +MPU9250_MAIN_TASK_PERF_ID,0x00000053,0x00ff00,0.000000, +MS5611_MAIN_TASK_PERF_ID,0x0000004a,0x00ff00,0.000000, +NAV_MAIN_TASK_PERF_ID,0x0000004f,0x00ff00,0.000000, +RCIN_MAIN_TASK_PERF_ID,0x00000050,0x00ff00,0.000000, +RGBLED_MAIN_TASK_PERF_ID,0x00000047,0x00ff00,0.000000, +RGBLED_RECEIVE_PERF_ID,0x00000049,0x00ff00,0.000000, +RGBLED_SEND_PERF_ID,0x00000048,0x00ff00,0.000000, +SC_APPMAIN_PERF_ID,0x0000003b,0x00ff00,0.000000, +SCH_MAIN_TASK_PERF_ID,0x0000003d,0x00ff00,0.000000, +SENS_MAIN_TASK_PERF_ID,0x0000004b,0x00ff00,0.000000, +TO_MAIN_TASK_PERF_ID,0x0000003c,0x00ff00,0.000000, +TO_SOCKET_SEND_PERF_ID,0x0000003e,0x00ff00,0.000000, +ULR_MAIN_TASK_PERF_ID,0x00000046,0x00ff00,0.000000, +VC_DEVICE_GET_PERF_ID,0x00000041,0x00ff00,0.000000, +VC_MAIN_TASK_PERF_ID,0x0000003f,0x00ff00,0.000000, +VC_SOCKET_SEND_PERF_ID,0x00000040,0x00ff00,0.000000, +VM_MAIN_TASK_PERF_ID,0x00000051,0x00ff00,0.000000, +VM_MAIN_TASK_PERF_ID,0x00000051,0x00ff00,0.000000, +RCIN_DEVICE_GET_PERF_ID,0x00000054,0x00ff00,0.000000, +SIM_MAIN_TASK_PERF_ID,0x00000055,0x00ff00,0.000000, +MAVLINK_MAIN_TASK_PERF_ID,0x00000056,0x00ff00,0.000000, +HMC5883_MAIN_TASK_PERF_ID,0x00000057,0x00ff00,0.000000, +HMC5883_RECEIVE_PERF_ID,0x00000058,0x00ff00,0.000000, +HMC5883_SEND_PERF_ID,0x00000059,0x00ff00,0.000000, +PARAMS_MAIN_TASK_PERF_ID,0x0000005a,0x00ff00,0.000000, +AE_MAIN_TASK_PERF_ID,0x0000005b,0x00ff00,0.000000, +PE_MAIN_TASK_PERF_ID,0x0000005c,0x00ff00,0.000000, +PE_UPDATE_TASK_PERF_ID,0x0000005d,0x00ff00,0.000000, +PE_SENSOR_GPS_PERF_ID,0x0000005e,0x00ff00,0.000000, +PE_SENSOR_BARO_PERF_ID,0x0000005f,0x00ff00,0.000000, +PE_SENSOR_LAND_PERF_ID,0x00000060,0x00ff00,0.000000, diff --git a/config/obc/ppd/sitl/set-vars.cmake b/config/obc/ppd/sitl/set-vars.cmake new file mode 100644 index 000000000..b8a43ba54 --- /dev/null +++ b/config/obc/ppd/sitl/set-vars.cmake @@ -0,0 +1,35 @@ +############################################################################# +# +# Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name Windhover Labs nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################# + +set(PSP ${PROJECT_SOURCE_DIR}/core/psp/pc-linux-wh) +set(OSAL ${PROJECT_SOURCE_DIR}/core/osal/posix-fast) diff --git a/config/obc/sitl/target/CMakeLists.txt b/config/obc/ppd/sitl/target/CMakeLists.txt similarity index 74% rename from config/obc/sitl/target/CMakeLists.txt rename to config/obc/ppd/sitl/target/CMakeLists.txt index 5a7523194..77a716680 100644 --- a/config/obc/sitl/target/CMakeLists.txt +++ b/config/obc/ppd/sitl/target/CMakeLists.txt @@ -3,10 +3,10 @@ include(../set-vars.cmake) buildliner_initialize( PSP ${PSP} OSAL ${OSAL} + CPU_ID PPD CORE_TOOLS ${CMAKE_CURRENT_SOURCE_DIR}/tools CONFIG - ${CMAKE_CURRENT_SOURCE_DIR}/inc - ${CMAKE_CURRENT_SOURCE_DIR}/../inc + ${CMAKE_CURRENT_SOURCE_DIR}/../../inc ${PROJECT_SOURCE_DIR}/config/shared/inc FILESYS /cf/apps @@ -15,13 +15,13 @@ buildliner_initialize( /cf/upload /ram STARTUP_SCRIPT - ${CMAKE_CURRENT_SOURCE_DIR}/cfe_es_startup.scr -) - -add_subdirectory(allstop allstop) -set_target_properties(allstop - PROPERTIES - RUNTIME_OUTPUT_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/exe + ${CMAKE_CURRENT_SOURCE_DIR}/../../cfe_es_startup.scr + + COMMANDER_WORKSPACE + ${CMAKE_BINARY_DIR}/../../../sitl_commander_workspace + + COMMANDER_WORKSPACE_OVERLAY + ${CMAKE_CURRENT_SOURCE_DIR}/../../cdr_workspace_overlay ) buildliner_add_app( @@ -38,27 +38,27 @@ buildliner_add_app( pq_lib DEFINITION ${PROJECT_SOURCE_DIR}/apps/pq_lib/fsw/for_build # TODO move this table build to sbn module? - CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/apps/pq_lib + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../../apps/pq_lib ) buildliner_add_app( prmlib DEFINITION ${PROJECT_SOURCE_DIR}/apps/prmlib/fsw/for_build - CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/apps/prm + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../../apps/prm ) buildliner_add_app( sch DEFINITION ${PROJECT_SOURCE_DIR}/apps/sch/fsw/for_build - CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/apps/sch + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../../apps/sch CONFIG_SOURCES - ${CMAKE_CURRENT_SOURCE_DIR}/apps/sch/sch_custom_rt.c + ${CMAKE_CURRENT_SOURCE_DIR}/../../apps/sch/sch_custom_rt.c ) buildliner_add_app( cf DEFINITION ${PROJECT_SOURCE_DIR}/apps/cf/fsw/for_build - CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/apps/cf + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../../apps/cf ) buildliner_add_app( @@ -70,7 +70,7 @@ buildliner_add_app( buildliner_add_app( ds DEFINITION ${PROJECT_SOURCE_DIR}/apps/ds/fsw/for_build - CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/apps/ds + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../../apps/ds ) buildliner_add_app( @@ -121,17 +121,17 @@ buildliner_add_app( buildliner_add_app( ea DEFINITION ${PROJECT_SOURCE_DIR}/apps/ea/fsw/for_build - CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/apps/ea + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../../apps/ea CONFIG_SOURCES - ${CMAKE_CURRENT_SOURCE_DIR}/apps/ea/src/ea_custom.c + ${CMAKE_CURRENT_SOURCE_DIR}/../../apps/ea/src/ea_custom.c ) buildliner_add_app( sbn DEFINITION ${PROJECT_SOURCE_DIR}/apps/sbn/fsw/for_build - CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/apps/sbn + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../../apps/sbn CONFIG_SOURCES - ${CMAKE_CURRENT_SOURCE_DIR}/apps/sbn/src/sbn_remap_tbl.c + ${CMAKE_CURRENT_SOURCE_DIR}/../../apps/sbn/src/sbn_remap_tbl.c ) buildliner_add_app( diff --git a/config/obc/ppd/sitl/target/gdbinit b/config/obc/ppd/sitl/target/gdbinit new file mode 100644 index 000000000..fad990b6a --- /dev/null +++ b/config/obc/ppd/sitl/target/gdbinit @@ -0,0 +1 @@ +handle SIG63 nostop noprint pass noignore \ No newline at end of file diff --git a/config/obc/ppd/sitl/wh_config.yaml b/config/obc/ppd/sitl/wh_config.yaml new file mode 100644 index 000000000..d194edcfe --- /dev/null +++ b/config/obc/ppd/sitl/wh_config.yaml @@ -0,0 +1,10 @@ +--- +config_base: ${PROJECT_SOURCE_DIR} + +modules: + core: + modules: + osal: + definition: ${PROJECT_SOURCE_DIR}/core/osal/fsw/posix-fast/wh_design.yaml + psp: + definition: ${PROJECT_SOURCE_DIR}/core/psp/fsw/pc-linux/wh_design.yaml diff --git a/config/obc/ppd/target/CMakeLists.txt b/config/obc/ppd/target/CMakeLists.txt index be2ded509..bf6c2a6a0 100644 --- a/config/obc/ppd/target/CMakeLists.txt +++ b/config/obc/ppd/target/CMakeLists.txt @@ -3,6 +3,7 @@ include(../set-vars.cmake) buildliner_initialize( PSP ${PSP} OSAL ${OSAL} + CPU_ID PPD CORE_TOOLS ${CMAKE_CURRENT_SOURCE_DIR}/tools CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/inc @@ -16,6 +17,12 @@ buildliner_initialize( /ram STARTUP_SCRIPT ${CMAKE_CURRENT_SOURCE_DIR}/cfe_es_startup.scr + + COMMANDER_WORKSPACE + ${CMAKE_BINARY_DIR}/../../commander_workspace + + COMMANDER_WORKSPACE_OVERLAY + ${CMAKE_CURRENT_SOURCE_DIR}/cdr_workspace_overlay ) add_subdirectory(allstop allstop) @@ -29,6 +36,11 @@ buildliner_add_app( DEFINITION ${PROJECT_SOURCE_DIR}/apps/cfs_lib/fsw/for_build ) +buildliner_add_app( + mbp_lib + DEFINITION ${PROJECT_SOURCE_DIR}/../private/apps/mbp_lib/fsw/for_build +) + buildliner_add_app( px4lib DEFINITION ${PROJECT_SOURCE_DIR}/apps/px4lib/fsw/for_build @@ -37,28 +49,28 @@ buildliner_add_app( buildliner_add_app( prmlib DEFINITION ${PROJECT_SOURCE_DIR}/apps/prmlib/fsw/for_build - CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/apps/prm + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../apps/prm ) buildliner_add_app( pq_lib DEFINITION ${PROJECT_SOURCE_DIR}/apps/pq_lib/fsw/for_build # TODO move this table build to sbn module? - CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/apps/pq_lib + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../apps/pq_lib ) buildliner_add_app( sch DEFINITION ${PROJECT_SOURCE_DIR}/apps/sch/fsw/for_build - CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/apps/sch + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../apps/sch CONFIG_SOURCES - ${CMAKE_CURRENT_SOURCE_DIR}/apps/sch/sch_custom_rt.c + ${CMAKE_CURRENT_SOURCE_DIR}/../apps/sch/sch_custom_rt.c ) buildliner_add_app( cf DEFINITION ${PROJECT_SOURCE_DIR}/apps/cf/fsw/for_build - CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/apps/cf + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../apps/cf ) buildliner_add_app( @@ -70,7 +82,7 @@ buildliner_add_app( buildliner_add_app( ds DEFINITION ${PROJECT_SOURCE_DIR}/apps/ds/fsw/for_build - CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/apps/ds + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../apps/ds ) buildliner_add_app( @@ -121,34 +133,34 @@ buildliner_add_app( buildliner_add_app( ci DEFINITION ${PROJECT_SOURCE_DIR}/apps/ci/fsw/for_build - CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/apps/ci + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../apps/ci CONFIG_SOURCES - ${CMAKE_CURRENT_SOURCE_DIR}/apps/ci/ci_custom.c + ${CMAKE_CURRENT_SOURCE_DIR}/../apps/ci/ci_custom.c ) buildliner_add_app( to DEFINITION ${PROJECT_SOURCE_DIR}/apps/to/fsw/for_build - CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/apps/to + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../apps/to CONFIG_SOURCES - ${CMAKE_CURRENT_SOURCE_DIR}/apps/to/tables/to_backup_cfg.c - ${CMAKE_CURRENT_SOURCE_DIR}/apps/to/to_custom.c + ${CMAKE_CURRENT_SOURCE_DIR}/../apps/to/tables/to_backup_cfg.c + ${CMAKE_CURRENT_SOURCE_DIR}/../apps/to/to_custom.c ) buildliner_add_app( ea DEFINITION ${PROJECT_SOURCE_DIR}/apps/ea/fsw/for_build - CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/apps/ea + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../apps/ea CONFIG_SOURCES - ${CMAKE_CURRENT_SOURCE_DIR}/apps/ea/src/ea_custom.c + ${CMAKE_CURRENT_SOURCE_DIR}/../apps/ea/src/ea_custom.c ) buildliner_add_app( sbn DEFINITION ${PROJECT_SOURCE_DIR}/apps/sbn/fsw/for_build - CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/apps/sbn + CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/../apps/sbn CONFIG_SOURCES - ${CMAKE_CURRENT_SOURCE_DIR}/apps/sbn/src/sbn_remap_tbl.c + ${CMAKE_CURRENT_SOURCE_DIR}/../apps/sbn/src/sbn_remap_tbl.c ) buildliner_add_app( @@ -158,8 +170,8 @@ buildliner_add_app( buildliner_add_app( sbn_uio_mbox - DEFINITION ${PROJECT_SOURCE_DIR}/apps/sbn/modules/uio_mbox/fsw/for_build + DEFINITION ${PROJECT_SOURCE_DIR}/../private/apps/sbn_uio_mbox/fsw/for_build CONFIG_SOURCES - ${CMAKE_CURRENT_SOURCE_DIR}/apps/pq_lib/tables/pq_backup_cfg.c + ${CMAKE_CURRENT_SOURCE_DIR}/../apps/pq_lib/tables/pq_backup_cfg.c ) diff --git a/config/obc/ppd/target/apps/pq_lib/tables/pq_backup_cfg.c b/config/obc/ppd/target/apps/pq_lib/tables/pq_backup_cfg.c deleted file mode 100644 index 0c6e3234e..000000000 --- a/config/obc/ppd/target/apps/pq_lib/tables/pq_backup_cfg.c +++ /dev/null @@ -1,73 +0,0 @@ -/************************************************************************ - ** Includes - *************************************************************************/ -#include "cfe_tbl_filedef.h" -#include "pq_structs.h" -#include "msg_ids.h" - - -/************************************************************************ - ** Defines - *************************************************************************/ - -#define PQ_PQUEUE_SINGLE_PASS_IDX 0 -#define PQ_PQUEUE_HIGH_OPS_RSRVD_IDX 1 -#define PQ_PQUEUE_HIGH_IDX 2 -#define PQ_PQUEUE_MEDIUM_IDX 3 -#define PQ_PQUEUE_LOW_IDX 4 - -/** - ** \brief Default TO config table data - */ -PQ_ChannelTbl_t PQ_BackupConfigTbl = -{ - /* Table ID */ - 0, - { - /* Message Flows */ - /* Ground Queues */ - {SBN_SUB_MID, 64, PQ_PQUEUE_MEDIUM_IDX}, - {SBN_UNSUB_MID, 64, PQ_PQUEUE_MEDIUM_IDX}, - {SBN_ALLSUB_MID, 1, PQ_PQUEUE_HIGH_IDX}, - {CFE_ES_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CFE_EVS_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CFE_SB_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CFE_TBL_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CFE_TIME_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CFE_TIME_DIAG_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CFE_EVS_EVENT_MSG_MID, 32, PQ_PQUEUE_LOW_IDX}, - {CFE_SB_STATS_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CFE_ES_APP_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CFE_TBL_REG_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CFE_ES_SHELL_TLM_MID, 32, PQ_PQUEUE_LOW_IDX}, - {CFE_ES_MEMSTATS_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CF_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CF_TRANS_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CF_CONFIG_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {CF_SPACE_TO_GND_PDU_MID, 32, PQ_PQUEUE_LOW_IDX}, - {FM_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {FM_FILE_INFO_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {FM_DIR_LIST_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {FM_OPEN_FILES_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {FM_FREE_SPACE_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {MD_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - {MM_HK_TLM_MID, 1, PQ_PQUEUE_LOW_IDX}, - },{ - /* Priority Queues */ - /* PQ_PQUEUE_SINGLE_PASS_IDX */ - {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_SINGLE}, - /* PQ_PQUEUE_HIGH_OPS_RSRVD_IDX */ - {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO}, - /* PQ_PQUEUE_HIGH_IDX */ - {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO}, - /* PQ_PQUEUE_MEDIUM_IDX */ - {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO}, - /* PQ_PQUEUE_LOW_IDX */ - {PQ_PQUEUE_ENA, 100, PQ_PRIORITY_QUEUE_TYPE_FIFO} - } -}; - - -/************************/ -/* End of File Comment */ -/************************/ diff --git a/config/obc/ppd/target/apps/sch/tables/sch_def_schtbl.c b/config/obc/ppd/target/apps/sch/tables/sch_def_schtbl.c deleted file mode 100644 index a8293f8e0..000000000 --- a/config/obc/ppd/target/apps/sch/tables/sch_def_schtbl.c +++ /dev/null @@ -1,4418 +0,0 @@ -#ifdef __cplusplus -extern "C" { -#endif - -/* -** Pragmas -*/ - -/* -** Include Files -*/ -#include "cfe.h" -#include "cfe_tbl_filedef.h" -#include "sch_platform_cfg.h" -#include "sch_msgdefs.h" -#include "sch_tbldefs.h" - -#include "sch_grpids.h" - - -/* -** Local Defines -*/ - -#define CFE_ES_SEND_HK_MIDX 1 -#define CFE_EVS_SEND_HK_MIDX 2 -#define CFE_SB_SEND_HK_MIDX 3 -#define CFE_TIME_SEND_HK_MIDX 4 -#define CFE_TBL_SEND_HK_MIDX 5 -#define CFE_TIME_FAKE_CMD_MIDX 6 - -#define LC_SAMPLE_AP_MIDX 9 - -#define SCH_SEND_HK_MIDX 15 -#define TO_SEND_HK_MIDX 16 -#define HK_SEND_HK_MIDX 17 - -#define TO_SEND_TLM_MIDX 19 -#define HK_SEND_COMBINED_PKT1_MIDX 20 -#define HK_SEND_COMBINED_PKT2_MIDX 21 -#define HK_SEND_COMBINED_PKT3_MIDX 22 -#define HK_SEND_COMBINED_PKT4_MIDX 23 -#define HK_SEND_COMBINED_PKT5_MIDX 24 -#define HK_SEND_COMBINED_PKT6_MIDX 25 -#define HK_SEND_COMBINED_PKT7_MIDX 26 -#define HK_SEND_COMBINED_PKT8_MIDX 27 -#define HK_SEND_COMBINED_PKT9_MIDX 28 -#define HK_SEND_COMBINED_PKT10_MIDX 29 -#define FM_SEND_HK_MIDX 30 -#define LC_SEND_HK_MIDX 31 -#define HS_WAKEUP_MIDX 32 -#define HS_SEND_HK_MIDX 33 -#define MD_SEND_HK_MIDX 34 -#define MD_WAKEUP_MIDX 35 -#define DS_SEND_HK_MIDX 37 -#define CS_SEND_HK_MIDX 38 -#define CS_BACKGROUND_CYCLE_MIDX 39 -#define SC_1HZ_WAKEUP_MIDX 40 -#define SC_SEND_HK_MIDX 41 - -#define VC_SEND_HK_MIDX 45 -#define VC_PROCESS_CMDS_MIDX 46 -#define RGBLED_WAKEUP_MIDX 47 -#define RGBLED_SEND_HK_MIDX 48 - -#define CI_READ_CMD_MIDX 50 -#define CI_1HZ_PROC_TIMEOUTS_MIDX 51 -#define CI_SEND_HK_MIDX 52 -#define PARAMS_WAKEUP_MIDX 53 -#define PARAMS_SEND_HK_MIDX 54 - -#define CF_SEND_HK_MIDX 57 -#define CF_WAKE_UP_REQ_CMD_MIDX 58 - -#define MAC_SEND_HK_MIDX 60 -#define MAC_RUN_CONTROLLER_MIDX 61 - -#define AMC_UPDATE_MOTORS_MIDX 65 -#define AMC_SEND_HK_MIDX 66 -#define MPU9250_SEND_HK_MIDX 67 -#define MPU9250_MEASURE_MIDX 68 - -#define MM_SEND_HK_MIDX 70 - -#define MPU6050_SEND_HK_MIDX 72 -#define MPU6050_MEASURE_MIDX 73 -#define PE_SEND_HK_MIDX 74 -#define PE_WAKEUP_MIDX 75 -#define MS5607_SEND_HK_MIDX 76 -#define MS5607_MEASURE_MIDX 77 -#define MS5611_SEND_HK_MIDX 78 -#define MS5611_MEASURE_MIDX 79 -#define ULR_MEASURE_MIDX 80 -#define ULR_SEND_HK_MIDX 81 -#define HMC5883_SEND_HK_MIDX 82 -#define AK8963_SEND_HK_MIDX 83 -#define AK8963_WAKEUP_MIDX 84 - -#define HMC5883_WAKEUP_MIDX 88 - -#define SENS_SEND_HK_MIDX 90 -#define SENS_WAKEUP_MIDX 91 - -#define LGC_WAKEUP_MIDX 93 -#define LGC_SEND_HK_MIDX 94 - -#define PRM_SEND_HK_MIDX 96 -#define PRM_WAKEUP_MIDX 97 - -#define QAE_SEND_HK_MIDX 102 -#define QAE_WAKEUP_MIDX 103 -#define LD_SEND_HK_MIDX 104 -#define LD_WAKEUP_MIDX 105 -#define MPC_SEND_HK_MIDX 106 -#define MPC_WAKEUP_MIDX 107 -#define NAV_SEND_HK_MIDX 108 -#define NAV_WAKEUP_MIDX 109 -#define CFE_TIME_TONE_CMD_MIDX 110 -#define CFE_TIME_1HZ_CMD_MIDX 111 -#define RCIN_SEND_HK_MIDX 112 -#define RCIN_WAKEUP_MIDX 113 -#define VM_SEND_HK_MIDX 114 -#define VM_WAKEUP_MIDX 115 - -#define BAT_SEND_HK_MIDX 117 -#define BAT_WAKEUP_MIDX 118 - -#define GPS_READ_SENSOR_MIDX 122 -#define GPS_SEND_HK_MIDX 123 - -#define EA_WAKEUP_MIDX 125 - -#define EA_SEND_HK_MIDX 127 - - -/* Default schedule table */ -SCH_ScheduleEntry_t SCH_DefaultScheduleTable[SCH_TABLE_ENTRIES] = -{ - - /* slot #0*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #1*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #2*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #3*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #4*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #5*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, GPS_READ_SENSOR_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #6*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, TO_SEND_TLM_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #7*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VC_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #8*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #9*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #10*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #11*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #12*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VC_PROCESS_CMDS_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #13*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #14*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #15*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #16*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #17*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, NAV_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - - /* slot #18*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #19*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #20*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CFE_ES_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #21*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #22*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #23*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #24*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #25*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CFE_EVS_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #26*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #27*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #28*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #29*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #30*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CFE_SB_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #31*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, TO_SEND_TLM_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #32*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #33*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #34*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #35*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CFE_TIME_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #36*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #37*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #38*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #39*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #40*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CFE_TIME_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #41*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #42*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, NAV_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - - - /* slot #43*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #44*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #45*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CFE_TBL_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #46*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #47*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #48*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #49*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #50*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #51*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #52*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #53*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #54*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #55*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, GPS_READ_SENSOR_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #56*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, TO_SEND_TLM_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #57*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #58*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #59*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #60*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CF_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #61*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #62*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #63*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #64*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #65*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CF_WAKE_UP_REQ_CMD_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #66*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #67*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, NAV_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - - /* slot #68*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #69*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #70*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CI_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #71*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #72*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #73*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #74*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CI_1HZ_PROC_TIMEOUTS_MIDX,SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #75*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, CS_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #76*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #77*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #78*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #79*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #80*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, DS_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #81*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, TO_SEND_TLM_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #82*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #83*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #84*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #85*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, EA_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #86*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #87*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #88*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #89*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #90*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #91*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #92*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, NAV_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - - /* slot #93*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #94*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #95*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #96*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #97*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #98*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #99*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #100*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, EA_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #101*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #102*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #103*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #104*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #105*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, GPS_READ_SENSOR_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #106*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, TO_SEND_TLM_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #107*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #108*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #109*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #110*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, GPS_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #111*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #112*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #113*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #114*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #115*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HK_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #116*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #117*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, NAV_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - - /* slot #118*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #119*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #120*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #121*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #122*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #123*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #124*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #125*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HS_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #126*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #127*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #128*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #129*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #130*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #131*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, TO_SEND_TLM_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #132*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #133*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #134*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #135*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, FM_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #136*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #137*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #138*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #139*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #140*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LC_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #141*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #142*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #143*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, NAV_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - - /* slot #144*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #145*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #146*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #147*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #148*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #149*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #150*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MD_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #151*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #152*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #153*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #154*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #155*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, GPS_READ_SENSOR_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #156*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, TO_SEND_TLM_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #157*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #158*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #159*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #160*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MM_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #161*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #162*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #163*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #164*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #165*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #166*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #167*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, NAV_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - - /* slot #168*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #169*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #170*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #171*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #172*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #173*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #174*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #175*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #176*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #177*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #178*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #179*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LGC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #180*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #181*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, TO_SEND_TLM_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #182*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #183*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #184*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #185*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, NAV_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - - /* slot #186*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #187*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #188*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #189*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LC_SAMPLE_AP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #190*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #191*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #192*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, NAV_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - - /* slot #193*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #194*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #195*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #196*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #197*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #198*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #199*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #200*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #201*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #202*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #203*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #204*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #205*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, GPS_READ_SENSOR_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #206*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, TO_SEND_TLM_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #207*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #208*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #209*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #210*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #211*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #212*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #213*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #214*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #215*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RGBLED_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #216*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #217*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, NAV_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - - /* slot #218*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #219*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #220*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RGBLED_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #221*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #222*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #223*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #224*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #225*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SC_1HZ_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #226*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #227*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LGC_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #228*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #229*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #230*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SC_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #231*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, TO_SEND_TLM_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #232*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #233*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #234*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #235*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SCH_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #236*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #237*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #238*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #239*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #240*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, BAT_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, TO_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #241*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #242*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, NAV_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - - /* slot #243*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #244*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #245*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MS5611_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_SEND_HK_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #246*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, RCIN_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #247*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #248*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, PE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE }, - - /* slot #249*/ - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, QAE_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, AMC_UPDATE_MOTORS_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, LD_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, HMC5883_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MAC_RUN_CONTROLLER_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPC_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, MPU9250_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, SENS_WAKEUP_MIDX, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, ULR_MEASURE_MIDX, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_UNUSED, 0, 0, 0, 0, SCH_GROUP_NONE }, - { SCH_ENABLED, SCH_ACTIVITY_SEND_MSG, 1, 0, VM_WAKEUP_MIDX, SCH_GROUP_NONE } -}; - -/* -** Local Variables -*/ - -/* -** Function Prototypes -*/ - -/* -** Function Definitions -*/ - - - -/* Table file header */ -CFE_TBL_FILEDEF(SCH_DefaultScheduleTable, SCH.SCHED_DEF, SCH schedule table, sch_def_schtbl.tbl ) - - - -#ifdef __cplusplus -} -#endif - -/*======================================================================================= -** End of file sch_def_schtbl.c -**=====================================================================================*/ - diff --git a/config/obc/ppd/target/apps/to/tables/to_backup_cfg.c b/config/obc/ppd/target/apps/to/tables/to_backup_cfg.c deleted file mode 100644 index dd007ca32..000000000 --- a/config/obc/ppd/target/apps/to/tables/to_backup_cfg.c +++ /dev/null @@ -1,74 +0,0 @@ -/************************************************************************ - ** Includes - *************************************************************************/ -#include "cfe_tbl_filedef.h" -#include "to_tbldefs.h" -#include "msg_ids.h" - - -/************************************************************************ - ** Defines - *************************************************************************/ - -#define TO_PQUEUE_SINGLE_PASS_IDX 0 -#define TO_PQUEUE_HIGH_OPS_RSRVD_IDX 1 -#define TO_PQUEUE_HIGH_IDX 2 -#define TO_PQUEUE_MEDIUM_IDX 3 -#define TO_PQUEUE_LOW_IDX 4 - -/** - ** \brief Default TO config table data - */ -TO_ChannelTbl_t TO_BackupConfigTbl = -{ - /* Table ID */ - 0, - { - /* Message Flows */ - /* Ground Queues */ - {TO_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {TO_DATA_TYPE_MID, 1, TO_PQUEUE_HIGH_IDX}, - {TO_DIAG_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {CFE_ES_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CFE_EVS_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CFE_SB_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CFE_TBL_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CFE_TIME_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CFE_TIME_DIAG_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CFE_EVS_EVENT_MSG_MID, 32, TO_PQUEUE_MEDIUM_IDX}, - {CFE_SB_STATS_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CFE_ES_APP_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CFE_TBL_REG_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CFE_SB_ONESUB_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CFE_ES_SHELL_TLM_MID, 32, TO_PQUEUE_MEDIUM_IDX}, - {CFE_ES_MEMSTATS_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CF_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CF_TRANS_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CF_CONFIG_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CF_SPACE_TO_GND_PDU_MID, 32, TO_PQUEUE_MEDIUM_IDX}, - {FM_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {FM_FILE_INFO_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {FM_DIR_LIST_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {FM_OPEN_FILES_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {FM_FREE_SPACE_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {MD_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {MM_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - },{ - /* Priority Queues */ - /* TO_PQUEUE_SINGLE_PASS_IDX */ - {TO_PQUEUE_ENA, 100, TO_PRIORITY_QUEUE_TYPE_SINGLE}, - /* TO_PQUEUE_HIGH_OPS_RSRVD_IDX */ - {TO_PQUEUE_ENA, 100, TO_PRIORITY_QUEUE_TYPE_FIFO}, - /* TO_PQUEUE_HIGH_IDX */ - {TO_PQUEUE_ENA, 100, TO_PRIORITY_QUEUE_TYPE_FIFO}, - /* TO_PQUEUE_MEDIUM_IDX */ - {TO_PQUEUE_ENA, 100, TO_PRIORITY_QUEUE_TYPE_FIFO}, - /* TO_PQUEUE_LOW_IDX */ - {TO_PQUEUE_ENA, 100, TO_PRIORITY_QUEUE_TYPE_FIFO} - } -}; - - -/************************/ -/* End of File Comment */ -/************************/ diff --git a/config/obc/ppd/target/cdr_workspace_overlay/.gitignore b/config/obc/ppd/target/cdr_workspace_overlay/.gitignore new file mode 100644 index 000000000..a1c13091d --- /dev/null +++ b/config/obc/ppd/target/cdr_workspace_overlay/.gitignore @@ -0,0 +1,2 @@ +yamcs-data +cache diff --git a/config/obc/ppd/target/cdr_workspace_overlay/README.md b/config/obc/ppd/target/cdr_workspace_overlay/README.md new file mode 100644 index 000000000..9b4693c1a --- /dev/null +++ b/config/obc/ppd/target/cdr_workspace_overlay/README.md @@ -0,0 +1,2 @@ +# YAMCS Configuration +This current configuration is not done yet. We still need to update the config files and our code base to use the [Plugin](https://yamcs.org/docs/yamcs-server-manual/yamcs-plugin-format/) Plugin interface in order for us to hook into the YAMCS workflow. diff --git a/config/obc/ppd/target/cdr_workspace_overlay/etc/yamcs.yamcs-cfs.yaml b/config/obc/ppd/target/cdr_workspace_overlay/etc/yamcs.yamcs-cfs.yaml new file mode 100644 index 000000000..f29c457c3 --- /dev/null +++ b/config/obc/ppd/target/cdr_workspace_overlay/etc/yamcs.yamcs-cfs.yaml @@ -0,0 +1,84 @@ +#Configuration tested on YAMCS 5.4.0 +services: + - class: org.yamcs.archive.XtceTmRecorder + - class: org.yamcs.archive.ParameterRecorder + - class: org.yamcs.archive.AlarmRecorder + - class: org.yamcs.archive.EventRecorder + - class: org.yamcs.archive.ReplayServer + - class: org.yamcs.parameter.SystemParametersCollector + args: + provideJvmVariables: true + provideFsVariables: true + - class: org.yamcs.ProcessorCreatorService + args: + name: realtime + type: realtime + - class: org.yamcs.archive.CommandHistoryRecorder + - class: org.yamcs.parameterarchive.ParameterArchive + args: + realtimeFiller: + enabled: false + backFiller: + enabled: true + warmupTime: 60 + - class: org.yamcs.tctm.cfs.CfsEventDecoder + args: + msgIds: [0x0815] #Always confirm this ID with CFE_EVS configuration + byteOrder: LITTLE_ENDIAN + appNameMax: 40 + eventMsgMax: 122 + - class: org.yamcs.cfdp.CfdpService + name: cfdp0 + args: + inStream: cfdp_in + outStream: cfdp_out + localEntities: + - name: "0.23" + id: 23 + bucket: cfdpUp + remoteEntities: + - name: "0.24" + id: 24 + bucket: cfdpDown + receiverFaultHandlers: + AckLimitReached: suspend + +dataLinks: + - name: tm_realtime + class: org.yamcs.tctm.UdpTmDataLink + stream: tm_realtime + port: 5011 + maxLength: 32768 #32KB is the default for CCSDS + packetPreprocessorClassName: com.windhoverlabs.yamcs.tctm.PacketPreprocessor + + - name: tc_realtime + class: org.yamcs.tctm.UdpTcDataLink + stream: tc_realtime + host: localhost + port: 5010 + commandPostprocessorClassName: org.yamcs.tctm.cfs.CfsCommandPostprocessor + commandPostprocessorArgs: + swapChecksumFc: true + +mdb: + # Configuration of the active loaders + # Valid loaders are: sheet, xtce or fully qualified name of the class + - type: "xtce" + spec: "mdb/cfs-ccsds.xml" + subLoaders: + - type: "xtce" + spec: "mdb/PPD.xml" + - type: "xtce" + spec: "mdb/CPD.xml" + +# Configuration for streams created at server startup +streamConfig: + tm: + - name: "tm_realtime" + - name: "tm_dump" + cmdHist: ["cmdhist_realtime", "cmdhist_dump"] + event: ["events_realtime", "events_dump"] + param: ["pp_realtime", "sys_param", "proc_param"] + parameterAlarm: ["alarms_realtime"] + tc: ["tc_realtime"] + sqlFile: "etc/extra_streams.sql" diff --git a/config/obc/ppd/target/cdr_workspace_overlay/mdb/SpaceSystem.xsd b/config/obc/ppd/target/cdr_workspace_overlay/mdb/SpaceSystem.xsd new file mode 100644 index 000000000..c9d99d902 --- /dev/null +++ b/config/obc/ppd/target/cdr_workspace_overlay/mdb/SpaceSystem.xsd @@ -0,0 +1,5918 @@ + + + + + + This XML Schema Definition (XSD) defines syntax with concrete semantics for describing space or remote device telemetry and commanding in a platform and program independent manner. + + + + + The top-level SpaceSystem is the root element for the set of metadata necessary to monitor and command a space device, such as a satellite. A SpaceSystem defines a namespace. Metadata areas include: packets/minor frames layout, telemetry, calibration, alarm, algorithms, streams and commands. A SpaceSystem may have child SpaceSystems, forming a SpaceSystem tree. See SpaceSystemType. + + + + This key ensures a unique parameter name at the system level. + + + + + + + This key ensures a unique parameter type name at the system level. + + + + + + + This key ensures a unique metaCommand name at the system level. + + + + + + + This key ensures a unique algorithm name at the system level. + + + + + + + This key ensures a unique stream name at the system level. + + + + + + + This key ensures a unique service name at the system level. + + + + + + + This key ensures a container stream name at the system level. + + + + + + + + + + + This key ensures a unique argument type name at the system level. + + + + + + + This key ensures a unique BlockMetaCommand name at the system level. + + + + + + + + SpaceSystem is a collection of SpaceSystem(s) including space assets, ground assets, multi-satellite systems and sub-systems. A SpaceSystem is the root element for the set of data necessary to monitor and command an arbitrary space device - this includes the binary decomposition the data streams going into and out of a device. + + + + + + + The Header element contains optional descriptive information about this SpaceSystem or the document as a whole when specified at the root SpaceSystem. + + + + + This element contains descriptions of the telemetry created on the space asset/device and sent to other data consumers. + + + + + This element contains descriptions of the commands and their associated constraints and verifications that can be sent to the space asset/device. + + + + + + Additional SpaceSystem elements may be used like namespaces to segregate portions of the space asset/device into convenient groupings or may be used to specialize a product line generic SpaceSystem to a specific asset instance. + + + + + + Optional descriptive attribute for document owner convenience. + + + + + + + + + Describe command related metadata. Items defined in this area may refer to items defined in TelemetryMetaData. See TelemetryMetaDataType. + + + + + A list of parameter types. + + + + + Parameters referenced by MetaCommands. This Parameter Set is located here so that MetaCommand data can be built independently of TelemetryMetaData. + + + + + A list of argument types. MetaCommand definitions can contain arguments and parameters. Arguments are user provided to the specific command definition. Parameters are provided/calculated/determined by the software creating the command instance. As a result, arguments contain separate type information. In some cases, arguments have different descriptive characteristics. + + + + + A list of command definitions with their arguments, parameters, and container encoding descriptions. + + + + + Similar to the ContainerSet for telemetry, the CommandContainerSet contains containers that can be referenced/shared by MetaCommand definitions. + + + + + Contains an unordered set of Streams. + + + + + Contains an unordered set of Algorithms. + + + + + + + All the data about telemetry is contained in TelemetryMetaData + + + + + A list of parameter types + + + + + A list of Parameters for this Space System. + + + + + Holds the list of all potential container definitions for telemetry. Containers may parts of packets or TDM, and then groups of the containers, and then an entire entity -- such as a packet. In order to maximize re-used for duplication, the pieces may defined once here, and then assembled as needed into larger structures, also here. + + + + + Messages are an alternative method of uniquely identifying containers within a Service. A message provides a test in the form of MatchCriteria to match to a container. A simple example might be: [When minorframeID=21, the message is the 21st minorframe container. The collection of messages to search thru will be bound by a Service. + + + + + + + + + + + This schema defines the dictionary for containers, which in turn describe the physical composition of data in a communication system + + + + Identical to ArgumentRefEntryType but supports argument instance references. + + + + + + + + + + Identical to ArrayParameterRefEntryType but supports argument instance references. + + + + + + Only used for subsetting an array. The array's true dimension sizes are set in the Type. + + + + The dimension here if used for subsetting must be less than the ones in the type. It's not a subset if its the same size. + + + + + + + + + + + Identical to ArrayParameterRefEntryType but supports argument instance references. + + + + + + Only used for subsetting an array. The array's true dimension sizes are set in the Type. + + + + The dimension here if used for subsetting must be less than the ones in the type. It's not a subset if its the same size. + + + + + + + + + + + Identical to ContainerRefEntryType but supports argument instance references. + + + + + + + + + + Identical to ContainerSegmentRefEntryType but supports argument instance references. + + + + + + + + + + + + Identical to FixedValueEntryType but supports argument instance references. + + + + + + An optional name for the fixed/constant field in the sequence. + + + + + The fixed/constant value that should be encoded into the sequence. This value provided should have sufficient bit length to accomodate the size in bits. If the value is larger, the most significant unnecessary bits are dropped. The value provided should be in network byte order for encoding. + + + + + The number of bits that this fixed/constant value should occupy in the sequence. + + + + + + + + Identical to IndirectParameterRefEntryType but supports argument instance references. + + + + + + + + + + + + + Identical to ParameterRefEntryType but supports argument instance references. + + + + + + + + + + Identical to ParameterSegmentRefEntryType but supports argument instance references. + + + + + + + + + + + + Identical to StreamRefEntryType but supports argument instance references. + + + + + + + + + + + + Describe an entry that is an array parameter. Specify the dimension sizes if you subsetting the array (the number of dimensions shall match the number defined in the parameter’s type definition), otherwise the ones in the ParameterType are assumed. See SequenceEntryType. + + + + + + Only used for subsetting an array. The array's maximum dimension sizes are set in the type. When a DimensionList is not used, the array is the full size provided in the type. + + + + The dimension here if used for subsetting must be less than the ones in the type. It's not a subset if its the same size. + + + + + + + + + + Supplies an optional non-reference-able name and short description for alarms. Also includes an optional ancillary data for any special local flags, note that these may not necessarily transfer to another recipient of an instance document. + + + + + + + The alarm definition may be named. + + + + + An optional brief description of this alarm definition. + + + + + + Describe a child/parent container inheritance relationship. Describe constraints with RestrictionCriteria, conditions that must be true for this container to be an extension of the parent container. A constraint can be used to convey the identifying features of the telemetry format such as the CCSDS application id or minor-frame id. See RestrictionCriteriaType and SequenceContainerType. + + + + + Contains the conditions that must evaluate to true in order for this container to be an extension of the parent container. + + + + + + Reference to the container that this container extends. + + + + + + An abstract block of data; used as the base type for more specific container types + + + + + + RateInStream is used to: a) generate alarms when the Container is updated too frequently or too infrequently, b) provide some 'guidelines' for generating forward link containers, c) provide some guidelines for spacecraft simulators to generate telemetry containers. If necessary, these rates may be defined on a per stream basis. + The software should check that any Stream names referenced in the RateInStreamSet actually exist. + + + + + + May be used to indicate error detection and correction, change byte order, provide the size (when it can't be derived), or perform some custom processing. + + + + + + + + + + + + + + Holds a reference to a container + + + + name of container + + + + + + An entry that is simply a reference to another container. + + + + + + + + + + An entry that is only a portion of a container indicating that the entire container must be assembled from other container segments. It is assumed that container segments happen sequentially in time, that is the first part of a container is first, however (and there's always a however), if this is not the case the order of this container segment may be supplied with the order attribute where the first segment order="0". Each instance of a container cannot overlap in the overall sequence with another instance + + + + + + + + + + + + Unordered Set of Containers + + + + + SequenceContainers define sequences of parameters or other containers. + + + + + + + Contains an ordered list of Entries. Used in Sequence Container + + + + + Specify a Parameter to be a part of this container layout definition. + + + + + Specify a portion of a Parameter to be a part of this container layout definition. This is used when the Parameter is reported in fractional parts in the container before being fully updated. + + + + + Specify the content of another Container to be a part of this container layout definition. + + + + + Specify a portion of another Container to be a part of this container layout definition. + + + + + Specify a portion of a Stream to be a part of this container layout definition. + + + + + Specify a previous (not last reported) value of a Parmeter to be a part of this container layout definition. + + + + + Specify an Array Type Parameter to be a part of this container layout definition when the Container does not populate the entire space of the Array contents. If the entire space of the Array is populated, a tolerant implementation will accept ParameterRefEntry also. + + + + + + + An entry whose name is given by the value of a ParamameterInstance. This entry may be used to implement dwell telemetry streams. The value of the parameter in ParameterInstance must use either the name of the Parameter or its alias. If it's an alias name, the alias namespace is supplied as an attribute. + + + + + + + + + + + + + Describe the absolute or relative bit location of an entry in a container. The "referenceLocation" attribute specifies the starting bit anchor. If no referenceLocation value is given, the entry is assumed to begin at the first bit position after the previous entry. Each container starts at bit 0, thus "containerStart" is an offset from 0. Negative container start bits are before the container and are implementation dependent – these should be flagged as likely errors. "containerEnd" is given as a positive offset from the end of the container, thus a container end of 0 is exactly at the end of the container. Negative container end addresses are after the container and are implementation dependent – these should be flagged as likely errors. Positive "previouEntry" values are offsets from the previous entry – zero (0) is the default which means it follows contiguously from the last occupied bit of the previous entry. A value of one means it is offset 1-bit from the previous entry, and a value of negative 1 (-1) means it overlaps the previous entry by one bit, and so forth. The "nextEntry" attribute value is proposed for deprecation and should be avoided. See SequenceEntryType. + + + + + + Defines the relative reference used to interpret the start bit position. The default is 0 bits from the end of the previousEntry, which makes the entry contiguous. + + + + + + + + Identical to LocationInContainerInBitsType but supports argument instance references. + + + + + + + + + + Holds a reference to a message + + + + name of message + + + + + + An entry that is a single Parameter + + + + + + + + + + An entry that is only a portion of a parameter value indicating that the entire parameter value must be assembled from other parameter segments. It is assumed that parameter segments happen sequentially in time, that is the first part if a telemetry parameter first, however (and there's always a however), if this is not the case the order of this parameter segment may be supplied with the order attribute where the first segment order="0". + + + + + + + + + + + + Describes the binary layout/packing of data and also related properties, including an entry list of parameters, parameter segments, array parameters, stream segments, containers, and container segments. Sequence containers may extend other sequence containers (see BaseContainerType). The parent container’s entries are placed before the entries in the child container forming one entry list. An inheritance chain may be formed using this mechanism, but only one entry list is being created. Sequence containers may be marked as "abstract", when this occurs an instance of it cannot itself be created. The idle pattern is part of any unallocated space in the container. See EntryListType. + + + + + + + List of item entries to pack/encode into this container definition. + + + + + Optional inheritance for this container from another named container. + + + + + + Abstract container definitions that are not instantiated, rather only used as bases to inherit from to create specialized container definitions. + + + + + The idle pattern is part of any unallocated space in the container. This is uncommon. + + + + + + + + Defines an abstract schema type used to create other entry types. Describe an entry’s location in the container (See LocationInContainerInBitsType). The location may be fixed or dynamic, absolute or relative. Entries may be included depending on the value of a condition (See IncludeConditionType), and entries may also repeat (see RepeatEntryType). The entry’s IncludeCondition resolves to true, it is fully-resolved when its size is computable after RepeatEntry has been accounted for and then offset by LocationInContainer. See EntryListType, IncludeConditionType, RepeatEntryType and LocationInContainerInBitsType. + + + + + The start bit 0 position for each container is local to the container, but does include space occupied by inherited containers. When a container is "included", as opposed to inherited, then the interpreting implementation takes into account the start bit position of the referring container when finally assembling the start bits for the post-processed entry content. The default start bit for any entry is 0 bits from the previous entry, making the content contiguous when this element is not used. + + + + + May be used when this entry repeats itself in the sequence container. When an entry repeats, it effectively specifies that the same entry is reported more than once in the container and has the same physical meaning. This should not be construed to be equivalent to arrays. + + + + + This entry will only be included in the sequence when this condition is true, otherwise it is always included. When the include condition evaluates to false, it is as if the entry does not exist such that any start bit interpretations cannot take into account the space that would have been occupied if this included condition were true. + + + + + Optional timing information associated with this entry. + + + + + Optional ancillary data associated with this element. + + + + + + Optional short description for this entry element. + + + + + + Identical to a SequenceEntryType but supports argument instance references. + + + + + The start bit 0 position for each container is local to the container, but does include space occupied by inherited containers. When a container is "included", as opposed to inherited, then the interpreting implementation takes into account the start bit position of the referring container when finally assembling the start bits for the post-processed entry content. The default start bit for any entry is 0 bits from the previous entry, making the content contiguous when this element is not used. + + + + + May be used when this entry repeats itself in the sequence container. When an entry repeats, it effectively specifies that the same entry is reported more than once in the container and has the same physical meaning. This should not be construed to be equivalent to arrays. + + + + + This entry will only be included in the sequence when this condition is true, otherwise it is always included. When the include condition evaluates to false, it is as if the entry does not exist such that any start bit interpretations cannot take into account the space that would have been occupied if this included condition were true. + + + + + Ancillary data associated with this entry. + + + + + + Optional short description for this entry element. + + + + + + Holds a set of services, logical groups of containers OR messages (not both). + + + + + + + + + + + + + An entry that is a portion of a stream (streams are by definition, assumed continuous) It is assumed that stream segments happen sequentially in time, that is the first part if a steam first, however, if this is not the case the order of the stream segments may be supplied with the order attribute where the first segment order="0". + + + + + + + + + + + + + + + + + The ContainerRef should point to ROOT container that will describe an entire packet/minor frame or chunk of telemetry. + + + + + + + + + + + + + + + + + + + + + + + Define the expected appearance (rate) of a container in a stream where the rate is defined on either a perSecond or perContainer update basis. Many programs and platforms have variable reporting rates for containers and these can be commanded. As a result, this element is only useful to some users and generally does not affect the processing of the received containers themselves. See ContainerType. + + + + The measurement unit basis for the minimum and maximum appearance count values. + + + + + The minimum rate for the specified basis for which this container should appear in the stream. + + + + + The maximum rate for the specified basis for which this container should appear in the stream. + + + + + + Define the expected appearance (rate) of a container in a named stream where the rate is defined on either a perSecond or perContainer update basis. Many programs and platforms have variable reporting rates for containers and these can be commanded. As a result, this element is only useful to some users and generally does not affect the processing of the received containers themselves. See ContainerType and RateInStreamType. + + + + + + Reference to a named stream for which this rate specification applies. + + + + + + + + The location may be relative to the start of the container (containerStart), relative to the end of the previous entry (previousEntry), relative to the end of the container (containerEnd), or relative to the entry that follows this one (nextEntry). If going forward (containerStart and previousEntry) then the location refers to the start of the Entry. If going backwards (containerEnd and nextEntry) then, the location refers to the end of the entry. + + + + + + + + + + + + + + + + + Define one or more conditions (constraints) for container inheritance. A container is instantiable if its constraints are true. Constraint conditions may be a comparison, a list of comparisons, a boolean expression, or a graph of containers that are instantiable (if all containers are instantiable the condition is true). See BaseContainerType, ComparisonType, ComparisonListType, BooleanExpressionType and NextContainerType. + + + + + + + Reference to the named container that must follow this container in the stream sequence. + + + + + + + + + + + This schema defines the dictionary for telemetry + + + + Describe an absolute time parameter type relative to a known epoch (such as TAI). The string representation of this time should use the [ISO 8601] extended format CCYY-MM-DDThh:mm:ss where "CC" represents the century, "YY" the year, "MM" the month and "DD" the day, preceded by an optional leading "-" sign to indicate a negative number. If the sign is omitted, "+" is assumed. The letter "T" is the date/time separator and "hh", "mm", "ss" represent hour, minute and second respectively. Additional digits can be used to increase the precision of fractional seconds if desired i.e. the format ss.ss... with any number of digits after the decimal point is supported. See TAIType, IntegerDataEncoding and AbsoluteTimeDataType. + + + + + + + + Describe a complex data type analogous to a C-struct. Each field of the data type is called a Member. Each Member is part of the MemberList which forms the list of items to be placed under this data type’s name. The MemberList defines a data block and block’s size is defined by the DataEncodings of each Member’s type reference. The data members are ordered and contiguous in the MemberList element (packed). Each member may be addressed by the dot syntax similar to C such as P.voltage if P is the referring parameter and voltage is of a member of P’s aggregate type. See MemberType, MemberListType, DataEncodingType, NameReferenceType, and AggregateDataType. + + + + + + + + Describe an array parameter type. The size and number of dimensions are described here. See ArrayParameterRefEntryType, NameReferenceType and ArrayDataType. + + + + + + + Describe the dimensions of this array. + + + + + + + + + Describe a binary engineering/calibrated parameter type (sometimes called a “blob type”). It may be of fixed or variable length, and has an optional encoding and decoding algorithm that may be defined to transform the data between space and ground. See BinaryDataEncodingType, IntegerValueType, InputAlgorithmType and BinaryDataType. + + + + + + + Optionally describe an alarm monitoring specification that is effective whenever a contextual alarm definition does not take precedence. + + + + + Optionally describe one or more alarm monitoring specifications that are effective whenever a contextual match definition evaluates to true. The first match that evaluates to true takes precedence. + + + + + + + + + Describe a boolean parameter type which has two values only: ‘True’ (1) or ‘False’ (0). The values one and zero may be mapped to a specific string using the attributes oneStringValue and zeroStringValue. This type is a simplified form of the EnumeratedDataType. See IntegerDataEncoding and BooleanDataType. + + + + + + + Optionally describe an alarm monitoring specification that is effective whenever a contextual alarm definition does not take precedence. + + + + + Optionally describe one or more alarm monitoring specifications that are effective whenever a contextual match definition evaluates to true. The first match that evaluates to true takes precedence. + + + + + + + + + Describe an enumerated parameter type. The enumeration list consists of label/value pairs. See EnumerationListType, IntegerDataEncodingType and EnumeratedDataType. + + + + + + + Describe labels for this parameter that should be in an alarm state. The default definition applies when there are no context alarm definitions or all the context alarm definitions evaluate to false in their matching criteria. + + + + + Describe labels for this parameter that should be in an alarm state when another parameter and value combination evaluates to true using the described matching criteria. + + + + + + + + + Describe an ordered collection of context enumeration alarms, duplicates are valid. Process the contexts in list order. See EnumerationContextAlarmType. + + + + + Describe the alarm matching context criteria and the alarm definition itself. + + + + + + + Describe a floating point parameter type. Several encodings are supported. Calibrated integer to float relationships should be described with this data type. Use the data encoding to define calibrators. Joins integer as one of the numerics. See FloatDataEncodingType, IntegerDataEncodingType and FloatDataType. + + + + + + + Default alarm definitions are those which do not adjust definition logic based on the value of other parameters. Other parameters may participate in the determination of an alarm condition for this parameter, but the definition logic of the alarm on this parameter is constant. If the alarming logic on this parameter changes based on the value of other parameters, then it is a ContextAlarm and belongs in the ContextAlarmList element. + + + + + Context alarm definitions are those which adjust the definition logic for this parameter based on the value of other parameters. A context which evaluates to being in effect, based on the testing of another parameter, takes precedence over the default alarms in the DefaultAlarm element. If the no context alarm evaluates to being in effect, based on the testing of another parameter, then the default alarm definitions from the DefaultAlarm element will remain in effect. If multiple contexts evaluate to being in effect, then the first one that appears will take precedence. + + + + + + + + + Describe an integer parameter type. Several are supported. Calibrated integer to integer relationships should be described with this data type. Use the integer data encoding to define calibrators. Joins float as one of the numerics. See IntegerDataEncoding and IntegerDataType. + + + + + + + Default alarm definitions are those which do not adjust definition logic based on the value of other parameters. Other parameters may participate in the determination of an alarm condition for this parameter, but the definition logic of the alarm on this parameter is constant. If the alarming logic on this parameter changes based on the value of other parameters, then it is a ContextAlarm and belongs in the ContextAlarmList element. + + + + + Context alarm definitions are those which adjust the definition logic for this parameter based on the value of other parameters. A context which evaluates to being in effect, based on the testing of another parameter, takes precedence over the default alarms in the DefaultAlarm element. If the no context alarm evaluates to being in effect, based on the testing of another parameter, then the default alarm definitions from the DefaultAlarm element will remain in effect. If multiple contexts evaluate to being in effect, then the first one that appears will take precedence. + + + + + + + + + + + + + + An ordered collection of numeric alarms associated with a context. A context is an alarm definition on a parameter which is valid only in the case of a test on the value of other parameters. Process the contexts in list order. Used by both FloatParameterType and IntegerParameterType. See NumericContextAlarmType. + + + + + A contextual alarm definition for the parameter that uses this type that is valid when a test against the value of one or more other parameters evaluates to true. + + + + + + + A reference to an instance of a Parameter. Used when the value of a parameter is required for a calculation or as an index value. A positive value for instance is forward in time, a negative value for count is backward in time, a 0 value for count means use the current value of the parameter or the first value in a container. + + + + + + + + + + + Describes extended properties/attributes of Parameter definitions. + + + + + Optional. Normally used when the database is built in a flat, non-hierarchical format. + + + + + Optional condition that must be true for this Parameter to be valid. + + + + + When present, this set of elements describes physical address location(s) of the parameter where it is stored. Typically this is on the data source, although that is not constrained by this schema. + + + + + This time will override any Default value for TimeAssociation. + + + + + + This attribute describes the nature of the source entity for which this parameter receives a value. Implementations assign different attributes/properties internally to a parameter based on the anticipated data source. + + + + + A Parameter marked as 'readOnly' true is non-settable by users and applications/services that do not represent the data source itself. Note that a slight conceptual overlap exists here between the 'dataSource' attribute and this attribute when the data source is 'constant'. For a constant data source, then 'readOnly' should be 'true'. Application implementations may choose to implicitly enforce this. Some implementations have both concepts of a Parameter that is settable or non-settable and a Constant in different parts of their internal data model. + + + + + A Parameter marked to persist should retain the latest value through resets/restarts to the extent that is possible or defined in the implementation. The net effect is that the initial/default value on a Parameter is only seen once or when the system has a reset to revert to initial/default values. + + + + + + Describe the properties of a telemetry parameter, including its data type (parameter type). The bulk of properties associated with a telemetry parameter are in its parameter type. The initial value specified here, overrides the initial value in the parameter type. A parameter may be local, in which case its parameter type would have no data encodings. Ideally such a definition would also set data source in parameter properties to ‘local’ but the syntax does not enforce this. See BaseDataType, BaseTimeDataType, and NameReferenceType. + + + + + + + Specify additional properties for this Parameter used by the implementation of tailor the behavior and attributes of the Parameter. When not specified, the defaults on the ParameterProperties element attributes are assumed. + + + + + + Specify the reference to the parameter type from the ParameterTypeSet area using the path reference rules, either local to this SpaceSystem, relative, or absolute. + + + + + Specify as: integer data type using xs:integer, float data type using xs:double, string data type using xs:string, boolean data type using xs:boolean, binary data type using xs:hexBinary, enum data type using label name, relative time data type using xs:duration, absolute time data type using xs:dateTime. Values must not exceed the characteristics for the data type or this is a validation error. Takes precedence over an initial value given in the data type. Values are calibrated unless there is an option to override it. + The value type must match the Parameter type + + + + + + + + Describe an unordered collection of parameter type definitions. These types named for the engineering/calibrated type of the parameter. See BaseDataType and BaseTimeDataType. + + + + + Describe a parameter type that has an engineering/calibrated value in the form of a character string. + + + + + Describe a parameter type that has an engineering/calibrated value in the form of an enumeration. + + + + + Describe a parameter type that has an engineering/calibrated value in the form of an integer. + + + + + Describe a parameter type that has an engineering/calibrated value in the form of a binary (usually hex represented). + + + + + Describe a parameter type that has an engineering/calibrated value in the form of a decimal. + + + + + Describe a parameter type that has an engineering/calibrated value in the form of a boolean enumeration. + + + + + Describe a parameter type that has an engineering/calibrated value in the form of a duration in time. + + + + + Describe a parameter type that has an engineering/calibrated value in the form of an instant in time. + + + + + Describe a parameter type that has an engineering/calibrated value in the form of an array of a primitive type. + + + + + Describe a parameter type that has an engineering/calibrated value in the form of a structure of parameters of other types. + + + + + + + A reference to a Parameter. Uses Unix ‘like’ naming across the SpaceSystem Tree (e.g., SimpleSat/Bus/EPDS/BatteryOne/Voltage). To reference an individual member of an array use the zero based bracket notation commonly used in languages like C, C++, and Java. + + + + + + One or more physical addresses may be associated with each Parameter. Examples of physical addresses include a location on the spacecraft or a location on a data collection bus. + + + + + Contains the address (e.g., channel information) required to process the spacecraft telemetry streams. May be an onboard id, a mux address, or a physical location. + Contains the address (channel information) required to process the spacecraft telemetry streams + + + + + + + Describe the physical address(s) that this parameter is collected from. Examples of physical addresses include a memory location on the spacecraft or a location on a data collection bus, with the source identified with a descriptive name for the region of memory, such as RAM, Flash, EEPROM, and other possibilities that can be adapted for program specific usage. + + + + + A sub-address may be used to further specify the location if it fractionally occupies the address. Additional possibilities exist for separating partitions of memory or other address based storage mechanisms. This specification does not specify spacecraft specific hardware properties, so usage of addressing information is largely program and platform specific. + + + + + + A descriptive name for the location, such as a memory type, where this address is located. + + + + + The address within the memory location. This specification does not specify program and hardware specific attributes, such as address size and address region starting location. These are part of the spacecraft hardware properties. + + + + + + A service is a logical grouping of container and/or messages. + + + + + + + + Describes a string parameter type. Three forms are supported: fixed length, variable length and variable length using a prefix. See StringDataEncodingType and StringDataType. + + + + + + + Default alarm definitions are those which do not adjust definition logic based on the value of other parameters. Other parameters may participate in the determination of an alarm condition for this parameter, but the definition logic of the alarm on this parameter is constant. If the alarming logic on this parameter changes based on the value of other parameters, then it is a ContextAlarm and belongs in the ContextAlarmList element. + + + + + Context alarm definitions are those which adjust the definition logic for this parameter based on the value of other parameters. A context which evaluates to being in effect, based on the testing of another parameter, takes precedence over the default alarms in the DefaultAlarm element. If the no context alarm evaluates to being in effect, based on the testing of another parameter, then the default alarm definitions from the DefaultAlarm element will remain in effect. If multiple contexts evaluate to being in effect, then the first one that appears will take precedence. + + + + + + + + + Describes a relative time parameter type. Relative time parameters are time offsets (e.g. 10 second, 1.24 milliseconds, etc.) See IntegerDataEncodingType, FloatDataEncoding and RelativeTimeDataType. + + + + + + + Default alarm definitions are those which do not adjust definition logic based on the value of other parameters. Other parameters may participate in the determination of an alarm condition for this parameter, but the definition logic of the alarm on this parameter is constant. If the alarming logic on this parameter changes based on the value of other parameters, then it is a ContextAlarm and belongs in the ContextAlarmList element. + + + + + Context alarm definitions are those which adjust the definition logic for this parameter based on the value of other parameters. A context which evaluates to being in effect, based on the testing of another parameter, takes precedence over the default alarms in the DefaultAlarm element. If the no context alarm evaluates to being in effect, based on the testing of another parameter, then the default alarm definitions from the DefaultAlarm element will remain in effect. If multiple contexts evaluate to being in effect, then the first one that appears will take precedence. + + + + + + + + + A telemetered Parameter is one that will have values in telemetry. A derived Parameter is one that is calculated, usually by an Algorithm. A constant Parameter is one that is used as a constant in the system (e.g. a vehicle id). A local Parameter is one that is used purely by the software locally (e.g. a ground command counter). A ground Parameter is one that is generated by an asset which is not the spacecraft. + + + + + + + + + + + + Describes a time association consisting of an instance of an absolute time parameter (parameterRef) and this entry. Because telemetry parameter instances are oftentimes "time-tagged" with a timing signal either provided on the ground or on the space system. This data element allows one to specify which of possibly many AbsoluteTimeParameters to use to "time-tag" parameter instances with. See AbsoluteTimeParameterType. + + + + + + If true, then the current value of the AbsoluteTime will be projected to current time. In other words, if the value of the AbsoluteTime parameter was set 10 seconds ago, then 10 seconds will be added to its value before associating this time with the parameter. + + + + + The offset is used to supply a relative time offset from the time association and to this parameter + + + + + Specify the units the offset is in, the default is si_second. + + + + + + + + + + + + + + + + This schema defines the dictionary for commanding + + + + Describe an absolute time argument type relative to a known epoch (such as TAI). The string representation of this time should use the [ISO 8601] extended format CCYY-MM-DDThh:mm:ss where "CC" represents the century, "YY" the year, "MM" the month and "DD" the day, preceded by an optional leading "-" sign to indicate a negative number. If the sign is omitted, "+" is assumed. The letter "T" is the date/time separator and "hh", "mm", "ss" represent hour, minute and second respectively. Additional digits can be used to increase the precision of fractional seconds if desired i.e. the format ss.ss... with any number of digits after the decimal point is supported. See TAIType, IntegerDataEncoding and AbsoluteTimeDataType. + + + + + + + + Describe an array argument type. The size and number of dimension are described here. See ArrayParameterRefEntryType, NameReferenceType and ArrayDataType. + + + + + + + Describe the dimensions of this array. + + + + + + + + + Describe a complex data type analogous to a C-struct. Each field of the data type is called a Member. Each Member is part of the MemberList which forms the list of items to be placed under this data type’s name. The MemberList defines a data block and block’s size is defined by the DataEncodings of each Member’s type reference. The data members are ordered and contiguous in the MemberList element (packed). Each member may be addressed by the dot syntax similar to C such as P.voltage if P is the referring parameter and voltage is of a member of P’s aggregate type. See MemberType, MemberListType, DataEncodingType, NameReferenceType, and AggregateDataType. + + + + + + + + Argument Assignments specialize a MetaCommand or BlockMetaCommand when inheriting from another MetaCommand. General argument values can be restricted to specific values to further specialize the MetaCommand. Use it to ‘narrow’ a MetaCommand from its base MetaCommand by specifying values of arguments for example, a power command may be narrowed to a power on’ command by assigning the value of an argument to ‘on’. See ArgumentAssignmentType and MetaCommandType. + + + + + Specialize this command definition when inheriting from a more general MetaCommand by restricting the specific values of otherwise general arguments. + + + + + + + Describe an assignment of an argument with a calibrated/engineering value. See ArgumentAssignmentListType. + + + + The named argument from the base MetaCommand to assign/restrict with a value. + + + + + Specify value as a string compliant with the XML schema (xs) type specified for each XTCE type: integer=xs:integer; float=xs:double; string=xs:string; boolean=xs:boolean; binary=xs:hexBinary; enum=xs:string from EnumerationList; relative time=xs:duration; absolute time=xs:dateTime. Supplied value must be within the ValidRange specified for the type. + + + + + + Identical to ComparisonType but supports argument instance references. + + + + + This parameter instance is being compared to the value in the parent element using the comparison defined there also. + + + + + This argument instance is being compared to the value in the parent element using the comparison defined there also. + + + + + + Comparison operator to use with equality being the common default. + + + + + Specify as: integer data type using xs:integer, float data type using xs:double, string data type using xs:string, boolean data type using xs:boolean, binary data type using xs:hexBinary, enum data type using label name, relative time data type using xs:duration, absolute time data type using xs:dateTime. Values must not exceed the characteristics for the data type or this is a validation error. Takes precedence over an initial value given in the data type. Values are calibrated unless there is an option to override it. + + + + + + Identical to ComparisonCheckType but supports argument instance references. + + + + + + + + Left hand side parameter instance. + + + + + Left hand side argument instance. + + + + + + Comparison operator. + + + + + + + Right hand side parameter instance. Parameter is assumed to be of the same type as the comparison Argument or Parameter. + + + + + Right hand side argument instance. Argument is assumed to be of the same type as the comparison Argument or Parameter. + + + + + + Specify as: integer data type using xs:integer, float data type using xs:double, string data type using xs:string, boolean data type using xs:boolean, binary data type using xs:hexBinary, enum data type using label name, relative time data type using xs:duration, absolute time data type using xs:dateTime. Values must not exceed the characteristics for the data type or this is a validation error. Takes precedence over an initial value given in the data type. Values are calibrated unless there is an option to override it. + + + + + + + + + + Identical to ComparisonListType but supports argument instance references. + + + + + List of Comparison elements must all be true for the comparison to evaluate to true. + + + + + + + Identical to ArgumentDiscreteLookupType but supports argument instance references. + + + + + + Value to use when the lookup conditions are true. + + + + + + + + Identical to DiscreteLookupListType but supports argument instance references. + + + + + Describe a lookup condition set using discrete values from arguments and/or parameters. + + + + + + + Identical to DynamicValueType but supports argument instance references. + + + + + + Retrieve the value by referencing the value of an Argument. + + + + + Retrieve the value by referencing the value of a Parameter. + + + + + + A slope and intercept may be applied to scale or shift the value selected from the argument or parameter. + + + + + + + Identical to InputAlgorithmType but supports argument instance references. + + + + + + + The InputSet describes the list of arguments and/or parameters that should be made available as input arguments to the algorithm. + + + + + + + + + Identical to InputSetType but supports argument instance references. + + + + + Reference a parameter to serve as an input to the algorithm. + + + + + Reference an argument to serve as an input to the algorithm. + + + + + + + An argument instance is the name of an argument as the reference is always resolved locally to the metacommand. + + + + Give the name of the argument. There is no path, this is a local reference. + + + + + Typically the calibrated/engineering value is used and that is the default. + + + + + + Defines a list of Arguments for a command definition. + + + + + Defines an Argument for a command definition. Arguments are local to the MetaCommand, BlockMetaCommand, and those that inherit from the definition. + Need to ensure that the named types actually exist + + + + + + + Identical to BooleanExpressionType but supports argument instance references. + + + + + Condition elements describe a test similar to the Comparison element except that the arguments/parameters used have additional flexibility. + + + + + This element describes tests similar to the ComparisonList element except that the arguments/parameters used are more flexible. + + + + + This element describes tests similar to the ComparisonList element except that the arguments/parameters used are more flexible. + + + + + + + Identical to ANDedConditionsType but supports argument instance references. + + + + + + + Condition elements describe a test similar to the Comparison element except that the arguments/parameters used have additional flexibility for the compare. + + + + + This element describes tests similar to the ComparisonList element except that the arguments/parameters used are more flexible and the and/or for multiple checks can be specified. + + + + + + + + + Identical to ORedConditionsType but supports argument instance references. + + + + + + + Condition elements describe a test similar to the Comparison element except that the arguments/parameters used have additional flexibility for the compare. + + + + + This element describes tests similar to the ComparisonList element except that the arguments/parameters used are more flexible and the and/or for multiple checks can be specified. + + + + + + + + + Identical to MatchCriteriaType but supports argument instance references. + + + + + A simple comparison check involving a single test of an argument or parameter value. + + + + + A series of simple comparison checks with an implicit 'and' in that they all must be true for the overall condition to be true. + + + + + An arbitrarily complex boolean expression that has additional flexibility on the terms beyond the Comparison and ComparisonList elements. + + + + + An escape to an externally defined algorithm. + + + + + + + An Argument has a name and can take on values with the underlying value type described by the ArgumentTypeRef. Describe the properties of a command argument referring to a data type (argument type). The bulk of properties associated with a command argument are in its argument type. The initial value specified here, overrides the initial value in the argument type. See BaseDataType, BaseTimeDataType and NameReferenceType. + + + + + + Specify the reference to the argument type from the ArgumentTypeSet area using the path reference rules, either local to this SpaceSystem, relative, or absolute. + + + + + Specify as: integer data type using xs:integer, float data type using xs:double, string data type using xs:string, boolean data type using xs:boolean, binary data type using xs:hexBinary, enum data type using label name, relative time data type using xs:duration, absolute time data type using xs:dateTime. Values must not exceed the characteristics for the data type or this is a validation error. Takes precedence over an initial value given in the data type. Values are calibrated unless there is an option to override it. + The value type must match the Argument type + + + + + + + + Describe an unordered collection of argument type definitions. These types named for the engineering/calibrated type of the argument. See BaseDataType and BaseTimeDataType. + + + + + Describe an argument type that has an engineering/calibrated value in the form of a character string. + + + + + Describe an argument type that has an engineering/calibrated value in the form of an enumeration. + + + + + Describe an argument type that has an engineering/calibrated value in the form of an integer. + + + + + Describe an argument type that has an engineering/calibrated value in the form of a binary (usually hex represented). + + + + + Describe an argument type that has an engineering/calibrated value in the form of a decimal. + + + + + Describe an argument type that has an engineering/calibrated value in the form of a boolean enumeration. + + + + + Describe an argument type that has an engineering/calibrated value in the form of a duration in time. + + + + + Describe an argument type that has an engineering/calibrated value in the form of an instant in time. + + + + + Describe an argument type that has an engineering/calibrated value in the form of an array of a primitive type. + + + + + Describe an argument type that has an engineering/calibrated value in the form of a structure of arguments of other types. + + + + + + + When specified, a BaseMetaCommand element identifies that this MetaCommand inherits (extends) another MetaCommand. It’s required ArgumentAssignmentList narrows or this command from the parent. This is typically used when specializing a generic MetaCommand to a specific MetaCommand. See MetaCommandType. + + + + + Argument Assignments specialize a MetaCommand or BlockMetaCommand when inheriting from another MetaCommand. General argument values can be restricted to specific values to further specialize the MetaCommand. + + + + + + Reference to the MetaCommand definition that this MetaCommand extends. + + + + + + Defines a binary engineering/calibrated argument type (often called “blob type”). The binary data may be of fixed or variable length, and has an optional encoding and decoding algorithm that may be defined to transform the data between space and ground. See BinaryDataEncodingType, IntegerValueType, InputAlgorithmType, and BinaryDataType. + + + + + + + + Describe an ordered grouping of MetaCommands into a list, duplicates are valid. The block contains argument values fully specified. See MetaCommandStepListType. + + + + + + + List of the MetaCommands to include in this BlockMetaCommand. + + + + + + + + + Defines a boolean argument type which has two values only: ‘True’ (1) or ‘False’ (0). The values one and zero may be mapped to a specific string using the attributes oneStringValue and zeroStringValue. This type is a simplified form of the EnumeratedDataType. See IntegerDataEncoding and BooleanDataType. + + + + + + + + Describe an entry list for a CommandContainer which is associated with a MetaCommand. The entry list for a MetaCommand CommandContainer element operates in a similar fashion as the entry list element for a SequenceContainer element. It adds fixed value and argument entries to the entry list not present in sequence containers. See MetaCommandType, CommandContainerType and EntryListType. + + + + + Specify a Parameter to be a part of this container layout definition. + + + + + Specify a portion of a Parameter to be a part of this container layout definition. This is used when the Parameter is reported in fractional parts in the container before being fully updated. + + + + + Specify the content of another Container to be a part of this container layout definition. + + + + + Specify a portion of another Container to be a part of this container layout definition. + + + + + Specify a portion of a Stream to be a part of this container layout definition. + + + + + Specify a previous (not last reported) value of a Parmeter to be a part of this container layout definition. + + + + + Specify an Array Type Parameter to be a part of this container layout definition when the Container does not populate the entire space of the Array contents. If the entire space of the Array is populated, a tolerant implementation will accept ParameterRefEntry also. + + + + + Specify an Argument to be a part of this container layout definition. + + + + + Specify an Array Type Argument to be a part of this container layout definition when the Container does not populate the entire space of the Array contents. If the entire space of the Array is populated, a tolerant implementation will accept ArgumentRefEntry also. + + + + + Specify an immutable value to be a part of this container layout definition. + + + + + + + Contains an unordered Set of Command Containers + + + + + + + + Describe a MetaCommand command container. The command container may contain arguments, parameters, other basic containers, and fixed values. Arguments are supplied by the user of a commanding application; parameters are supplied by the controlling system. Parameters and arguments map source data types to encodings. See MetaCommandType. + + + + + + + List of item entries to pack/encode into this container definition. + + + + + When a MetaCommand inherits/extends another MetaCommand, this references the CommandContainer from the BaseMetaCommand. + + + + + + + + + A command verifier is used to check that the command has been successfully executed. Command Verifiers may be either a Custom Algorithm or a Boolean Check or the presence of a Container for a relative change in the value of a Parameter. The CheckWindow is a time period where the verification must test true to pass. + + + + + + + + Verification is a list of comparisons. + + + + + Verification is a new instance of the referenced container. For example, sending a command to download memory then receiving a packet with the memory download would be verified upon receipt of the packet. + + + + + Verification is a telemetry parameter value change on the ground. For example, a command counter. + + + + + Verification is outside the scope of regular command and telemetry processing. + + + + + Verification is a boolean expression of conditions. + + + + + Verification is a single comparison. + + + + + + + Define a time window for checking for verification. + + + + + Define a time window algorithmically for verification. + + + + + + + + + + Describes an enumerated argument type. The enumeration list consists of label/value pairs. See EnumerationListType, IntegerDataEncodingType and EnumeratedDataType. + + + + + + + + Describe a floating point argument type. Several encodings are supported. Calibrated integer to float relationships should be described with this data type. Use the data encoding to define calibrators. Joins integer as one of the numerics. See FloatDataEncodingType, IntegerDataEncodingType and FloatDataType. + + + + + + + Provides additional platform/program specific ranging information. + + + + + + + + + Describes an integer argument type. Several encodings supported. Calibrated integer to integer relationships should be described with this data type. Use the integer data encoding to define calibrators. Joins float as one of the numerics. See IntegerDataEncoding and IntegerDataType. + + + + + + + Provides additional platform/program specific ranging information. + + + + + + + + + Describes an unordered collection of command definitions. Duplicates are invalid based on the name attribute of MetaCommand and BlockMetaCommand. See MetaCommandType and BlockMetaCommandType. + + + + + All atomic commands to be sent on this mission are listed here. In addition this area has verification and validation information. + + + + + + + + + Used to include a MetaCommand defined in another sub-system in this sub-system. + + + + + Used to define a command that includes more than one atomic MetaCommand definition. + + + + + + + Describe the list of MetaCommand definitions that form the block command. Contains an ordered list of MetaCommandSteps where each step is a MetaCommand with associated arguments, duplicates are valid. See BlockMetaCommandType. + + + + + A MetaCommand with specific specified argument values to include in the BlockMetaCommand. + + + + + + + Describe a MetaCommand step, consisting MetaCommand reference and argument list. See MetaCommandStepListType and NameReferenceType. + + + + + + + + + Describe a command which consists of an abstract portion (MetaCommand) and an optional packaging portion (MetaCommand CommandContainer). An argument list is provided. MetaCommand may extend other MetaCommands and their CommandContainer may extend other CommandContainer or SequenceContainers. A MetaCommand’s CommandContainer is private except as referred to in BaseMetaCommand (they are not visible to other containers and cannot be used in an entry list). MetaCommands may also define various other behavioral aspects of a command such as command verifiers. See CommandContainerType, ArgumentListType, BaseMetaCommandType and BaseContainerType. + + + + + + + Optional inheritance for this MetaCommand from another named MetaCommand. + + + + + Optional. Normally used when the database is built in a flat, non-hierarchical format. May be used by implementations to group MetaCommands together. + + + + + Many commands have one or more options. These are called command arguments. Command arguments may be of any of the standard data types. MetaCommand arguments are local to the MetaCommand, but may be referenced in inherited MetaCommand definitions, generally to apply Argument Assignments to the values. + + + + + Tells how to package/encode this command definition in binary form. + + + + + List of constraints to check when sending this command. + + + + + Some Command and Control Systems may require special user access or confirmations before transmitting commands with certain levels. The level is inherited from the Base MetaCommand. + + + + + Some Command and Control Systems may require special user access or confirmations before transmitting commands with certain levels. In addition to the default, Significance can be defined in contexts where it changes based on the values of parameters. + + + + + An Interlock is a type of Constraint, but not on Command instances of this MetaCommand; Interlocks apply instead to the next command. An Interlock will block successive commands until this command has reached a certain stage (through verifications). Interlocks are scoped to a SpaceSystem basis. + + + + + Functional list of conditions/changes to check after sending this command to determine success or failure. + + + + + List of parameters to set new values upon completion of sending this command. + + + + + List of parameters to suspend alarm processing/detection upon completion of sending this command. + + + + + + Abstract MetaCommand definitions that are not instantiated, rather only used as bases to inherit from to create specialized command definitions. + + + + + + + + Describes a relative time argument type. Relative time parameters are time offsets (e.g. 10 second, 1.24 milliseconds, etc.) See IntegerDataEncodingType, FloatDataEncoding and RelativeTimeDataType. + + + + + + + + Significance provides some cautionary information about the potential consequence of each MetaCommand. + + + + If none is supplied, then the current SpaceSystem is assumed to be the one at risk by the issuance of this command + + + + + + + + Describes a string parameter type. Three forms are supported: fixed length, variable length and variable length using a prefix. See StringDataEncodingType and StringDataType. + + + + + + + + + + A verifier that means the SpaceSystem has accepted the command + + + + + + + + Used by CommandVerifiers to limit the time allocated to check for the verification. See CheckWindowAlgorithmsType. + + + + + + + + Used by CommandVerifiers to limit the time allocated to check for the verification. See CommandVerifierType. + + + + + + + + + A possible set of verifiers that all must be true for the command be considered completed. + + + + + + + + + + + + Describe a significance level for a MetaCommand definition where the significance level depends on matching a context value. See ContextMatchType and SignificanceType. + + + + + Describe the context matching value and source that will enable the Significance listed in the Significance element. + + + + + Describe the signficance of this MetaCommand definition. See SignificanceType. + + + + + + + Describe an ordered list of ContextSignificance elements where the significance on the first context match to test true is used as the significance of the MetaCommand. If there is a DefaultSignificance, it is overrideen by the matching context. See ContextSignificantType and MetaCommandType. + + + + + Describe a significance level for a MetaCommand definition where the significance level depends on matching a context value. See ContextMatchType and SignificanceType. + + + + + + + A verifier that indicates that the command is being executed. An optional Element indicates how far along the command has progressed either as a fixed value or an (possibly scaled) ParameterInstance value. + + + + + + + + + + + + When true, indicates that the command failed. timeToWait is how long to wait for the FailedVerifier to test true. + + + + + + + + + + + + Describe a type of constraint on the next command, rather than this command. Interlocks apply only to the next command. An interlock will block successive commands until this command has reached a certain stage of verifier. Interlocks are scoped to a SpaceSystem basis: they by default apply to the SpaceSystem the MetaCommand is defined in but this may be overridden. See MetaCommandType and VerifierSetType. + + + + The name of a SpaceSystem this Interlock applies to. By default, it only applies to the SpaceSystem that contains this MetaCommand. + + + + + The verification stage of the command that releases the interlock, with the default being complete. + + + + + Only applies when the verificationToWaitFor attribute is 'queued' or 'executing'. + + + + + A flag that indicates that under special circumstances, this Interlock can be suspended. + + + + + + Sets a Parameter to a new value (either from a derivation or explicitly) after the command has been verified (all verifications have passed). + Value type must match Parameter type. + + + + + + + Specify a MathOperation to use to set the Parameter value. See MathOperationType. + + + + + Specify value as a string compliant with the XML schema (xs) type specified for each XTCE type: integer=xs:integer; float=xs:double; string=xs:string; boolean=xs:boolean; binary=xs:hexBinary; enum=xs:string from EnumerationList; relative time= xs:duration; absolute time=xs:dateTime. Supplied value must be within the ValidRange specified for the Parameter and appropriate for the type. + + + + + + This attribute provides more specific control over when the Parameter value is set. By default, it is when the command have all verifications complete. See VerifierEnumerationType. + + + + + + + + Parameters that are set with a new value after the command has been sent. Appended to the Base Command list + + + + + + + + Will suspend all Alarms associated with this Parameter for the given suspense time after the given verifier + + + + + + + + + + + Sometimes it is necessary to suspend alarms - particularly 'change' alarms for commands that will change the value of a Parameter + + + + + + + + A parameter change in value or specified delta change in value. + + + + + + + + + A verifer that means the command is scheduled for execution by the SpaceSystem. + + + + + + + + A verifier that simply means the SpaceSystem has received the command. + + + + + + + + Sent from range means the command has been transmitted to the spacecraft by the network that connects the ground system to the spacecraft. Obviously, this verifier must come from something other than the spacecraft. + + + + + + + + Time units the time association decimal value is in. + + + + + + + + + + + + + + Transferred to range means the command has been received to the network that connects the ground system to the spacecraft. Obviously, this verifier must come from something other than the spacecraft. + + + + + + + + A CommandTransmission constraint is used to check that the command can be run in the current operating mode and may block the transmission of the command if the constraint condition is true. + + + + + + Pause during timeOut, fail when the timeout passes + + + + + + Indicates whether the constraints for a Command may be suspended. + + + + + + + + Appended to the TramsmissionConstraint List of the base command. Constraints are checked in order. + + + + + + + + An enumerated list of verifier types + + + + + + + + + + + + + + + + Describe a collection of unordered verifiers. A command verifier is a conditional check on the telemetry from a SpaceSystem that that provides positive indication on the processing state of a command. There are eight different verifiers each associated with difference states in command processing: TransferredToRange, TransferredFromRange, Received, Accepted, Queued, Execution, Complete, and Failed. There may be multiple ‘complete’ and 'execution' verifiers. If the MetaCommand is part of an inheritance relation (BaseMetaCommand), the 'complete' and 'execution' verifier sets are appended to any defined in the parent MetaCommand. All others will override a verifier defined in a BaseMetaCommand. Duplicate verifiers in the list of CompleteVerifiers and ExecutionVerifiers before and after appending to the verifiers in BaseMetaCommand should be avoided. See MetaCommandType and BaseMetaCommandType for additional information. + + + + + + + + + + + + + + + + + This schema defines the structure for an Algorithm. An Algorithm may be one of a growing set of pre-defined algorithms or a named escape into a user defined algorithm where (depending on the system) the name of the algorithm may be a java class, a function in a shared library, an external program or some other reference to an outside algorithm. At some later date, this schema may also allow the logic of the user defined algorithm to be defined within the instance document itself (perhaps using MathML?). + + + + This optional element may be used to enter Pseudo or actual code for the algorithm. The language for the algorithm is specified with the language attribute + + + + + + + + + + A base type for the various triggers, purely to improve the mappings created by data binding compilers. + + + + + Describe checksum information. + + + + + Assumed to return the computed checksum. + + + + + + + + Qualified list of name checksum algorithms. If custom is chosen, InputAlgorithm must be set. + + + + + + + + + + + + + + + + + + + Document a custom checksum algorithm + + + + + + + + + + Names and provides a value for a constant input to the algorithm. There are two attributes to Constant, constantName and value. constantName is a variable name in the algorithm to be executed. value is the value of the constant to be used. + + + + + + + Describe an ordered list of calibrators with a context match. Useful when different calibrations must be used depending on a matching value. The first context that matches determines which calibrator to use. See IntegerDataEncodingType and FloatDataEncodingType. + + + + + Describe a calibrator that depends on a matching value using a ContextMatch. When the context matches for the calibrator, the default calibrator is overridden, if it exists. + + + + + + + This is the external algorithm. Multiple entries are provided so that the same database may be used for multiple implementation s + + + + + + + + + + + + A set of labeled inputs is added to the SimpleAlgorithmType + + + + + + + The InputSet describes the list of parameters that should be made available as input arguments to the algorithm. + + + + + + + + + A set of labeled outputs are added to the SimpleInputAlgorithmType + + + + + + + + + + + + + Input output algorithm is extended with a set of labeled triggers. See InputOutputAlgorithmType. + + + + + + + + + First telemetry container from which the output parameter should be calculated. + + + + + Algorithm processing priority. If more than one algorithm is triggered by the same container, the lowest priority algorithm should be calculated first. + + + + + + + + Names an input parameter to the algorithm. There are two attributes to InputParm, inputName and parameterName. parameterName is a parameter reference name for a parameter that will be used in this algorithm. inputName is an optional "friendly" name for the input parameter. + + + + + + + + + + + + + + + + Describe a postfix (Reverse Polish Notation (RPN)) notation based mathmatical equations. See MathOperationType. + + + + + + + The contents of the Math Operation as an algorithm definition in RPN. See TriggeredMathOperationType. + + + + + + + + + Describe a reference to container that triggers an event when the telemetry container referred to is updated (processed). See TriggerSetType. + + + + + + Reference to the Container whose update/receipt triggers this algorithm to evaluate. + + + + + + + + Describe a periodic time basis to trigger an event. See TriggerSetType. + + + + + + The periodic rate in time in which this algorithm is triggered to evaluate. + + + + + + + + Describe a reference to parameter that triggers an event when the telemetry parameter referred to is updated (processed) with a new value. See TriggerSetType. + + + + + + Reference to the Parameter whose update triggers this algorithm to evaluate. + + + + + + + + Names an output parameter to the algorithm. There are two attributes to OutputParm, outputName and parameterName. parameterName is a parameter reference name for a parameter that will be updated by this algorithm. outputName is an optional "friendly" name for the output parameter. + + + + + + + + + + + + + + + The simplest form of algorithm, a SimpleAlgorithmType contains an area for a free-form pseudo code description of the algorithm plus a Set of references to external algorithms. External algorithms are usually unique to a ground system type. Multiple external algorithms are possible because XTCE documents may be used across multiple ground systems. + + + + + + + + + + + + + + + + + + + + + + + A trigger is used to initiate the processing of some algorithm. A trigger may be based on an update of a Parameter, receipt of a Container, or on a time basis. Triggers may also have a maximum rate that limits how often the trigger can be invoked. + + + + + This element instructs the trigger to invoke the algorithm evaluation when a Parameter update is received. + + + + + This element instructs the trigger to invoke the algorithm evaluation when a Container is received. + + + + + This element instructs the trigger to invoke the algorithm evaluation using a timer. + + + + + + Triggers may optionally be named. + + + + + This attribute is a maximum rate that constrains how quickly this trigger may evaluate the algorithm to avoid flooding the implementation. The default is once per second. Setting to 0 results in no maximum. + + + + + + + + Supplies an optional non-reference-able name and short description for calibrators. Also includes an optional ancillary data for any special local flags, note that these may not necessarily transfer to another recipient of an instance document. + + + + + Optional additional ancillary information for this calibrator/algorithm + + + + + + Optional name for this calibrator/algorithm + + + + + Optional description for this calibrator/algorithm + + + + + + Describe a calibrator to transform a source data type raw/uncalibrated value (e.g. an integer count from a spacecraft) to an engineering unit/calibrated value for users (e.g. a float). + + + + + + + Describes a calibrator in the form of a piecewise defined function + + + + + Describes a calibrator in the form of a polynomial function + + + + + Describes a calibrator in the form of a user/program/implementation defined function + + + + + + + + + Describe a change value used to test verification status. See CommandVerifierType. + + + + Value as a floating point number. + + + + + + Describe a mathematical function for calibration where the mathematical function is defined using the MathOperationType. + + + + + + Describe a postfix (aka Reverse Polish Notation (RPN)) expression for mathematical equations. It uses a stack where operands (either fixed values or ParameterInstances) are pushed onto the stack from first to last in the XML. As the operators are specified, each pops off operands as it evaluates them, and pushes the result back onto the stack. For example, the stack, 4 8 /, would result as 0.5. In this case postfix is used to avoid having to specify parenthesis. To convert from infix to postfix, use Dijkstra's "shunting yard" algorithm. + + + + Use a constant in the calculation. + + + + + Use the value of this parameter in the calculation. It is the calibrator's value only. If the raw value is needed, specify it explicitly using ParameterInstanceRefOperand. Note this element has no content. + + + + + All operators utilize operands on the top values in the stack and leaving the result on the top of the stack. Ternary operators utilize the top three operands on the stack, binary operators utilize the top two operands on the stack, and unary operators use the top operand on the stack. + + + + + This element is used to reference the last received/assigned value of any Parameter in this math operation. + + + + + + + + + Describe a polynomial equation for calibration. This is a calibration type where a curve in a raw vs calibrated plane is described using a set of polynomial coefficients. Raw values are converted to calibrated values by finding a position on the curve corresponding to the raw value. The first coefficient belongs with the X^0 term, the next coefficient belongs to the X^1 term and so on. See CalibratorType. + + + + + + + A single term in the polynomial function. + Generally only up to second order powers are reflexive. Implementations may limit the maximum number of terms supported. + + + + + + + + + Describe a spline function for calibration using a set of at least 2 points. Raw values are converted to calibrated values by finding a position on the line corresponding to the raw value. The line may be interpolated and/or extrapolated as needed. The interpolation order may be specified for all the points and overridden on individual points. The algorithm triggers on the input parameter. See CalibratorType. + + + + + + + Describes a single point of the spline or piecewise function. + + + + + + The interpolation order to apply to the overall spline function. Order 0 is no slope between the points (flat). Order 1 is linear interpolation. Order 2 would be quadratic and in this special case, 3 points would be required, etc. + + + + + Extrapolation allows the closest outside point and the associated interpolation to extend outside of the range of the points in the spline function. + + + + + + + + + + This schema provides a language for defining binary stream data. + + + + After searching for the frame sync marker for some number of bits, it may be desirable to invert the incoming data, and then look for frame sync. In some cases this will require an external algorithm + + + + + + + + + A stream type where some level of custom processing (e.g. convolutional, encryption, compression) is performed. Has a reference to external algorithms for encoding and decoding algorithms. + Must check to ensure that the attributes encodedStreamRef and decodedStreamRef point to valid Streams + + + + + + + + Algorithm outputs may be used to set decoding quality parameters. + + + + + + + + + + + + + + + + + The pattern of bits used to look for frame synchronization. + + + + + + + The top level type definition for all data streams that are frame based. + + + + + + + + This Container (usually abstract) is the container that is in the fixed frame stream. Normally, this is a general container type from which many specific containers are inherited. + + + + + + + This is a reference to a connecting stream - say a custom stream. + + + + + + + + + For streams that contain a series of frames with a fixed frame length where the frames are found by looking for a marker in the data. This marker is sometimes called the frame sync pattern and sometimes the Asynchronous Sync Marker (ASM). This marker need not be contiguous although it usually is. + + + + + + + + + Allowed slip (in bits) in either direction for the sync pattern + + + + + + + + + Describe a sync pattern and an optional reference to an algorithm used to invert the stream if the frame sync pattern is not found. See FixedFrameStreamType. + + + + + + + The pattern of bits used to look for frame synchronization. See SyncPatternType. + + + + + + + + + A PCM Stream Type is the high level definition for all Pulse Code Modulated (PCM) (i.e., binary) streams. + + + + + + + + + + + + + + + + + + + + + + Holds a reference to a stream + + + + name of reference stream + + + + + + Contains an unordered set of Streams. + + + + + + + + + + A Sync Strategy specifies the strategy on how to find frames within a stream of PCM data. The sync strategy is based upon a state machine that begins in the 'Search' state until the first sync marker is found. Then it goes into the 'Verify' state until a specified number of successive good sync markers are found. Then, the state machine goes into the 'Lock' state, in the 'Lock' state frames are considered good. Should a sync marker be missed in the 'Lock' state, the state machine will transition into the 'Check' state, if the next sync marker is where it's expected within a specified number of frames, then the state machine will transition back to the 'Lock' state, it not it will transition back to 'Search'. + + + + + + + + + Maximum number of bit errors in the sync pattern (marker). + + + + + + The pattern of bits used to look for frame synchronization. + + + + CCSDS ASM for non-turbocoded frames = 1acffc1d + + + + + + + truncate the mask from the left + + + + + truncate the pattern from the left + + + + + + For streams that contain a series of frames with a variable frame length where the frames are found by looking for a series of one's or zero's (usually one's). The series is called the flag. in the PCM stream that are usually made to be illegal in the PCM stream by zero or one bit insertion. + + + + + + + + + + + + + + + + + + + + + + + + A base schema type for describing an absolute time data type. Contains an absolute (to a known epoch) time. Use the [ISO 8601] extended format CCYY-MM-DDThh:mm:ss where "CC" represents the century, "YY" the year, "MM" the month and "DD" the day, preceded by an optional leading "-" sign to indicate a negative number. If the sign is omitted, "+" is assumed. The letter "T" is the date/time separator and "hh", "mm", "ss" represent hour, minute and second respectively. Additional digits can be used to increase the precision of fractional seconds if desired i.e. the format ss.ss... with any number of digits after the decimal point is supported. See AbsoluteTimeParameterType and AbsoluteTimeArgumentType. See AbsouteTimeParameterType, AbsoluteTimeArgumentType and BaseTimeDataType. + + + + + + Default/Initial value is always given in calibrated form. + + + + + + + + A base schema type for describing an absolute time data type. Contains an absolute (to a known epoch) time. Use the [ISO 8601] extended format CCYY-MM-DDThh:mm:ss where "CC" represents the century, "YY" the year, "MM" the month and "DD" the day, preceded by an optional leading "-" sign to indicate a negative number. If the sign is omitted, "+" is assumed. The letter "T" is the date/time separator and "hh", "mm", "ss" represent hour, minute and second respectively. Additional digits can be used to increase the precision of fractional seconds if desired i.e. the format ss.ss... with any number of digits after the decimal point is supported. See AbsoluteTimeParameterType and AbsoluteTimeArgumentType. See AbsouteTimeParameterType, AbsoluteTimeArgumentType and BaseTimeDataType. + + + + + + Default/Initial value is always given in calibrated form. + + + + + + + + A base schema type for describing a complex data type analogous to a C-struct. Each field of the data type is called a Member. Each Member is part of the MemberList which forms the list of items to be placed under this data type’s name. The MemberList defines a data block and block’s size is defined by the DataEncodings of each Member’s type reference. The data members are ordered and contiguous in the MemberList element (packed). Each member may be addressed by the dot syntax similar to C such as P.voltage if P is the referring parameter and voltage is of a member of P’s aggregate type. See MemberType, MemberListType, DataEncodingType, NameReferenceType, AggregateParameterType and AggregateArgumentType. + + + + + + + Ordered list of the members of the aggregate/structure. Members are contiguous. + + + + + + + + + A base schema type for describing an array data type. The number of and size of each dimension is defined in its two child types. See NameReferenceType, ArrayArgumentType and ArrayParameterType. + + + + + + Reference to the data type that represents the type of the elements for this array. + + + + + + + + An abstract schema type used by within the schema to derive the other simple/primitive engineering form data types: BooleanDataType, BinaryDataType, StringDataType, EnumeratedDataType, FloatDataType and IntegerDataType. The encoding elements are optional because they describe the raw wire encoded form of the data type. Encoding is only necessary when the type is telemetered in some form. Local variables and derived typically do not require encoding. + + + + + + + When appropriate, describe the units of measure that are represented by this parameter value. + + + + + + Binary encoding is typically a "pass through" raw encoding form where one of the more common encodings is not required for the parameter. A custom transformation capability is available if needed. + + + + + Float encoding is a common encoding where the raw binary is in a form that gets interpreted as a decimal numeric value. + + + + + Integer encoding is a common encoding where the raw binary is in a form that gets interpreted as an integral value, either signed or unsigned. + + + + + String encoding is a common encoding where the raw binary is in a form that gets interpreted as a character sequence. + + + + + + + Must be derived from a like type (e.g,, String from String). No circular derivations. + Used to derive one Data Type from another - will inherit all the attributes from the baseType any of which may be redefined in this type definition. + + + + + + + + Identical to BaseDataType but supports argument instance references. + + + + + + + When appropriate, describe the units of measure that are represented by this argument value. + + + + + + Binary encoding is typically a "pass through" raw encoding form where one of the more common encodings is not required for the argument. A custom transformation capability is available if needed. + + + + + Float encoding is a common encoding where the raw binary is in a form that gets interpreted as a decimal numeric value. + + + + + Integer encoding is a common encoding where the raw binary is in a form that gets interpreted as an integral value, either signed or unsigned. + + + + + String encoding is a common encoding where the raw binary is in a form that gets interpreted as a character sequence. + + + + + + + Must be derived from a like type (e.g,, String from String). No circular derivations. + Used to derive one Data Type from another - will inherit all the attributes from the baseType any of which may be redefined in this type definition. + + + + + + + + Identical to BaseTimeDataType but supports argument instance references. + + + + + + + Describes how the raw base counts of the time type are encoded/decoded. + + + + + Describes origin (epoch or reference) of this time type. + + + + + + Extend another absolute or relative time type. + + + + + + + + An abstract schema type used within the schema to derive other time based data types: RelativeTimeDataType and AbsoluteTimeDataType. An absolute time data type is a telemetered source/destination data type. A data encoding must be set. An optional epoch may be set. Time types are an exception to other primitives because, if the time data type is not telemetered, it still must have a data encoding set. See DataEncodingType, AbsoluteTimeDataType and RelativeTimeDataType. + + + + + + + Describes how the raw base counts of the time type are encoded/decoded. + + + + + Describes origin (epoch or reference) of this time type. + + + + + + Extend another absolute or relative time type. + + + + + + + + Identical to BinaryDataType but supports argument instance references. + + + + + + Default/Initial value is always given in calibrated form. Extra bits are truncated from the MSB (leftmost). + + + + + + + + A base schema type for describing a binary data engineering/calibrated type (often called “blob type”). The binary data may be of fixed or variable length, and has an optional encoding and decoding algorithm that may be defined to transform the data between space and ground. See BaseDataType, BinaryParameterType and BinaryArgumentType. + + + + + + Default/Initial value is always given in calibrated form. Extra bits are truncated from the MSB (leftmost). + + + + + + + + Identical to BooleanDataType but supports argument instance references. + + + + + + Initial value must match either the oneStringValue or the zeroStringValue + Default/Initial value is always given in calibrated form. + + + + + Enumeration string representing the 1 value, with the default being 'True'. + + + + + Enumeration string representing the 0 value, with the default being 'False'. + + + + + + + + A base schema type for describing a boolean data type which has two values only: ‘True’ (1) or ‘False’ (0). The values one and zero may be mapped to a specific string using the attributes oneStringValue and zeroStringValue. This type is a simplified form of the EnumeratedDataType. See BaseDataType, BooleanParameterType and BooleanArgumentType. + + + + + + Initial value must match either the oneStringValue or the zeroStringValue + Default/Initial value is always given in calibrated form. + + + + + Enumeration string representing the 1 value, with the default being 'True'. + + + + + Enumeration string representing the 0 value, with the default being 'False'. + + + + + + + + For partial entries of an array, the starting and ending index for each dimension, OR the Size must be specified. Indexes are zero based. + + + + + zero based index + + + + + + + + Identical to DimensionType but supports argument instance references. + + + + + zero based index + + + + + + + + Where the Dimension list is in this form: Array[1stDim][2ndDim][lastDim]. The last dimension is assumed to be the least significant - that is this dimension will cycle through its combination before the next to last dimension changes. The order MUST ascend or the array will need to be broken out entry by entry. + + + + + For an ArrayParameterType of size N, their should be N Dimensions + An array made up by multiple Entries should not have indexes that overlap, but should be continuous. + + + + + + + Identical to DimensionListType but supports argument instance references. + + + + + For an ArrayParameterType of size N, their should be N Dimensions + An array made up by multiple Entries should not have indexes that overlap, but should be continuous. + + + + + + + Identical to EnumeratedDataType but supports argument instance references. + + + + + + + Unordered list of label/value pairs where values cannot be duplicated. + Check that values do not overlap in the mappings. + + + + + + Default/Initial value is always given in calibrated form. Use the label, it must be in the enumeration list to be valid. + Label must be in the enumeration list to be valid. + + + + + + + + Describes an enumerated parameter type. The enumeration list consists of label/value pairs. See EnumerationListType, EnumeratedParameterType and EnumeratedArgumentType. + + + + + + + Unordered list of label/value pairs where values cannot be duplicated. + Check that values do not overlap in the mappings. + + + + + + Default/Initial value is always given in calibrated form. Use the label, it must be in the enumeration list to be valid. + Label must be in the enumeration list to be valid. + + + + + + + + + + + + + Identical to FloatDataType but supports argument instance references. + + + + + + + This element provides the implementation with assistance rendering the value as a string for users. + + + + + + Default/Initial value is always given in calibrated form. + + + + + Optional hint to the implementation about the size of the engineering/calibrated data type to use internally. Generally this can be determined by examination of the space required to capture the full range of the encoding, but it is not always clear when calibrators are in use. A tolerant implementation will endeavor to always make sufficient size engineering data types to capture the entire range of possible values. + + + + + + + + A base schema type for describing a floating point engineering/calibrated data type. Several encodings are supported. Calibrated integer to float relationships should be described with this data type. Use the data encoding to define calibrators. Joins integer as one of the numerics. See BaseDataType, FloatParameterType and FloatArgumentType. + + + + + + + This element provides the implementation with assistance rendering the value as a string for users. + + + + + The Valid Range provides additional boundary/constraint information beyond that of the data encoding in the range of possible values that are meaningful to this parameter. Not to be construed as an alarm definition, violations of the valid range make a parameter value "unreasonable", as opposed to reasonable to be reported, but in a state which should be of concern. + + + + + + + By default and general recommendation, the valid range is specified in engineering/calibrated values, although this can be adjusted. + + + + + + + + + + Initial value is always given in calibrated form + + + + + Optional hint to the implementation about the size of the engineering/calibrated data type to use internally. Generally this can be determined by examination of the space required to capture the full range of the encoding, but it is not always clear when calibrators are in use. A tolerant implementation will endeavor to always make sufficient size engineering data types to capture the entire range of possible values. + + + + + + + + Identical to IntegerDataType but supports argument instance references. + + + + + + + This element provides the implementation with assistance rendering the value as a string for users. + + + + + + Default/Initial value is always given in calibrated form. Default is base 10 form; binary, octal, or hexadecimal values may be given by preceding value with 0[b|B], 0[o|O|, 0[x|X] respectively. + + + + + Optional hint to the implementation about the size of the engineering/calibrated data type to use internally. Generally this can be determined by examination of the space required to capture the full range of the encoding, but it is not always clear when calibrators are in use. A tolerant implementation will endeavor to always make sufficient size engineering data types to capture the entire range of possible values. + + + + + Flag indicating if the engineering/calibrated data type used should support signed representation. This should not be confused with the encoding type for the raw value. The default is true. + + + + + + + + Describe an integer engineering/calibrated data type. Several encodings are supported. See BaseDataType, IntegerParameterType and IntegerArgumentType. + + + + + + + This element provides the implementation with assistance rendering the value as a string for users. + + + + + The Valid Range provides additional boundary/constraint information beyond that of the data encoding in the range of possible values that are meaningful to this parameter. Not to be construed as an alarm definition, violations of the valid range make a parameter value "unreasonable", as opposed to reasonable to be reported, but in a state which should be of concern. + + + + + + + By default and general recommendation, the valid range is specified in engineering/calibrated values, although this can be adjusted. + + + + + + + + + + Default/Initial value is always given in calibrated form. Default is base 10 form; binary, octal, or hexadecimal values may be given by preceding value with 0[b|B], 0[o|O|, 0[x|X] respectively. + + + + + Optional hint to the implementation about the size of the engineering/calibrated data type to use internally. Generally this can be determined by examination of the space required to capture the full range of the encoding, but it is not always clear when calibrators are in use. A tolerant implementation will endeavor to always make sufficient size engineering data types to capture the entire range of possible values. + + + + + Flag indicating if the engineering/calibrated data type used should support signed representation. This should not be confused with the encoding type for the raw value. The default is true. + + + + + + + + Describe a member field in an AggregateDataType. Each member has a name and a type reference to a data type for the aggregate member name. If this aggregate is a Parameter aggregate, then the typeRef is a parameter type reference. If this aggregate is an Argument aggregate, then the typeRef is an argument type reference. References to an array data type is currently not supported. Circular references are not allowed. See MemberListType. AggregateParameterType and AggregateArgumentType. + ensure no circular references + + + + + + + Used to set the initial calibrated values of Parameters. Will overwrite an initial value defined for the ParameterType. For integer types base 10 (decimal) form is assumed unless: if proceeded by a 0b or 0B, value is in base two (binary form, if proceeded by a 0o or 0O, values is in base 8 (octal) form, or if proceeded by a 0x or 0X, value is in base 16 (hex) form. Floating point types may be specified in normal (100.0) or scientific (1.0e2) form. Time types are specified using the ISO 8601 formats described for XTCE time data types. Initial values for string types, may include C language style (\n, \t, \", \\, etc.) escape sequences. + The value type must match the Parameter type + + + + + + + + Order is important only if the name of the AggregateParameter or Aggregate Argument is directly referenced in SequenceContainers. In this case the members are assued to be added sequentially (in the order listed here) into the Container. + + + + + + + + Used to contain a relative time value. Used to describe a relative time. Normally used for time offsets. A Relative time is expressed as PnYn MnDTnH nMnS, where nY represents the number of years, nM the number of months, nD the number of days, 'T' is the date/time separator, nH the number of hours, nM the number of minutes and nS the number of seconds. The number of seconds can include decimal digits to arbitrary precision. For example, to indicate a duration of 1 year, 2 months, 3 days, 10 hours, and 30 minutes, one would write: P1Y2M3DT10H30M. One could also indicate a duration of minus 120 days as: -P120D. An extension of Schema duration type. + + + + + + + + + + Used to contain a relative time value. Used to describe a relative time. Normally used for time offsets. A Relative time is expressed as PnYn MnDTnH nMnS, where nY represents the number of years, nM the number of months, nD the number of days, 'T' is the date/time separator, nH the number of hours, nM the number of minutes and nS the number of seconds. The number of seconds can include decimal digits to arbitrary precision. For example, to indicate a duration of 1 year, 2 months, 3 days, 10 hours, and 30 minutes, one would write: P1Y2M3DT10H30M. One could also indicate a duration of minus 120 days as: -P120D. An extension of Schema duration type. + + + + + + + + + + Identical to StringDataType but supports argument instance references. + + + + + + + + + Initial values for string types, may include C language style (\n, \t, \", \\, etc.) escape sequences. + + + + + restriction pattern is a regular expression + + + + + + + + + Defines a base schema type for StringParameterType and StringArgumentType, adding initial value, restriction pattern, character width, and size range in characters. The initial value if set is the initial value of all instances of the child types. The restriction pattern is a regular expression enforcing the string value to this pattern. The character width is on the local data type side. And the size range in character restricts the character set. For telemetered values, if the restriction pattern of size range in character is not met, the item is invalid. See BaseDataType, StringParameterType, StringArgumentType, CharacterWidthType and IntegerRangeType. + + + + + + + The size in bits may be greater than or equal to minInclusive. It may be less than or equal to maxInclusive. They both may be set indicating a closed range. + + + + + + Initial values for string types, may include C language style (\n, \t, \", \\, etc.) escape sequences. + + + + + restriction pattern is a regular expression + + + + + + + + + Describe an ordered collection of units that form a unit-expression. Units may be described for both calibrated/engineering values and also potentially uncalibrated/raw values. See UnitType. + + + + + Describe the exponent, factor, form, and description for a unit. The attributes are optional because different programs use this element in different ways, depending on vendor support. + + + + + + + Numerical ranges that define the universe of valid values for this argument. A single range is the most common, although it is possible to define multiple ranges when the valid values are not contiguous. + + + + + A valid range constrains the whole set of possible values that could be encoded by the data type to a more "valid" or "reasonable" set of values. This should be treated as a boundary check in an implementation to validate the input or output value. Typically, only 1 range is used. In cases where multiple ranges are used, then the value is valid when it is valid in any of the provided ranges. Implementations may also use these ranges to enhance user interface displays and other visualization widgets as appropriate for the type. + + + + + + By default and general recommendation, the valid range is specified in engineering/calibrated values, although this can be adjusted. + + + + + + Numerical ranges that define the universe of valid values for this argument. A single range is the most common, although it is possible to define multiple ranges when the valid values are not contiguous. + + + + + A valid range constrains the whole set of possible values that could be encoded by the data type to a more "valid" or "reasonable" set of values. This should be treated as a boundary check in an implementation to validate the input or output value. Typically, only 1 range is used. In cases where multiple ranges are used, then the value is valid when it is valid in any of the provided ranges. Implementations may also use these ranges to enhance user interface displays and other visualization widgets as appropriate for the type. + + + + + + By default and general recommendation, the valid range is specified in engineering/calibrated values, although this can be adjusted. + + + + + + + + Defines two bit-order types: most significant bit first and least significant bit first. See DataEncodingType. + + + + + + + + + Identical to BinaryDataEncodingType but supports argument instance references. + + + + + + + Number of bits this value occupies on the stream being encoded/decoded. + + + + + Used to convert binary data to an application data type + + + + + Used to convert binary data from an application data type to binary data + + + + + + + + + Describe binary data that is unmolested in the decoding/encoding or cannot be represented in any of the other data encoding formats. Optionally use the FromBinaryTransformAlgorithm and ToBinaryTransformAlgorithm element to describe the transformation process. See InputAlgorithmType for the transformation structure. + + + + + + + Number of bits this value occupies on the stream being encoded/decoded. + + + + + Used to convert binary data to an application data type + + + + + Used to convert binary data from an application data type to binary data + + + + + + + + + + + + + + + + + + Cyclic Redundancy Check (CRC) definition. The polynomial coefficients for the CRC +are defined as a truncated hex value. The coefficient for the nth bit of an n-bit CRC will always be 1 and is not +represented in the truncated hex value. For example, the truncated hex value of CRC-32 (width=32 bits) used in the +Ethernet specification is 0x04C11DB7, where each non-zero bit of the truncated hex represents a coefficient of 1 in +the polynomial and the bit position represents the exponent. There may also be an initial remainder "InitRemainder" +and a final XOR "FinalXOR" to fully specify the CRC. reflectData and reflectRemainder may also be specified to +reverse the bit order in the incoming data and/or the result. + + + + + + + + + + + + + + + + Describes how a particular piece of data is sent or received from some non-native, off-platform device. (e.g. a spacecraft) + + + + + + + + + + Describe the data encoding for a time data type. It includes the units and other attributes scale and offset. Use scale and offset to describe a y=mx+b relationship (where m is the slope/scale and b is the intercept/offset) to make adjustments to the encoded time value so that it matches the time units. For binary encoded time use transform algorithms to convert time data formats that are too difficult to describe in XTCE. See AbsoluteTimeDataType and RelativeTimeDataType. + + + + + Binary encoding is typically a "pass through" raw encoding form where one of the more common encodings is not required for the parameter. A custom transformation capability is available if needed. + + + + + Float encoding is a common encoding where the raw binary is in a form that gets interpreted as a decimal numeric value. + + + + + Integer encoding is a common encoding where the raw binary is in a form that gets interpreted as an integral value, either signed or unsigned. + + + + + String encoding is a common encoding where the raw binary is in a form that gets interpreted as a character sequence. + + + + + + Time units, with the default being in seconds. + + + + + Linear slope used as a shorter form of specifying a calibrator to convert between the raw value and the engineering units. + + + + + Linear intercept used as a shorter form of specifying a calibrator to convert between the raw value and the engineering units. + + + + + + Epochs may be specified as an xs date where time is implied to be 00:00:00, xs dateTime, or string enumeration of common epochs. The enumerations are TAI (used by CCSDS and others), J2000, UNIX (also known as POSIX), and GPS. + + + + + + For common encodings of floating point data + + + + + + + Calibrator to be applied to the raw uncalibrated value to arrive at the engineering/calibrated value when no Context Calibrators are provided or evaluate to true, based on their MatchCriteria. + + + + + Calibrator to be applied to the raw uncalibrated value to arrive at the engineering/calibrated value when a MatchCriteria evaluates to true. + + + + + + Specifies real/decimal numeric value to raw encoding method, with the default being "IEEE754_1985". + + + + + Number of bits to use for the float raw encoding method, with 32 being the default. Not every number of bits is valid for each encoding method. + Verify the number of bits for encoding is valid for the encoding method. + + + + + A changeThreshold may optionally be specified to inform systems of the minimum change in value that is significant. This is used by some systems to limit the telemetry processing and/or recording requirements. If the value is unspecified or zero, any change is significant. + + + + + + + + + + At the time of this writing, 16 bit encoding size is only valid in cases of IEEE754 and vendor specific MILSTD_1750A variation that is not a part of the standard. This is not meant to preclude use in the event that future floating point formats may also define this value. + + + + + At the time of this writing, 32 bit encoding size is only valid in cases of IEEE754_1985, IEEE754, MILSTD_1750A, DEC, IBM, and TI. This is not meant to preclude use in the event that future floating point formats may also define this value. The IEEE754 enumeration and the IEEE754_1985 enumeration are allowed in this case and the interpretation is the same. + + + + + At the time of this writing, 40 bit encoding size is only valid in the case of TI. This is not meant to preclude use in the event that future floating point formats may also define this value. + + + + + At the time of this writing, 48 bit encoding size is only valid in the case of MILSTD_1750A. This is not meant to preclude use in the event that future floating point formats may also define this value. + + + + + At the time of this writing, 64 bit encoding size is only valid in cases of IEEE754_1985, IEEE754, DEC, and IBM. This is not meant to preclude use in the event that future floating point formats may also define this value. The IEEE754 enumeration and the IEEE754_1985 enumeration are allowed in this case and the interpretation is the same. + + + + + At the time of this writing, 80 bit encoding size is only valid in the case of IEEE754_1985. This is not meant to preclude use in the event that future floating point formats may also define this value. + + + + + At the time of this writing, 128 bit encoding size is only valid in the case of IEEE754_1985 and IEEE754. This is not meant to preclude use in the event that future floating point formats may also define this value. The IEEE754 enumeration and the IEEE754_1985 enumeration are allowed in this case and the interpretation is the same. + + + + + + + + + + + + + + + + + + + + + + + + For all major encodings of integer data + + + + + + + Calibrator to be applied to the raw uncalibrated value to arrive at the engineering/calibrated value when no Context Calibrators are provided or evaluate to true, based on their MatchCriteria. + + + + + Calibrator to be applied to the raw uncalibrated value to arrive at the engineering/calibrated value when a MatchCriteria evaluates to true. + + + + + + Specifies integer numeric value to raw encoding method, with the default being "unsigned". + + + + + Number of bits to use for the raw encoding, with 8 being the default. + + + + + A changeThreshold may optionally be specified to inform systems of the minimum change in value that is significant. This is used by some systems to limit the telemetry processing and/or recording requirements, such as for an analog-to-digital converter that dithers in the least significant bit. If the value is unspecified or zero, any change is significant. + + + + + + + + + + + + + + + + + + Like PASCAL strings, the size of the string is given as an integer at the start of the string. SizeTag must be an unsigned Integer + + + + + + + + + + + + Bit position starts with 'zero'. + + + + + + + + + + This is the simplest case of a string data type where the encoding size of the string does not change. + + + + + + Size in bits of this string data type for both the memory allocation in the implementing software and also the size in bits for this parameter when it appears in a container. + + + + + + + + The termination character that represents the end of the string contents. For C and most strings, this is null (00), which is the default. + + + + + In some string implementations, the size of the string contents (not the memory allocation size) is determined by a leading numeric value. This is sometimes referred to as Pascal strings. If a LeadingSize is specified, then the TerminationChar element does not have a functional meaning. + + + + + + + Identical to VariableStringType but supports argument instance references. + + + + + + Determine the container size in bits by interrogating an instance of a parameter or argument. + + + + + Determine the container size in bits by interrogating an instance of a parameter or argument and selecting a specified value based on tests of the value of that parameter or argument. + + + + + + In some string implementations, the size of the string contents (not the memory allocation size) is determined by a leading numeric value. This is sometimes referred to as Pascal strings. If a LeadingSize is specified, then the TerminationChar element does not have a functional meaning. + + + + + The termination character that represents the end of the string contents. For C and most strings, this is null (00), which is the default. + + + + + + The upper bound of the size of this string data type so that the implementation can reserve/allocate enough memory to capture all reported instances of the string. + + + + + + Describe a variable string whose length may change between samples. + + + + + + Determine the container size in bits by interrogating an instance of a parameter. + + + + + Determine the container size in bits by interrogating an instance of a parameter and selecting a specified value based on tests of the value of that parameter. + + + + + + In some string implementations, the size of the string contents (not the memory allocation size) is determined by a leading numeric value. This is sometimes referred to as Pascal strings. If a LeadingSize is specified, then the TerminationChar element does not have a functional meaning. + + + + + The termination character that represents the end of the string contents. For C and most strings, this is null (00), which is the default. + + + + + + The upper bound of the size of this string data type so that the implementation can reserve/allocate enough memory to capture all reported instances of the string. + + + + + + Identical to StringDataEncodingType but supports argument instance references. + + + + + + + Static length strings do not change in overall length between samples. They may terminate before the end of their buffer using a terminating character, or by various lookups, or calculations. But they have a maximum fixed size, and the data itself is always within that maximum size. + + + + + Variable length strings are those where the space occupied in a container can vary. If the string has variable content but occupies the same amount of space when encoded should use the SizeInBits element. Specification of a variable length string needs to consider that the implementation needs to allocate space to store the string. Specify the maximum possible length of the string data type for memory purposes and also specify the bit size of the string to use in containers with the dynamic elements. + + + + + + The character set encoding of this string data type. + + + + + + + + Describe common encodings of string data: UTF-8 and UTF-16. See StringDataType. + + + + + + + Static length strings do not change in overall length between samples. They may terminate before the end of their buffer using a terminating character, or by various lookups, or calculations. But they have a maximum fixed size, and the data itself is always within that maximum size. + + + + + Variable length strings are those where the space occupied in a container can vary. If the string has variable content but occupies the same amount of space when encoded should use the SizeInBits element. Specification of a variable length string needs to consider that the implementation needs to allocate space to store the string. Specify the maximum possible length of the string data type for memory purposes and also specify the bit size of the string to use in containers with the dynamic elements. + + + + + + The character set encoding of this string data type. + + + + + + + + Defines string encodings. US-ASCII (7-bit), ISO-8859-1 (8-bit Extended ASCII), Windows-1252 (8-bit Extended ASCII), UTF-8 (Unicode), UTF-16 (Unicode with Byte Order Mark), UTF-16LE (Unicode Little Endian), UTF-16BE (Unicode Big Endian). See StringDataEncodingType. + + + + + + + + + With UTF-16, encoded bits must be prepended with a Byte Order Mark. This mark indicates whether the data is encoded in big or little endian. + + + + + With UTF-16LE, encoded bits will always be represented as little endian. Bits are not prepended with a Byte Order Mark. + + + + + With UTF-16BE, encoded bits will always be represented as big endian. Bits are not prepended with a Byte Order Mark. + + + + + With UTF-32, encoded bits must be prepended with a Byte Order Mark. This mark indicates whether the data is encoded in big or little endian. + + + + + With UTF-32LE, encoded bits will always be represented as little endian. Bits are not prepended with a Byte Order Mark. + + + + + With UTF-32BE, encoded bits will always be represented as big endian. Bits are not prepended with a Byte Order Mark. + + + + + + + + + This element describes how a numeric value should be represented in engineering/calibrated form. The defaults reflect the most common form. + + + + + + + Union values of common epoch definitions for document convenience. + + + + + + + + + + + + + + + An unordered collection of algorithms + + + + + + + + + Contains an unordered collection of Alias elements to describe alternate names or IDs for this named item. + Applications should enforce uniqueness of individual nameSpace attribute values. Aliases are usually unique within the same nameSpace attribute value, depending on the physical meaning of that nameSpace. There are some cases where Alias values can be duplicated in a single nameSpace value. + + + + + An alternate name, ID number, and sometimes flight software variable name in the code for this item. + + + + + + + Used to contain an alias (alternate) name or ID for the object. For example, a parameter may have a mnemonic, an on-board id, and special IDs used by various ground software applications; all of these are alias's. Some ground system processing equipment has some severe naming restrictions on parameters (e.g., names must less then 12 characters, single case or integral id's only); their alias's provide a means of capturing each name in a "nameSpace". Note: the name is not reference-able (it cannot be used in a name reference substituting for the name of the item of interest). See NameDescriptionType. + + + + Aliases should be grouped together in a "namespace" so that they can be switched in and out of data extractions. The namespace generally identifies the purpose of the alternate name, whether for software variable names, additional operator names, or whatever the purpose. + + + + + The alternate name or ID to use. The alias does not have the restrictions that apply to name attributes. This is useful for capturing legacy identifiers for systems with unusual naming conventions. It is also useful for capturing variable names in software, amongst other things. + + + + + + Use for any other data associated with a named item. May be used to include administrative data (e.g., version, CM or tags) or potentially any MIME type. Data may be included or given as an href. + + + + + + Identifier for this Ancillary Data characteristic, feature, or data. + + + + + Optional text encoding method for the element text content of this element. The default is "text/plain". + + + + + Optional Uniform Resource Identifier for this characteristic, feature, or data. + + + + + + + + Describe an unordered collection of ancillary data. AncillaryData elements capture platform/program/implementation specific data about the parent element object that is non-standard and would not fit into the schema. See AncillaryDataType. + + + + + Optional list of AncillaryData elements associated with this item. + + + + + + + Describe two or more conditions that are logically anded together. Conditions may be a mix of Condition and ORedCondition. See ORedConditionType and BooleanExpressionType. + + + + + + + Condition elements describe a test similar to the Comparison element except that the parameters used have additional flexibility for the compare. + + + + + This element describes tests similar to the ComparisonList element except that the parameters used are more flexible and the and/or for multiple checks can be specified. + + + + + + + + + Describe an unordered collection of authors. See AuthorType. + + + + + Contains information about an author, maintainer, or data source regarding this document. + + + + + + + Type definition that describes the format of the contents of the Author element. + + + + + + A base type for boolean expression related elements that improves the mapping produced by data binding tools. + + + + + A simple restriction on string for hexadecimal numbers. Must be in 0b or 0B form. + + + + + + + + Holds an arbitrarily complex boolean expression + + + + + Condition elements describe a test similar to the Comparison element except that the parameters used have additional flexibility. + + + + + This element describes tests similar to the ComparisonList element except that the parameters used are more flexible. + + + + + This element describes tests similar to the ComparisonList element except that the parameters used are more flexible. + + + + + + + Describe a byte order: big/little or byte list. + + + + + + Common byte orderings: most significant byte first (also known as big endian) and least significant byte first (also known as little endian). + + + + + + + + + Describe a byte order using a byte list. The list is viewed as representing memory, the first item in the list is address 0. For mostSignificantByteFirst/big endian, the high order byte is the first byte in the list and has the highest significance followed by the less significant bytes ending with the least significant byte. For leastSignificantByteFirst/little endian, the first byte starts with the least significant byte which is first in the least and ends at the highest significant byte. For example given the value 0x0A0B0C0D the following example orderings can be formed. For mostSignificantByteFirst/big endian the significances would be listed as 3 (0x0A), 2 (0x0B), 1 (0x0C), 0 (0x0D) with ‘3’ being first in the list, and for leastSignificantByteFirst/little endian as 0 (0x0D), 1 (0x0C), 2 (0x0B), 3 (0x0A) with ‘0’ being first in the list. See DataEncodingType. + + + + + + + + Describe the comparison between the instance (value) of a parameter against either a specified value or another parameter instance. + + + + + + + Left hand side parameter instance. + + + + + Comparison operator. + + + + + + Right hand side parameter instance. Parameter is assumed to be of the same type as the comparison Parameter. + + + + + Right hand side value. Specify as: integer data type using xs:integer, float data type using xs:double, string data type using xs:string, boolean data type using xs:boolean, binary data type using xs:hexBinary, enum data type using label name, relative time data type using xs:duration, absolute time data type using xs:dateTime. Values must not exceed the characteristics for the data type or this is a validation error. Takes precedence over an initial value given in the data type. Values are calibrated unless there is an option to override it. + + + + + + + + + + All comparisons must be true + + + + + List of Comparison elements must all be true for the comparison to evaluate to true. + + + + + + + Operators to use when testing a boolean condition for a validity check + + + + + + + + + + + + + A simple ParameterInstanceRef to value comparison. The string supplied in the value attribute needs to be converted to a type matching the Parameter being compared to. Numerical values are assumed to be base 10 unless proceeded by 0x (hexadecimal), 0o (octal), or 0b (binary). The value is truncated to use the least significant bits that match the bit size of the Parameter being compared to. + + + + + + Operator to use for the comparison with the common equality operator as the default. + + + + + Specify value as a string compliant with the XML schema (xs) type specified for each XTCE type: integer=xs:integer; float=xs:double; string=xs:string; boolean=xs:boolean; binary=xs:hexBinary; enum=xs:string from EnumerationList; relative time= xs:duration; absolute time=xs:dateTime. Supplied value must be within the ValidRange specified for the type. + + + + + + + + Context calibrations are applied when the ContextMatch is true. Context calibrators overide Default calibrators + + + + + + + + + A MatchCriteriaType used for Context selection. + + + + + + + + Describe a custom, algorithmic alarm condition. The algorithm is assumed to return a boolean value: true or false. See AlarmType. + + + + + + + Algorithm returns a boolean. + + + + + + + + + Describe a percentage complete that is fixed from 0 to 100, or as value from a parameter. See ExecutionVerifierType. + + + + + 0 to 100 percent + + + + + + + + + + + Uses a parameter instance to obtain the value. The parameter value may be optionally adjusted by a Linear function or use a series of boolean expressions to lookup the value. Anything more complex and a DynamicValue with a CustomAlgorithm may be used. + + + + + + + Defines an abstract schema type used as basis for NameDescriptionType and OptionalNameDescriptionType, includes an attribute for a short description and an element for a longer unbounded description. This type also provides alias set and ancillary data set See AliasSetType and AncillaryDataSetType. + + + + + Optional long form description to be used for explanatory descriptions of this item and may include HTML markup using CDATA. Long Descriptions are of unbounded length. + + + + + Used to contain an alias (alternate) name or ID for this item. See AliasSetType for additional explanation. + + + + + Use for any non-standard data associated with this named item. See AncillaryDataSetType for additional explanation. + + + + + + Optional short description to be used for explanation of this item. It is recommended that the short description be kept under 80 characters in length. + + + + + + Describe an ordered table of integer values and associated conditions, forming a lookup table. The list may have duplicates. The table is evaluated from first to last, the first condition to be true returns the value associated with it. See DiscreteLookupType. + + + + + Describe a lookup condition set using discrete values from parameters. + + + + + + + Uses a parameter instance to obtain the value. The parameter value may be optionally adjusted by a Linear function or use a series of boolean expressions to lookup the value. Anything more complex and a DynamicValue with a CustomAlgorithm may be used + + + + + Retrieve the value by referencing the value of a Parameter. + + + + + A slope and intercept may be applied to scale or shift the value selected from the argument or parameter. + + + + + + + Describe error detection/correction algorithm. + + + + + + + + + + A simple union type combining integer, octal, binary, and hexadecimal types + + + + + + Schema for a Header record. A header contains general information about the system or subsystem. + + + + + The AuthorSet contains optional contact information for this document. + + + + + The NoteSet contains optional technical information related to the content of this document. + + + + + The HistorySet contains optional evolutionary information for data contained in this document. + + + + + + This attribute contains an optional version descriptor for this document. + + + + + This attribute contains an optional date to be associated with this document. + + + + + This attribute contains optional classification status for use by programs for which that is applicable. + + + + + This attribute contains an optional additional instructions attribute to be interpreted by programs that use this attribute. + + + + + This attribute contains a flag describing the state of this document in the evolution of the project using it. + + + + + + A simple restriction on string for hexadecimal numbers. Must be in 0x or 0X form. + + + + + + + + Describe an unordered collection of History elements. Usage is user defined. See HistoryType. + + + + + Contains a history record related to the evolution of this document. + + + + + + + + + + Contains an Integer value; value may be provided directly or via the value in a parameter. + + + + + Use a fixed integer value. + + + + + Determine the value by interrogating an instance of a parameter. + + + + + Determine the value by interrogating an instance of a parameter and selecting a specified value based on tests of the value of that parameter. + + + + + + + Identical to IntegerValueType but supports argument instance references. + + + + + Use a fixed integer value. + + + + + Determine the value by interrogating an instance of an argument or parameter. + + + + + Determine the value by interrogating an instance of an argument or parameter and selecting a specified value based on tests of the value of that argument or parameter. + + + + + + + The Long Description is intended to be used for explanatory descriptions of the object and may include HTML markup. Long Descriptions are of unbounded length + + + + + + Mathematical operators used in the math operation. Behavior of each operator on the stack is described using notation (before -- after), where "before" represents the stack before execution of the operator and "after" represent the stack after execution. + + + + + addition (x1 x2 -- x1+x2) + + + + + subtraction (x1 x2 -- x1-x2) + + + + + multiplication (x1 x2 -- x1*x2) + + + + + division (x1 x2 -- x1/x2) + An undefined condition exists if x2 is 0 + + + + + modulo (x1 x2 -- x3) Divide x1 by x2, giving the modulo x3 + An undefined condition exists if x2 is 0. Implementations should verify modulo versus remainder behavior. + + + + + power function (x1 x2 -- x1**x2) + An undefined condition exists if an imaginary number is the result. Imaginary numbers are not supported + + + + + reverse power function (x1 x2 -- x2**x1) + + + + + natural (base e) logarithm (x -- ln(x)) + An undefined condition exists if x is less than or equal to 0 + + + + + base-10 logarithm (x-- log(x)) + An undefined condition exists if x is less than or equal to 0 + + + + + exponentiation (x -- exp(x)) + + + + + inversion (x -- 1/x) + An undefined condition exists if x is less than 0 + + + + + factorial (x -- x!) + An undefined condition exists if x is less than 0 + + + + + tangent (x -- tan(x)) radians + + + + + cosine (x -- cos(x)) radians + + + + + sine (x -- sin(x)) radians + + + + + arctangent (x -- atan(x)) radians + + + + + arctangent (x1 x2 -- atan2(x2, x1)) radians + An undefined condition exists if x1 and x2 are 0 + + + + + arccosine (x -- acos(x)) radians + + + + + arcsine (x -- asin(x)) radians + + + + + hyperbolic tangent (x -- tanh(x)) + + + + + hyperbolic cosine (x -- cosh(x)) + + + + + hyperbolic sine (x -- sinh(x)) + + + + + hyperbolic arctangent (x -- atanh(x)) + An undefined condition exists if x is outside the range [-1.0,+1.0] + + + + + hyperbolic arccosine (x -- acosh(x)) + An undefined condition exists if n is less than 1 + + + + + hyperbolic arcsine (x -- asinh(x)) + + + + + swap the top two stack items (x1 x2 -- x2 x1) + + + + + Remove top item from the stack (x -- ) + + + + + Duplicate top item on the stack (x -- x x) + + + + + Duplicate top item on the stack (x1 x2 -- x1 x2 x1) + + + + + signed bitwise left shift (x1 x2 -- x1 << x2) + Limitation from SEI INT13-C. Use bitwise operators only on unsigned operands + + + + + signed bitwise right shift (x1 x2 -- x1 >> x2) + Limitation from SEI INT13-C. Use bitwise operators only on unsigned operands + + + + + bitwise and (x1 x2 -- x1 & x2) + Limitation from SEI INT13-C. Use bitwise operators only on unsigned operands + + + + + bitwise or (x1 x2 -- x1 | x2) + Limitation from SEI INT13-C. Use bitwise operators only on unsigned operands + + + + + logical and (x1 x2 -- x1 && x2) + The result of this can only be 0 or 1 + + + + + logical or (x1 x2 -- x1 || x2) + The result of this can only be 0 or 1 + + + + + logical not (x1 x2 -- x1 ! x2) + The result of this can only be 0 or 1 + + + + + absolute value (x1 -- abs(x1)) + + + + + Euclidean division quotient (x1 -- div(x1)) + + + + + integer part (x1 -- int(x1)) + + + + + greater than x,y (x1 x2 -- x1 > x2) + The result of this can only be 0 or 1 + + + + + greater than or equal x,y (x1 x2 -- x1 >= x2) + The result of this can only be 0 or 1 + + + + + less than x,y (x1 x2 -- x1 < x2) + The result of this can only be 0 or 1 + + + + + less than or equal x,y (x1 x2 -- x1 <= x2) + The result of this can only be 0 or 1 + + + + + equal x,y (x1 x2 -- x1 == x2) + The result of this can only be 0 or 1 + + + + + not equal x,y (x1 x2 -- x1 != x2) + The result of this can only be 0 or 1 + + + + + minimum of x,y (x1 x2 -- min(x1, x2)) + + + + + maximum of x,y (x1 x2 -- max(x1, x2)) + + + + + Bitwise exclusive or (XOR) (x1 x2 -- x1 xor x2) + Limitation from SEI INT13-C. Use bitwise operators only on unsigned operands + + + + + Bitwise not operation (x1 x2 -- x1 ~ x2) The result of this can only be 0 or 1 + Limitation from SEI INT13-C. Use bitwise operators only on unsigned operands + + + + + + + Contains either a simple Comparison, a ComparisonList, an arbitrarily complex BooleanExpression or an escape to an externally defined algorithm + + + + + A simple comparison check involving a single test of a parameter value. + + + + + A series of simple comparison checks with an implicit 'and' in that they all must be true for the overall condition to be true. + + + + + An arbitrarily complex boolean expression that has additional flexibility on the terms beyond the Comparison and ComparisonList elements. + + + + + An escape to an externally defined algorithm. + + + + + + + Postfix (aka Reverse Polish Notation (RPN)) notation is used to describe mathmatical equations. It uses a stack where operands (either fixed values or ParameterInstances) are pushed onto the stack from first to last in the XML. As the operators are specified, each pops off operands as it evaluates them, and pushes the result back onto the stack. In this case postfix is used to avoid having to specify parenthesis. To convert from infix to postfix, use Dijkstra's "shunting yard" algorithm. + + + + + + + + Defines a name where all characters are allowed except '.', '[', ']', ':', ' ', and '/'. See NameDescriptionType. + + + + + + + + Defines a base schema type definition used by many other schema types throughout schema. Use it to describe a name with optional descriptions, aliases, and ancillary data. See NameType, LongDescriptionType, ShortDescriptionType, AliasSetType and AncillaryDataSetType. + + + + + + The name of this defined item. See NameType for restriction information. + + + + + + + + Describe a reference to a named item in an XTCE instance document. The named must be of schema type NameType. All name references use a Unix style file system name format where the SpaceSystem names form a path in the SpaceSystem tree. The following characters are reserved for the path: '/', ‘..’ and ‘.’ (multiple consecutive ‘/’s are treated as one). The path portion is similar to the directory path used in file system names and the path characters have similar meaning (e.g., SimpleSat/Bus/EPDS/BatteryOne/Voltage). There are three overall forms for name references: absolute path, relative path and just the name. The first two forms are called qualified name references; the last form is called an unqualified name reference. The unqualified form refers to an item in the SpaceSystem the reference is used in. The unqualified form refers to an item in the SpaceSystem the reference is used in. It is illegal for a name reference to point to no item (“a dangling name reference”). + + + + + + + + Contains an unordered collection of Notes. Usage is user defined. See NoteType. + + + + + Contains a program defined technical note regarding this document. + + + + + + + + + + This type describes how a numeric value should be represented in engineering/calibrated form. The defaults reflect the most common form. + + + + Describes how the engineering/calibrated value of this number should be displayed with respect to the radix. Default is base 10. + + + + + Describes how the engineering/calibrated value of this number should be displayed with respect to the minimum number of fractional digits. The default is 0. + + + + + Describes how the engineering/calibrated value of this number should be displayed with respect to the maximum or upper bound of the number of digits. There is no default. No value specified should be interpreted as no upper bound such that all requires digits are used to fully characterize the value. + + + + + Describes how the engineering/calibrated value of this number should be displayed with respect to the minimum number of integer digits. The default is 1. + + + + + Describes how the engineering/calibrated value of this number should be displayed with respect to the maximum or upper bound of the integer digits. There is no default. No value specified should be interpreted as no upper bound such that all requires digits are used to fully characterize the value. + + + + + Describes how the engineering/calibrated value of this number should be displayed with respect to negative values. This attribute specifies the character or characters that should be appended to the numeric value to indicate negative values. The default is none. + + + + + Describes how the engineering/calibrated value of this number should be displayed with respect to positive values. This attribute specifies the character or characters that should be appended to the numeric value to indicate positive values. The default is none. Zero is considered to be specific to the implementation/platform and is not implied here. + + + + + Describes how the engineering/calibrated value of this number should be displayed with respect to negative values. This attribute specifies the character or characters that should be prepended to the numeric value to indicate negative values. The default is a minus character "-". + + + + + Describes how the engineering/calibrated value of this number should be displayed with respect to positive values. This attribute specifies the character or characters that should be prepended to the numeric value to indicate positive values. The default is none. Zero is considered to be specific to the implementation/platform and is not implied here. + + + + + Describes how the engineering/calibrated value of this number should be displayed with respect to larger values. Groupings by thousand are specific to locale, so the schema only specifies whether they will be present and not which character separators are used. The default is false. + + + + + Describes how the engineering/calibrated value of this number should be displayed with respect to notation. Engineering, scientific, or traditional decimal notation may be specified. The precise characters used is locale specific for the implementation/platform. The default is "normal" for the traditional notation. + + + + + + A simple restriction on string for hexadecimal numbers. Must be in 0o or 0O form. + + + + + + + + The type definition used by most elements that have an optional name with optional descriptions. + + + + + + Optional name of this defined item. See NameType for restriction information. + + + + + + + + Describe two or more conditions that are logically ored together. Conditions may be a mix of Condition and ANDedCondition. See ORedConditionType and BooleanExpressionType. + + + + + + + Condition elements describe a test similar to the Comparison element except that the parameters used have additional flexibility for the compare. + + + + + This element describes tests similar to the ComparisonList element except that the parameters used are more flexible and the and/or for multiple checks can be specified. + + + + + + + + + Describe an unordered collection of parameters where duplicates defined by the Parameter name attribute are invalid. The ParameterSet exists in both the TelemetryMetaData and the CommandMetaData element so that each may be built independently but from a single namespace. See TelemetryMetaDataType and CommandMetaDataType. + + + + + Defines a named and typed Parameter. + Need to ensure that the named types actually exist + + + + + Used to include a Parameter defined in another sub-system in this sub-system. + + + + + + + Specifies the number base + + + + + + + + + + + Defines whether the defined range between the minimum and maximum is the outside or inside the range being defined. The default, outside matches values less than the minimum and greater than the maximum. Inside matches values between the minimum and maximum. + + + + + + + + + Most time values are relative to another time e.g. seconds are relative to minutes, minutes are relative to hours. This type is used to describe this relationship starting with the least significant time Parameter to and progressing to the most significant time parameter. + + + + + + Epochs may be specified as an xs date where time is implied to be 00:00:00, xs dateTime, or string enumeration of common epochs. The enumerations are TAI (used by CCSDS and others), J2000, UNIX (also known as POSIX), and GPS. + + + + + + + Used to describe a relative time. Normally used for time offsets. A Relative time is expressed as PnYn MnDTnH nMnS, where nY represents the number of years, nM the number of months, nD the number of days, 'T' is the date/time separator, nH the number of hours, nM the number of minutes and nS the number of seconds. The number of seconds can include decimal digits to arbitrary precision. For example, to indicate a duration of 1 year, 2 months, 3 days, 10 hours, and 30 minutes, one would write: P1Y2M3DT10H30M. One could also indicate a duration of minus 120 days as: -P120D. An extension of Schema duration type. + + + + + + Hold a structure that can be repeated X times, where X is the Count + + + + + Value (either fixed or dynamic) that contains the count of repeated structures. + + + + + + + + Identical to RepeatType but supports argument instance references. + + + + + Value (either fixed or dynamic) that contains the count of repeated structures. + + + + + + + + A reference to a Service + + + + + + + + + + It is strongly recommended that the short description be kept under 80 characters in length + + + + + + A spline, or piecewise defined function, is a set on points from which a curve may be drawn to interpolate raw to calibrated values + + + + The order of a SplineCalibrator refers to the interpolation function. Order 0 is a flat line from the defined point (inclusive) to the next point (exclusive). Order 1 is linear interpolation between two points. Order 2 is quadratic fit and requires at least 3 points (unusual case). This order is generally not needed, but may be used to override the interpolation order for this point. + + + + + The raw encoded value. + + + + + The engineering/calibrated value associated with the raw value for this point. + + + + + + A term in a polynomial expression. + + + + The coefficient in a single term of a polynomial expression. + + + + + The exponent in a single term of a polynomial expression. Should negative exponents be required, use a Math Calibrator style of definition for this type. + + + + + + base time units. days, months, years have obvoius ambiguity and should be avoided + + + + + + + + + + + + Describe the exponent, factor, form, and description for a unit. The unit itself is in element Unit in UnitSet. See UnitSetType. The attributes are optional because different programs use this element in different ways, depending on vendor support. + + + + Optional attribute used in conjunction with the "factor" attribute where some programs choose to specify the unit definition with these machine processable algebraic features. For example, a unit text of "meters" may have a "power" attribute of 2, resulting "meters squared" as the actual unit. This is not commonly used. The most common method for "meters squared" is to use the text content of the Unit element in a form like "m^2". + + + + + Optional attribute used in conjunction with the "power" attribute where some programs choose to specify the unit definition with these machine processable algebraic features. For example, a unit text of "meters" may have a "factor" attribute of 2, resulting "2 times meters" as the actual unit. This is not commonly used. The most common method for "2 times meters" is to use the text content of the Unit element in a form like "2*m". + + + + + A description of the unit, which may be for expanded human readability or for specification of the nature/property of the unit. For example, meters per second squared is of a nature/property of acceleration. + + + + + The default value "calibrated" is most common practice to specify units at the engineering/calibrated value, it is possible to specify an additional Unit element for the raw/uncalibrated value. + + + + + + + + + + + + + + + + + Describe a value and an associated string label, see EnumerationListType. + + + + Numeric raw/uncalibrated value to associate with a string enumeration label. + + + + + If max value is given, the label maps to a range where value is less than or equal to maxValue. The range is inclusive. + + + + + String enumeration label to apply to this value definition in the enumeration. + + + + + An optional additional string description can be specified for this enumeration label to provide extended information if desired. + + + + + + + + Describe up to six levels: Normal, Watch, Warning, Distress, Critical, and Severe of conditions the alarm will trigger when true. The types are conditions available are a single comparison, a comparison list, a discrete lookup list, and custom algorithm. See MatchCriteriaType. + + + + + An alarm state of least concern. Considered to be below the most commonly used Warning level. + + + + + An alarm state of concern that represents the most commonly used minimum concern level for many software applications. + + + + + An alarm state of concern in between the most commonly used Warning and Critical levels. + + + + + An alarm state of concern that represents the most commonly used maximum concern level for many software applications. + + + + + An alarm state of highest concern. Considered to be above the most commonly used Critical level. + + + + + + + Describe up to six ranges where either less severe ranges are a subset of more severe ranges (outside), or more severe ranges are a subset of less severe ranges (inside). In both forms, the undefined least severe range is normal. Range values are in calibrated engineering units. See FloatRangeType. + + + + + + + A range of least concern. Considered to be below the most commonly used Warning level. + + + + + A range of concern that represents the most commonly used minimum concern level for many software applications. + + + + + A range of concern in between the most commonly used Warning and Critical levels. + + + + + A range of concern that represents the most commonly used maximum concern level for many software applications. + + + + + A range of highest concern. Considered to be above the most commonly used Critical level. + + + + + + A value of outside specifies that the most severe range is outside all the other ranges: -severe -critical -distress -warning -watch normal +watch +warning +distress +critical +severe. A value of inside "inverts" these bands: -green -watch -warning -distress -critical severe +critical +distress +warning +watch. The most common form used is "outside" and is the default. + + + + + + + + Defines a base schema type used to build up the other data type specific alarm types. The definition includes a count to go into alarm (minViolations – the counts to go out of alarm is the same), a condition style alarm and a custom alarm. See AlarmConditionType, CustomAlgorithmType, BinaryAlarmConditionType, BooleanAlarmType, BinaryContextAlarmType, EnumerationAlarmType, NumericAlarmType, StringAlarmType, TimeAlarmType, TimeAlarmConditionType. + + + + + + + + A MatchCriteria may be specified for each of the 5 alarm levels. Each level is optional and the alarm should be the highest level to test true. + + + + + An escape for ridiculously complex alarm conditions. Will trigger on changes to the containing Parameter. + + + + + + + The number of successive instances that meet the alarm conditions for the alarm to trigger. The default is 1. + + + + + Optionally specify the number of successive instances that do not meet the alarm conditions to leave the alarm state. If this attribute is not specified, it is treated as being equal to minViolations (symmetric). + + + + + + + + Describe any number of alarm ranges, each with its own level (normal, warning, watch, distress, critical, severe) and range form (inside or outside). Ranges may overlap, be disjoint and so forth. Ranges within the value sprectrum non-specified are non-normal. The most severe range level of value within the ranges is the level of the alarm. Range values are in calibrated engineering units. See FloatRangeType. + + + + + + + Describe any number of alarm ranges, each with its own level (normal, warning, watch, distress, critical, severe) and range form (inside or outside). Ranges may overlap, be disjoint and so forth. Ranges within the value sprectrum non-specified are non-normal. The most severe range level of value within the ranges is the level of the alarm. Range values are in calibrated engineering units. See FloatRangeType. + + + + + + + + + Defines to type of update rates: perSecond and perContainerUpdate. See RateInStreamType. + + + + + + + + + Describe alarm conditions specific to the binary data type, extends the basic AlarmType. + + + + + + + + Alarm conditions for Boolean types + + + + + + + + Describe an ordered collection of context binary alarms, duplicates are valid. Process the contexts in list order. See BinaryContextAlarmType. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Describe an alarm when the parameter value's rate-of-change is either too fast or too slow. The change may be with respect to time (the default) or with respect to samples (delta alarms). Use the changeType attribute to select the type: changePerSecond (time) or changePerSample (delta). The change may also be ether relative (as a percentage change) or absolute as set by the changeBasis attribute. (Delta alarms are typically absolute but percentage is conceivable). The alarm also requires the spanOfInterest in both samples and seconds to have passed before it is to trigger. For time based rate of change alarms, the time specified in spanOfInterestInSeconds is used to calculate the change. For sample based rate of change alarms, the change is calculated over the number of samples specified in spanOfInterestInSamples. A typical delta alarm would set: changeType=changePerSample, changeBasis=absoluteChange, spanOfInterestInSamples=1. A typical time based version would set: changeType=changePerSecond, changeBasis=percentageChange, and spaceOfInterestInSeconds=1. To set the ranges use maxInclusive, the following definition applies: | Normal.maxInclusive | <= | Watch.maxInclusive | <= | Warning.maxInclusive | <= | Distress.maxInclusive | <= | Critical.maxInclusive | <= | Severe.maxInclusive |. And it is further assumed the absolute value of each range and sampled value it taken to evaluate the alarm. See NumericAlarmType. + + + + + + + + + + + + + Defines absoluteChange and percentageChange for use in rate of change alarms. Used by ChangeAlarmRangesType. + + + + + + + + + Defines six levels: Normal, Watch, Warning, Distress, Critical and Severe. Typical implementations color the "normal" level as green, "warning" level as yellow, and "critical" level as red. These level definitions are used throughout the alarm definitions. Some systems provide a greater fidelity with the additional levels provided here. The "normal" level is not typically needed because "normal" should be construed as none of the concern levels evaluating to true. For cases where definiing "normal" is needed, refer to the specific alarm definition types. + + + + + + + + + + + + + Defines the criticality level of a command. Criticality levels follow ISO 14950. + + + + + Normal command. Corresponds to ISO 14950 Level D telecommand criticality. + + + + + Command that is not a critical command but is essential to the success of the mission and, if sent at the wrong time, could cause momentary loss of the mission. Corresponds to ISO 14950 Level C telecommand criticality. + + + + + Command that, if executed at the wrong time or in the wrong configuration, could cause irreversible loss or damage for the mission. Corresponds to ISO 14950 Level B telecommand criticality. Some space programs have called this "restricted" and may be implemented with a secondary confirmation before transmission. + + + + + Command that is not expected to be used for nominal or foreseeable contingency operations, that is included for unforeseen contingency operations, and that could cause irreversible damage if executed at the wrong time or in the wrong configuration. Corresponds to ISO 14950 Level A telecommand criticality. Some space programs have called this "prohibited". + + + + + In the event that a program uses this value, that program will need to define the meaning of this value to their system. + + + + + In the event that a program uses this value, that program will need to define the meaning of this value to their system. + + + + + + + Defines a changePerSecond and changePerSample for use in rate of change alarms. Used by ChangeAlarmRangesType. + + + + + + + + + Describe a discrete value lookup and the value associated when the lookup evaluates to true. + + + + + + Value to use when the lookup conditions are true. + + + + + + + + Describe an alarm level and its enumeration label to trigger from. See EnumeratedAlarmType and EnumeratedParameterType. + + + + Defines six levels: Normal, Watch, Warning, Distress, Critical and Severe. Typical implementations color the "normal" level as green, "warning" level as yellow, and "critical" level as red. In the case of enumeration alarms, the "normal" is assumed by implementations to be any label not otherwise in an alarm state. + + + + + The enumeration label is the engineering/calibrated value for enumerated types. + + + + + + + + Describe an alarm state for an enumeration label where the label is engineer/calibrated value. Note that labels may represent multiple raw/uncalbrated values. + + + + + + + Describe a context that when true the alarm condition may be evaluated. See ContextMatchType and EnumerationAlarmType. + + + + + + + Describe a context in terms of a parameter and value that when true enables the context alarm definition. + + + + + + + + + Describe alarm conditions specific to the enumeration data type, extends the basic AlarmType with an EnumerationAlarmList. The alarms are described using the label (engineering/calibrated value) of the enumerated parameter. Enumeration labels may represent several raw/uncalibrated values, so as a result, a single alarm definition here may represent multiple raw values in the enumerated parameter. It is not necessary to define an alarm for raw/uncalibrated values that do not map to an enumeration. Implementations should implicitly define this as an alarm case, of which the manifestation of that is program/implementation specific. See EnumeratedParameterType. + An additional check needs to be performed to ensure that the enumeration values in the alarms are valid enumeration values for the Parameter + + + + + + + List of alarm state definitions for this enumerated type. + + + + + + Alarm state name for when no enumeration alarms evaluate to true. This defaults to "normal", which is almost always the case. Setting it to another alarm state permits a form of "inverted logic" where the alarm list can specify the normal states instead of the alarm states. + + + + + + + + + + + + + + + Describe a floating point based range, several types of ranges are supported -- one sided and two sided, inclusive or exclusive. It would not make sense to set two mins or maxes. Used in a number of locations related to ranges: ValidFloatRangeSetType or AlarmRangeType for example. + Verify that the combination provided is usable. + + + + Minimum decimal/real number value including itself. + + + + + Minimum decimal/real number value excluding itself. + + + + + Maximum decimal/real number value including itself. + + + + + Maximum decimal/real number value excluding itself. + + + + + + Describe an integral based range: minInclusive and maxInclusive. Used in a number of locations related to ranges: ValidIntegerRangeSetType for example. + + + + Minimum integer value including itself. + + + + + Maximum integer value including itself. + + + + + + A slope and intercept may be applied to scale or shift the value of the parameter in the dynamic value + + + + + + + The alarm multi-range element type permits users to define multiple alarm ranges in a sequence that goes beyond the more typical "inside" and "outside" range definitions. It can be thought of as a "barber pole" definition. + + + + + + A value of outside specifies that the most severe range is outside all the other ranges: -severe -critical -distress -warning -watch normal +watch +warning +distress +critical +severe. A value of inside "inverts" these bands: -green -watch -warning -distress -critical severe +critical +distress +warning +watch. The most common form used is "outside" and is the default. + + + + + The level of concern for this alarm definition. + + + + + + + + Describe alarm conditions specific to the numeric data types, extends the basic AlarmType with StaticAlarmRanges and ChangeAlarmRanges. See FloatParameterType and IntegerParameterType. + + + + + + + StaticAlarmRanges are used to trigger alarms when the parameter value passes some threshold value. + + + + + ChangeAlarmRanges are used to trigger alarms when the parameter value changes by a rate or quantity from a reference. + + + + + Similar to but more lenient form of StaticAlarmRanges. + + + + + + + + + Describe a parameter dependent context, that when evaluates to true, enables the use of this alarm definition. See ContextMatchType and NumericAlarmType. + + + + + + + Contains the evaluation criteria for a parameter dependent test, that when evaluates to true, enables this alarm definition. + + + + + + + + + Describe a string alarm condition based on matching a regular expression. The level and regular expression are described. The specific implementation of the regular expression syntax is not specified in the schema at this time. See StringAlarmListType. + + + + + + + Describe an ordered collection of string alarms, where duplicates are valid. Evaluate the alarms in list order. The first to evaluate to true takes precedence. See StringAlarmLevelType. + + + + + + + + Describe alarms specific to the string data type, extends the basic AlarmType, while adding a StringAlarmList and defaultAlarmLevel attribute. The string alarm list is evaluated in list order. See ConcernsLevelsType and StringAlarmListType. + + + + + + + + + + + + + Describe a context that when true the alarm may be evaluated. See ContextMatchType and StringAlarmType. + + + + + + + + + + + + An ordered collection of numeric alarms associated with a context. Process the contexts in list order. See StringContextAlarmType. + + + + + + + + Alarms associated with time data types + + + + + + + StaticAlarmRanges are used to trigger alarms when the parameter value passes some threshold value + + + + + ChangePerSecondAlarmRanges are used to trigger alarms when the parameter value's rate-of-change passes some threshold value. An alarm condition that triggers when the value changes too fast (or too slow) + + + + + + + + + + + + + + + + + + + + + Context alarms are applied when the ContextMatch is true. Context alarms override Default alarms + + + + + + + + + + + + XTCE-specific replacement for xtce:NonNegativeLongType which more cleanly maps to native data types. + + + + + + + + XTCE-specific replacement for xtce:PositiveLongType which more cleanly maps to native data types. + + + + + + + + Optionally specify if this information pertains to something other than the calibrated/engineering value. + + + + + + + + + + \ No newline at end of file diff --git a/config/obc/ppd/target/cdr_workspace_overlay/mdb/cfs-ccsds.xml b/config/obc/ppd/target/cdr_workspace_overlay/mdb/cfs-ccsds.xml new file mode 100644 index 000000000..48e9c7f30 --- /dev/null +++ b/config/obc/ppd/target/cdr_workspace_overlay/mdb/cfs-ccsds.xml @@ -0,0 +1,178 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 160 + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/config/obc/ppd/target/cfe_es_startup.scr b/config/obc/ppd/target/cfe_es_startup.scr index d99d08a36..c963f5392 100644 --- a/config/obc/ppd/target/cfe_es_startup.scr +++ b/config/obc/ppd/target/cfe_es_startup.scr @@ -1,4 +1,5 @@ CFE_LIB, /cf/apps/CFS_LIB.so, CFS_LibInit, CFS_LIB, 0, 0, 0x0, 0, 2; +CFE_LIB, /cf/apps/MBP_LIB.so, MBP_LibInit, MBP_LIB, 0, 0, 0x0, 0, 2; CFE_LIB, /cf/apps/PRMLIB.so, PRMLIB_LibInit, PRMLIB, 0, 0, 0x0, 0, 2; CFE_LIB, /cf/apps/PX4LIB.so, PX4LIB_LibInit, PX4LIB, 0, 0, 0x0, 0, 2; CFE_LIB, /cf/apps/PQ_LIB.so, PQ_LibInit, PQ_LIB, 0, 0, 0x0, 0, 2; diff --git a/config/obc/ppd/wh_config.yaml b/config/obc/ppd/wh_config.yaml index 220188630..67c6b5df6 100644 --- a/config/obc/ppd/wh_config.yaml +++ b/config/obc/ppd/wh_config.yaml @@ -1,6 +1,6 @@ --- config_base: ${PROJECT_SOURCE_DIR} - +cpu_id: PPD modules: core: modules: @@ -8,3 +8,31 @@ modules: definition: ${PROJECT_SOURCE_DIR}/core/osal/fsw/posix-fast/wh_design.yaml psp: definition: ${PROJECT_SOURCE_DIR}/core/psp/fsw/obc-ppd/wh_design.yaml + to: + commands: + TO_CMD_MID: + msgID: 0x189f + commands: + EnableChannel: + cc: 10 + struct: TO_EnableChannelCmd_t + DisableChannel: + cc: 11 + struct: TO_DisableChannelCmd_t + + events: + TO_TLMOUTSOCKET_ERR_EID: + id: 29 + TO_TLMOUTENA_INF_EID: + id: 30 + TO_TLMOUTENA_ERR_EID: + id: 31 + TO_TLMOUTDIS_INF_EID: + id: 32 + TO_TLMOUTDIS_ERR_EID: + id: 33 + TO_TLMOUTSEND_ERR_EID: + id: 34 + TO_TLMOUTSTOP_ERR_EID: + id: 35 + diff --git a/config/obc/sitl/target/airliner.service b/config/obc/sitl/target/airliner.service deleted file mode 100644 index 578bcb234..000000000 --- a/config/obc/sitl/target/airliner.service +++ /dev/null @@ -1,19 +0,0 @@ -[Unit] -Description=Airliner UAS Flight Software -After=network.target auditd.service -ConditionPathExists=!/opt/airliner/disable - -[Service] -Type=simple -WorkingDirectory=/opt/airliner/ -ExecStart=/opt/airliner/core-bin -ExecReload=/bin/kill -9 $MAINPID -#ExecReload=/opt/airliner/allstop -ExecStop=/bin/kill -9 $MAINPID -ExecStop=/opt/airliner/allstop -KillMode=process -#Restart=on-failure - -[Install] -WantedBy=multi-user.target -Alias=airliner.service diff --git a/config/obc/sitl/target/allstop/CMakeLists.txt b/config/obc/sitl/target/allstop/CMakeLists.txt deleted file mode 100644 index 1e64d682c..000000000 --- a/config/obc/sitl/target/allstop/CMakeLists.txt +++ /dev/null @@ -1,4 +0,0 @@ - -add_executable(allstop - main.cpp -) \ No newline at end of file diff --git a/config/obc/sitl/target/allstop/main.cpp b/config/obc/sitl/target/allstop/main.cpp deleted file mode 100644 index 8101039b8..000000000 --- a/config/obc/sitl/target/allstop/main.cpp +++ /dev/null @@ -1,117 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include - - -#define RCOUT_ZYNQ_PWM_BASE (0x43c00000) -#define FREQUENCY_PWM (400) -#define TICK_PER_S (50000000) -#define TICK_PER_US (50) -#define DEVICE_PATH "/dev/mem" -#define MAX_MOTOR_OUTPUTS (8) -#define PWM_DISARMED (900) - - -/* The following struct is used by the SharedMemCmd_t struct and overlayed - * over the ocpoc PPM registers to control the PWM hardware. - */ -typedef struct -{ - unsigned int Period; - unsigned int Hi; -} PeriodHi_t; - - -/* The following struct is overlayed over the ocpoc PPM registers to control - * the PWM hardware. - */ -typedef struct -{ - PeriodHi_t PeriodHi[MAX_MOTOR_OUTPUTS]; -} SharedMemCmd_t; - -volatile SharedMemCmd_t *SharedMemCmd; - - -void StopMotors(void); -unsigned int Freq2tick(unsigned short FreqHz); -void SetMotorOutputs(const unsigned short *PWM); - - -int main( int argc, const char* argv[] ) -{ - unsigned int i = 0; - int returnVal = 0; - int fd = 0; - - printf("Stopping all motors.\n"); - - /* Get the handle to the shared memory. */ - fd = open(DEVICE_PATH, O_RDWR | O_SYNC); - SharedMemCmd = (SharedMemCmd_t *) mmap(0, 0x1000, - PROT_READ | PROT_WRITE, MAP_SHARED, fd, - RCOUT_ZYNQ_PWM_BASE); - close(fd); - - if (SharedMemCmd <= 0) - { - returnVal = errno; - goto end_of_function; - } - - /* Note: this appears to be required actuators to initialize. */ - for (i = 0; i < MAX_MOTOR_OUTPUTS; ++i) - { - SharedMemCmd->PeriodHi[i].Period = - Freq2tick(FREQUENCY_PWM); - SharedMemCmd->PeriodHi[i].Hi = - Freq2tick(FREQUENCY_PWM) / 2; - } - - /* Stop all the motors. */ - StopMotors(); - -end_of_function: - return returnVal; -} - - -void StopMotors(void) -{ - unsigned short disarmed_pwm[MAX_MOTOR_OUTPUTS]; - - for (unsigned int i = 0; i < MAX_MOTOR_OUTPUTS; ++i) - { - disarmed_pwm[i] = PWM_DISARMED; - } - - SetMotorOutputs(disarmed_pwm); -} - - -unsigned int Freq2tick(unsigned short FreqHz) -{ - unsigned int duty = TICK_PER_S / (unsigned long)FreqHz; - - return duty; -} - - - -void SetMotorOutputs(const unsigned short *PWM) -{ - unsigned int i = 0; - - if(SharedMemCmd != 0) - { - /* Convert this to duty_cycle in ns */ - for (i = 0; i < MAX_MOTOR_OUTPUTS; ++i) - { - SharedMemCmd->PeriodHi[i].Hi = TICK_PER_US * PWM[i]; - } - } -} diff --git a/config/obc/sitl/target/apps/cf/CMakeLists.txt b/config/obc/sitl/target/apps/cf/CMakeLists.txt deleted file mode 100644 index 248a08896..000000000 --- a/config/obc/sitl/target/apps/cf/CMakeLists.txt +++ /dev/null @@ -1,10 +0,0 @@ -set(APP_NAME cf) - -buildliner_add_table( - ${APP_NAME} - NAME cf_cfgtable - SOURCES ${CMAKE_CURRENT_SOURCE_DIR}/tables/cf_cfgtable.c - INCLUDES ${CMAKE_CURRENT_SOURCE_DIR}/src/ -) - - diff --git a/config/obc/sitl/target/apps/cf/tables/cf_cfgtable.c b/config/obc/sitl/target/apps/cf/tables/cf_cfgtable.c deleted file mode 100644 index e4dd91e34..000000000 --- a/config/obc/sitl/target/apps/cf/tables/cf_cfgtable.c +++ /dev/null @@ -1,323 +0,0 @@ -/************************************************************************ -** Includes -*************************************************************************/ -#include "cfe.h" -#include "cfe_tbl_filedef.h" -#include "cf_tbldefs.h" -#include "cf_platform_cfg.h" -#include "cf_msgids.h" -#include "cf_defs.h" - -static OS_USED CFE_TBL_FileDef_t CFE_TBL_FileDef = -{ - "CF_ConfigTable", "CF.ConfigTable", "CF Config Tbl", - "cf_cfgtable.tbl", sizeof (cf_config_table_t) -}; - - -/* -** Default playback table data - See NOTE Above -*/ - -cf_config_table_t CF_ConfigTable = -{ - - "CF Default Table",/* TableIdString */ - 2, /* TableVersion (integer) */ - 4, /* NumEngCyclesPerWakeup */ - 2, /* NumWakeupsPerQueueChk */ - 4, /* NumWakeupsPerPollDirChk */ - 100, /* UplinkHistoryQDepth */ - 0, /* Reserved1 */ - 0, /* Reserved2 */ - "10", /* AckTimeout (secs, entered as string) */ - "2", /* AckLimit (max timeouts, string) */ - "5", /* NakTimeout (secs, string) */ - "3", /* NakLimit (max timeouts, string) */ - "20", /* InactivityTimeout (secs, string) */ - "200", /* OutgoingFileChunkSize (bytes, string)*/ - "no", /* SaveIncompleteFiles (yes,no, string) */ - "0.24", /* Flight EntityId - 2 byte dotted-decimal string eg. "0.255"*/ - - { /* Input Channel Array */ - - { /* Input Channel 0 */ - - CF_INCOMING_PDU_MID, - 0, /* Output Chan for Class 2 Uplink Responses, ACK-EOF,Nak,Fin etc) */ - 0, /* spare */ - - }, /* end Input Channel 0 */ - - }, /* end Input Channel Array */ - - { /* Playback Channel Array */ - - { /* Playback Channel #0 */ - CF_ENTRY_IN_USE, /* Playback Channel Entry In Use */ - CF_ENABLED, /* Dequeue Enable */ - CF_SPACE_TO_GND_PDU_MID, /* Space To Gnd PDU MsgId */ - 100, /* Pending Queue Depth */ - 100, /* History Queue Depth */ - "OutputChan0", /* Playback Channel Name */ - "TO_CF_CH0_SEM", /* Handshake Semaphore Name */ - - { /* Polling Directory Array */ - - { /* Polling Directory 0 */ - CF_ENTRY_IN_USE,/* Poll Directory In Use or Not */ - CF_DISABLED, /* Enable State */ - 1, /* Class (1 or 2)*/ - 5, /* Priority */ - CF_KEEP_FILE, /* Preserve files after successful transfer? */ - 0, /* Reserved1 */ - 0, /* Reserved2 */ - 0, /* Reserved3 */ - "0.23", /* Gnd EntityId - 2 byte dotted-decimal string eg. "0.255"*/ - "/cf/ch0poll0/", /* SrcPath, no spaces, fwd slash at end */ - "cftesting/", /* DstPath, no spaces */ - },/* End Polling Directory 0 */ - - { /* Polling Directory 1 */ - CF_ENTRY_IN_USE,/* Poll Directory In Use or Not */ - CF_DISABLED, /* Enable State */ - 1, /* Class (1 or 2)*/ - 0, /* Priority */ - CF_KEEP_FILE, /* Preserve files after successful transfer? */ - 0, /* Reserved1 */ - 0, /* Reserved2 */ - 0, /* Reserved3 */ - "0.23", /* Gnd EntityId - 2 byte dotted-decimal string eg. "0.255"*/ - "/cf/ch0poll1/", /* SrcPathname */ - "/gnd/", /* DestPathname */ - - },/* End Polling Directory 1 */ - - - { /* Polling Directory 2 */ - CF_ENTRY_IN_USE,/* Poll Directory In Use or Not */ - CF_DISABLED, /* Enable State */ - 1, /* Class (1 or 2)*/ - 5, /* Priority */ - CF_DELETE_FILE, /* Preserve files after successful transfer? */ - 0, /* Reserved1 */ - 0, /* Reserved2 */ - 0, /* Reserved3 */ - "0.23", /* Gnd EntityId - 2 byte dotted-decimal string eg. "0.255"*/ - "/cf/ch0poll2/", /* SrcPathname */ - "cftesting/", /* DstPathname */ - },/* End Polling Directory 2 */ - - { /* Polling Directory 3 */ - CF_ENTRY_IN_USE,/* Poll Directory In Use or Not */ - CF_DISABLED, /* Enable State */ - 1, /* Class (1 or 2)*/ - 0, /* Priority */ - CF_KEEP_FILE, /* Preserve files after successful transfer? */ - 0, /* Reserved1 */ - 0, /* Reserved2 */ - 0, /* Reserved3 */ - "0.23", /* Gnd EntityId - 2 byte dotted-decimal string eg. "0.255"*/ - "/cf/ch0poll3/", /* SrcPathname */ - "/gnd/", /* DestPathname */ - - },/* End Polling Directory 3 */ - - { /* Polling Directory 4 */ - CF_ENTRY_IN_USE,/* Poll Directory In Use or Not */ - CF_DISABLED, /* Enable State */ - 1, /* Class (1 or 2)*/ - 5, /* Priority */ - CF_DELETE_FILE, /* Preserve files after successful transfer? */ - 0, /* Reserved1 */ - 0, /* Reserved2 */ - 0, /* Reserved3 */ - "0.23", /* Gnd EntityId - 2 byte dotted-decimal string eg. "0.255"*/ - "/cf/ch0poll4/", /* SrcPathname */ - "cftesting/", /* DstPathname */ - },/* End Polling Directory 4 */ - - { /* Polling Directory 5 */ - CF_ENTRY_IN_USE,/* Poll Directory In Use or Not */ - CF_DISABLED, /* Enable State */ - 1, /* Class (1 or 2)*/ - 0, /* Priority */ - CF_KEEP_FILE, /* Preserve files after successful transfer? */ - 0, /* Reserved1 */ - 0, /* Reserved2 */ - 0, /* Reserved3 */ - "0.23", /* Gnd EntityId - 2 byte dotted-decimal string eg. "0.255"*/ - "/cf/ch0poll5/", /* SrcPathname */ - "/gnd/", /* DestPathname */ - - },/* End Polling Directory 5 */ - - { /* Polling Directory 6 */ - CF_ENTRY_IN_USE,/* Poll Directory In Use or Not */ - CF_DISABLED, /* Enable State */ - 1, /* Class (1 or 2)*/ - 5, /* Priority */ - CF_DELETE_FILE, /* Preserve files after successful transfer? */ - 0, /* Reserved1 */ - 0, /* Reserved2 */ - 0, /* Reserved3 */ - "0.23", /* Gnd EntityId - 2 byte dotted-decimal string eg. "0.255"*/ - "/cf/ch0poll6/", /* SrcPathname */ - "cftesting/", /* DstPathname */ - },/* End Polling Directory 6 */ - - { /* Polling Directory 7 */ - CF_ENTRY_IN_USE,/* Poll Directory In Use or Not */ - CF_DISABLED, /* Enable State */ - 1, /* Class (1 or 2)*/ - 0, /* Priority */ - CF_KEEP_FILE, /* Preserve files after successful transfer? */ - 0, /* Reserved1 */ - 0, /* Reserved2 */ - 0, /* Reserved3 */ - "0.23", /* Gnd EntityId - 2 byte dotted-decimal string eg. "0.255"*/ - "/cf/ch0poll7/", /* SrcPathname */ - "/gnd/", /* DestPathname */ - - },/* End Polling Directory 7 */ - - }, /* End Polling Directory Array */ - - }, /* End Playback Channel #0 */ - - - { /* Playback Channel #1 */ - CF_ENTRY_UNUSED, /* Playback Channel Entry In Use */ - CF_DISABLED, /* Dequeue Enable */ - CF_SPACE_TO_GND_PDU_MID, /* Space To Gnd PDU MsgId */ - 100, /* Pending Queue Depth */ - 100, /* History Queue Depth */ - "OutputChan1", /* Playback Channel Name */ - "TO_CF_CH1_SEM", /* Handshake Semaphore Name */ - - { /* Polling Directory Array */ - - { /* Polling Directory 0 */ - CF_ENTRY_UNUSED,/* Poll Directory In Use or Not */ - CF_DISABLED, /* Enable State */ - 1, /* Class (1 or 2)*/ - 0, /* Priority */ - CF_DELETE_FILE, /* Preserve files after successful transfer? */ - 0, /* Reserved1 */ - 0, /* Reserved2 */ - 0, /* Reserved3 */ - "0.23", /* Gnd EntityId - 2 byte dotted-decimal string eg. "0.255"*/ - "/cf/ch1poll0/", /* SrcPathname */ - "cftesting/", /* DstPathname */ - },/* End Polling Directory 0 */ - - { /* Polling Directory 1 */ - CF_ENTRY_UNUSED,/* Poll Directory In Use or Not */ - CF_DISABLED, /* Enable State */ - 1, /* Class (1 or 2)*/ - 0, /* Priority */ - CF_DELETE_FILE, /* Preserve files after successful transfer? */ - 0, /* Reserved1 */ - 0, /* Reserved2 */ - 0, /* Reserved3 */ - "0.23", /* Gnd EntityId - 2 byte dotted-decimal string eg. "0.255"*/ - "/cf/ch1poll1/", /* SrcPathname */ - "cftesting/", /* DstPathname */ - }, /* End Polling Directory 1 */ - - { /* Polling Directory 2 */ - CF_ENTRY_UNUSED,/* Poll Directory In Use or Not */ - CF_DISABLED, /* Enable State */ - 1, /* Class (1 or 2)*/ - 0, /* Priority */ - CF_DELETE_FILE, /* Preserve files after successful transfer? */ - 0, /* Reserved1 */ - 0, /* Reserved2 */ - 0, /* Reserved3 */ - "0.23", /* Gnd EntityId - 2 byte dotted-decimal string eg. "0.255"*/ - "/cf/ch1poll2/", /* SrcPathname */ - "cftesting/", /* DstPathname */ - },/* End Polling Directory 2 */ - - { /* Polling Directory 3 */ - CF_ENTRY_UNUSED,/* Poll Directory In Use or Not */ - CF_DISABLED, /* Enable State */ - 1, /* Class (1 or 2)*/ - 0, /* Priority */ - CF_DELETE_FILE, /* Preserve files after successful transfer? */ - 0, /* Reserved1 */ - 0, /* Reserved2 */ - 0, /* Reserved3 */ - "0.23", /* Gnd EntityId - 2 byte dotted-decimal string eg. "0.255"*/ - "/cf/ch1poll3/", /* SrcPathname */ - "cftesting/", /* DstPathname */ - }, /* End Polling Directory 3 */ - - { /* Polling Directory 4 */ - CF_ENTRY_UNUSED,/* Poll Directory In Use or Not */ - CF_DISABLED, /* Enable State */ - 1, /* Class (1 or 2)*/ - 0, /* Priority */ - CF_DELETE_FILE, /* Preserve files after successful transfer? */ - 0, /* Reserved1 */ - 0, /* Reserved2 */ - 0, /* Reserved3 */ - "0.23", /* Gnd EntityId - 2 byte dotted-decimal string eg. "0.255"*/ - "/cf/ch1poll4/", /* SrcPathname */ - "cftesting/", /* DstPathname */ - },/* End Polling Directory 4 */ - - { /* Polling Directory 5 */ - CF_ENTRY_UNUSED,/* Poll Directory In Use or Not */ - CF_DISABLED, /* Enable State */ - 1, /* Class (1 or 2)*/ - 0, /* Priority */ - CF_DELETE_FILE, /* Preserve files after successful transfer? */ - 0, /* Reserved1 */ - 0, /* Reserved2 */ - 0, /* Reserved3 */ - "0.23", /* Gnd EntityId - 2 byte dotted-decimal string eg. "0.255"*/ - "/cf/ch1poll5/", /* SrcPathname */ - "cftesting/", /* DstPathname */ - }, /* End Polling Directory 5 */ - - { /* Polling Directory 6 */ - CF_ENTRY_UNUSED,/* Poll Directory In Use or Not */ - CF_DISABLED, /* Enable State */ - 1, /* Class (1 or 2)*/ - 0, /* Priority */ - CF_DELETE_FILE, /* Preserve files after successful transfer? */ - 0, /* Reserved1 */ - 0, /* Reserved2 */ - 0, /* Reserved3 */ - "0.23", /* Gnd EntityId - 2 byte dotted-decimal string eg. "0.255"*/ - "/cf/ch1poll6/", /* SrcPathname */ - "cftesting/", /* DstPathname */ - },/* End Polling Directory 6 */ - - { /* Polling Directory 7 */ - CF_ENTRY_UNUSED,/* Poll Directory In Use or Not */ - CF_DISABLED, /* Enable State */ - 1, /* Class (1 or 2)*/ - 0, /* Priority */ - CF_DELETE_FILE, /* Preserve files after successful transfer? */ - 0, /* Reserved1 */ - 0, /* Reserved2 */ - 0, /* Reserved3 */ - "0.23", /* Gnd EntityId - 2 byte dotted-decimal string eg. "0.255"*/ - "/cf/ch1poll7/", /* SrcPathname */ - "cftesting/", /* DstPathname */ - }, /* End Polling Directory 7 */ - - }, /* End Polling Directory Array */ - - }, /* End Playback Channel #1 */ - - }, /* End Playback Channel Array */ - -}; /* End CF_ConfigTable */ - - -/************************/ -/* End of File Comment */ -/************************/ diff --git a/config/obc/sitl/target/apps/ci/CMakeLists.txt b/config/obc/sitl/target/apps/ci/CMakeLists.txt deleted file mode 100644 index 9d3031d32..000000000 --- a/config/obc/sitl/target/apps/ci/CMakeLists.txt +++ /dev/null @@ -1,36 +0,0 @@ -set(APP_NAME ci) - -buildliner_add_table( - ${APP_NAME} - NAME ci_config - SOURCES ${CMAKE_CURRENT_SOURCE_DIR}/tables/ci_config.c - INCLUDES ${CMAKE_CURRENT_SOURCE_DIR}/src/ -) - -buildliner_add_app_unit_test_src(${APP_NAME} SOURCES ${CMAKE_CURRENT_SOURCE_DIR}/tables/ci_config.c) - -buildliner_add_app_unit_test(ci-custom-ut - UTASSERT - NO_HELGRIND - NO_MASSIF - - SOURCES - ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/ci_testrunner.c - ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/ci_custom_test.c - ${CMAKE_CURRENT_SOURCE_DIR}/ci_custom.c - ${PROJECT_SOURCE_DIR}/apps/ci/fsw/src/ci_app.c - ${PROJECT_SOURCE_DIR}/apps/ci/fsw/src/ci_config_utils.c - ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/ci_mock_os_calls.c - ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/ci_test_utils.c - ${PROJECT_SOURCE_DIR}/core/base/ut_assert/src/ut_cfe_es_hooks.c - - INCLUDES - ${PROJECT_SOURCE_DIR}/apps/ci/fsw/src/ - - WRAPPERS - socket - bind - - VALGRIND_SUPPRESSION_FILE - ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/ci-custom.supp -) diff --git a/config/obc/sitl/target/apps/ci/ci_custom.c b/config/obc/sitl/target/apps/ci/ci_custom.c deleted file mode 100644 index 5a9c11ef3..000000000 --- a/config/obc/sitl/target/apps/ci/ci_custom.c +++ /dev/null @@ -1,111 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#include "ci_custom.h" -#include "ci_platform_cfg.h" -#include -#include -#include -#include "ci_events.h" -#include -#include - -#define CI_CUSTOM_RETURN_CODE_NULL_POINTER (-1) - - -typedef struct -{ - int Socket; - uint16 Port; -} CI_AppCustomData_t; - -CI_AppCustomData_t CI_AppCustomData = {0, 5010}; - - -osalbool CI_AddCustomEventFilters(uint32 *count) -{ - return TRUE; -} - - -int32 CI_InitCustom(void) -{ - int32 Status = CFE_SUCCESS; - int reuseaddr = 1; - struct sockaddr_in address; - - if((CI_AppCustomData.Socket = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP)) < 0) - { - CFE_EVS_SendEvent(CI_SOCKET_ERR_EID, CFE_EVS_ERROR, - "Socket errno: %i", errno); - Status = -1; - goto end_of_function; - } - - setsockopt(CI_AppCustomData.Socket, SOL_SOCKET, SO_REUSEADDR, &reuseaddr, sizeof(reuseaddr)); - - bzero((char *) &address, sizeof(address)); - address.sin_family = AF_INET; - address.sin_addr.s_addr = htonl (INADDR_ANY); - address.sin_port = htons(CI_AppCustomData.Port); - - if ( (bind(CI_AppCustomData.Socket, (struct sockaddr *) &address, sizeof(address)) < 0) ) - { - CFE_EVS_SendEvent(CI_SOCKET_ERR_EID, CFE_EVS_ERROR,"Bind socket failed = %d", errno); - Status = -1; - goto end_of_function; - } - - CFE_EVS_SendEvent(CI_ENA_INF_EID, CFE_EVS_INFORMATION, - "UDP command input enabled on port %u.", - CI_AppCustomData.Port); - -end_of_function: - return Status; - -} - - -void CI_ReadMessage(uint8* buffer, uint32* size) -{ - *size = recv(CI_AppCustomData.Socket, - (char *)buffer, - (size_t)size, 0); -} - - -void CI_CleanupCustom(void) -{ - close(CI_AppCustomData.Socket); -} - diff --git a/config/obc/sitl/target/apps/ci/tables/ci_config.c b/config/obc/sitl/target/apps/ci/tables/ci_config.c deleted file mode 100644 index dcd0efdce..000000000 --- a/config/obc/sitl/target/apps/ci/tables/ci_config.c +++ /dev/null @@ -1,68 +0,0 @@ -/* -** Pragmas -*/ - -/* -** Include Files -*/ -#include "cfe_tbl_filedef.h" -#include "ci_tbldefs.h" - -/* -** Local Defines -*/ - -/* -** Local Structure Declarations -*/ -static OS_USED CFE_TBL_FileDef_t CFE_TBL_FileDef = -{ - /* Content format: ObjName[64], TblName[38], Desc[32], TgtFileName[20], ObjSize - ** ObjName - variable name of config table, e.g., CI_ConfigDefTbl[] - ** TblName - app's table name, e.g., CI.CONFIG_TBL, where CI is the same app name - ** used in cfe_es_startup.scr, and CI_defConfigTbl is the same table - ** name passed in to CFE_TBL_Register() - ** Desc - description of table in string format - ** TgtFileName[20] - table file name, compiled as .tbl file extension - ** ObjSize - size of the entire table - */ - - "CI_ConfigTbl", "CI.CONFIG_TBL", "CI default config table", - "ci_config.tbl", sizeof(CI_ConfigTblEntry_t) -}; - -/* -** External Global Variables -*/ - -/* -** Global Variables -*/ - -/* Default CI config table data */ -CI_ConfigTblEntry_t CI_ConfigTbl = -{ - /* Table ID */ - 1, - { - /* Registered Commands */ - {0x1806, 2, STEP_2, UNAUTHORIZED, 0, LOG} // CFE ES Proc/Power Reset - } -}; - -/* -** Local Variables -*/ - -/* -** Function Prototypes -*/ - -/* -** Function Definitions -*/ - -/*======================================================================================= -** End of file ci_config.c -**=====================================================================================*/ - diff --git a/config/obc/sitl/target/apps/ci/unit_test/ci-custom.supp b/config/obc/sitl/target/apps/ci/unit_test/ci-custom.supp deleted file mode 100644 index 1864afc99..000000000 --- a/config/obc/sitl/target/apps/ci/unit_test/ci-custom.supp +++ /dev/null @@ -1,59 +0,0 @@ -# The following hits are a result of mallocs in UtList_Add. This is -# unit test specific code and does not impact the flight code. -{ - - Memcheck:Leak - match-leak-kinds: reachable - fun:malloc - fun:UtList_Add - fun:Ut_CFE_EVS_SendEventHook - fun:CFE_EVS_SendEvent - fun:CI_InitCustom - fun:Test_CI_InitCustom_Nominal - fun:UtTest_Run - fun:main -} - -{ - - Memcheck:Leak - match-leak-kinds: reachable - fun:malloc - fun:UtList_Add - fun:Ut_CFE_EVS_SendEventHook - fun:CFE_EVS_SendEvent - fun:CI_InitCustom - fun:Test_CI_InitCustom_Nominal - fun:UtTest_Run - fun:main -} - -{ - - Memcheck:Leak - match-leak-kinds: reachable - fun:malloc - fun:UtList_Add - fun:Ut_CFE_EVS_SendEventHook - fun:CFE_EVS_SendEvent - fun:CI_InitCustom - fun:Test_CI_InitCustom_Nominal - fun:UtTest_Run - fun:main -} - -{ - - Memcheck:Leak - match-leak-kinds: reachable - fun:malloc - fun:UtList_Add - fun:Ut_CFE_EVS_SendEventHook - fun:CFE_EVS_SendEvent - fun:CI_InitCustom - fun:Test_CI_InitCustom_Nominal - fun:UtTest_Run - fun:main -} - -################################### diff --git a/config/obc/sitl/target/apps/ci/unit_test/ci_custom_test.c b/config/obc/sitl/target/apps/ci/unit_test/ci_custom_test.c deleted file mode 100644 index f45ed5441..000000000 --- a/config/obc/sitl/target/apps/ci/unit_test/ci_custom_test.c +++ /dev/null @@ -1,124 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#include "ci_custom_test.h" -#include "ci_app.h" -#include "ci_test_utils.h" - -#include "uttest.h" -#include "ut_osapi_stubs.h" -#include "ut_cfe_sb_stubs.h" -#include "ut_cfe_es_stubs.h" -#include "ut_cfe_es_hooks.h" -#include "ut_cfe_evs_stubs.h" -#include "ut_cfe_evs_hooks.h" -#include "ut_cfe_time_stubs.h" -#include "ut_cfe_psp_memutils_stubs.h" -#include "ut_cfe_tbl_stubs.h" -#include "ut_cfe_fs_stubs.h" -#include "ut_cfe_time_stubs.h" - -int SOCK_RET_CODE; -int BIND_RET_CODE; - -/** - * Test CI_InitCustom(), Bad socket - */ -void Test_CI_InitCustom_Bad_Socket(void) -{ - int32 retCode = 0; - - /* Set to cause to fail */ - SOCK_RET_CODE = -1; - - /* Execute the function being tested */ - retCode = CI_InitCustom(); - - /* Verify results */ - UtAssert_True(retCode==-1,"Return = -1"); - UtAssert_EventSent(CI_SOCKET_ERR_EID, CFE_EVS_ERROR, "", "Socket error"); - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); -} - -/** - * Test CI_InitCustom(), Bad bind - */ -void Test_CI_InitCustom_Bad_Bind(void) -{ - int32 retCode = 0; - - /* Set to cause to fail */ - SOCK_RET_CODE = 0; - BIND_RET_CODE = -1; - - /* Execute the function being tested */ - retCode = CI_InitCustom(); - - /* Verify results */ - UtAssert_True(retCode==-1,"Return = -1"); - UtAssert_EventSent(CI_SOCKET_ERR_EID, CFE_EVS_ERROR, "", "Bind error"); - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); -} - -/** - * Test CI_InitCustom(), Nominal - */ -void Test_CI_InitCustom_Nominal(void) -{ - int32 retCode = -1; - - /* Set to cause to pass */ - SOCK_RET_CODE = 0; - BIND_RET_CODE = 0; - - /* Execute the function being tested */ - retCode = CI_InitCustom(); - - /* Verify results */ - UtAssert_True(retCode==0,"Return = 0"); - UtAssert_EventSent(CI_ENA_INF_EID, CFE_EVS_INFORMATION, "", "Socket opened"); - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); -} - -/************************************************************************** - * Rollup Test Cases - **************************************************************************/ -void CI_Custom_Test_AddTestCases(void) -{ - UtTest_Add(Test_CI_InitCustom_Bad_Socket, CI_Test_Setup, CI_Test_TearDown, - "Test_CI_InitCustom_Bad_Socket"); - UtTest_Add(Test_CI_InitCustom_Bad_Bind, CI_Test_Setup, CI_Test_TearDown, - "Test_CI_InitCustom_Bad_Bind"); - UtTest_Add(Test_CI_InitCustom_Nominal, CI_Test_Setup, CI_Test_TearDown, - "Test_CI_InitCustom_Nominal"); -} diff --git a/config/obc/sitl/target/apps/ci/unit_test/ci_custom_test.h b/config/obc/sitl/target/apps/ci/unit_test/ci_custom_test.h deleted file mode 100644 index dbc880681..000000000 --- a/config/obc/sitl/target/apps/ci/unit_test/ci_custom_test.h +++ /dev/null @@ -1,48 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - - -#ifndef CI_CUSTOM_TEST_H -#define CI_CUSTOM_TEST_H - -#ifdef __cplusplus -extern "C" { -#endif - -void CI_Custom_Test_AddTestCases(void); - -#ifdef __cplusplus -} -#endif - -#endif /* CI_CUSTOM_TEST_H */ diff --git a/config/obc/sitl/target/apps/ci/unit_test/ci_mock_os_calls.c b/config/obc/sitl/target/apps/ci/unit_test/ci_mock_os_calls.c deleted file mode 100644 index f16a1cc2a..000000000 --- a/config/obc/sitl/target/apps/ci/unit_test/ci_mock_os_calls.c +++ /dev/null @@ -1,57 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -int SOCK_RET_CODE = 0; -int HTONL_RET_CODE = 0; -int HTONS_RET_CODE = 0; -int BIND_RET_CODE = 0; - -int __wrap_socket (int namespace, int style, int protocol) -{ - return SOCK_RET_CODE; -} - -//int __wrap_htonl (int hostlong) -//{ -// return HTONL_RET_CODE; -//} -// -//int __wrap_htons (int hostshort) -//{ -// return HTONS_RET_CODE; -//} - -int __wrap_bind (int socket, int *addr, int length) -{ - return BIND_RET_CODE; -} diff --git a/config/obc/sitl/target/apps/ci/unit_test/ci_mock_os_calls.h b/config/obc/sitl/target/apps/ci/unit_test/ci_mock_os_calls.h deleted file mode 100644 index 876608286..000000000 --- a/config/obc/sitl/target/apps/ci/unit_test/ci_mock_os_calls.h +++ /dev/null @@ -1,50 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#ifndef CI_MOCK_OS_CALLS_H -#define CI_MOCK_OS_CALLS_H - -#ifdef __cplusplus -extern "C" { -#endif - -extern int SOCK_RET_CODE; -extern int HTONL_RET_CODE; -extern int HTONS_RET_CODE; -extern int BIND_RET_CODE - -#ifdef __cplusplus -} -#endif - -#endif /* MOCK_OS_CALLS_H */ diff --git a/config/obc/sitl/target/apps/ci/unit_test/ci_test_utils.c b/config/obc/sitl/target/apps/ci/unit_test/ci_test_utils.c deleted file mode 100644 index 2f1db3298..000000000 --- a/config/obc/sitl/target/apps/ci/unit_test/ci_test_utils.c +++ /dev/null @@ -1,83 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - - -#include "ci_test_utils.h" - -#include "ut_cfe_evs_hooks.h" -#include "ut_cfe_time_stubs.h" -#include "ut_cfe_psp_memutils_stubs.h" -#include "ut_cfe_tbl_stubs.h" -#include "ut_cfe_tbl_hooks.h" -#include "ut_cfe_fs_stubs.h" -#include "ut_cfe_time_stubs.h" -#include "ut_osapi_stubs.h" -#include "ut_osfileapi_stubs.h" -#include "ut_cfe_sb_stubs.h" -#include "ut_cfe_es_stubs.h" -#include "ut_cfe_evs_stubs.h" - -#include - -/* - * Config table for testing - */ -CI_ConfigTblEntry_t CI_configtable = { - 1 /* iParam*/ -}; - -/* - * Function Definitions - */ - -void CI_Test_Setup(void) -{ - /* initialize test environment to default state for every test */ - - CFE_PSP_MemSet(&CI_AppData, 0x00, sizeof(CI_AppData_t)); - - Ut_CFE_EVS_Reset(); - Ut_CFE_FS_Reset(); - Ut_CFE_TIME_Reset(); - Ut_CFE_TBL_Reset(); - Ut_CFE_SB_Reset(); - Ut_CFE_ES_Reset(); - Ut_OSAPI_Reset(); - Ut_OSFILEAPI_Reset(); - - Ut_CFE_TBL_AddTable(CI_CONFIG_TABLE_FILENAME, (void *) &CI_configtable); -} - -void CI_Test_TearDown(void) { - CFE_PSP_MemSet(&CI_AppData, 0x00, sizeof(CI_AppData_t)); -} diff --git a/config/obc/sitl/target/apps/ci/unit_test/ci_test_utils.h b/config/obc/sitl/target/apps/ci/unit_test/ci_test_utils.h deleted file mode 100644 index 423dc5455..000000000 --- a/config/obc/sitl/target/apps/ci/unit_test/ci_test_utils.h +++ /dev/null @@ -1,63 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - - -#ifndef CI_TEST_UTILS_H -#define CI_TEST_UTILS_H - -/* - * Includes - */ - -#include "ci_app.h" - -extern CI_AppData_t CI_AppData; - -#ifdef __cplusplus -extern "C" { -#endif - -/* - * Function Definitions - */ - -void CI_Test_Setup(void); -void CI_Test_TearDown(void); - - -#ifdef __cplusplus -} -#endif - -#endif /* CI_TEST_UTILS_H */ - diff --git a/config/obc/sitl/target/apps/ci/unit_test/ci_testrunner.c b/config/obc/sitl/target/apps/ci/unit_test/ci_testrunner.c deleted file mode 100644 index f2e1fc97c..000000000 --- a/config/obc/sitl/target/apps/ci/unit_test/ci_testrunner.c +++ /dev/null @@ -1,45 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - - -#include "uttest.h" - -#include "ci_custom_test.h" - -int main(void) -{ - CI_Custom_Test_AddTestCases(); - - return(UtTest_Run()); -} - diff --git a/config/obc/sitl/target/apps/ds/CMakeLists.txt b/config/obc/sitl/target/apps/ds/CMakeLists.txt deleted file mode 100644 index 6379c18b4..000000000 --- a/config/obc/sitl/target/apps/ds/CMakeLists.txt +++ /dev/null @@ -1,16 +0,0 @@ -set(APP_NAME ds) - -buildliner_add_table( - ${APP_NAME} - NAME ds_file_tbl - SOURCES ${CMAKE_CURRENT_SOURCE_DIR}/tables/ds_file_tbl.c - INCLUDES ${CMAKE_CURRENT_SOURCE_DIR}/src/ -) - -buildliner_add_table( - ${APP_NAME} - NAME ds_filter_tbl - SOURCES ${CMAKE_CURRENT_SOURCE_DIR}/tables/ds_filter_tbl.c - INCLUDES ${CMAKE_CURRENT_SOURCE_DIR}/src/ -) - diff --git a/config/obc/sitl/target/apps/ds/tables/ds_file_tbl.c b/config/obc/sitl/target/apps/ds/tables/ds_file_tbl.c deleted file mode 100644 index 008c69860..000000000 --- a/config/obc/sitl/target/apps/ds/tables/ds_file_tbl.c +++ /dev/null @@ -1,292 +0,0 @@ -#include "cfe.h" -#include "cfe_tbl_filedef.h" -#include "ds_platform_cfg.h" -#include "ds_appdefs.h" -#include "ds_app.h" -#include "ds_msg.h" - - -/* -** Note: It is suggested that missions pre-define their file table -** index numbers in a public header file to be included by -** both the packet filter table source file and the destination -** file table source file. Common definitions may also be used -** when creating ground system database entries that require -** file index numbers for command arguments. -*/ -/* All events */ -#define FILE_ALL_EVENTS 0 -/* All housekeeping packets */ -#define FILE_ALL_APP_HK_PKTS 1 -/* Log all flight application messages */ -#define FILE_FLIGHT_APP_TLM_PKTS 2 -/* Log just default flight application messages */ -#define FILE_FLIGHT_DEFAULT_APP_TLM_PKTS 3 -/* Log just sensor application messages */ -#define FILE_FLIGHT_SENSOR_APP_TLM_PKTS 4 -/* Log all flight messages at a low rate */ -#define FILE_FLIGHT_MIN_APP_TLM_PKTS 5 -/* CFE core applications commands */ -#define FILE_CORE_APP_CMD_PKTS 6 - - -/* -** Sample Destination File Table Data -*/ -DS_DestFileTable_t DS_DestFileTable = -{ - /* .Descriptor = */ "Events", - /* .File = */ - { - /* File Index 00 -- event packets only */ - { -#if (DS_MOVE_FILES == TRUE) - /* .Movename = */ DS_EMPTY_STRING, -#endif - /* .Pathname = */ "/cf/log/", - /* .Basename = */ "events", - /* .Extension = */ ".dat", - - /* .FileNameType = */ DS_BY_COUNT, - /* .EnableState = */ DS_ENABLED, - /* .MaxFileSize = */ (1024 * 1024 * 200), /* 200 M-bytes */ - /* .MaxFileAge = */ (60 * 60 * 2), /* 2 hours */ - /* .SequenceCount = */ 1000, - }, - /* File Index 01 -- application housekeeping packets */ - { -#if (DS_MOVE_FILES == TRUE) - /* .Movename = */ DS_EMPTY_STRING, -#endif - /* .Pathname = */ "/cf/log/", - /* .Basename = */ "hk", - /* .Extension = */ ".hk", - - /* .FileNameType = */ DS_BY_COUNT, - /* .EnableState = */ DS_ENABLED, - /* .MaxFileSize = */ (1024 * 1024 * 200), /* 200 M-bytes */ - /* .MaxFileAge = */ (60 * 60 * 2), /* 2 hours */ - /* .SequenceCount = */ 2000, - }, - /* File Index 02 -- application telemetry packets */ - { -#if (DS_MOVE_FILES == TRUE) - /* .Movename = */ DS_EMPTY_STRING, -#endif - /* .Pathname = */ "/cf/log/", - /* .Basename = */ "flight", - /* .Extension = */ ".tlm", - - /* .FileNameType = */ DS_BY_COUNT, - /* .EnableState = */ DS_ENABLED, - /* .MaxFileSize = */ (1024 * 1024 * 200), /* 200 M-bytes */ - /* .MaxFileAge = */ (60 * 60 * 2), /* 2 hours */ - /* .SequenceCount = */ 3000, - }, - /* File Index 03 -- hardware telemetry packets */ - { -#if (DS_MOVE_FILES == TRUE) - /* .Movename = */ DS_EMPTY_STRING, -#endif - /* .Pathname = */ "/cf/log/", - /* .Basename = */ "default", - /* .Extension = */ ".tlm", - - /* .FileNameType = */ DS_BY_COUNT, - /* .EnableState = */ DS_DISABLED, - /* .MaxFileSize = */ (1024 * 1024 * 200), /* 200 M-bytes */ - /* .MaxFileAge = */ (60 * 60 * 2), /* 2 hours */ - /* .SequenceCount = */ 4000, - }, - /* File Index 04 -- cFE housekeeping packets */ - { -#if (DS_MOVE_FILES == TRUE) - /* .Movename = */ DS_EMPTY_STRING, -#endif - /* .Pathname = */ "/cf/log/", - /* .Basename = */ "sensor", - /* .Extension = */ ".tlm", - - /* .FileNameType = */ DS_BY_COUNT, - /* .EnableState = */ DS_DISABLED, - /* .MaxFileSize = */ (1024 * 1024 * 200), /* 200 M-bytes */ - /* .MaxFileAge = */ (60 * 60 * 2), /* 2 hours */ - /* .SequenceCount = */ 5000, - }, - /* File Index 05 -- cFE telemetry packets */ - { -#if (DS_MOVE_FILES == TRUE) - /* .Movename = */ DS_EMPTY_STRING, -#endif - /* .Pathname = */ "/cf/log/", - /* .Basename = */ "minimum", - /* .Extension = */ ".tlm", - - /* .FileNameType = */ DS_BY_COUNT, - /* .EnableState = */ DS_DISABLED, - /* .MaxFileSize = */ (1024 * 1024 * 200), /* 200 M-bytes */ - /* .MaxFileAge = */ (60 * 60 * 2), /* 2 hours */ - /* .SequenceCount = */ 6000, - }, - /* File Index 06 */ - { -#if (DS_MOVE_FILES == TRUE) - /* .Movename = */ DS_EMPTY_STRING, -#endif - /* .Pathname = */ "/cf/log/", - /* .Basename = */ "commands", - /* .Extension = */ ".cmd", - - /* .FileNameType = */ DS_BY_COUNT, - /* .EnableState = */ DS_ENABLED, - /* .MaxFileSize = */ (1024 * 1024 * 200), /* 200 M-bytes */ - /* .MaxFileAge = */ (60 * 60 * 2), /* 2 hours */ - /* .SequenceCount = */ 7000, - }, - /* File Index 07 */ - { -#if (DS_MOVE_FILES == TRUE) - /* .Movename = */ DS_EMPTY_STRING, -#endif - /* .Pathname = */ DS_EMPTY_STRING, - /* .Basename = */ DS_EMPTY_STRING, - /* .Extension = */ DS_EMPTY_STRING, - - /* .FileNameType = */ DS_UNUSED, - /* .EnableState = */ DS_UNUSED, - /* .MaxFileSize = */ DS_UNUSED, - /* .MaxFileAge = */ DS_UNUSED, - /* .SequenceCount = */ DS_UNUSED, - }, - /* File Index 08 */ - { -#if (DS_MOVE_FILES == TRUE) - /* .Movename = */ DS_EMPTY_STRING, -#endif - /* .Pathname = */ DS_EMPTY_STRING, - /* .Basename = */ DS_EMPTY_STRING, - /* .Extension = */ DS_EMPTY_STRING, - - /* .FileNameType = */ DS_UNUSED, - /* .EnableState = */ DS_UNUSED, - /* .MaxFileSize = */ DS_UNUSED, - /* .MaxFileAge = */ DS_UNUSED, - /* .SequenceCount = */ DS_UNUSED, - }, - /* File Index 09 */ - { -#if (DS_MOVE_FILES == TRUE) - /* .Movename = */ DS_EMPTY_STRING, -#endif - /* .Pathname = */ DS_EMPTY_STRING, - /* .Basename = */ DS_EMPTY_STRING, - /* .Extension = */ DS_EMPTY_STRING, - - /* .FileNameType = */ DS_UNUSED, - /* .EnableState = */ DS_UNUSED, - /* .MaxFileSize = */ DS_UNUSED, - /* .MaxFileAge = */ DS_UNUSED, - /* .SequenceCount = */ DS_UNUSED, - }, - /* File Index 10 */ - { -#if (DS_MOVE_FILES == TRUE) - /* .Movename = */ DS_EMPTY_STRING, -#endif - /* .Pathname = */ DS_EMPTY_STRING, - /* .Basename = */ DS_EMPTY_STRING, - /* .Extension = */ DS_EMPTY_STRING, - - /* .FileNameType = */ DS_UNUSED, - /* .EnableState = */ DS_UNUSED, - /* .MaxFileSize = */ DS_UNUSED, - /* .MaxFileAge = */ DS_UNUSED, - /* .SequenceCount = */ DS_UNUSED, - }, - /* File Index 11 */ - { -#if (DS_MOVE_FILES == TRUE) - /* .Movename = */ DS_EMPTY_STRING, -#endif - /* .Pathname = */ DS_EMPTY_STRING, - /* .Basename = */ DS_EMPTY_STRING, - /* .Extension = */ DS_EMPTY_STRING, - - /* .FileNameType = */ DS_UNUSED, - /* .EnableState = */ DS_UNUSED, - /* .MaxFileSize = */ DS_UNUSED, - /* .MaxFileAge = */ DS_UNUSED, - /* .SequenceCount = */ DS_UNUSED, - }, - /* File Index 12 */ - { -#if (DS_MOVE_FILES == TRUE) - /* .Movename = */ DS_EMPTY_STRING, -#endif - /* .Pathname = */ DS_EMPTY_STRING, - /* .Basename = */ DS_EMPTY_STRING, - /* .Extension = */ DS_EMPTY_STRING, - - /* .FileNameType = */ DS_UNUSED, - /* .EnableState = */ DS_UNUSED, - /* .MaxFileSize = */ DS_UNUSED, - /* .MaxFileAge = */ DS_UNUSED, - /* .SequenceCount = */ DS_UNUSED, - }, - /* File Index 13 */ - { -#if (DS_MOVE_FILES == TRUE) - /* .Movename = */ DS_EMPTY_STRING, -#endif - /* .Pathname = */ DS_EMPTY_STRING, - /* .Basename = */ DS_EMPTY_STRING, - /* .Extension = */ DS_EMPTY_STRING, - - /* .FileNameType = */ DS_UNUSED, - /* .EnableState = */ DS_UNUSED, - /* .MaxFileSize = */ DS_UNUSED, - /* .MaxFileAge = */ DS_UNUSED, - /* .SequenceCount = */ DS_UNUSED, - }, - /* File Index 14 */ - { -#if (DS_MOVE_FILES == TRUE) - /* .Movename = */ DS_EMPTY_STRING, -#endif - /* .Pathname = */ DS_EMPTY_STRING, - /* .Basename = */ DS_EMPTY_STRING, - /* .Extension = */ DS_EMPTY_STRING, - - /* .FileNameType = */ DS_UNUSED, - /* .EnableState = */ DS_UNUSED, - /* .MaxFileSize = */ DS_UNUSED, - /* .MaxFileAge = */ DS_UNUSED, - /* .SequenceCount = */ DS_UNUSED, - }, - /* File Index 15 */ - { -#if (DS_MOVE_FILES == TRUE) - /* .Movename = */ DS_EMPTY_STRING, -#endif - /* .Pathname = */ DS_EMPTY_STRING, - /* .Basename = */ DS_EMPTY_STRING, - /* .Extension = */ DS_EMPTY_STRING, - - /* .FileNameType = */ DS_UNUSED, - /* .EnableState = */ DS_UNUSED, - /* .MaxFileSize = */ DS_UNUSED, - /* .MaxFileAge = */ DS_UNUSED, - /* .SequenceCount = */ DS_UNUSED, - }, - } -}; - -/* -** Sample Destination File Table Header -*/ -CFE_TBL_FILEDEF(DS_DestFileTable, DS.FILE_TBL, DS Destination File Table,ds_file_tbl.tbl) - - -/************************/ -/* End of File Comment */ -/************************/ diff --git a/config/obc/sitl/target/apps/ds/tables/ds_filter_tbl.c b/config/obc/sitl/target/apps/ds/tables/ds_filter_tbl.c deleted file mode 100644 index 1afc76432..000000000 --- a/config/obc/sitl/target/apps/ds/tables/ds_filter_tbl.c +++ /dev/null @@ -1,3145 +0,0 @@ -#include "cfe.h" -#include "cfe_tbl_filedef.h" -#include "ds_platform_cfg.h" -#include "ds_appdefs.h" -#include "ds_app.h" -#include "ds_msg.h" - -/* -** Note: Include header files that define the message ID's for the -** mission specific list of packets that need to be stored. -*/ -#include "cfe_msgids.h" -#include "ds_msgids.h" - -/* #include "ci_lab_msgids.h" */ -/* #include "to_lab_msgids.h" */ - -/* #include "cs_msgids.h" */ -/* #include "ds_msgids.h" */ -/* #include "fm_msgids.h" */ -/* #include "hk_msgids.h" */ -/* #include "hs_msgids.h" */ -/* #include "lc_msgids.h" */ -/* #include "md_msgids.h" */ -/* #include "mm_msgids.h" */ -/* #include "sc_msgids.h" */ -/* #include "sch_msgids.h" */ - - -/* -** Note: It is suggested that missions pre-define their file table -** index numbers in a public header file to be included by -** both the packet filter table source file and the destination -** file table source file. Common definitions may also be used -** when creating command database entries that require file -** index numbers for command arguments. -*/ -/* All events */ -#define FILE_ALL_EVENTS 0 -/* All housekeeping packets */ -#define FILE_ALL_APP_HK_PKTS 1 -/* Log all flight application messages */ -#define FILE_FLIGHT_APP_TLM_PKTS 2 -/* Log just default flight application messages */ -#define FILE_FLIGHT_DEFAULT_APP_TLM_PKTS 3 -/* Log just sensor application messages */ -#define FILE_FLIGHT_SENSOR_APP_TLM_PKTS 4 -/* Log all flight messages at a low rate */ -#define FILE_FLIGHT_MIN_APP_TLM_PKTS 5 -/* CFE core applications commands */ -#define FILE_CORE_APP_CMD_PKTS 6 - - -/* -** Sample packet filter table data -*/ -DS_FilterTable_t DS_FilterTable = -{ - /* .Descriptor = */ "Sample filter table data", - /* .Packet = */ - { - /* Packet Index 000 */ - { - /* .MessageID = */ CFE_ES_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 2, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 001 */ - { - /* .MessageID = */ CFE_EVS_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 2, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 002 */ - { - /* .MessageID = */ CFE_SB_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 2, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 003 */ - { - /* .MessageID = */ CFE_TBL_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 2, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 004 */ - { - /* .MessageID = */ CFE_TIME_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 2, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 005 */ - { - /* .MessageID = */ CFE_EVS_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_CORE_APP_CMD_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 006 */ - { - /* .MessageID = */ CFE_EVS_EVENT_MSG_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_EVENTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 007 */ - { - /* .MessageID = */ CFE_SB_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_CORE_APP_CMD_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 008 */ - { - /* .MessageID = */ CFE_TIME_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_CORE_APP_CMD_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 009 */ - { - /* .MessageID = */ CFE_ES_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_CORE_APP_CMD_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 010 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 011 */ - { - /* .MessageID = */ CFE_SB_ONESUB_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 012 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 013 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 014 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 015 */ - { - /* .MessageID = */ PX4_SENSOR_ACCEL_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_SENSOR_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 2000, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 016 */ - { - /* .MessageID = */ PX4_SENSOR_BARO_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 10, 50, 0 }, - { FILE_FLIGHT_SENSOR_APP_TLM_PKTS, DS_BY_COUNT, 10, 50, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 2000, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 017 */ - { - /* .MessageID = */ PX4_SENSOR_GYRO_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_SENSOR_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 2000, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 018 */ - { - /* .MessageID = */ PX4_SENSOR_MAG_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_SENSOR_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 2000, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 019 */ - { - /* .MessageID = */ PX4_SENSOR_COMBINED_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_SENSOR_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 2000, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 020 */ - { - /* .MessageID = */ PX4_VEHICLE_GPS_POSITION_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 5, 6, 0 }, - { FILE_FLIGHT_SENSOR_APP_TLM_PKTS, DS_BY_COUNT, 5, 6, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 500, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 021 */ - { - /* .MessageID = */ PX4_DISTANCE_SENSOR_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_SENSOR_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 1000, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 022 */ - { - /* .MessageID = */ PX4_INPUT_RC_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 5, 50, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 1000, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 023 */ - { - /* .MessageID = */ PX4_RC_CHANNELS_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 1, 250, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 2000, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 024 */ - { - /* .MessageID = */ PX4_ACTUATOR_CONTROLS_0_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_DEFAULT_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 1000, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 025 */ - { - /* .MessageID = */ PX4_ACTUATOR_CONTROLS_1_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_DEFAULT_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 1000, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 026 */ - { - /* .MessageID = */ PX4_ACTUATOR_OUTPUTS_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_DEFAULT_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 1000, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 027 */ - { - /* .MessageID = */ PX4_ACTUATOR_ARMED_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 028 */ - { - /* .MessageID = */ PX4_BATTERY_STATUS_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 2, 50, 0 }, - { FILE_FLIGHT_DEFAULT_APP_TLM_PKTS, DS_BY_COUNT, 2, 50, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 500, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 029 */ - { - /* .MessageID = */ PX4_COMMANDER_STATE_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 1000, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 030 */ - { - /* .MessageID = */ PX4_CONTROL_STATE_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 1000, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 031 */ - { - /* .MessageID = */ PX4_ESTIMATOR_STATUS_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 5, 125, 0 }, - { FILE_FLIGHT_DEFAULT_APP_TLM_PKTS, DS_BY_COUNT, 5, 125, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 500, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 032 */ - { - /* .MessageID = */ PX4_EKF2_INNOVATIONS_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 5, 125, 0 }, - { FILE_FLIGHT_DEFAULT_APP_TLM_PKTS, DS_BY_COUNT, 5, 125, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 500, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 033 */ - { - /* .MessageID = */ PX4_MANUAL_CONTROL_SETPOINT_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 5, 250, 0 }, - { FILE_FLIGHT_DEFAULT_APP_TLM_PKTS, DS_BY_COUNT, 5, 250, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 1000, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 034 */ - { - /* .MessageID = */ PX4_POSITION_SETPOINT_TRIPLET_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 5, 250, 0 }, - { FILE_FLIGHT_DEFAULT_APP_TLM_PKTS, DS_BY_COUNT, 5, 250, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 1000, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 035 */ - { - /* .MessageID = */ PX4_VEHICLE_ATTITUDE_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 20, 250, 0 }, - { FILE_FLIGHT_DEFAULT_APP_TLM_PKTS, DS_BY_COUNT, 20, 250, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 500, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 036 */ - { - /* .MessageID = */ PX4_VEHICLE_ATTITUDE_SETPOINT_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_DEFAULT_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 1000, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 037 */ - { - /* .MessageID = */ PX4_VEHICLE_RATES_SETPOINT_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 20, 250, 0 }, - { FILE_FLIGHT_DEFAULT_APP_TLM_PKTS, DS_BY_COUNT, 20, 250, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 500, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 038 */ - { - /* .MessageID = */ PX4_VEHICLE_COMMAND_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { FILE_FLIGHT_DEFAULT_APP_TLM_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 039 */ - { - /* .MessageID = */ PX4_VEHICLE_GLOBAL_POSITION_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 5, 125, 0 }, - { FILE_FLIGHT_DEFAULT_APP_TLM_PKTS, DS_BY_COUNT, 5, 125, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 1000, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 040 */ - { - /* .MessageID = */ PX4_VEHICLE_GLOBAL_VELOCITY_SETPOINT_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 5, 250, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 2000, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 041 */ - { - /* .MessageID = */ PX4_VEHICLE_LAND_DETECTED_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { FILE_FLIGHT_DEFAULT_APP_TLM_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 042 */ - { - /* .MessageID = */ PX4_VEHICLE_LOCAL_POSITION_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 10, 125, 0 }, - { FILE_FLIGHT_DEFAULT_APP_TLM_PKTS, DS_BY_COUNT, 10, 125, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 1000, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 043 */ - { - /* .MessageID = */ PX4_VEHICLE_LOCAL_POSITION_SETPOINT_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_DEFAULT_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 1000, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 044 */ - { - /* .MessageID = */ PX4_VEHICLE_STATUS_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 5, 250, 0 }, - { FILE_FLIGHT_DEFAULT_APP_TLM_PKTS, DS_BY_COUNT, 5, 250, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 2000, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 045 */ - { - /* .MessageID = */ PX4_HOME_POSITION_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 046 */ - { - /* .MessageID = */ PX4_VEHICLE_CONTROL_MODE_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_FLIGHT_APP_TLM_PKTS, DS_BY_COUNT, 10, 250, 0 }, - { FILE_FLIGHT_MIN_APP_TLM_PKTS, DS_BY_COUNT, 1, 1000, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 047 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 048 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 049 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 050 */ - { - /* .MessageID = */ TO_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 051 */ - { - /* .MessageID = */ CI_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 052 */ - { - /* .MessageID = */ CF_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 053 */ - { - /* .MessageID = */ CS_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 054 */ - { - /* .MessageID = */ DS_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 055 */ - { - /* .MessageID = */ HK_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 056 */ - { - /* .MessageID = */ HS_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 057 */ - { - /* .MessageID = */ LC_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 058 */ - { - /* .MessageID = */ MM_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 059 */ - { - /* .MessageID = */ MD_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 060 */ - { - /* .MessageID = */ SC_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 061 */ - { - /* .MessageID = */ SCH_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 062 */ - { - /* .MessageID = */ MPU9250_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 063 */ - { - /* .MessageID = */ MS5611_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 064 */ - { - /* .MessageID = */ EA_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 065 */ - { - /* .MessageID = */ VC_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 066 */ - { - /* .MessageID = */ AMC_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 067 */ - { - /* .MessageID = */ MAC_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 068 */ - { - /* .MessageID = */ ULR_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 069 */ - { - /* .MessageID = */ RGBLED_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 070 */ - { - /* .MessageID = */ GPS_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 071 */ - { - /* .MessageID = */ SENS_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 072 */ - { - /* .MessageID = */ QAE_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 073 */ - { - /* .MessageID = */ LD_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 074 */ - { - /* .MessageID = */ MPC_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 075 */ - { - /* .MessageID = */ NAV_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 076 */ - { - /* .MessageID = */ RCIN_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 077 */ - { - /* .MessageID = */ VM_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 078 */ - { - /* .MessageID = */ BAT_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 079 */ - { - /* .MessageID = */ PE_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 080 */ - { - /* .MessageID = */ HMC5883_HK_TLM_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_ALL_APP_HK_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 081 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 082 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 083 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 084 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 085 */ - { - /* .MessageID = */ TO_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_CORE_APP_CMD_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 086 */ - { - /* .MessageID = */ CI_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_CORE_APP_CMD_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 087 */ - { - /* .MessageID = */ CF_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_CORE_APP_CMD_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 088 */ - { - /* .MessageID = */ CS_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_CORE_APP_CMD_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 089 */ - { - /* .MessageID = */ DS_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_CORE_APP_CMD_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 090 */ - { - /* .MessageID = */ FM_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_CORE_APP_CMD_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 091 */ - { - /* .MessageID = */ HK_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_CORE_APP_CMD_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 092 */ - { - /* .MessageID = */ LC_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_CORE_APP_CMD_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 093 */ - { - /* .MessageID = */ MM_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_CORE_APP_CMD_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 094 */ - { - /* .MessageID = */ MD_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_CORE_APP_CMD_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 095 */ - { - /* .MessageID = */ SC_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_CORE_APP_CMD_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 096 */ - { - /* .MessageID = */ SCH_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_CORE_APP_CMD_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 097 */ - { - /* .MessageID = */ MPU9250_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_CORE_APP_CMD_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 098 */ - { - /* .MessageID = */ MS5611_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_CORE_APP_CMD_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 099 */ - { - /* .MessageID = */ EA_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_CORE_APP_CMD_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 100 */ - { - /* .MessageID = */ VC_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_CORE_APP_CMD_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 101 */ - { - /* .MessageID = */ AMC_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_CORE_APP_CMD_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 102 */ - { - /* .MessageID = */ MAC_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { FILE_CORE_APP_CMD_PKTS, DS_BY_COUNT, 1, 1, 0 }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 103 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 104 */ - { - /* .MessageID = */ ULR_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 105 */ - { - /* .MessageID = */ RGBLED_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 106 */ - { - /* .MessageID = */ GPS_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 107 */ - { - /* .MessageID = */ SENS_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 108 */ - { - /* .MessageID = */ QAE_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 109 */ - { - /* .MessageID = */ LD_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 110 */ - { - /* .MessageID = */ MPC_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 111 */ - { - /* .MessageID = */ NAV_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 112 */ - { - /* .MessageID = */ RCIN_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 113 */ - { - /* .MessageID = */ VM_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 114 */ - { - /* .MessageID = */ BAT_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 115 */ - { - /* .MessageID = */ PE_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 116 */ - { - /* .MessageID = */ HMC5883_CMD_MID, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 117 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 118 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 119 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 120 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 121 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 122 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 123 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 124 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 125 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 126 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 127 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 128 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 129 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 130 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 131 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 132 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 133 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 134 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 135 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 136 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 137 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 138 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 139 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 140 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 141 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 142 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 143 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 144 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 145 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 146 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 147 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 148 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 149 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 150 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 151 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 152 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 153 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 154 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 155 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 156 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 157 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 158 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 159 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 160 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 161 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 162 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 163 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 164 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 165 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 166 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 167 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 168 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 169 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 170 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 171 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 172 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 173 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 174 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 175 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 176 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 177 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 178 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 179 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 180 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 181 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 182 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 183 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 184 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 185 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 186 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 187 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 188 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 189 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 190 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 191 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 192 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 193 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 194 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 195 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 196 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 197 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 198 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 199 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 200 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 201 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 202 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 203 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 204 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 205 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 206 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 207 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 208 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 209 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 210 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 211 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 212 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 213 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 214 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 215 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 216 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 217 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 218 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 219 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 220 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 221 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 222 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 223 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 224 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 225 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 226 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 227 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 228 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 229 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 230 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 231 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 232 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 233 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 234 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 235 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 236 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 237 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 238 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 239 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 240 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 241 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 242 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 243 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 244 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 245 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 246 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 247 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 248 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 249 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 250 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 251 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 252 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 253 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 254 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - }, - /* Packet Index 255 */ - { - /* .MessageID = */ DS_UNUSED, - /* .Filter = */ - { - /* File table index, filter type, N, X, O */ - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED }, - { DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED, DS_UNUSED } - } - } - } -}; - -/* -** Sample packet filter table header -*/ -CFE_TBL_FILEDEF(DS_FilterTable, DS.FILTER_TBL, DS Packet Filter Table,ds_filter_tbl.tbl) - - -/************************/ -/* End of File Comment */ -/************************/ diff --git a/config/obc/sitl/target/apps/ea/CMakeLists.txt b/config/obc/sitl/target/apps/ea/CMakeLists.txt deleted file mode 100644 index ae0506220..000000000 --- a/config/obc/sitl/target/apps/ea/CMakeLists.txt +++ /dev/null @@ -1,55 +0,0 @@ -set(APP_NAME ea) - -buildliner_add_app_unit_test(ea-custom-ut - UTASSERT - NANOPB - SOURCES - ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/ea_testrunner.c - ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/ea_custom_test.c - ${CMAKE_CURRENT_SOURCE_DIR}/src/ea_custom.c - ${PROJECT_SOURCE_DIR}/apps/ea/fsw/src/ea_app.c - ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/ea_mock_os_calls.c - ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/ea_test_utils.c - ${PROJECT_SOURCE_DIR}/core/base/ut_assert/src/ut_cfe_es_hooks.c - - INCLUDES - ${PROJECT_SOURCE_DIR}/apps/ea/fsw/src/ - - WRAPPERS - fork - execvp - waitpid - kill - - VALGRIND_SUPPRESSION_FILE - ${CMAKE_CURRENT_SOURCE_DIR}/ea-custom-ut.supp -) - -buildliner_add_app_unit_test(ea-perfmon-ut - UTASSERT - NANOPB - SOURCES - ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/ea_perfmon_testrunner.c - ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/ea_perfmon_test.c - ${CMAKE_CURRENT_SOURCE_DIR}/src/ea_custom.c - ${PROJECT_SOURCE_DIR}/apps/ea/fsw/src/ea_app.c - ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/ea_test_utils.c - ${PROJECT_SOURCE_DIR}/core/base/ut_assert/src/ut_cfe_es_hooks.c - - INCLUDES - ${PROJECT_SOURCE_DIR}/apps/ea/fsw/src/ - - VALGRIND_SUPPRESSION_FILE - ${CMAKE_CURRENT_SOURCE_DIR}/ea-perfmon-ut.supp -) - -add_custom_target( - ea-ut-custom-input-files - COMMAND cp ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/sleep.py ${CMAKE_CURRENT_BINARY_DIR} - COMMAND cp ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/fib.py ${CMAKE_CURRENT_BINARY_DIR} - COMMAND cp ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/noop.py ${CMAKE_CURRENT_BINARY_DIR} -) - -add_dependencies(ea-custom-ut ea-ut-custom-input-files) -add_dependencies(ea-perfmon-ut ea-ut-custom-input-files) - diff --git a/config/obc/sitl/target/apps/ea/ea-custom-ut.supp b/config/obc/sitl/target/apps/ea/ea-custom-ut.supp deleted file mode 100644 index d87eb5ce5..000000000 --- a/config/obc/sitl/target/apps/ea/ea-custom-ut.supp +++ /dev/null @@ -1,27 +0,0 @@ -{ - - Memcheck:Leak - match-leak-kinds: reachable - fun:malloc - fun:UtList_Add - fun:Ut_CFE_EVS_SendEventHook - fun:CFE_EVS_SendEvent - fun:EA_TermAppCustom - fun:Test_EA_Custom_TermApp_Nominal - fun:UtTest_Run - fun:main -} - -{ - - Memcheck:Leak - match-leak-kinds: reachable - fun:malloc - fun:UtList_Add - fun:Ut_CFE_EVS_SendEventHook - fun:CFE_EVS_SendEvent - fun:EA_TermAppCustom - fun:Test_EA_Custom_TermApp_Nominal - fun:UtTest_Run - fun:main -} \ No newline at end of file diff --git a/config/obc/sitl/target/apps/ea/ea-perfmon-ut.supp b/config/obc/sitl/target/apps/ea/ea-perfmon-ut.supp deleted file mode 100644 index e69de29bb..000000000 diff --git a/config/obc/sitl/target/apps/ea/src/ea_custom.c b/config/obc/sitl/target/apps/ea/src/ea_custom.c deleted file mode 100644 index 28daf8659..000000000 --- a/config/obc/sitl/target/apps/ea/src/ea_custom.c +++ /dev/null @@ -1,249 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#include "ea_custom.h" -#include -#include -#include -#include -#include -#include -#include - -#include "ea_platform_cfg.h" -#include "ea_app.h" -#include "ea_msg.h" - -void EA_StartAppCustom() -{ - int32 Status = -1; - Status = CFE_ES_RegisterChildTask(); - - if (Status == CFE_SUCCESS) - { - /* - ** Create child process to execute app - */ - pid_t pid = fork(); - - /* - ** Child process - */ - if (pid == 0) - { - char *argv[] = {EA_AppData.ChildData.Cmd, EA_AppData.ChildData.Args, NULL}; - if(execvp(EA_AppData.ChildData.Cmd, argv) == -1) - { - CFE_EVS_SendEvent(EA_CMD_ERR_EID, CFE_EVS_ERROR, - "Error starting external application"); - } - /* - ** NOTE: This exit is required here as a means to shut down the child process. - */ - exit(0); - } - /* - ** Failed Fork - */ - else if (pid == -1) - { - EA_AppData.HkTlm.usCmdErrCnt++; - CFE_EVS_SendEvent(EA_CMD_ERR_EID, CFE_EVS_ERROR, - "Error starting new process"); - } - /* - ** Parent process - */ - else - { - EA_AppData.HkTlm.usCmdCnt++; - CFE_EVS_SendEvent(EA_INF_APP_START_EID, CFE_EVS_INFORMATION, - "External application started"); - strncpy(EA_AppData.HkTlm.ActiveApp, EA_AppData.ChildData.Args, OS_MAX_PATH_LEN); - EA_AppData.HkTlm.ActiveAppPID = pid; - waitpid(pid, (int*)&EA_AppData.HkTlm.LastAppStatus, 0); - EA_AppData.HkTlm.LastAppStatus = EA_AppData.HkTlm.LastAppStatus; - EA_AppData.HkTlm.ActiveAppPID = 0; - EA_AppData.HkTlm.ActiveAppUtil = 0; - strncpy(EA_AppData.HkTlm.LastAppRun, EA_AppData.HkTlm.ActiveApp, OS_MAX_PATH_LEN); - memset(EA_AppData.HkTlm.ActiveApp, '\0', OS_MAX_PATH_LEN); - memset(EA_AppData.ChildData.Cmd, '\0', OS_MAX_PATH_LEN); - memset(EA_AppData.ChildData.Args, '\0', OS_MAX_PATH_LEN); - - } - }/*end if register child task*/ - else - { - (void) CFE_ES_WriteToSysLog("EA - StartApp Child Task Registration failed!\n"); - } - - EA_AppData.ChildAppTaskID = 0; - EA_AppData.ChildAppTaskInUse = FALSE; - CFE_ES_ExitChildTask(); - - return; -} - -void EA_TermAppCustom() -{ - int kill_status = -1; - - /* - ** Ensure app is currently running - */ - if(EA_AppData.HkTlm.ActiveAppPID != 0) - { - CFE_ES_DeleteChildTask(EA_AppData.ChildAppTaskID); - kill_status = kill(EA_AppData.HkTlm.ActiveAppPID, SIGKILL); - - /* - ** Check kill call return code - */ - if(kill_status == 0) - { - EA_AppData.HkTlm.usCmdCnt++; - EA_AppData.HkTlm.ActiveAppPID = 0; - EA_AppData.HkTlm.ActiveAppUtil = 0; - strncpy(EA_AppData.HkTlm.LastAppRun, EA_AppData.HkTlm.ActiveApp, OS_MAX_PATH_LEN); - EA_AppData.HkTlm.LastAppStatus = -1; // TODO: Add meaningful number to this - memset(EA_AppData.HkTlm.ActiveApp, '\0', OS_MAX_PATH_LEN); - EA_AppData.ChildAppTaskInUse = FALSE; - CFE_EVS_SendEvent(EA_INF_APP_TERM_EID, CFE_EVS_INFORMATION, - "External application terminated"); - } - else - { - EA_AppData.HkTlm.usCmdErrCnt++; - CFE_EVS_SendEvent(EA_CMD_ERR_EID, CFE_EVS_ERROR, - "Unable to terminate application"); - } - } - else - { - EA_AppData.HkTlm.usCmdErrCnt++; - CFE_EVS_SendEvent(EA_CMD_ERR_EID, CFE_EVS_ERROR, - "Attempted to terminate app while none executing"); - } - - return; -} - -void EA_PerfmonCustom(int32 pid) -{ - EA_ProcData_t proc_data = EA_ParsePidUtil(pid); - int dp = proc_data.p_time - EA_AppData.ProcData.p_time; - int dt = proc_data.total_time - EA_AppData.ProcData.total_time; - float util = 100 * EA_APP_NUM_THREADS * (float)dp/ (float)dt; - EA_AppData.ProcData.p_time = proc_data.p_time; - EA_AppData.ProcData.total_time = proc_data.total_time; - EA_AppData.HkTlm.ActiveAppUtil = util; - - return; -} - -EA_ProcData_t EA_ParsePidUtil(int32 pid) -{ - EA_ProcData_t procData; - unsigned long long int utime = 0; - unsigned long long int ntime = 0; - unsigned long long int stime = 0; - unsigned long long int itime = 0; - unsigned long long int io_wait = 0; - unsigned long long int irq = 0; - unsigned long long int soft_irq = 0; - unsigned long long int steal = 0; - unsigned long long int guest = 0; - unsigned long long int guest_nice = 0; - unsigned long long int sys_time, idle_time, total_time, virt_time; - - FILE* proc_stat = fopen("/proc/stat", "r"); - if (proc_stat == NULL) { - OS_printf("Unable to open stat"); - } - - char buf[1024]; - char* data = fgets(buf, sizeof(buf) - 1, proc_stat); - if (data == NULL) - { - OS_printf("Unable to read stat"); - } - - fclose(proc_stat); - - sscanf(buf, "cpu %16llu %16llu %16llu %16llu %16llu %16llu %16llu %16llu %16llu %16llu", - &utime, &ntime, &stime, &itime, &io_wait, &irq, &soft_irq, &steal, &guest, &guest_nice); - utime = utime - guest; - ntime = ntime - guest_nice; - idle_time = itime + io_wait; - sys_time = stime + irq + soft_irq; - virt_time = guest + guest_nice; - total_time = utime + ntime + sys_time + idle_time + steal + virt_time; - procData.total_time = total_time; - - char path[64]; - snprintf(path, sizeof(path), "/proc/%li/stat", pid); - FILE* pid_stat = fopen(path, "r"); - if (pid_stat == NULL) { - OS_printf("Unable to open pid_stat"); - } - - memset(buf, '\0', 1024); - data = fgets(buf, sizeof(buf) - 1, pid_stat); - if (data == NULL) - { - OS_printf("Unable to read pid_stat"); - } - - int utime_ln = 13; - int stime_ln = 14; - int count_ndx = 0; - char *tok; - for (tok = strtok(data," "); tok != NULL; tok = strtok(NULL, " ")) - { - if (count_ndx == utime_ln) - { - utime = atol(tok); - } - if (count_ndx == stime_ln) - { - stime = atol(tok); - } - count_ndx++; - } - - fclose(pid_stat); - - procData.p_time = utime + stime; - - return(procData); -} diff --git a/config/obc/sitl/target/apps/ea/unit_test/ea-custom-ut.supp b/config/obc/sitl/target/apps/ea/unit_test/ea-custom-ut.supp deleted file mode 100644 index f460b1d85..000000000 --- a/config/obc/sitl/target/apps/ea/unit_test/ea-custom-ut.supp +++ /dev/null @@ -1,32 +0,0 @@ -# The following hits are a result of mallocs in UtList_Add. This is -# unit test specific code and does not impact the flight code. - -{ - - Memcheck:Leak - match-leak-kinds: reachable - fun:malloc - fun:UtList_Add - fun:Ut_CFE_EVS_SendEventHook - fun:CFE_EVS_SendEvent - fun:EA_TermAppCustom - fun:Test_EA_Custom_TermApp_Nominal - fun:UtTest_Run - fun:main -} - -{ - - Memcheck:Leak - match-leak-kinds: reachable - fun:malloc - fun:UtList_Add - fun:Ut_CFE_EVS_SendEventHook - fun:CFE_EVS_SendEvent - fun:EA_TermAppCustom - fun:Test_EA_Custom_TermApp_Nominal - fun:UtTest_Run - fun:main -} - -################################### diff --git a/config/obc/sitl/target/apps/ea/unit_test/ea_custom_test.c b/config/obc/sitl/target/apps/ea/unit_test/ea_custom_test.c deleted file mode 100644 index cf816c08d..000000000 --- a/config/obc/sitl/target/apps/ea/unit_test/ea_custom_test.c +++ /dev/null @@ -1,200 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#include "ea_custom_test.h" -#include "ea_test_utils.h" -#include "ea_app.h" -#include "ea_custom.h" -#include "ea_msg.h" - -#include "uttest.h" -#include "ut_osapi_stubs.h" -#include "ut_cfe_sb_stubs.h" -#include "ut_cfe_es_stubs.h" -#include "ut_cfe_es_hooks.h" -#include "ut_cfe_evs_stubs.h" -#include "ut_cfe_evs_hooks.h" -#include "ut_cfe_time_stubs.h" -#include "ut_cfe_psp_memutils_stubs.h" -#include "ut_cfe_tbl_stubs.h" -#include "ut_cfe_fs_stubs.h" -#include "ut_cfe_time_stubs.h" - -char CUSTOM_APP_PATH[OS_MAX_PATH_LEN] = "/usr/bin/python"; -char CUSTOM_TEST_ARG[OS_MAX_PATH_LEN] = "noop.py"; - -int FORK_RET_CODE; -int EXECVP_RET_CODE; -int KILL_RET_CODE; -int WAITPID_RET_CODE; - -int PERFMON_SAMPLES = 50; - -/** - * Test EA_StartAppCustom(), Register Child Task Error - */ -void Test_EA_Custom_StartApp_RegisterChildTaskError(void) -{ - /* Set to cause message "StartApp Child Task Registration failed!" to be printed */ - Ut_CFE_ES_SetReturnCode(UT_CFE_ES_REGISTERCHILDTASK_INDEX, -1, 1); - - /* Execute the function being tested */ - EA_StartAppCustom(); - - /* Verify results */ - /* Note: Cannot verify line OS_printf("StartApp Child Task Registration failed!\n") */ - UtAssert_True (EA_AppData.ChildAppTaskID == 0, "Child task ID = 0"); - UtAssert_True (EA_AppData.ChildAppTaskInUse == FALSE, "Child task not in use"); -} - -/** - * Test EA_StartAppCustom(), Failed fork - */ -void Test_EA_Custom_StartApp_FailFork(void) -{ - /* Set to cause fork to fail */ - FORK_RET_CODE = -1; - - /* Execute the function being tested */ - EA_StartAppCustom(); - - /* Verify results */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_EventSent(EA_CMD_ERR_EID, CFE_EVS_ERROR, - "Error starting new process", "Error starting new process"); - UtAssert_True(EA_AppData.HkTlm.usCmdErrCnt==1,"Command Error Count = 1"); -} - -/** - * Test EA_StartAppCustom(), Nominal - */ -void Test_EA_Custom_StartApp_Nominal(void) -{ - /* Set so everything looks valid */ - strncpy(EA_AppData.ChildData.Cmd, CUSTOM_APP_PATH, OS_MAX_PATH_LEN); - strncpy(EA_AppData.ChildData.Args, CUSTOM_TEST_ARG, OS_MAX_PATH_LEN); - FORK_RET_CODE = 1; - WAITPID_RET_CODE = 2; - - /* Execute the function being tested */ - EA_StartAppCustom(); - - /* Verify results */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_EventSent(EA_INF_APP_START_EID, CFE_EVS_INFORMATION, "External application started", "External application started"); - UtAssert_True(EA_AppData.HkTlm.usCmdCnt==1,"Command Count = 1"); - - /* Verify cleanup too since app instantly exits for test */ - UtAssert_True(EA_AppData.HkTlm.ActiveAppPID==0,"ActiveAppPID = 0"); - UtAssert_True(EA_AppData.HkTlm.ActiveAppUtil==0,"ActiveAppUtil = 0");// - UtAssert_True(EA_AppData.ChildAppTaskInUse==FALSE,"ChildAppTaskInUse = FALSE"); - UtAssert_StrCmp(EA_AppData.HkTlm.LastAppRun, CUSTOM_TEST_ARG, "Last Active App set"); - UtAssert_True(EA_AppData.HkTlm.LastAppStatus==2,"LastAppStatus = waitpid return code"); -} - -/** - * Test EA_TermAppCustom(), No app running - */ -void Test_EA_Custom_TermApp_NoneActive(void) -{ - /* Set to cause conditional to fail */ - EA_AppData.HkTlm.ActiveAppPID = 0; - - /* Execute the function being tested */ - EA_TermAppCustom(); - - /* Verify results */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_EventSent(EA_CMD_ERR_EID, CFE_EVS_ERROR, - "Attempted to terminate app while none executing", "No active app"); - UtAssert_True(EA_AppData.HkTlm.usCmdErrCnt==1,"Command Error Count = 1"); -} - -/** - * Test EA_TermAppCustom(), Failed kill - */ -void Test_EA_Custom_TermApp_KillFail(void) -{ - /* Set to cause kill to fail */ - EA_AppData.HkTlm.ActiveAppPID = 1; - KILL_RET_CODE = -1; - - /* Execute the function being tested */ - EA_TermAppCustom(); - - /* Verify results */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_EventSent(EA_CMD_ERR_EID, CFE_EVS_ERROR, - "Unable to terminate application", "Unable to terminate application"); - UtAssert_True(EA_AppData.HkTlm.usCmdErrCnt==1,"Command Error Count = 1"); -} - -/** - * Test EA_TermAppCustom(), Nominal - */ -void Test_EA_Custom_TermApp_Nominal(void) -{ - /* Set active app params that TermApp will clear or copy to last app params */ - EA_AppData.HkTlm.ActiveAppPID = 1; - EA_AppData.HkTlm.ActiveAppUtil = 2; - EA_AppData.ChildAppTaskInUse = TRUE; - strncpy(EA_AppData.HkTlm.ActiveApp, CUSTOM_TEST_ARG, OS_MAX_PATH_LEN); - KILL_RET_CODE = 0; - - /* Execute the function being tested */ - EA_TermAppCustom(); - - /* Verify results */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_EventSent(EA_INF_APP_TERM_EID, CFE_EVS_INFORMATION,"", "External application terminated"); - UtAssert_True(EA_AppData.HkTlm.usCmdCnt==1,"Command Count = 1"); - UtAssert_True(EA_AppData.HkTlm.ActiveAppPID==0,"ActiveAppPID = 0"); - UtAssert_True(EA_AppData.HkTlm.ActiveAppUtil==0,"ActiveAppUtil = 0");// - UtAssert_True(EA_AppData.ChildAppTaskInUse==FALSE,"ChildAppTaskInUse = FALSE"); - UtAssert_StrCmp(EA_AppData.HkTlm.LastAppRun, CUSTOM_TEST_ARG, "Last Active App set"); - UtAssert_True(EA_AppData.HkTlm.LastAppStatus==-1,"LastAppStatus = -1"); -} - -/************************************************************************** - * Rollup Test Cases - **************************************************************************/ -void EA_Custom_Test_AddTestCases(void) -{ - UtTest_Add(Test_EA_Custom_StartApp_RegisterChildTaskError, EA_Test_Setup, EA_Test_TearDown, "Test_EA_Custom_StartApp_RegisterChildTaskError"); - UtTest_Add(Test_EA_Custom_StartApp_FailFork, EA_Test_Setup, EA_Test_TearDown, "Test_EA_Custom_StartApp_FailFork"); - UtTest_Add(Test_EA_Custom_StartApp_Nominal, EA_Test_Setup, EA_Test_TearDown, "Test_EA_Custom_StartApp_Nominal"); - UtTest_Add(Test_EA_Custom_TermApp_NoneActive, EA_Test_Setup, EA_Test_TearDown, "Test_EA_Custom_TermApp_NoneActive"); - UtTest_Add(Test_EA_Custom_TermApp_KillFail, EA_Test_Setup, EA_Test_TearDown, "Test_EA_Custom_TermApp_KillFail"); - UtTest_Add(Test_EA_Custom_TermApp_Nominal, EA_Test_Setup, EA_Test_TearDown, "Test_EA_Custom_TermApp_Nominal"); -} - diff --git a/config/obc/sitl/target/apps/ea/unit_test/ea_custom_test.h b/config/obc/sitl/target/apps/ea/unit_test/ea_custom_test.h deleted file mode 100644 index 0ba43986e..000000000 --- a/config/obc/sitl/target/apps/ea/unit_test/ea_custom_test.h +++ /dev/null @@ -1,49 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#ifndef EA_CUSTOM_TEST_H -#define EA_CUSTOM_TEST_H - -#ifdef __cplusplus -extern "C" { -#endif - -void EA_Custom_Test_AddTestCases(void); -int EA_CalibrateTop(int pid); -int EA_GetPidUtil(int pid, int util_ndx); - -#ifdef __cplusplus -} -#endif - -#endif /* EA_CUSTOM_TEST_H */ diff --git a/config/obc/sitl/target/apps/ea/unit_test/ea_mock_os_calls.c b/config/obc/sitl/target/apps/ea/unit_test/ea_mock_os_calls.c deleted file mode 100644 index ec8b52ec8..000000000 --- a/config/obc/sitl/target/apps/ea/unit_test/ea_mock_os_calls.c +++ /dev/null @@ -1,62 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#include - -int FORK_RET_CODE = 0; -int EXECVP_RET_CODE = 0; -int KILL_RET_CODE = 0; -int WAITPID_RET_CODE = 0; - -//void __real_fork(); - -pid_t __wrap_fork() -{ - return FORK_RET_CODE; -} - -int __wrap_execvp(const char *file, char *const argv[]) -{ - return EXECVP_RET_CODE; -} - -int __wrap_kill(int pid, int signal) -{ - return KILL_RET_CODE; -} - -pid_t __wrap_waitpid(pid_t pid, int *status, int options) -{ - *status = WAITPID_RET_CODE; - return WAITPID_RET_CODE; -} diff --git a/config/obc/sitl/target/apps/ea/unit_test/ea_mock_os_calls.h b/config/obc/sitl/target/apps/ea/unit_test/ea_mock_os_calls.h deleted file mode 100644 index ac9d19b7f..000000000 --- a/config/obc/sitl/target/apps/ea/unit_test/ea_mock_os_calls.h +++ /dev/null @@ -1,57 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#ifndef EA_MOCK_OS_CALLS_H -#define EA_MOCK_OS_CALLS_H - -#ifdef __cplusplus -extern "C" { -#endif - -//#define fork() mock_fork() -//#define execvp(...) mock_execvp(__VA_ARGS__) -//#define kill(...) mock_kill(__VA_ARGS__) - -extern int FORK_RET_CODE; -extern int EXECVP_RET_CODE; -extern int KILL_RET_CODE; -extern int WAITPID_RET_CODE -//int __wrap_fork(); -//int __wrap_execvp(const char *file, char *const argv[]); -//int __wrap_kill(int pid, int signal); - -#ifdef __cplusplus -} -#endif - -#endif /* MOCK_OS_CALLS_H */ diff --git a/config/obc/sitl/target/apps/ea/unit_test/ea_perfmon_test.c b/config/obc/sitl/target/apps/ea/unit_test/ea_perfmon_test.c deleted file mode 100644 index c3554a95f..000000000 --- a/config/obc/sitl/target/apps/ea/unit_test/ea_perfmon_test.c +++ /dev/null @@ -1,192 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#include "ea_perfmon_test.h" -#include "ea_test_utils.h" -#include "ea_app.h" -#include "ea_custom.h" -#include "ea_msg.h" - -#include "uttest.h" -#include "ut_osapi_stubs.h" -#include "ut_cfe_sb_stubs.h" -#include "ut_cfe_es_stubs.h" -#include "ut_cfe_es_hooks.h" -#include "ut_cfe_evs_stubs.h" -#include "ut_cfe_evs_hooks.h" -#include "ut_cfe_time_stubs.h" -#include "ut_cfe_psp_memutils_stubs.h" -#include "ut_cfe_tbl_stubs.h" -#include "ut_cfe_fs_stubs.h" -#include "ut_cfe_time_stubs.h" - -char PERFMON_APP_PATH[OS_MAX_PATH_LEN] = "/usr/bin/python"; -char PERFMON_TEST_ARG_FIB[OS_MAX_PATH_LEN] = "fib.py"; -char PERFMON_TEST_ARG_SLP[OS_MAX_PATH_LEN] = "sleep.py"; -int PERFMON_SAMPLES = 5; - -/** - * Test EA_PerfmonCustom(), Nominal - */ -void Test_EA_PerfmonCustom_Nominal(void) -{ - /* - ** Create child process to execute test app - */ - pid_t pid = fork(); - /* - ** Child process - */ - if (pid == 0) - { - char *argv[] = {PERFMON_APP_PATH, PERFMON_TEST_ARG_FIB, NULL}; - if(execvp(PERFMON_APP_PATH, argv) == -1) - { - printf("Unable to execute new process\n"); - } - exit(0); - } - /* - ** Failed Fork - */ - else if (pid == -1) - { - printf("Unable to execute fork\n"); - } - /* - ** Parent process - */ - else - { - int high_util_flag = 0; - int low_util_flag = 0; - int util = 0; - int count = 0; - while(count < PERFMON_SAMPLES) - { - /* Get current util */ - EA_PerfmonCustom(pid); - util = EA_AppData.HkTlm.ActiveAppUtil; - - /* Test if util in expected ranges */ - if(util >= 0 && util <= 100) - { - low_util_flag = 1; - } - if(util > 30 && util <= 100) - { - high_util_flag = 1; - } - count += 1; - sleep(1); - } - - /* Verify results */ - UtAssert_True(low_util_flag==1, "Hit low util threshold"); - UtAssert_True(high_util_flag==1, "Hit high util threshold"); - } -} - -/** - * Test EA_PerfmonCustom(), Idle - */ -void Test_EA_PerfmonCustom_Idle(void) -{ - /* - ** Create child process to execute test app - */ - pid_t pid = fork(); - /* - ** Child process - */ - if (pid == 0) - { - char *argv[] = {PERFMON_APP_PATH, PERFMON_TEST_ARG_SLP, NULL}; - if(execvp(PERFMON_APP_PATH, argv) == -1) - { - printf("Unable to execute new process\n"); - } - exit(0); - } - /* - ** Failed Fork - */ - else if (pid == -1) - { - printf("Unable to execute fork\n"); - } - /* - ** Parent process - */ - else - { - int high_util_flag = 0; - int low_util_flag = 0; - int util = 0; - int count = 0; - while(count < PERFMON_SAMPLES) - { - /* Get current util */ - EA_PerfmonCustom(pid); - util = EA_AppData.HkTlm.ActiveAppUtil; - - /* Test if util in expected ranges */ - if(util >= 0 && util <= 100) - { - low_util_flag = 1; - } - if(util > 50 && util <= 100) - { - high_util_flag = 1; - } - count += 1; - sleep(1); - } - - /* Verify results */ - UtAssert_True(low_util_flag==1, "Hit low util threshold"); - UtAssert_True(high_util_flag==0, "Hit high util threshold"); - } -} - - - -/************************************************************************** - * Rollup Test Cases - **************************************************************************/ -void EA_Perfmon_Test_AddTestCases(void) -{ - UtTest_Add(Test_EA_PerfmonCustom_Nominal, EA_Test_Setup, EA_Test_TearDown, "Test_EA_PerfmonCustom_Nominal"); - UtTest_Add(Test_EA_PerfmonCustom_Idle, EA_Test_Setup, EA_Test_TearDown, "Test_EA_PerfmonCustom_Idle"); -} - diff --git a/config/obc/sitl/target/apps/ea/unit_test/ea_perfmon_test.h b/config/obc/sitl/target/apps/ea/unit_test/ea_perfmon_test.h deleted file mode 100644 index 0ba43986e..000000000 --- a/config/obc/sitl/target/apps/ea/unit_test/ea_perfmon_test.h +++ /dev/null @@ -1,49 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#ifndef EA_CUSTOM_TEST_H -#define EA_CUSTOM_TEST_H - -#ifdef __cplusplus -extern "C" { -#endif - -void EA_Custom_Test_AddTestCases(void); -int EA_CalibrateTop(int pid); -int EA_GetPidUtil(int pid, int util_ndx); - -#ifdef __cplusplus -} -#endif - -#endif /* EA_CUSTOM_TEST_H */ diff --git a/config/obc/sitl/target/apps/ea/unit_test/ea_perfmon_testrunner.c b/config/obc/sitl/target/apps/ea/unit_test/ea_perfmon_testrunner.c deleted file mode 100644 index cbfb60861..000000000 --- a/config/obc/sitl/target/apps/ea/unit_test/ea_perfmon_testrunner.c +++ /dev/null @@ -1,46 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#include "uttest.h" - -#include "ea_perfmon_test.h" - -void EA_Perfmon_Test_AddTestCases(void); - -int main(void) -{ - EA_Perfmon_Test_AddTestCases(); - - return(UtTest_Run()); -} - diff --git a/config/obc/sitl/target/apps/ea/unit_test/ea_test_utils.c b/config/obc/sitl/target/apps/ea/unit_test/ea_test_utils.c deleted file mode 100644 index b82004805..000000000 --- a/config/obc/sitl/target/apps/ea/unit_test/ea_test_utils.c +++ /dev/null @@ -1,73 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#include "ea_test_utils.h" - -#include "ut_cfe_evs_hooks.h" -#include "ut_cfe_time_stubs.h" -#include "ut_cfe_psp_memutils_stubs.h" -#include "ut_cfe_tbl_stubs.h" -#include "ut_cfe_tbl_hooks.h" -#include "ut_cfe_fs_stubs.h" -#include "ut_cfe_time_stubs.h" -#include "ut_osapi_stubs.h" -#include "ut_osfileapi_stubs.h" -#include "ut_cfe_sb_stubs.h" -#include "ut_cfe_es_stubs.h" -#include "ut_cfe_evs_stubs.h" - -#include - -/* - * Function Definitions - */ - -void EA_Test_Setup(void) -{ - /* initialize test environment to default state for every test */ - - CFE_PSP_MemSet(&EA_AppData, 0x00, sizeof(EA_AppData_t)); - - Ut_CFE_EVS_Reset(); - Ut_CFE_FS_Reset(); - Ut_CFE_TIME_Reset(); - Ut_CFE_TBL_Reset(); - Ut_CFE_SB_Reset(); - Ut_CFE_ES_Reset(); - Ut_OSAPI_Reset(); - Ut_OSFILEAPI_Reset(); -} - -void EA_Test_TearDown(void) { - CFE_PSP_MemSet(&EA_AppData, 0x00, sizeof(EA_AppData_t)); -} diff --git a/config/obc/sitl/target/apps/ea/unit_test/ea_test_utils.h b/config/obc/sitl/target/apps/ea/unit_test/ea_test_utils.h deleted file mode 100644 index f4f8f8518..000000000 --- a/config/obc/sitl/target/apps/ea/unit_test/ea_test_utils.h +++ /dev/null @@ -1,62 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#ifndef EA_TEST_UTILS_H -#define EA_TEST_UTILS_H - -/* - * Includes - */ - -#include "ea_app.h" - -extern EA_AppData_t EA_AppData; - -#ifdef __cplusplus -extern "C" { -#endif - -/* - * Function Definitions - */ - -void EA_Test_Setup(void); -void EA_Test_TearDown(void); - - -#ifdef __cplusplus -} -#endif - -#endif /* EA_TEST_UTILS_H */ - diff --git a/config/obc/sitl/target/apps/ea/unit_test/ea_testrunner.c b/config/obc/sitl/target/apps/ea/unit_test/ea_testrunner.c deleted file mode 100644 index 9f37d7cb6..000000000 --- a/config/obc/sitl/target/apps/ea/unit_test/ea_testrunner.c +++ /dev/null @@ -1,44 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#include "uttest.h" - -#include "ea_custom_test.h" - -int main(void) -{ - EA_Custom_Test_AddTestCases(); - - return(UtTest_Run()); -} - diff --git a/config/obc/sitl/target/apps/ea/unit_test/fib.py b/config/obc/sitl/target/apps/ea/unit_test/fib.py deleted file mode 100644 index 863d2a64d..000000000 --- a/config/obc/sitl/target/apps/ea/unit_test/fib.py +++ /dev/null @@ -1,14 +0,0 @@ -import sys -import time - -def fib(n): - if n < 0: - return 0 - if n == 0 or n == 1: - return 1 - else: - return fib(n-1) + fib(n-2) - -f = fib(40) - -sys.exit(3) diff --git a/config/obc/sitl/target/apps/ea/unit_test/noop.py b/config/obc/sitl/target/apps/ea/unit_test/noop.py deleted file mode 100644 index de2b0fb69..000000000 --- a/config/obc/sitl/target/apps/ea/unit_test/noop.py +++ /dev/null @@ -1,3 +0,0 @@ -import sys -print "Python: Noop" -sys.exit(3) diff --git a/config/obc/sitl/target/apps/ea/unit_test/sleep.py b/config/obc/sitl/target/apps/ea/unit_test/sleep.py deleted file mode 100644 index 90aa057a5..000000000 --- a/config/obc/sitl/target/apps/ea/unit_test/sleep.py +++ /dev/null @@ -1,6 +0,0 @@ -import sys -import time - -time.sleep(5) - -sys.exit(3) diff --git a/config/obc/sitl/target/apps/pq_lib/CMakeLists.txt b/config/obc/sitl/target/apps/pq_lib/CMakeLists.txt deleted file mode 100644 index 94754ad68..000000000 --- a/config/obc/sitl/target/apps/pq_lib/CMakeLists.txt +++ /dev/null @@ -1,7 +0,0 @@ -set(APP_NAME pq_lib) - -buildliner_add_table( - ${APP_NAME} - NAME pq_cfg - SOURCES ${CMAKE_CURRENT_SOURCE_DIR}/tables/pq_cfg.c -) diff --git a/config/obc/sitl/target/apps/prm/CMakeLists.txt b/config/obc/sitl/target/apps/prm/CMakeLists.txt deleted file mode 100644 index 64806fbfe..000000000 --- a/config/obc/sitl/target/apps/prm/CMakeLists.txt +++ /dev/null @@ -1,7 +0,0 @@ -set(APP_NAME prm) - -buildliner_add_table( - ${APP_NAME} - NAME prm_config - SOURCES ${CMAKE_CURRENT_SOURCE_DIR}/tables/prm_config.c -) diff --git a/config/obc/sitl/target/apps/sbn/CMakeLists.txt b/config/obc/sitl/target/apps/sbn/CMakeLists.txt deleted file mode 100644 index 044cfcec4..000000000 --- a/config/obc/sitl/target/apps/sbn/CMakeLists.txt +++ /dev/null @@ -1 +0,0 @@ -set(APP_NAME sbn) diff --git a/config/obc/sitl/target/apps/sbn/src/sbn_remap_tbl.c b/config/obc/sitl/target/apps/sbn/src/sbn_remap_tbl.c deleted file mode 100644 index 2c46ce253..000000000 --- a/config/obc/sitl/target/apps/sbn/src/sbn_remap_tbl.c +++ /dev/null @@ -1,15 +0,0 @@ -#include "sbn_tbl.h" -#include "cfe_tbl_filedef.h" -#include "msg_ids.h" - -SBN_RemapTbl_t SBN_RemapTbl = -{ - SBN_REMAP_DEFAULT_SEND, /* Remap Default */ - 0, /* number of entries, initialized at validation time */ - { /* remap table */ - /* {CPU_ID, from, to} and if to is 0x0000, filter rather than remap */ - {0, 0x0000, 0x0000} - } -};/* end SBN_RemapTbl */ - -CFE_TBL_FILEDEF(SBN_RemapTbl, SBN.REMAP_TBL, SBN Remap Table,sbn_remap_tbl.tbl) diff --git a/config/obc/sitl/target/apps/sbn/tables/udp/SbnModuleData.dat b/config/obc/sitl/target/apps/sbn/tables/udp/SbnModuleData.dat deleted file mode 100644 index e34c95032..000000000 --- a/config/obc/sitl/target/apps/sbn/tables/udp/SbnModuleData.dat +++ /dev/null @@ -1,8 +0,0 @@ -1, UDP, /cf/apps/sbn_udp.so, SBN_UDP_Ops; -! -! Format: ProtocolId, ModuleLocation, IFStructName -! -! Protocol id 1 = UDP, 2 = TCP, 3 = SpacewireRMAP, 4 = Spacewire packet, 5 = Shared Memory, 6 = Serial, 7 = 1553, 8 = DTN -! -! IFStructName is the name of the SBN_InterfaceOperations struct defined for the -! module. diff --git a/config/obc/sitl/target/apps/sbn/tables/udp/SbnPeerData.dat b/config/obc/sitl/target/apps/sbn/tables/udp/SbnPeerData.dat deleted file mode 100644 index 88b192086..000000000 --- a/config/obc/sitl/target/apps/sbn/tables/udp/SbnPeerData.dat +++ /dev/null @@ -1,51 +0,0 @@ -PPD, 1, 1, 0x42, 0, 0, 127.0.0.1, 15820; -CPD, 2, 1, 0x42, 0, 0, 127.0.0.1, 15820; -! -! The '!' is inserted after the last valid peer line, -! it is not a comment character. -! -! The file may contain up to SBN_MAX_NETWORK_PEERS as defined in sbn_app.h -! -! Column 1: CPU Name (must match CFE_CPU_NAME [in cfe_platform_cfg.h]) -! -! Column 2: CPU ID (must match CFE_CPU_ID [in cfe_platform_cfg.h]) -! -! Column 3: Protocol ID (1 = UDP, 2 = TCP, 3 = SpacewireRMAP, -! 4 = Spacewire packet, 5 = Shared Memory, 6 = Serial, 7 = 1553, -! 8 = DTN -! -! Column 4: Spacecraft ID (must match return value of CFE_PSP_GetSpacecraftID()) -! -! Column 5: QoS (need to describe) -! -! Column 6: Network Number (for grouping affiliated peers, to determine -! which host interface is needed for which peer.) -! -! Columns 7+: Protocol ID-dependent. -! UDP/TCP: 7 = hostname/ip, 8 = port -! -! UDP example: -! -! CPU1, 1, 1, 42, 0, 0, 192.168.1.76, 15820; -! CPU2, 2, 1, 42, 1, 0, 192.168.1.77, 15820; -! The ProtoPort is arbitrary, but must be unique for processor/system. -! -! Shared Memory example (may need updates): -! -! CPU1, 1, 5, 0, 0, 0, 0xfffd0000, 0x1000, 0xfffd1000, 0x1000, 0xfffd2000, 0x1000, 0xfffd3000, 0x1000; -! CPU2, 2, 5, 0, 1, 0, 0xfffd1000, 0x1000, 0xfffd0000, 0x1000, 0xfffd3000, 0x1000, 0xfffd2000, 0x1000; -! -! Serial example (may need updates): -! -! CPU1, 1, 6, 0, 0, 0, /dev/ttyS1, 230400; -! CPU2, 2, 6, 0, 0, 0, /dev/ttyS1, 230400; -! CPU1, 1, 6, 0, 1, 1, /dev/ttyS2, 115200; -! CPU3, 2, 6, 0, 1, 1, /dev/ttyS1, 115200; -! -! NOTE on baud rate: The baud rate must match between pairs, and must be one of the following values: -! 38400, 57600, 115200, 230400 -! Larger baud rates are preferred, especially if SBN will be routing messages larger than 100 bytes. -! However, the highest baud rate may produce tty overruns so test different baud rates for your -! specific system. diff --git a/config/obc/sitl/target/apps/sch/CMakeLists.txt b/config/obc/sitl/target/apps/sch/CMakeLists.txt deleted file mode 100644 index 749725f7c..000000000 --- a/config/obc/sitl/target/apps/sch/CMakeLists.txt +++ /dev/null @@ -1,48 +0,0 @@ -set(APP_NAME sch) - -buildliner_add_app_unit_test_src( - ${APP_NAME} - SOURCES - ${CMAKE_CURRENT_SOURCE_DIR}/sch_custom_rt.c -) - -buildliner_add_table( - ${APP_NAME} - NAME sch_def_schtbl - SOURCES ${CMAKE_CURRENT_SOURCE_DIR}/tables/sch_def_schtbl.c - INCLUDES ${CMAKE_CURRENT_SOURCE_DIR}/src/ -) - -buildliner_add_table( - ${APP_NAME} - NAME sch_def_msgtbl - SOURCES ${CMAKE_CURRENT_SOURCE_DIR}/tables/sch_def_msgtbl.c - INCLUDES ${CMAKE_CURRENT_SOURCE_DIR}/src/ -) - -#buildliner_add_app_unit_test(sch-custom-ut -# UTASSERT -# NO_HELGRIND -# NO_MASSIF -# -# SOURCES -# ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/sch_testrunner.c -# ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/sch_custom_test.c -# #${CMAKE_CURRENT_SOURCE_DIR}/unit_test/sch_mock_os_calls.c -# ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/sch_test_utils.c -# ${CMAKE_CURRENT_SOURCE_DIR}/sch_custom.c -## ${PROJECT_SOURCE_DIR}/apps/sch/fsw/src/sch_app.c -## ${PROJECT_SOURCE_DIR}/apps/sch/fsw/src/sch_cds_utils.c -## ${PROJECT_SOURCE_DIR}/apps/sch/fsw/src/sch_config_utils.c -## ${PROJECT_SOURCE_DIR}/core/base/ut_assert/src/ut_cfe_es_hooks.c -# -# INCLUDES -# ${PROJECT_SOURCE_DIR}/apps/sch/fsw/src/ -# -## WRAPPERS -## socket -## bind -# -#) - - diff --git a/config/obc/sitl/target/apps/sch/sch_custom_rt.c b/config/obc/sitl/target/apps/sch/sch_custom_rt.c deleted file mode 100644 index c1f404c16..000000000 --- a/config/obc/sitl/target/apps/sch/sch_custom_rt.c +++ /dev/null @@ -1,451 +0,0 @@ -/* -** $Id: sch_custom.c 1.5 2017/06/21 15:29:41EDT mdeschu Exp $ -** -** Copyright (c) 2007-2014 United States Government as represented by the -** Administrator of the National Aeronautics and Space Administration. -** All Other Rights Reserved. -** -** This software was created at NASA's Goddard Space Flight Center. -** This software is governed by the NASA Open Source Agreement and may be -** used, distributed and modified only pursuant to the terms of that -** agreement. -** -** Purpose: Scheduler (SCH) application custom component -** -** Author: -** -** Notes: -** -*/ - -/************************************************************************* -** -** Include section -** -**************************************************************************/ - -#include "cfe.h" -#include "sch_platform_cfg.h" - -#include "sch_app.h" -#include "sch_custom.h" - -#include "cfe_time_msg.h" - - -/************************************************************************* -** -** Macro definitions -** -**************************************************************************/ - -/************************************************************************* -** Local function prototypes -**************************************************************************/ - - -/************************************************************************* -** -** Function definitions -** -**************************************************************************/ - - - - -/******************************************************************* -** -** SCH_CustomEarlyInit -** -** NOTE: For complete prolog information, see 'sch_custom.h' -** -** This function MUST update SCH_AppData.ClockAccuracy to the -** resolution of the minor frame timer. -********************************************************************/ - -int32 SCH_CustomEarlyInit(void) -{ - int32 Status = CFE_SUCCESS; - - Status = OS_TimerCreate(&SCH_AppData.TimerId, - SCH_TIMER_NAME, - &SCH_AppData.ClockAccuracy, - SCH_MinorFrameCallback); - - return Status; - -} /* End of CustomEarlyInit() */ - - -/******************************************************************* -** -** SCH_CustomLateInit -** -** NOTE: For complete prolog information, see 'sch_custom.h' -** -** This function MUST perform any startup synchronization required, -** and MUST finish setting up the major and minor frame timers. -********************************************************************/ - -int32 SCH_CustomLateInit(void) -{ - int32 Status = CFE_SUCCESS; - - CFE_ES_WaitForStartupSync(SCH_STARTUP_SYNC_TIMEOUT); - - /* - ** Connect to cFE TIME's time reference marker (typically 1 Hz) - ** to use it as the Major Frame synchronization source - */ - Status = CFE_TIME_RegisterSynchCallback((CFE_TIME_SynchCallbackPtr_t)&SCH_MajorFrameCallback); - if (Status == CFE_SUCCESS) - { - /* - ** Start the Minor Frame Timer with an extended delay to allow a Major Frame Sync - ** to start processing. If the Major Frame Sync fails to arrive, then we will - ** start when this timer expires and synch ourselves to the MET clock. - */ - Status = OS_TimerSet(SCH_AppData.TimerId, SCH_STARTUP_PERIOD, 0); - } - - return Status; - -} /* End of SH_CustomLateInit() */ - - -/******************************************************************* -** -** SCH_CustomGetCurrentSlotNumber -** -** NOTE: For complete prolog information, see 'sch_custom.h' -********************************************************************/ - -uint32 SCH_CustomGetCurrentSlotNumber(void) -{ - uint32 CurrentSlot; - - if (SCH_AppData.SyncToMET != SCH_NOT_SYNCHRONIZED) - { - CurrentSlot = SCH_GetMETSlotNumber(); - - /* - ** If we are only concerned with synchronizing the minor frames to an MET, - ** then we need to adjust the current slot by whatever MET time is prevalent - ** when the Major Frame Signal is received. - ** If we are synchronizing the Major Frame, then, by definition, LastSyncMETSlot - ** would be a zero and the current slot would be appropriate. - */ - if (CurrentSlot < SCH_AppData.LastSyncMETSlot) - { - CurrentSlot = CurrentSlot + SCH_TOTAL_SLOTS - SCH_AppData.LastSyncMETSlot; - } - else - { - CurrentSlot = CurrentSlot - SCH_AppData.LastSyncMETSlot; - } - } - else - { - CurrentSlot = SCH_AppData.MinorFramesSinceTone; - } - - return CurrentSlot; -} /* End of SH_CustomGetCurrentSlotNumber() */ - -/******************************************************************* -** -** SCH_CustomCleanup -** -** NOTE: For complete prolog information, see 'sch_custom.h' -********************************************************************/ - -void SCH_CustomCleanup(void) -{ - /* unregister the TIME callback for the major frame */ - CFE_TIME_UnregisterSynchCallback((CFE_TIME_SynchCallbackPtr_t)&SCH_MajorFrameCallback); - -} /* End of SH_CustomCleanup() */ - - -/******************************************************************* -** -** SCH_GetMETSlotNumber -** -** NOTE: For complete prolog information, see above -********************************************************************/ - -uint32 SCH_GetMETSlotNumber(void) -{ - uint32 SubSeconds = 0; - uint32 MicroSeconds; - uint32 Remainder; - uint32 METSlot; - - /* - ** Use MET rather than current time to avoid time changes - */ - SubSeconds = CFE_TIME_GetMETsubsecs(); - - /* - ** Convert sub-seconds to micro-seconds - */ - MicroSeconds = CFE_TIME_Sub2MicroSecs(SubSeconds); - - /* - ** Calculate schedule table slot number - */ - METSlot = (MicroSeconds / SCH_NORMAL_SLOT_PERIOD); - - /* - ** Check to see if close enough to round up to next slot - */ - Remainder = MicroSeconds - (METSlot * SCH_NORMAL_SLOT_PERIOD); - - /* - ** Add one more microsecond and see if it is sufficient to add another slot - */ - Remainder += 1; - METSlot += (Remainder / SCH_NORMAL_SLOT_PERIOD); - - /* - ** Check to see if the Current Slot number needs to roll over - */ - if (METSlot == SCH_TOTAL_SLOTS) - { - METSlot = 0; - } - - return METSlot; - -} - - -/******************************************************************* -** -** SCH_MajorFrameCallback -** -** NOTE: For complete prolog information, see above -********************************************************************/ - -void SCH_MajorFrameCallback(void) -{ - /* - ** Synchronize slot zero to the external tone signal - */ - uint16 StateFlags; - - /* - ** If cFE TIME is in FLYWHEEL mode, then ignore all synchronization signals - */ - StateFlags = CFE_TIME_GetClockInfo(); - - if ((StateFlags & CFE_TIME_FLAG_FLYING) == 0) - { - /* - ** Determine whether the major frame is noisy or not - ** - ** Conditions below are as follows: - ** If we are NOT synchronized to the MET (i.e. - the Minor Frame timer - ** has an acceptable resolution), then the Major Frame signal should - ** only occur in the last slot of the schedule table. - ** - ** If we ARE synchronized to the MET (i.e. - the Minor Frame timer is - ** not as good as we would like), then the Major Frame signal should - ** occur within a window of slots at the end of the table. - */ - if (((SCH_AppData.SyncToMET == SCH_NOT_SYNCHRONIZED) && - (SCH_AppData.MinorFramesSinceTone != SCH_TIME_SYNC_SLOT)) || - ((SCH_AppData.SyncToMET == SCH_MINOR_SYNCHRONIZED) && - (SCH_AppData.NextSlotNumber != 0) && - (SCH_AppData.NextSlotNumber < - (SCH_TOTAL_SLOTS - SCH_AppData.WorstCaseSlotsPerMinorFrame - 1)))) - { - /* - ** Count the number of consecutive noisy major frames and the Total number - ** of noisy major frames. Also, indicate in telemetry that this particular - ** Major Frame signal is considered noisy. - */ - SCH_AppData.UnexpectedMajorFrame = TRUE; - SCH_AppData.UnexpectedMajorFrameCount++; - - /* - ** If the Major Frame is not being ignored yet, then increment the consecutive noisy - ** Major Frame counter. - */ - if (!SCH_AppData.IgnoreMajorFrame) - { - SCH_AppData.ConsecutiveNoisyFrameCounter++; - - /* - ** If the major frame is too "noisy", then send event message and ignore future signals - */ - if (SCH_AppData.ConsecutiveNoisyFrameCounter >= SCH_MAX_NOISY_MAJORF) - { - SCH_AppData.IgnoreMajorFrame = TRUE; - } - } - } - else /* Major Frame occurred when expected */ - { - SCH_AppData.UnexpectedMajorFrame = FALSE; - SCH_AppData.ConsecutiveNoisyFrameCounter = 0; - } - - /* - ** Ignore this callback if SCH has detected a noisy Major Frame Synch signal - */ - if (SCH_AppData.IgnoreMajorFrame == FALSE) - { - /* - ** Stop Minor Frame Timer (which should be waiting for an unusually long - ** time to allow the Major Frame source to resynchronize timing) and start - ** it again with nominal Minor Frame timing - */ - OS_TimerSet(SCH_AppData.TimerId, SCH_NORMAL_SLOT_PERIOD, SCH_NORMAL_SLOT_PERIOD); - - /* - ** Increment Major Frame process counter - */ - SCH_AppData.ValidMajorFrameCount++; - - /* - ** Set current slot = zero to synchronize activities - */ - SCH_AppData.MinorFramesSinceTone = 0; - - /* - ** Major Frame Source is now from CFE TIME - */ - SCH_AppData.MajorFrameSource = SCH_MAJOR_FS_CFE_TIME; - - /* Clear any Major Frame In Sync with MET flags */ - /* But keep the Minor Frame In Sync with MET flag if it is set */ - SCH_AppData.SyncToMET &= SCH_MINOR_SYNCHRONIZED; - - /* - ** Give "wakeup SCH" semaphore - */ - OS_BinSemGive(SCH_AppData.TimeSemaphore); - } - } - - /* - ** We should assume that the next Major Frame will be in the same MET slot as this - */ - SCH_AppData.LastSyncMETSlot = SCH_GetMETSlotNumber(); - - return; - -} /* End of SCH_MajorFrameCallback() */ - - -/******************************************************************* -** -** SCH_MinorFrameCallback -** -** NOTE: For complete prolog information, see above -********************************************************************/ - -void SCH_MinorFrameCallback(uint32 TimerId) -{ - uint32 CurrentSlot; - - /* - ** If this is the very first timer interrupt, then the initial - ** Major Frame Synchronization timed out. This can occur when - ** either the signal is not arriving or the clock has gone into - ** FLYWHEEL mode. We should synchronize to the MET time instead. - */ - if (SCH_AppData.MajorFrameSource == SCH_MAJOR_FS_NONE) - { - SCH_AppData.MajorFrameSource = SCH_MAJOR_FS_MINOR_FRAME_TIMER; - - /* Synchronize timing to MET */ - SCH_AppData.SyncToMET |= SCH_PENDING_MAJOR_SYNCH; - SCH_AppData.SyncAttemptsLeft = SCH_MAX_SYNC_ATTEMPTS; - SCH_AppData.LastSyncMETSlot = 0; - } - - /* If attempting to synchronize the Major Frame with MET, then wait for zero subsecs before starting */ - if (((SCH_AppData.SyncToMET & SCH_PENDING_MAJOR_SYNCH) != 0) && - (SCH_AppData.MajorFrameSource == SCH_MAJOR_FS_MINOR_FRAME_TIMER)) - { - /* Whether we have found the Major Frame Start or not, wait another slot */ - OS_TimerSet(SCH_AppData.TimerId, SCH_NORMAL_SLOT_PERIOD, SCH_NORMAL_SLOT_PERIOD); - - /* Determine if this was the last attempt */ - SCH_AppData.SyncAttemptsLeft--; - - CurrentSlot = SCH_GetMETSlotNumber(); - if ((CurrentSlot != 0) && (SCH_AppData.SyncAttemptsLeft > 0)) - { - return; - } - else /* Synchronization achieved (or at least, aborted) */ - { - /* Clear the pending synchronization flag and set the "Major In Sync" flag */ - SCH_AppData.SyncToMET &= ~SCH_PENDING_MAJOR_SYNCH; - SCH_AppData.SyncToMET |= SCH_MAJOR_SYNCHRONIZED; - - /* CurrentSlot should be equal to zero. If not, this is the best estimate we can use */ - SCH_AppData.MinorFramesSinceTone = CurrentSlot; - SCH_AppData.LastSyncMETSlot = 0; - } - } - else - { - /* - ** If we are already synchronized with MET or don't care to be, increment current slot - */ - SCH_AppData.MinorFramesSinceTone++; - } - - if (SCH_AppData.MinorFramesSinceTone >= SCH_TOTAL_SLOTS) - { - /* - ** If we just rolled over from the last slot to slot zero, - ** It means that the Major Frame Callback did not cancel the - ** "long slot" timer that was started in the last slot - ** - ** It also means that we may now need a "short slot" - ** timer to make up for the previous long one - */ - OS_TimerSet(SCH_AppData.TimerId, SCH_SHORT_SLOT_PERIOD, SCH_NORMAL_SLOT_PERIOD); - - SCH_AppData.MinorFramesSinceTone = 0; - - SCH_AppData.MissedMajorFrameCount++; - } - - /* - ** Determine the timer delay value for the next slot - */ - if (SCH_AppData.MinorFramesSinceTone == SCH_TIME_SYNC_SLOT) - { - /* - ** Start "long slot" timer (should be stopped by Major Frame Callback) - */ - OS_TimerSet(SCH_AppData.TimerId, SCH_SYNC_SLOT_PERIOD, 0); - } - - /* - ** Note that if this is neither the first "short" minor frame nor the - ** last "long" minor frame, the timer is not modified. This should - ** provide more stable timing than introducing the dither associated - ** with software response times to timer interrupts. - */ - - /* - ** Give "wakeup SCH" semaphore - */ - OS_BinSemGive(SCH_AppData.TimeSemaphore); - - return; - -} /* End of SCH_MinorFrameCallback() */ - - -/************************/ -/* End of File Comment */ -/************************/ - diff --git a/config/obc/sitl/target/apps/sch/tables/sch_def_msgtbl.c b/config/obc/sitl/target/apps/sch/tables/sch_def_msgtbl.c deleted file mode 100644 index a46ba95d1..000000000 --- a/config/obc/sitl/target/apps/sch/tables/sch_def_msgtbl.c +++ /dev/null @@ -1,326 +0,0 @@ -#ifdef __cplusplus -extern "C" { -#endif - -/* -** Pragmas -*/ - -/* -** Include Files -*/ -#include "cfe.h" -#include "cfe_tbl_filedef.h" -#include "sch_platform_cfg.h" -#include "sch_tbldefs.h" -#include "msg_ids.h" - - -/* -** Local Defines -*/ - -/* -** Local Structure Declarations -*/ - -/* -** External Global Variables -*/ - - -/* -** Global Variables -*/ - -#define SCH_FIX_HEADER(a, b, c) CFE_MAKE_BIG16(a), CFE_MAKE_BIG16(b), CFE_MAKE_BIG16(c) - -/* Message table entry map */ -SCH_MessageEntry_t SCH_DefaultMessageTable[SCH_MAX_MESSAGES] = -{ - /* ** DO NOT USE -- entry #0 reserved for "unused" command ID - DO NOT USE */ - /* Command ID #0 */ - { { SCH_UNUSED_MID, 0, 0, 0 } }, - /* Command ID #1 - Executive Services HK Request */ - { { SCH_FIX_HEADER(CFE_ES_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #2 - Event Services HK Request */ - { { SCH_FIX_HEADER(CFE_EVS_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #3 - Software Bus HK Request */ - { { SCH_FIX_HEADER(CFE_SB_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #4 - Time Services HK Request */ - { { SCH_FIX_HEADER(CFE_TIME_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #5 - Table Services HK Request */ - { { SCH_FIX_HEADER(CFE_TBL_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #6 */ - { { SCH_FIX_HEADER(CFE_TIME_FAKE_CMD_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #7 - Data storage HK request*/ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0,0), 0 } }, - /* Command ID #8 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0,0), 0 } }, - /* Command ID #9 */ - { { SCH_FIX_HEADER(LC_SAMPLE_AP_MID, 0xC000, 0x0007), 0x0000, 0x0000, 0x0001, 0x0001 } }, - /* Command ID #10 - Health and safety HK request*/ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0,0), 0 } }, - /* Command ID #11 - Limit checker HK request*/ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0,0), 0 } }, - /* Command ID #12 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0,0), 0 } }, - /* Command ID #13 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0,0), 0 } }, - /* Command ID #14 - Wakeup store command app*/ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0,0), 0 } }, - /* Command ID #15 - Scheduler HK request*/ - { { SCH_FIX_HEADER(SCH_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #16 */ - { { SCH_FIX_HEADER(TO_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #17 */ - { { SCH_FIX_HEADER(HK_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #18 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #19 */ - { { SCH_FIX_HEADER(TO_SEND_TLM_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #20 */ - { { SCH_FIX_HEADER(HK_SEND_COMBINED_PKT_MID, 0xC000, 0x0003), 0x0000, HK_COMBINED_PKT1_MID } }, - /* Command ID #21 */ - { { SCH_FIX_HEADER(HK_SEND_COMBINED_PKT_MID, 0xC000, 0x0003), 0x0000, HK_COMBINED_PKT2_MID } }, - /* Command ID #22 */ - { { SCH_FIX_HEADER(HK_SEND_COMBINED_PKT_MID, 0xC000, 0x0003), 0x0000, HK_COMBINED_PKT3_MID } }, - /* Command ID #23 */ - { { SCH_FIX_HEADER(HK_SEND_COMBINED_PKT_MID, 0xC000, 0x0003), 0x0000, HK_COMBINED_PKT4_MID } }, - /* Command ID #24 */ - { { SCH_FIX_HEADER(HK_SEND_COMBINED_PKT_MID, 0xC000, 0x0003), 0x0000, HK_COMBINED_PKT5_MID } }, - /* Command ID #25 */ - { { SCH_FIX_HEADER(HK_SEND_COMBINED_PKT_MID, 0xC000, 0x0003), 0x0000, HK_COMBINED_PKT6_MID } }, - /* Command ID #26 */ - { { SCH_FIX_HEADER(HK_SEND_COMBINED_PKT_MID, 0xC000, 0x0003), 0x0000, HK_COMBINED_PKT7_MID } }, - /* Command ID #27 */ - { { SCH_FIX_HEADER(HK_SEND_COMBINED_PKT_MID, 0xC000, 0x0003), 0x0000, HK_COMBINED_PKT8_MID } }, - /* Command ID #28 */ - { { SCH_FIX_HEADER(HK_SEND_COMBINED_PKT_MID, 0xC000, 0x0003), 0x0000, HK_COMBINED_PKT9_MID } }, - /* Command ID #29 */ - { { SCH_FIX_HEADER(HK_SEND_COMBINED_PKT_MID, 0xC000, 0x0003), 0x0000, HK_COMBINED_PKT10_MID } }, - /* Command ID #30 */ - { { SCH_FIX_HEADER(FM_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #31 */ - { { SCH_FIX_HEADER(LC_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #32 */ - { { SCH_FIX_HEADER(HS_WAKEUP_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #33 */ - { { SCH_FIX_HEADER(HS_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #34 */ - { { SCH_FIX_HEADER(MD_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #35 */ - { { SCH_FIX_HEADER(MD_WAKEUP_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #36 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #37 */ - { { SCH_FIX_HEADER(DS_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #38 */ - { { SCH_FIX_HEADER(CS_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #39 */ - { { SCH_FIX_HEADER(CS_BACKGROUND_CYCLE_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #40 */ - { { SCH_FIX_HEADER(SC_1HZ_WAKEUP_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #41 */ - { { SCH_FIX_HEADER(SC_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #42 */ - { { SCH_FIX_HEADER(FLOW_WAKEUP_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #43 */ - { { SCH_FIX_HEADER(FLOW_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #44 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #45 */ - { { SCH_FIX_HEADER(VC_PROCESS_CMDS_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #46 */ - { { SCH_FIX_HEADER(VC_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #47 */ - { { SCH_FIX_HEADER(RGBLED_WAKEUP_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #48 */ - { { SCH_FIX_HEADER(RGBLED_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #49 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #50 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #51 */ - { { SCH_FIX_HEADER(CI_PROCESS_TIMEOUTS_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #52 */ - { { SCH_FIX_HEADER(CI_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #53 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #54 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #55 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #56 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #57 */ - { { SCH_FIX_HEADER(CF_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #58 */ - { { SCH_FIX_HEADER(CF_WAKE_UP_REQ_CMD_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #59 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #60 */ - { { SCH_FIX_HEADER(MAC_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #61 */ - { { SCH_FIX_HEADER(MAC_RUN_CONTROLLER_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #62 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #63 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #64 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #65 */ - { { SCH_FIX_HEADER(AMC_UPDATE_MOTORS_MID, 0xC000, 0x0001), 0 } }, - /* Command ID #66 */ - { { SCH_FIX_HEADER(AMC_SEND_HK_MID, 0xC000, 0x0001), 0 } }, - /* Command ID #67 */ - { { SCH_FIX_HEADER(MPU9250_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #68 */ - { { SCH_FIX_HEADER(MPU9250_MEASURE_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #69 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #70 */ - { { SCH_FIX_HEADER(MM_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #71 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #72 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #73 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #74 */ - { { SCH_FIX_HEADER(PE_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #75 */ - { { SCH_FIX_HEADER(PE_WAKEUP_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #76 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #77 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #78 */ - { { SCH_FIX_HEADER(MS5611_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #79 */ - { { SCH_FIX_HEADER(MS5611_MEASURE_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #80 */ - { { SCH_FIX_HEADER(ULR_MEASURE_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #81 */ - { { SCH_FIX_HEADER(ULR_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #82 */ - { { SCH_FIX_HEADER(HMC5883_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #83 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #84 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #85 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #86 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #87 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #88 */ - { { SCH_FIX_HEADER(HMC5883_WAKEUP_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #89 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #90 */ - { { SCH_FIX_HEADER(SENS_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #91 */ - { { SCH_FIX_HEADER(SENS_WAKEUP_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #92 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #93 */ - { { SCH_FIX_HEADER(LGC_WAKEUP_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #94 */ - { { SCH_FIX_HEADER(LGC_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #95*/ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #96 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #97 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #98 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #99 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #100 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #101 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #102 */ - { { SCH_FIX_HEADER(QAE_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #103 */ - { { SCH_FIX_HEADER(QAE_WAKEUP_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #104 */ - { { SCH_FIX_HEADER(LD_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #105 */ - { { SCH_FIX_HEADER(LD_WAKEUP_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #106 */ - { { SCH_FIX_HEADER(MPC_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #107 */ - { { SCH_FIX_HEADER(MPC_WAKEUP_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #108 */ - { { SCH_FIX_HEADER(NAV_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #109 */ - { { SCH_FIX_HEADER(NAV_WAKEUP_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #110 */ - { { SCH_FIX_HEADER(CFE_TIME_TONE_CMD_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #111 */ - { { SCH_FIX_HEADER(CFE_TIME_1HZ_CMD_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #112 */ - { { SCH_FIX_HEADER(RCIN_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #113 */ - { { SCH_FIX_HEADER(RCIN_WAKEUP_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #114 */ - { { SCH_FIX_HEADER(VM_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #115 */ - { { SCH_FIX_HEADER(VM_WAKEUP_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #116 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #117 */ - { { SCH_FIX_HEADER(BAT_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #118 */ - { { SCH_FIX_HEADER(BAT_WAKEUP_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #119 */ - { { SCH_FIX_HEADER(MAVLINK_WAKEUP_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #120 */ - { { SCH_FIX_HEADER(MAVLINK_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #121 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #122 */ - { { SCH_FIX_HEADER(GPS_READ_SENSOR_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #123 */ - { { SCH_FIX_HEADER(GPS_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #124 */ - { { SCH_FIX_HEADER(SCH_UNUSED_MID, 0, 0), 0 } }, - /* Command ID #125 */ - { { SCH_FIX_HEADER(EA_WAKEUP_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #126 */ - { { SCH_FIX_HEADER(EA_PERFMON_MID, 0xC000, 0x0001), 0x0000 } }, - /* Command ID #127 */ - { { SCH_FIX_HEADER(EA_SEND_HK_MID, 0xC000, 0x0001), 0x0000 } } -}; - -/* -** Local Variables -*/ - -/* -** Function Prototypes -*/ - -/* -** Function Definitions -*/ - - - -/* Table file header */ -CFE_TBL_FILEDEF(SCH_DefaultMessageTable, SCH.MSG_DEFS, SCH message definitions table, sch_def_msgtbl.tbl ) - - - -#ifdef __cplusplus -} -#endif - -/*======================================================================================= -** End of file sch_def_msgtbl.c -**=====================================================================================*/ - diff --git a/config/obc/sitl/target/apps/sch/unit_test/sch_custom_test.c b/config/obc/sitl/target/apps/sch/unit_test/sch_custom_test.c deleted file mode 100644 index 3d6b0eef3..000000000 --- a/config/obc/sitl/target/apps/sch/unit_test/sch_custom_test.c +++ /dev/null @@ -1,415 +0,0 @@ - /************************************************************************* - ** File: - ** $Id: sch_custom_test.c 1.3 2017/06/21 15:29:03EDT mdeschu Exp $ - ** - ** Purpose: - ** This file contains unit test cases for the functions contained in the file sch_custom.c - ** - ** References: - ** Flight Software Branch C Coding Standard Version 1.2 - ** CFS Development Standards Document - ** Notes: - ** - *************************************************************************/ - -/* - * Includes - */ - -#include "sch_custom_test.h" -#include "sch_custom.h" -#include "sch_app.h" -#include "sch_msg.h" -#include "sch_msgdefs.h" -#include "sch_events.h" -#include "sch_version.h" -#include "sch_test_utils.h" -#include -#include -#include - -/* - * Function Definitions - */ -void SCH_CustomEarlyInit_Test(void) -{ - int32 Result; - - /* Execute the function being tested */ - Result = SCH_CustomEarlyInit(); - - /* Verify results */ - UtAssert_True (Result == CFE_SUCCESS, "Result == CFE_SUCCESS"); - - UtAssert_True (Ut_CFE_EVS_GetEventQueueDepth() == 0, "Ut_CFE_EVS_GetEventQueueDepth() == 0"); - -} /* end SCH_CustomEarlyInit_Test */ - -void SCH_CustomLateInit_Test_Nominal(void) -{ - int32 Result; - - /* Execute the function being tested */ - Result = SCH_CustomLateInit(); - - /* Verify results */ - UtAssert_True (Result == CFE_SUCCESS, "Result == CFE_SUCCESS"); - - UtAssert_True (Ut_CFE_EVS_GetEventQueueDepth() == 0, "Ut_CFE_EVS_GetEventQueueDepth() == 0"); - -} /* end SCH_CustomLateInit_Test_Nominal */ - -void SCH_CustomLateInit_Test_RegisterSynchCallbackError(void) -{ - int32 Result; - - /* Set to make function under test return -1 */ - Ut_CFE_TIME_SetReturnCode(UT_CFE_TIME_REGISTERSYNCHCALLBACK_INDEX, -1, 1); - - /* Execute the function being tested */ - Result = SCH_CustomLateInit(); - - /* Verify results */ - UtAssert_True (Result == -1, "Result == -1"); - - UtAssert_True (Ut_CFE_EVS_GetEventQueueDepth() == 0, "Ut_CFE_EVS_GetEventQueueDepth() == 0"); - -} /* end SCH_CustomLateInit_Test_RegisterSynchCallbackError */ - -void SCH_CustomLateInit_Test_TimerSetError(void) -{ - int32 Result; - - /* Set to make function under test return -1 */ -#ifndef CFE_PSP_MAX_TIMERS - Ut_OSTIMER_SetReturnCode(UT_OSTIMER_SET_INDEX, -1, 1); -#else - Ut_CFE_PSP_SetReturnCode(UT_CFE_PSP_TIMERSET_INDEX, -1, 1); -#endif - - /* Execute the function being tested */ - Result = SCH_CustomLateInit(); - - /* Verify results */ - UtAssert_True (Result == -1, "Result == -1"); - - UtAssert_True (Ut_CFE_EVS_GetEventQueueDepth() == 0, "Ut_CFE_EVS_GetEventQueueDepth() == 0"); - -} /* end SCH_CustomLateInit_Test_TimerSetError */ - -void SCH_CustomGetCurrentSlotNumber_Test_LowCurrentSlot(void) -{ - int32 Result = 0; - - SCH_AppData.SyncToMET = 99; - SCH_AppData.LastSyncMETSlot = 10; - - /* Execute the function being tested */ - //Result = SCH_CustomGetCurrentSlotNumber(); - - /* Verify results */ - UtAssert_True (Result == SCH_TOTAL_SLOTS - 10, "Result == SCH_TOTAL_SLOTS - 10"); - - UtAssert_True (Ut_CFE_EVS_GetEventQueueDepth() == 0, "Ut_CFE_EVS_GetEventQueueDepth() == 0"); - -} /* end SCH_CustomGetCurrentSlotNumber_Test_LowCurrentSlot */ - -void SCH_CustomGetCurrentSlotNumber_Test_HighCurrentSlot(void) -{ - int32 Result = 0; - - SCH_AppData.SyncToMET = 99; - SCH_AppData.LastSyncMETSlot = 0; - - /* Set to make SCH_GetMETSlotNumber return 1 */ - Ut_CFE_TIME_SetReturnCode(UT_CFE_TIME_SUB2MICROSECS_INDEX, SCH_NORMAL_SLOT_PERIOD, 1); - - /* Execute the function being tested */ - //Result = SCH_CustomGetCurrentSlotNumber(); - - /* Verify results */ - UtAssert_True (Result == 1, "Result == 1"); - - UtAssert_True (Ut_CFE_EVS_GetEventQueueDepth() == 0, "Ut_CFE_EVS_GetEventQueueDepth() == 0"); - -} /* end SCH_CustomGetCurrentSlotNumber_Test_HighCurrentSlot */ - -void SCH_CustomGetCurrentSlotNumber_Test_NotSynchronized(void) -{ - int32 Result = 0; - - SCH_AppData.SyncToMET = SCH_NOT_SYNCHRONIZED; - SCH_AppData.MinorFramesSinceTone = 10; - - /* Execute the function being tested */ - //Result = SCH_CustomGetCurrentSlotNumber(); - - /* Verify results */ - UtAssert_True (Result == 10, "Result == 10"); - - UtAssert_True (Ut_CFE_EVS_GetEventQueueDepth() == 0, "Ut_CFE_EVS_GetEventQueueDepth() == 0"); - -} /* end SCH_CustomGetCurrentSlotNumber_Test_NotSynchronized */ - -void SCH_CustomCleanup_Test(void) -{ - /* Execute the function being tested */ - SCH_CustomCleanup(); - - /* Verify results */ - UtAssert_True (Ut_CFE_EVS_GetEventQueueDepth() == 0, "Ut_CFE_EVS_GetEventQueueDepth() == 0"); - -} /* end SCH_CustomCleanup_Test */ - -void SCH_GetMETSlotNumber_Test_Rollover(void) -{ - uint32 Result = 1; - - /* Set to make function under test return 0 by rollover */ - Ut_CFE_TIME_SetReturnCode(UT_CFE_TIME_SUB2MICROSECS_INDEX, SCH_NORMAL_SLOT_PERIOD * SCH_TOTAL_SLOTS, 1); - - /* Execute the function being tested */ - //Result = SCH_GetMETSlotNumber(); - - /* Verify results */ - UtAssert_True (Result == 0, "Result == 0"); - - UtAssert_True (Ut_CFE_EVS_GetEventQueueDepth() == 0, "Ut_CFE_EVS_GetEventQueueDepth() == 0"); - -} /* end SCH_GetMETSlotNumber_Test_Rollover */ - -void SCH_GetMETSlotNumber_Test_NoRollover(void) -{ - uint32 Result = 0; - - /* Set to make function under test return 1 */ - Ut_CFE_TIME_SetReturnCode(UT_CFE_TIME_SUB2MICROSECS_INDEX, SCH_NORMAL_SLOT_PERIOD, 1); - - /* Execute the function being tested */ - //Result = SCH_GetMETSlotNumber(); - - /* Verify results */ - UtAssert_True (Result == 1, "Result == 1"); - - UtAssert_True (Ut_CFE_EVS_GetEventQueueDepth() == 0, "Ut_CFE_EVS_GetEventQueueDepth() == 0"); - -} /* end SCH_GetMETSlotNumber_Test_NoRollover */ - -void SCH_MajorFrameCallback_Test_NoisyNotSynchronized(void) -{ - SCH_AppData.SyncToMET = SCH_NOT_SYNCHRONIZED; - SCH_AppData.MinorFramesSinceTone = 1; - SCH_AppData.IgnoreMajorFrame = FALSE; - SCH_AppData.ConsecutiveNoisyFrameCounter = SCH_MAX_NOISY_MAJORF - 1; - - /* Set to make SCH_GetMETSlotNumber return 1 */ - Ut_CFE_TIME_SetReturnCode(UT_CFE_TIME_SUB2MICROSECS_INDEX, SCH_NORMAL_SLOT_PERIOD, 1); - - /* Execute the function being tested */ - //SCH_MajorFrameCallback(); - - /* Verify results */ - UtAssert_True (SCH_AppData.UnexpectedMajorFrame == TRUE, "SCH_AppData.UnexpectedMajorFrame == TRUE"); - UtAssert_True (SCH_AppData.UnexpectedMajorFrameCount == 1, "SCH_AppData.UnexpectedMajorFrameCount == 1"); - UtAssert_True (SCH_AppData.ConsecutiveNoisyFrameCounter == SCH_MAX_NOISY_MAJORF, "SCH_AppData.ConsecutiveNoisyFrameCounter == SCH_MAX_NOISY_MAJORF"); - UtAssert_True (SCH_AppData.IgnoreMajorFrame == TRUE, "SCH_AppData.IgnoreMajorFrame == TRUE"); - UtAssert_True (SCH_AppData.LastSyncMETSlot == 1, "SCH_AppData.LastSyncMETSlot == 1"); - - UtAssert_True (Ut_CFE_EVS_GetEventQueueDepth() == 0, "Ut_CFE_EVS_GetEventQueueDepth() == 0"); - -} /* end SCH_MajorFrameCallback_Test_NoisyNotSynchronized */ - -void SCH_MajorFrameCallback_Test_NoisySynchronized(void) -{ - SCH_AppData.SyncToMET = SCH_MINOR_SYNCHRONIZED; - SCH_AppData.NextSlotNumber = 1; - SCH_AppData.IgnoreMajorFrame = FALSE; - SCH_AppData.ConsecutiveNoisyFrameCounter = SCH_MAX_NOISY_MAJORF - 1; - - /* Set to make SCH_GetMETSlotNumber return 1 */ - Ut_CFE_TIME_SetReturnCode(UT_CFE_TIME_SUB2MICROSECS_INDEX, SCH_NORMAL_SLOT_PERIOD, 1); - - /* Execute the function being tested */ - //SCH_MajorFrameCallback(); - - /* Verify results */ - UtAssert_True (SCH_AppData.UnexpectedMajorFrame == TRUE, "SCH_AppData.UnexpectedMajorFrame == TRUE"); - UtAssert_True (SCH_AppData.UnexpectedMajorFrameCount == 1, "SCH_AppData.UnexpectedMajorFrameCount == 1"); - UtAssert_True (SCH_AppData.ConsecutiveNoisyFrameCounter == SCH_MAX_NOISY_MAJORF, "SCH_AppData.ConsecutiveNoisyFrameCounter == SCH_MAX_NOISY_MAJORF"); - UtAssert_True (SCH_AppData.IgnoreMajorFrame == TRUE, "SCH_AppData.IgnoreMajorFrame == TRUE"); - UtAssert_True (SCH_AppData.LastSyncMETSlot == 1, "SCH_AppData.LastSyncMETSlot == 1"); - - UtAssert_True (Ut_CFE_EVS_GetEventQueueDepth() == 0, "Ut_CFE_EVS_GetEventQueueDepth() == 0"); - -} /* end SCH_MajorFrameCallback_Test_NoisySynchronized */ - -void SCH_MajorFrameCallback_Test_FrameOccurredWhenExpected(void) -{ - SCH_AppData.SyncToMET = 99; - SCH_AppData.IgnoreMajorFrame = FALSE; - SCH_AppData.ConsecutiveNoisyFrameCounter = 1; - - /* Set to make SCH_GetMETSlotNumber return 1 */ - Ut_CFE_TIME_SetReturnCode(UT_CFE_TIME_SUB2MICROSECS_INDEX, SCH_NORMAL_SLOT_PERIOD, 1); - - /* Execute the function being tested */ - //SCH_MajorFrameCallback(); - - /* Verify results */ - UtAssert_True (SCH_AppData.UnexpectedMajorFrame == FALSE, "SCH_AppData.UnexpectedMajorFrame == FALSE"); - UtAssert_True (SCH_AppData.ConsecutiveNoisyFrameCounter == 0, "SCH_AppData.ConsecutiveNoisyFrameCounter == 0"); - UtAssert_True (SCH_AppData.ValidMajorFrameCount == 1, "SCH_AppData.ValidMajorFrameCount == 1"); - UtAssert_True (SCH_AppData.MinorFramesSinceTone == 0, "SCH_AppData.MinorFramesSinceTone == 0"); - UtAssert_True (SCH_AppData.MajorFrameSource == SCH_MAJOR_FS_CFE_TIME, "MajorFrameSource == SCH_MAJOR_FS_CFE_TIME"); - UtAssert_True (SCH_AppData.SyncToMET == (SCH_AppData.SyncToMET & SCH_MINOR_SYNCHRONIZED), "SCH_AppData.SyncToMET == (SCH_AppData.SyncToMET & SCH_MINOR_SYNCHRONIZED)"); - UtAssert_True (SCH_AppData.LastSyncMETSlot == 1, "SCH_AppData.LastSyncMETSlot == 1"); - - UtAssert_True (Ut_CFE_EVS_GetEventQueueDepth() == 0, "Ut_CFE_EVS_GetEventQueueDepth() == 0"); - -} /* end SCH_MajorFrameCallback_Test_FrameOccurredWhenExpected */ - -#define CFE_TIME_FLAG_FLYING 1 -void SCH_MajorFrameCallback_Test_FlywheelMode(void) -{ - /* Set to make fail condition "(StateFlags & CFE_TIME_FLAG_FLYING) == 0" */ - Ut_CFE_TIME_SetReturnCode(UT_CFE_TIME_GETCLOCKINFO_INDEX, CFE_TIME_FLAG_FLYING, 1); - - /* Set to make SCH_GetMETSlotNumber return 1 */ - Ut_CFE_TIME_SetReturnCode(UT_CFE_TIME_SUB2MICROSECS_INDEX, SCH_NORMAL_SLOT_PERIOD, 1); - - /* Execute the function being tested */ - //SCH_MajorFrameCallback(); - - /* Verify results */ - UtAssert_True (SCH_AppData.LastSyncMETSlot == 1, "SCH_AppData.LastSyncMETSlot == 1"); - - UtAssert_True (Ut_CFE_EVS_GetEventQueueDepth() == 0, "Ut_CFE_EVS_GetEventQueueDepth() == 0"); - -} /* end SCH_MajorFrameCallback_Test_FlywheelMode */ - -void SCH_MinorFrameCallback_Test_SyncAttemptsLeft(void) -{ - uint32 TimerId = 1; - - SCH_AppData.MajorFrameSource = SCH_MAJOR_FS_NONE; - - /* Set to make SCH_GetMETSlotNumber return 1 */ - Ut_CFE_TIME_SetReturnCode(UT_CFE_TIME_SUB2MICROSECS_INDEX, SCH_NORMAL_SLOT_PERIOD, 1); - - /* Execute the function being tested */ - //SCH_MinorFrameCallback(TimerId); - - /* Verify results */ - UtAssert_True(SCH_AppData.MajorFrameSource == SCH_MAJOR_FS_MINOR_FRAME_TIMER, "SCH_AppData.MajorFrameSource == SCH_MAJOR_FS_MINOR_FRAME_TIMER"); - UtAssert_True(SCH_AppData.SyncToMET == SCH_PENDING_MAJOR_SYNCH, "SCH_AppData.SyncToMET == SCH_PENDING_MAJOR_SYNCH"); - UtAssert_True(SCH_AppData.SyncAttemptsLeft == SCH_MAX_SYNC_ATTEMPTS - 1, "SCH_AppData.SyncAttemptsLeft == SCH_MAX_SYNC_ATTEMPTS - 1"); - UtAssert_True(SCH_AppData.LastSyncMETSlot == 0, "SCH_AppData.LastSyncMETSlot == 0"); - - UtAssert_True (Ut_CFE_EVS_GetEventQueueDepth() == 0, "Ut_CFE_EVS_GetEventQueueDepth() == 0"); - -} /* end SCH_MinorFrameCallback_Test_SyncAttemptsLeft */ - -void SCH_MinorFrameCallback_Test_SynchronizationAchievedNominal(void) -{ - uint32 TimerId = 1; - - SCH_AppData.MajorFrameSource = SCH_MAJOR_FS_NONE; - - /* Execute the function being tested */ - //SCH_MinorFrameCallback(TimerId); - - /* Verify results */ - UtAssert_True(SCH_AppData.MajorFrameSource == SCH_MAJOR_FS_MINOR_FRAME_TIMER, "SCH_AppData.MajorFrameSource == SCH_MAJOR_FS_MINOR_FRAME_TIMER"); - UtAssert_True(SCH_AppData.SyncAttemptsLeft == SCH_MAX_SYNC_ATTEMPTS - 1, "SCH_AppData.SyncAttemptsLeft == SCH_MAX_SYNC_ATTEMPTS - 1"); - UtAssert_True(SCH_AppData.SyncToMET == SCH_MAJOR_SYNCHRONIZED, "SCH_AppData.SyncToMET == SCH_MAJOR_SYNCHRONIZED"); - UtAssert_True(SCH_AppData.MinorFramesSinceTone == 0, "SCH_AppData.MinorFramesSinceTone == 0"); - UtAssert_True(SCH_AppData.LastSyncMETSlot == 0, "SCH_AppData.LastSyncMETSlot == 0"); - - UtAssert_True (Ut_CFE_EVS_GetEventQueueDepth() == 0, "Ut_CFE_EVS_GetEventQueueDepth() == 0"); - -} /* end SCH_MinorFrameCallback_Test_SynchronizationAchievedNominal */ - -void SCH_MinorFrameCallback_Test_AlreadySynchronizedNominal(void) -{ - uint32 TimerId = 1; - - SCH_AppData.MajorFrameSource = 99; - - /* Execute the function being tested */ - //SCH_MinorFrameCallback(TimerId); - - /* Verify results */ - UtAssert_True(SCH_AppData.MinorFramesSinceTone == 1, "SCH_AppData.MinorFramesSinceTone == 1"); - - UtAssert_True (Ut_CFE_EVS_GetEventQueueDepth() == 0, "Ut_CFE_EVS_GetEventQueueDepth() == 0"); - -} /* end SCH_MinorFrameCallback_Test_AlreadySynchronizedNominal */ - -void SCH_MinorFrameCallback_Test_AlreadySynchronizedRollover(void) -{ - uint32 TimerId = 1; - - SCH_AppData.MajorFrameSource = 99; - SCH_AppData.MinorFramesSinceTone = SCH_TOTAL_SLOTS; - - /* Execute the function being tested */ - //SCH_MinorFrameCallback(TimerId); - - /* Verify results */ - UtAssert_True(SCH_AppData.MinorFramesSinceTone == 0, "SCH_AppData.MinorFramesSinceTone == 0"); - UtAssert_True(SCH_AppData.MissedMajorFrameCount == 1, "SCH_AppData.MissedMajorFrameCount == 1"); - - UtAssert_True (Ut_CFE_EVS_GetEventQueueDepth() == 0, "Ut_CFE_EVS_GetEventQueueDepth() == 0"); - -} /* end SCH_MinorFrameCallback_Test_AlreadySynchronizedRollover */ - -void SCH_MinorFrameCallback_Test_AlreadySynchronizedStartTimer(void) -{ - uint32 TimerId = 1; - - SCH_AppData.MajorFrameSource = 99; - SCH_AppData.MinorFramesSinceTone = SCH_TIME_SYNC_SLOT - 1; - - /* Execute the function being tested */ - //SCH_MinorFrameCallback(TimerId); - - /* Verify results */ - UtAssert_True(SCH_AppData.MinorFramesSinceTone == SCH_TIME_SYNC_SLOT, "SCH_AppData.MinorFramesSinceTone == SCH_TIME_SYNC_SLOT"); - - UtAssert_True (Ut_CFE_EVS_GetEventQueueDepth() == 0, "Ut_CFE_EVS_GetEventQueueDepth() == 0"); - -} /* end SCH_MinorFrameCallback_Test_AlreadySynchronizedStartTimer */ - -void SCH_Custom_Test_AddTestCases(void) -{ - UtTest_Add(SCH_CustomEarlyInit_Test, SCH_Test_Setup, SCH_Test_TearDown, "SCH_CustomEarlyInit_Test"); - - UtTest_Add(SCH_CustomLateInit_Test_Nominal, SCH_Test_Setup, SCH_Test_TearDown, "SCH_CustomLateInit_Test_Nominal"); - UtTest_Add(SCH_CustomLateInit_Test_RegisterSynchCallbackError, SCH_Test_Setup, SCH_Test_TearDown, "SCH_CustomLateInit_Test_RegisterSynchCallbackError"); - UtTest_Add(SCH_CustomLateInit_Test_TimerSetError, SCH_Test_Setup, SCH_Test_TearDown, "SCH_CustomLateInit_Test_TimerSetError"); - - UtTest_Add(SCH_CustomGetCurrentSlotNumber_Test_LowCurrentSlot, SCH_Test_Setup, SCH_Test_TearDown, "SCH_CustomGetCurrentSlotNumber_Test_LowCurrentSlot"); - UtTest_Add(SCH_CustomGetCurrentSlotNumber_Test_HighCurrentSlot, SCH_Test_Setup, SCH_Test_TearDown, "SCH_CustomGetCurrentSlotNumber_Test_HighCurrentSlot"); - UtTest_Add(SCH_CustomGetCurrentSlotNumber_Test_NotSynchronized, SCH_Test_Setup, SCH_Test_TearDown, "SCH_CustomGetCurrentSlotNumber_Test_NotSynchronized"); - - UtTest_Add(SCH_CustomCleanup_Test, SCH_Test_Setup, SCH_Test_TearDown, "SCH_CustomCleanup_Test"); - - UtTest_Add(SCH_GetMETSlotNumber_Test_Rollover, SCH_Test_Setup, SCH_Test_TearDown, "SCH_GetMETSlotNumber_Test_Rollover"); - UtTest_Add(SCH_GetMETSlotNumber_Test_NoRollover, SCH_Test_Setup, SCH_Test_TearDown, "SCH_GetMETSlotNumber_Test_NoRollover"); - - UtTest_Add(SCH_MajorFrameCallback_Test_NoisyNotSynchronized, SCH_Test_Setup, SCH_Test_TearDown, "SCH_MajorFrameCallback_Test_NoisyNotSynchronized"); - UtTest_Add(SCH_MajorFrameCallback_Test_NoisySynchronized, SCH_Test_Setup, SCH_Test_TearDown, "SCH_MajorFrameCallback_Test_NoisySynchronized"); - UtTest_Add(SCH_MajorFrameCallback_Test_FrameOccurredWhenExpected, SCH_Test_Setup, SCH_Test_TearDown, "SCH_MajorFrameCallback_Test_FrameOccurredWhenExpected"); - UtTest_Add(SCH_MajorFrameCallback_Test_FlywheelMode, SCH_Test_Setup, SCH_Test_TearDown, "SCH_MajorFrameCallback_Test_FlywheelMode"); - - UtTest_Add(SCH_MinorFrameCallback_Test_SyncAttemptsLeft, SCH_Test_Setup, SCH_Test_TearDown, "SCH_MinorFrameCallback_Test_SyncAttemptsLeft"); - UtTest_Add(SCH_MinorFrameCallback_Test_SynchronizationAchievedNominal, SCH_Test_Setup, SCH_Test_TearDown, "SCH_MinorFrameCallback_Test_SynchronizationAchievedNominal"); - UtTest_Add(SCH_MinorFrameCallback_Test_AlreadySynchronizedNominal, SCH_Test_Setup, SCH_Test_TearDown, "SCH_MinorFrameCallback_Test_AlreadySynchronizedNominal"); - UtTest_Add(SCH_MinorFrameCallback_Test_AlreadySynchronizedRollover, SCH_Test_Setup, SCH_Test_TearDown, "SCH_MinorFrameCallback_Test_AlreadySynchronizedRollover"); - UtTest_Add(SCH_MinorFrameCallback_Test_AlreadySynchronizedStartTimer, SCH_Test_Setup, SCH_Test_TearDown, "SCH_MinorFrameCallback_Test_AlreadySynchronizedStartTimer"); - -} /* end SCH_Custom_Test_AddTestCases */ - -/************************/ -/* End of File Comment */ -/************************/ diff --git a/config/obc/sitl/target/apps/sch/unit_test/sch_custom_test.h b/config/obc/sitl/target/apps/sch/unit_test/sch_custom_test.h deleted file mode 100644 index f59634e83..000000000 --- a/config/obc/sitl/target/apps/sch/unit_test/sch_custom_test.h +++ /dev/null @@ -1,31 +0,0 @@ - /************************************************************************* - ** File: - ** $Id: sch_custom_test.h 1.2 2017/06/21 15:29:02EDT mdeschu Exp $ - ** - ** Purpose: - ** This file contains the function prototypes for the unit test cases for sch_custom.c - ** - ** References: - ** Flight Software Branch C Coding Standard Version 1.2 - ** CFS Development Standards Document - ** Notes: - ** - *************************************************************************/ - -/* - * Includes - */ - -#include "utassert.h" -#include "uttest.h" - -/* - * Function Prototypes - */ - -void SCH_Custom_Test_AddTestCases(void); - - -/************************/ -/* End of File Comment */ -/************************/ diff --git a/config/obc/sitl/target/apps/sch/unit_test/sch_test_utils.c b/config/obc/sitl/target/apps/sch/unit_test/sch_test_utils.c deleted file mode 100644 index dfa7dd3e8..000000000 --- a/config/obc/sitl/target/apps/sch/unit_test/sch_test_utils.c +++ /dev/null @@ -1,58 +0,0 @@ - /************************************************************************* - ** File: - ** $Id: sch_test_utils.c 1.2 2017/06/21 15:28:59EDT mdeschu Exp $ - ** - ** Purpose: - ** This file contains unit test utilities for the sch application. - ** - ** References: - ** Flight Software Branch C Coding Standard Version 1.2 - ** CFS Development Standards Document - ** Notes: - ** - *************************************************************************/ - -#include "sch_test_utils.h" -#include "sch_tbldefs.h" - -SCH_MessageEntry_t MessageTable[SCH_MAX_MESSAGES]; -SCH_ScheduleEntry_t ScheduleTable[SCH_TABLE_ENTRIES]; - -/* - * Function Definitions - */ - -void SCH_Test_Setup(void) -{ - /* initialize test environment to default state for every test */ - - CFE_PSP_MemSet(&SCH_AppData, 0, sizeof(SCH_AppData_t)); - - SCH_AppData.MessageTable = &MessageTable[0]; - SCH_AppData.ScheduleTable = &ScheduleTable[0]; - - CFE_PSP_MemSet(SCH_AppData.MessageTable, 0, sizeof(SCH_MessageEntry_t)*SCH_MAX_MESSAGES); - CFE_PSP_MemSet(SCH_AppData.ScheduleTable, 0, sizeof(SCH_ScheduleEntry_t)*SCH_TABLE_ENTRIES); - - Ut_CFE_EVS_Reset(); - Ut_CFE_FS_Reset(); - Ut_CFE_TIME_Reset(); - Ut_CFE_TBL_Reset(); - Ut_CFE_SB_Reset(); - Ut_CFE_ES_Reset(); - Ut_OSAPI_Reset(); - Ut_OSFILEAPI_Reset(); - Ut_OSTIMER_Reset(); -} /* end SCH_Test_Setup */ - -void SCH_Test_TearDown(void) -{ - /* cleanup test environment */ -} /* end SCH_Test_TearDown */ - -Ut_CFE_EVS_HookTable_t Ut_CFE_EVS_HookTable; -Ut_CFE_EVS_ReturnCodeTable_t Ut_CFE_EVS_ReturnCodeTable[UT_CFE_EVS_MAX_INDEX]; - -/************************/ -/* End of File Comment */ -/************************/ diff --git a/config/obc/sitl/target/apps/sch/unit_test/sch_test_utils.h b/config/obc/sitl/target/apps/sch/unit_test/sch_test_utils.h deleted file mode 100644 index 34dc6c3a7..000000000 --- a/config/obc/sitl/target/apps/sch/unit_test/sch_test_utils.h +++ /dev/null @@ -1,32 +0,0 @@ - /************************************************************************* - ** File: - ** $Id: sch_test_utils.h 1.2 2017/06/21 15:28:58EDT mdeschu Exp $ - ** - ** Purpose: - ** This file contains the function prototypes and global variables for the unit test utilities for the SCH application. - ** - ** References: - ** Flight Software Branch C Coding Standard Version 1.2 - ** CFS Development Standards Document - ** Notes: - ** - *************************************************************************/ - -/* - * Includes - */ - -#include "sch_app.h" - -/* - * Function Definitions - */ - -void SCH_Test_Setup(void); -void SCH_Test_TearDown(void); - - - -/************************/ -/* End of File Comment */ -/************************/ diff --git a/config/obc/sitl/target/apps/sch/unit_test/sch_testrunner.c b/config/obc/sitl/target/apps/sch/unit_test/sch_testrunner.c deleted file mode 100644 index 98973d29f..000000000 --- a/config/obc/sitl/target/apps/sch/unit_test/sch_testrunner.c +++ /dev/null @@ -1,36 +0,0 @@ - /************************************************************************* - ** File: - ** $Id: sch_testrunner.c 1.2 2017/06/21 15:29:03EDT mdeschu Exp $ - ** - ** Purpose: - ** This file contains the unit test runner for the SCH application. - ** - ** References: - ** Flight Software Branch C Coding Standard Version 1.2 - ** CFS Development Standards Document - ** Notes: - ** - *************************************************************************/ - -/* - * Includes - */ - -#include "uttest.h" -#include "sch_custom_test.h" - -/* - * Function Definitions - */ - -int main(void) -{ - SCH_Custom_Test_AddTestCases(); - - return(UtTest_Run()); -} /* end main */ - - -/************************/ -/* End of File Comment */ -/************************/ diff --git a/config/obc/sitl/target/apps/to/CMakeLists.txt b/config/obc/sitl/target/apps/to/CMakeLists.txt deleted file mode 100644 index dee6a31c0..000000000 --- a/config/obc/sitl/target/apps/to/CMakeLists.txt +++ /dev/null @@ -1,38 +0,0 @@ -set(APP_NAME to) - -buildliner_add_table( - ${APP_NAME} - NAME to_udp_cfg - SOURCES ${CMAKE_CURRENT_SOURCE_DIR}/tables/to_udp_cfg.c - INCLUDES ${CMAKE_CURRENT_SOURCE_DIR}/src/ -) - -buildliner_add_app_unit_test(to-custom-ut - UTASSERT - NO_HELGRIND - NO_MASSIF - - SOURCES - ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/to_app_custom_test.c - ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/to_app_custom_test.h - ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/to_custom_testrunner.c - ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/to_custom_test_utils.c - ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/to_custom_test_utils.h - ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/to_app_stubs.c - ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/to_app_stubs.h - ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/to_platform_stubs.c - ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/to_platform_stubs.h - ${CMAKE_CURRENT_SOURCE_DIR}/tables/to_backup_cfg.c - ${CMAKE_CURRENT_SOURCE_DIR}/to_custom.c - ${CMAKE_CURRENT_SOURCE_DIR}/to_custom_udp.h - - INCLUDES - ${CMAKE_CURRENT_SOURCE_DIR}/ - ${CMAKE_CURRENT_SOURCE_DIR}/unit_test/ - ${PROJECT_SOURCE_DIR}/apps/to/fsw/src - - WRAPPERS - socket - bind - sendto -) diff --git a/config/obc/sitl/target/apps/to/tables/to_udp_cfg.c b/config/obc/sitl/target/apps/to/tables/to_udp_cfg.c deleted file mode 100644 index f699d479c..000000000 --- a/config/obc/sitl/target/apps/to/tables/to_udp_cfg.c +++ /dev/null @@ -1,224 +0,0 @@ -/************************************************************************ - ** Includes - *************************************************************************/ -#include "cfe_tbl_filedef.h" -#include "to_tbldefs.h" -#include "msg_ids.h" - -/** - ** \brief The cFE TO config table definition. - ** - ** Content format: ObjName[64], TblName[38], Desc[32], TgtFileName[20], ObjSize - ** ObjName - variable name of config table, e.g., TO_ConfigDefTbl[] - ** TblName - app's table name, e.g., TO.CONFIG_TBL, where TO is the same app name - ** used in cfe_es_startup.scr, and TO_defConfigTbl is the same table - ** name passed in to CFE_TBL_Register() - ** Desc - description of table in string format - ** TgtFileName[20] - table file name, compiled as .tbl file extension - ** ObjSize - size of the entire table - ** - */ -static CFE_TBL_FileDef_t CFE_TBL_FileDef OS_USED = -{ - "TO_ConfigTbl", "TO.UDP_CFG", "TO ground dev udp table", - "to_udp_cfg.tbl", (sizeof(TO_ChannelTbl_t)) -}; - - -/************************************************************************ - ** Defines - *************************************************************************/ - -#define TO_PQUEUE_SINGLE_PASS_IDX 0 -#define TO_PQUEUE_HIGH_OPS_RSRVD_IDX 1 -#define TO_PQUEUE_HIGH_IDX 2 -#define TO_PQUEUE_MEDIUM_IDX 3 -#define TO_PQUEUE_LOW_IDX 4 - -/** - ** \brief Default TO config table data - */ -TO_ChannelTbl_t TO_ConfigTbl = -{ - /* Table ID */ - 1, - { - /* Message Flows */ - /* Ground Queues */ - {AMC_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {MAC_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {MPC_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {ULR_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {RGBLED_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {GPS_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {SENS_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {LD_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {NAV_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {RCIN_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {VM_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {BAT_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {PE_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {AK8963_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {AK8963_DIAG_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {MS5611_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {MS5611_DIAG_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {MPU6050_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {MPU6050_DIAG_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {TO_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {TO_DATA_TYPE_MID, 1, TO_PQUEUE_HIGH_IDX}, - {EA_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {VC_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {TO_DIAG_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {TO_DIAG_MSG_FLOW_MID, 1, TO_PQUEUE_HIGH_IDX}, - {GPS_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {MAVLINK_HK_TLM_MID, 1, TO_PQUEUE_HIGH_IDX}, - {CFE_ES_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CFE_EVS_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CFE_SB_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CFE_TBL_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CFE_TIME_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CFE_TIME_DIAG_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CFE_EVS_EVENT_MSG_MID, 32, TO_PQUEUE_MEDIUM_IDX}, - {CFE_SB_STATS_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CFE_ES_APP_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CFE_TBL_REG_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CFE_SB_ONESUB_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CFE_ES_SHELL_TLM_MID, 32, TO_PQUEUE_MEDIUM_IDX}, - {CFE_ES_MEMSTATS_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CF_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CF_TRANS_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CF_CONFIG_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CF_SPACE_TO_GND_PDU_MID, 32, TO_PQUEUE_MEDIUM_IDX}, - {CS_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {DS_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {DS_DIAG_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {FM_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {FM_FILE_INFO_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {FM_DIR_LIST_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {FM_OPEN_FILES_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {FM_FREE_SPACE_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {HK_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {HS_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {LC_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {MD_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {MM_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {SCH_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {SCH_DIAG_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {CI_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {QAE_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {FLOW_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {FLOW_DIAG_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {MPC_DIAG_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {LD_DIAG_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {PRM_HK_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - {VM_CONFIG_TLM_MID, 1, TO_PQUEUE_MEDIUM_IDX}, - -// {PX4_ACTUATOR_ARMED_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_ACTUATOR_CONTROLS_0_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_ACTUATOR_CONTROLS_1_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_ACTUATOR_CONTROLS_2_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_ACTUATOR_CONTROLS_3_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_ACTUATOR_DIRECT_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_ACTUATOR_OUTPUTS_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_ADC_REPORT_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_AIRSPEED_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_ATT_POS_MOCAP_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_BATTERY_STATUS_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_CAMERA_TRIGGER_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_COMMANDER_STATE_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_CONTROL_STATE_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_CPULOAD_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_DEBUG_KEY_VALUE_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_DIFFERENTIAL_PRESSURE_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_DISTANCE_SENSOR_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_FW_POS_CTRL_STATUS_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_FW_VIRTUAL_ATTITUDE_SETPOINT_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_FW_VIRTUAL_RATES_SETPOINT_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_EKF2_INNOVATIONS_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_EKF2_REPLAY_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_ESC_REPORT_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_ESC_STATUS_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_ESTIMATOR_STATUS_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_FENCE_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_FENCE_VERTEX_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_FILTERED_BOTTOM_FLOW_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_FOLLOW_TARGET_MID, 1, TO_PQUEUE_LOW_IDX}, - {PX4_GEOFENCE_RESULT_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_GPS_DUMP_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_GPS_INJECT_DATA_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_HIL_SENSOR_MID, 1, TO_PQUEUE_LOW_IDX}, - {PX4_HOME_POSITION_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_INPUT_RC_MID, 1, TO_PQUEUE_LOW_IDX}, - {PX4_LED_CONTROL_MID, 1, TO_PQUEUE_LOW_IDX}, - {PX4_LOG_MESSAGE_MID, 1, TO_PQUEUE_LOW_IDX}, - {PX4_MANUAL_CONTROL_SETPOINT_MID, 1, TO_PQUEUE_LOW_IDX}, - {PX4_MAVLINK_LOG_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_MC_ATT_CTRL_STATUS_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_MC_VIRTUAL_ATTITUDE_SETPOINT_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_MC_VIRTUAL_RATES_SETPOINT_MID, 1, TO_PQUEUE_LOW_IDX}, - {PX4_MISSION_MID, 1, TO_PQUEUE_LOW_IDX}, - {PX4_MISSION_RESULT_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_MULTIROTOR_MOTOR_LIMITS_MID, 1, TO_PQUEUE_LOW_IDX}, - {PX4_OFFBOARD_CONTROL_MODE_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_OPTICAL_FLOW_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_OUTPUT_PWM_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_PARAMETER_UPDATE_MID, 1, TO_PQUEUE_LOW_IDX}, - {PX4_POSITION_SETPOINT_TRIPLET_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_PWM_INPUT_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_QSHELL_REQ_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_RC_CHANNELS_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_RC_PARAMETER_MAP_MID, 1, TO_PQUEUE_LOW_IDX}, - {PX4_SAFETY_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_SATELLITE_INFO_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_SENSOR_ACCEL_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_SENSOR_BARO_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_SENSOR_COMBINED_MID, 1, TO_PQUEUE_LOW_IDX}, - {PX4_SENSOR_CORRECTION_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_SENSOR_GYRO_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_SENSOR_MAG_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_SERVORAIL_STATUS_MID, 1, TO_PQUEUE_LOW_IDX}, - {PX4_SUBSYSTEM_INFO_MID, 1, TO_PQUEUE_LOW_IDX}, - {PX4_SYSTEM_POWER_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_TECS_STATUS_MID, 1, TO_PQUEUE_LOW_IDX}, - {PX4_TELEMETRY_STATUS_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_TEST_MOTOR_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_TIME_OFFSET_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_TRANSPONDER_REPORT_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_UAVCAN_PARAMETER_REQUEST_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_UAVCAN_PARAMETER_VALUE_MID, 1, TO_PQUEUE_LOW_IDX}, - {PX4_VEHICLE_ATTITUDE_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_VEHICLE_ATTITUDE_SETPOINT_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_VEHICLE_COMMAND_ACK_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_VEHICLE_COMMAND_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_VEHICLE_CONTROL_MODE_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_VEHICLE_FORCE_SETPOINT_MID, 1, TO_PQUEUE_LOW_IDX}, - {PX4_VEHICLE_GLOBAL_POSITION_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_VEHICLE_GLOBAL_VELOCITY_SETPOINT_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_VEHICLE_GPS_POSITION_MID, 1, TO_PQUEUE_LOW_IDX}, - {PX4_VEHICLE_LAND_DETECTED_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_VEHICLE_LOCAL_POSITION_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_VEHICLE_LOCAL_POSITION_SETPOINT_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_VEHICLE_RATES_SETPOINT_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_VEHICLE_STATUS_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_VISION_POSITION_ESTIMATE_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_VTOL_VEHICLE_STATUS_MID, 1, TO_PQUEUE_LOW_IDX}, -// {PX4_WIND_ESTIMATE_MID, 1, TO_PQUEUE_LOW_IDX} - },{ - /* Priority Queues */ - /* TO_PQUEUE_SINGLE_PASS_IDX */ - {TO_PQUEUE_ENA, 100, TO_PRIORITY_QUEUE_TYPE_SINGLE}, - /* TO_PQUEUE_HIGH_OPS_RSRVD_IDX */ - {TO_PQUEUE_ENA, 100, TO_PRIORITY_QUEUE_TYPE_FIFO}, - /* TO_PQUEUE_HIGH_IDX */ - {TO_PQUEUE_ENA, 100, TO_PRIORITY_QUEUE_TYPE_FIFO}, - /* TO_PQUEUE_MEDIUM_IDX */ - {TO_PQUEUE_ENA, 100, TO_PRIORITY_QUEUE_TYPE_FIFO}, - /* TO_PQUEUE_LOW_IDX */ - {TO_PQUEUE_ENA, 100, TO_PRIORITY_QUEUE_TYPE_FIFO} - } -}; - - -/************************/ -/* End of File Comment */ -/************************/ diff --git a/config/obc/sitl/target/apps/to/to_custom.c b/config/obc/sitl/target/apps/to/to_custom.c deleted file mode 100644 index 17b682c26..000000000 --- a/config/obc/sitl/target/apps/to/to_custom.c +++ /dev/null @@ -1,526 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -/************************************************************************ -** Pragmas -*************************************************************************/ - -/************************************************************************ -** Includes -*************************************************************************/ - -#include "to_custom_udp.h" -#include "to_platform_cfg.h" -#include -#include -#include "to_events.h" -#include -#include -#include - -/************************************************************************ -** Local Defines -*************************************************************************/ -#define TO_CUSTOM_CHANNEL_GET_TIMEOUT (500) /* msec */ - - -/************************************************************************ -** Local Function Definitions -*************************************************************************/ - - - -TO_AppCustomData_t TO_AppCustomData; - -TO_EnableChannelCmd_t TO_EnableChannelCmd_S; -TO_DisableChannelCmd_t TO_DisableChannelCmd_S; - -extern TO_ChannelTbl_t TO_BackupConfigTbl; - - -uint8 TO_OutputChannel_Status(uint32 Index) -{ - /* Use Index, instead of index, because vxworks-6.9/target/h/string.h:100 - * has a global named "index". */ - return TO_AppCustomData.Channel[Index].Mode; -} - - - -/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ -/* */ -/* Custom Initialize All. Nothing to do here. */ -/* */ -/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ -int32 TO_Custom_Init(void) -{ - int32 iStatus = 0; - uint32 i = 0; - - /* - * UDP development interface - */ - TO_AppCustomData.Channel[0].Mode = TO_CHANNEL_ENABLED; - strncpy(TO_AppCustomData.Channel[0].IP, TO_UDP_CHANNEL_ADDRESS, INET_ADDRSTRLEN); - TO_AppCustomData.Channel[0].DstPort = TO_UDP_CHANNEL_PORT; - TO_AppCustomData.Channel[0].Priority = TO_UDP_CHANNEL_TASK_PRIORITY; - TO_AppCustomData.Channel[0].ListenerTask = TO_OutputChannel_UDPChannelTask; - TO_AppCustomData.Channel[0].Socket = 0; - TO_AppCustomData.Channel[0].ChildTaskID = 0; - - /* Ground dev interface is optional */ - iStatus = TO_Channel_OpenChannel( - 0, - TO_UDP_CHANNEL_NAME, - TO_UDP_CONFIG_TABLENAME, - TO_UDP_CONFIG_TABLE_FILENAME, - &TO_BackupConfigTbl, - TO_UDP_DUMP_TABLENAME, - 1, - TO_UDP_CF_THROTTLE_SEM_NAME); - - for (i=0; i < TO_MAX_CHANNELS; i++) - { - if(TO_OutputChannel_Status(i) == TO_CHANNEL_ENABLED) - { - if(TO_OutputChannel_Enable(i, TO_AppCustomData.Channel[i].IP, TO_AppCustomData.Channel[i].DstPort)) - { - TO_AppCustomData.Channel[i].Mode = TO_CHANNEL_DISABLED; - } - else - { - CFE_EVS_SendEvent(TO_TLMOUTENA_INF_EID, CFE_EVS_INFORMATION, - "UDP telemetry output enabled channel %u to %s:%u", - (unsigned int)i, TO_AppCustomData.Channel[i].IP, - (unsigned int)TO_AppCustomData.Channel[i].DstPort); - } - } - } - - return iStatus; -} - - - -/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ -/* */ -/* Custom Send. Send the message out the socket. */ -/* */ -/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ -int32 TO_OutputChannel_Send(uint32 ChannelID, const char* Buffer, uint32 Size) -{ - struct sockaddr_in s_addr; - int status = 0; - int32 returnCode = 0; - - bzero((char *) &s_addr, sizeof(s_addr)); - s_addr.sin_family = AF_INET; - - if((Size > 0) && (ChannelID < TO_MAX_CHANNELS)) - { - TO_TlmChannels_t *channel = &TO_AppCustomData.Channel[ChannelID]; - - if(channel->Mode == TO_CHANNEL_ENABLED) - { - CFE_ES_PerfLogEntry(TO_SOCKET_SEND_PERF_ID); - /* Send message via UDP socket */ - s_addr.sin_addr.s_addr = inet_addr(channel->IP); - s_addr.sin_port = htons(channel->DstPort); - status = sendto(channel->Socket, (char *)Buffer, Size, 0, - (struct sockaddr *) &s_addr, - sizeof(s_addr)); - if (status < 0) - { - CFE_EVS_SendEvent(TO_TLMOUTSTOP_ERR_EID,CFE_EVS_ERROR, - "L%d TO sendto errno %d.", __LINE__, errno); - channel->Mode = TO_CHANNEL_DISABLED; - returnCode = -1; - } - CFE_ES_PerfLogExit(TO_SOCKET_SEND_PERF_ID); - } - } - - return returnCode; -} - - - -/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ -/* */ -/* Custom Cleanup All. Disable all the enable channels so we */ -/* don't try sending messages when the sealed framework is torn */ -/* down. */ -/* */ -/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ -void TO_OutputChannel_CustomCleanupAll(void) -{ - uint32 i = 0; - - for (i=0; i < TO_MAX_CHANNELS; i++) - { - if(TO_OutputChannel_Status(i) == TO_CHANNEL_ENABLED) - { - TO_OutputChannel_Disable(i); - } - } -} - - - -/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ -/* */ -/* Custom Buildup All. Enable all the 'enabled' channels. If it */ -/* fails, disable it. */ -/* */ -/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ -int32 TO_OutputChannel_CustomBuildupAll(uint32 index) -{ - return 0; -} - - - -/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ -/* */ -/* Custom Teardown All. Nothing to do here. */ -/* */ -/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ -int32 TO_OutputChannel_CustomTeardown(uint32 index) -{ - return 0; -} - - - -/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ -/* */ -/* Process New Custom Commands. Raise an error event if the */ -/* command is unknown. */ -/* */ -/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ -void TO_OutputChannel_ProcessNewCustomCmds(CFE_SB_Msg_t* MsgPtr) -{ - uint32 uiCmdCode=0; - - if (MsgPtr != NULL) - { - uint16 inSize = CFE_SB_GetTotalMsgLength(MsgPtr); - uiCmdCode = CFE_SB_GetCmdCode(MsgPtr); - - OS_MutSemTake(TO_AppData.MutexID); - switch (uiCmdCode) - { - case TO_ENABLE_CHANNEL_CC: - { - TO_EnableChannelCmd_t *cmd = (TO_EnableChannelCmd_t*) MsgPtr; - /* Validate arguments. */ - if(inSize != sizeof(TO_EnableChannelCmd_t)) - { - TO_AppData.HkTlm.usCmdErrCnt++; - (void) CFE_EVS_SendEvent(TO_MSG_LEN_ERR_EID, CFE_EVS_ERROR, - "Invalid message length. Received %u. Expected %u.", - (unsigned int)inSize, sizeof(TO_EnableChannelCmd_t)); - break; - } - - if(TO_OutputChannel_Enable(cmd->ChannelID, cmd->DestinationAddress, cmd->DestinationPort)) - { - TO_AppData.HkTlm.usCmdErrCnt++; - break; - } - - TO_AppData.HkTlm.usCmdCnt++; - (void) CFE_EVS_SendEvent(TO_TLMOUTENA_INF_EID, CFE_EVS_INFORMATION, - "Enabled channel %u to %s:%u.", - cmd->ChannelID, - cmd->DestinationAddress, - cmd->DestinationPort); - break; - } - - case TO_DISABLE_CHANNEL_CC: - { - TO_DisableChannelCmd_t *cmd = (TO_DisableChannelCmd_t*) MsgPtr; - /* Validate arguments. */ - if(inSize != sizeof(TO_DisableChannelCmd_t)) - { - TO_AppData.HkTlm.usCmdErrCnt++; - (void) CFE_EVS_SendEvent(TO_MSG_LEN_ERR_EID, CFE_EVS_ERROR, - "Invalid message length. Received %u. Expected %u.", - (unsigned int)inSize, sizeof(TO_DisableChannelCmd_t)); - break; - } - - if(TO_OutputChannel_Disable(cmd->ChannelID)) - { - TO_AppData.HkTlm.usCmdErrCnt++; - break; - } - - TO_AppData.HkTlm.usCmdCnt++; - break; - } - - default: - TO_AppData.HkTlm.usCmdErrCnt++; - (void) CFE_EVS_SendEvent(TO_CC_ERR_EID, CFE_EVS_ERROR, - "Recvd invalid cmdId (%u)", (unsigned int)uiCmdCode); - break; - } - OS_MutSemGive(TO_AppData.MutexID); - } -} - - - -/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ -/* */ -/* Enable Channel. This will bind the socket for transmission. */ -/* */ -/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ -int32 TO_OutputChannel_Enable(uint32 ChannelID, const char *DestinationAddress, uint16 DestinationPort) -{ - int32 returnCode = 0; - uint32 i = 0; - struct sockaddr_in servaddr; - int status; - int reuseaddr=1; - - if(DestinationAddress == 0) - { - CFE_EVS_SendEvent(TO_TLMOUTENA_ERR_EID, CFE_EVS_ERROR, - "Destination address for channel %u is null.", (unsigned int)i); - returnCode = -1; - goto end_of_function; - } - - if(ChannelID >= TO_MAX_CHANNELS) - { - CFE_EVS_SendEvent(TO_TLMOUTENA_ERR_EID, CFE_EVS_ERROR, - "ChannelID (%u) invalid.", (unsigned int)ChannelID); - returnCode = -1; - goto end_of_function; - } - - if((TO_AppCustomData.Channel[ChannelID].Socket = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP)) < 0) - { - TO_AppCustomData.Channel[ChannelID].Mode = TO_CHANNEL_DISABLED; - CFE_EVS_SendEvent(TO_TLMOUTSOCKET_ERR_EID, CFE_EVS_ERROR, - "TLM socket errno: %i on channel %u", errno, (unsigned int)ChannelID); - returnCode = -1; - goto end_of_function; - } - - /* Set the Reuse Address flag. If we don't set this flag, the socket will - * lock the port on termination and the kernel won't unlock it until it - * times out after a minute or so. - */ - setsockopt(TO_AppCustomData.Channel[i].Socket, SOL_SOCKET, SO_REUSEADDR, &reuseaddr, sizeof(reuseaddr)); - strncpy(TO_AppCustomData.Channel[ChannelID].IP, DestinationAddress, sizeof(TO_AppCustomData.Channel[ChannelID].IP)); - TO_AppCustomData.Channel[ChannelID].DstPort = DestinationPort; - - /* Set the input arguments to the socket bind. - */ - bzero((void*)&servaddr,sizeof(servaddr)); - servaddr.sin_family = AF_INET; - servaddr.sin_addr.s_addr = htonl(INADDR_ANY); - servaddr.sin_port=0; - status = bind(TO_AppCustomData.Channel[ChannelID].Socket, - (struct sockaddr *)&servaddr,sizeof(servaddr)); - if(status < 0) - { - CFE_EVS_SendEvent(TO_TLMOUTSOCKET_ERR_EID, CFE_EVS_ERROR, - "TLM bind errno: %i on channel %u", errno, (unsigned int)i); - TO_AppCustomData.Channel[ChannelID].Mode = TO_CHANNEL_DISABLED; - returnCode = -1; - goto end_of_function; - } - - /* Enable the channel for transmission. */ - TO_AppCustomData.Channel[ChannelID].Mode = TO_CHANNEL_ENABLED; - - /* Create the child listener task. */ - char TaskName[OS_MAX_API_NAME]; - snprintf(TaskName, OS_MAX_API_NAME, "TO_OUTCH_%u", (unsigned int)ChannelID); - returnCode = CFE_ES_CreateChildTask( - &TO_AppCustomData.Channel[ChannelID].ChildTaskID, - (const char *)TaskName, - TO_AppCustomData.Channel[ChannelID].ListenerTask, - 0, - TO_CUSTOM_TASK_STACK_SIZE, - TO_AppCustomData.Channel[ChannelID].Priority, - TO_CUSTOM_CHILD_TASK_FLAGS); - -end_of_function: - return returnCode; -} - - - -/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ -/* */ -/* Disable channel. Close the socket. */ -/* */ -/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ -int32 TO_OutputChannel_Disable(uint32 ChannelID) -{ - int32 returnCode = 0; - uint32 i = 0; - - if(TO_AppCustomData.Channel[ChannelID].Mode != TO_CHANNEL_ENABLED) - { - CFE_EVS_SendEvent(TO_TLMOUTDIS_ERR_EID, CFE_EVS_ERROR, - "UDP telemetry for channel %u is not enabled.", (unsigned int)i); - returnCode = -1; - goto end_of_function; - } - - /* Disable the channel before we close the socket so if the handler - * task is in the loop it will know the reason why the send - * function failed is because the channel is disabled. - */ - TO_AppCustomData.Channel[ChannelID].Mode = TO_CHANNEL_DISABLED; - close(TO_AppCustomData.Channel[ChannelID].Socket); - TO_AppCustomData.Channel[ChannelID].Socket = 0; - - CFE_EVS_SendEvent(TO_TLMOUTDIS_INF_EID, CFE_EVS_INFORMATION, - "Disabled channel %u.", - (unsigned int)ChannelID); - -end_of_function: - return returnCode; -} - - - -/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ -/* */ -/* The UDP Development Channel Task Entry Point */ -/* */ -/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ -void TO_OutputChannel_UDPChannelTask(void) -{ - CFE_ES_RegisterChildTask(); - - TO_OutputChannel_ChannelHandler(0); - - CFE_ES_ExitChildTask(); -} - - - -/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ -/* */ -/* Channel Handler */ -/* */ -/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ -void TO_OutputChannel_ChannelHandler(uint32 ChannelIdx) -{ - int32 iStatus = CFE_SUCCESS; - uint32 msgSize = 0; - char *buffer; - - while(TO_OutputChannel_Status(ChannelIdx) == TO_CHANNEL_ENABLED) - { - if(TO_Channel_State(ChannelIdx) == TO_CHANNEL_OPENED) - { - TO_OutputQueue_t *chQueue = &TO_AppData.ChannelData[ChannelIdx].OutputQueue; - - iStatus = OS_QueueGet( - chQueue->OSALQueueID, - &buffer, sizeof(buffer), &msgSize, TO_CUSTOM_CHANNEL_GET_TIMEOUT); - - if(iStatus == OS_SUCCESS) - { - struct sockaddr_in s_addr; - uint16 actualMessageSize = CFE_SB_GetTotalMsgLength((CFE_SB_MsgPtr_t)buffer); - - bzero((char *) &s_addr, sizeof(s_addr)); - s_addr.sin_family = AF_INET; - - int32 sendResult = TO_OutputChannel_Send(ChannelIdx, (const char*)buffer, actualMessageSize); - - if (sendResult != 0) - { - TO_OutputChannel_Disable(ChannelIdx); - } - - iStatus = CFE_ES_PutPoolBuf(TO_AppData.ChannelData[ChannelIdx].MemPoolHandle, (uint32 *)buffer); - if(iStatus < 0) - { - (void) CFE_EVS_SendEvent(TO_PUT_POOL_ERR_EID, CFE_EVS_ERROR, - "PutPoolBuf: error=0x%08lx", - (unsigned long)iStatus); - } - else - { - OS_MutSemTake(TO_AppData.MutexID); - TO_AppData.ChannelData[ChannelIdx].MemInUse -= iStatus; - OS_MutSemGive(TO_AppData.MutexID); - - TO_Channel_LockByIndex(ChannelIdx); - chQueue->CurrentlyQueuedCnt--; - chQueue->SentCount++; - TO_Channel_UnlockByIndex(ChannelIdx); - } - - } - else if(iStatus == OS_QUEUE_TIMEOUT) - { - /* Do nothing. Just loop back around and check the guard. */ - } - else - { - CFE_EVS_SendEvent(TO_OSQUEUE_GET_ERROR_EID, CFE_EVS_ERROR, - "Listener failed to pop message from queue. (%i).", (int)iStatus); - OS_MutSemTake(TO_AppData.MutexID); - TO_AppData.ChannelData[ChannelIdx].State = TO_CHANNEL_CLOSED; - OS_MutSemGive(TO_AppData.MutexID); - } - } - } -} - - - -int32 TO_Custom_InitEvent(int32 *ind) -{ - return 0; -} - - - -void TO_PrintCustomVersion(void) -{ - -} diff --git a/config/obc/sitl/target/apps/to/to_custom_udp.h b/config/obc/sitl/target/apps/to/to_custom_udp.h deleted file mode 100644 index 224ecae5c..000000000 --- a/config/obc/sitl/target/apps/to/to_custom_udp.h +++ /dev/null @@ -1,141 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#ifndef TO_CUSTOM_UDP_H -#define TO_CUSTOM_UDP_H - -/************************************************************************ -** Includes -*************************************************************************/ -#include "to_app.h" -#include "to_custom.h" -#include - -/************************************************************************ -** Local Defines -*************************************************************************/ -#define TO_CUSTOM_RETURN_CODE_NULL_POINTER (-1) -#define TO_CUSTOM_RETURN_CODE_MESSAGE_TOO_BIG (-2) - -/* TODO: Add Doxygen markup. */ -#define TO_ENABLE_CHANNEL_CC (10) -#define TO_DISABLE_CHANNEL_CC (11) - -/************************************************************************ -** Local Structure Declarations -*************************************************************************/ -typedef struct -{ - uint8 ucCmdHeader[CFE_SB_CMD_HDR_SIZE]; - uint8 ChannelID; - char DestinationAddress[INET_ADDRSTRLEN]; - uint16 DestinationPort; -} TO_EnableChannelCmd_t; - -typedef struct -{ - uint8 ucCmdHeader[CFE_SB_CMD_HDR_SIZE]; - uint8 ChannelID; -} TO_DisableChannelCmd_t; - -typedef enum { - /* TODO: Add Doxygen markup. */ - TO_TLMOUTSOCKET_ERR_EID = TO_EVT_CNT, - TO_TLMOUTENA_INF_EID, - TO_TLMOUTENA_ERR_EID, - TO_TLMOUTDIS_INF_EID, - TO_TLMOUTDIS_ERR_EID, - TO_TLMOUTSEND_ERR_EID, - TO_TLMOUTSTOP_ERR_EID, - TO_CUSTOM_EVT_CNT -} TO_CustomEventIds_t; - -typedef enum -{ - TO_CHANNEL_UNUSED = 0, - TO_CHANNEL_DISABLED = 1, - TO_CHANNEL_ENABLED = 2 -} TO_TLM_ChannelMode_t; - -typedef struct -{ - TO_TLM_ChannelMode_t Mode; - char IP[INET_ADDRSTRLEN]; - uint16 DstPort; - uint8 Priority; - CFE_ES_ChildTaskMainFuncPtr_t ListenerTask; - int Socket; - uint32 ChildTaskID; - uint32 TaskFlags; -} TO_TlmChannels_t; - -typedef struct -{ - TO_TlmChannels_t Channel[TO_MAX_CHANNELS]; -} TO_AppCustomData_t; - -/************************************************************************ -** External Global Variables -*************************************************************************/ - -extern TO_AppData_t TO_AppData; - -/************************************************************************ -** Local Function Definitions -*************************************************************************/ - -/** - * The routine to send a buffer out the channel. This routine - * abstracts the formatting and output of different channels. - */ -int32 TO_OutputChannel_Send(uint32 ChannelID, const char* Buffer, uint32 Size); - -int32 TO_OutputChannel_Enable(uint32 ChannelID, const char *DestinationAddress, uint16 DestinationPort); -int32 TO_OutputChannel_Disable(uint32 ChannelID); - -/** - * The UDP Development Channel Task Entry Point - */ -void TO_OutputChannel_UDPChannelTask(void); - -/** - * The child task routine for a pulling from the output queue and sending - * out the channel. - */ -void TO_OutputChannel_ChannelHandler(uint32 ChannelIndex); - -int32 TO_OutputChannel_CustomBuildupAll(uint32 index); -int32 TO_OutputChannel_CustomTeardownAll(uint32 index); - - -#endif diff --git a/config/obc/sitl/target/apps/to/unit_test/to_app_custom_test.c b/config/obc/sitl/target/apps/to/unit_test/to_app_custom_test.c deleted file mode 100644 index beec9f79b..000000000 --- a/config/obc/sitl/target/apps/to/unit_test/to_app_custom_test.c +++ /dev/null @@ -1,985 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#include "to_app_custom_test.h" -#include "to_custom_test_utils.h" -#include "to_platform_stubs.h" - -#include "uttest.h" -#include "ut_osapi_stubs.h" -#include "ut_cfe_sb_stubs.h" -#include "ut_cfe_sb_hooks.h" -#include "ut_cfe_es_stubs.h" -#include "ut_cfe_es_hooks.h" -#include "ut_cfe_evs_stubs.h" -#include "ut_cfe_evs_hooks.h" -#include "ut_cfe_time_stubs.h" -#include "ut_cfe_psp_memutils_stubs.h" -#include "ut_cfe_tbl_stubs.h" -#include "ut_cfe_fs_stubs.h" -#include "ut_cfe_time_stubs.h" -#include "to_custom.h" - - -/************************************************************************** - * Tests for TO_Custom_Init() - **************************************************************************/ -/** - * Test TO_Custom_Init() fail TO_Channel_OpenChannel() - */ -void TO_Custom_Init_OpenChannelFail(void) -{ - int32 result = 0; - int32 expected = 1; - - TO_App_Return.TO_Channel_OpenChannel_Return = 1; - - /* Execute the function being tested */ - result = TO_Custom_Init(); - - /* Verify results */ - UtAssert_True (result == expected, - "TO_Custom_Init() did not return an expected value"); -} - - -/** - * Test TO_Custom_Init() fail TO_OutputChannel_Enable() - */ -void TO_Custom_Init_EnableChannelFail(void) -{ - int32 result = -1; - int32 expected = 0; - uint8 ChannelID = 0; - - /* Set channel 0 to enabled */ - TO_AppCustomData.Channel[ChannelID].Mode = TO_CHANNEL_ENABLED; - - /* Set socket call in TO_OutputChannel_Enable to fail */ - TO_Platform_Stubs_Returns.TO_Wrap_Socket_Return = -1; - - /* Execute the function being tested */ - result = TO_Custom_Init(); - - /* Verify results */ - UtAssert_True (result == expected, - "TO_Custom_Init() did not return an expected value"); - UtAssert_True(TO_AppCustomData.Channel[ChannelID].Mode == TO_CHANNEL_DISABLED, - "TO_Custom_Init() did not set correct mode"); -} - - -/** - * Test TO_Custom_Init() nothing enabled - */ -void TO_Custom_Init_NothingEnabled(void) -{ - int32 result = -1; - int32 expected = 0; - - /* Execute the function being tested */ - result = TO_Custom_Init(); - - /* Verify results */ - UtAssert_True (result == expected, - "TO_Custom_Init() did not return an expected value"); -} - - -/** - * Test TO_Custom_Init() nominal - */ -void TO_Custom_Init_Nominal(void) -{ - int32 result = -1; - int32 expected = 0; - uint8 ChannelID = 0; - uint16 testPort = TO_UDP_CHANNEL_PORT; - char *testIP = TO_UDP_CHANNEL_ADDRESS; - - char returnString[128]; - snprintf(returnString, 128, "UDP telemetry output enabled channel %u to %s:%u", - ChannelID, testIP, testPort); - - /* Execute the function being tested */ - result = TO_Custom_Init(); - - /* Verify results */ - UtAssert_True (result == expected, - "TO_Custom_Init() did not return an expected value"); - UtAssert_True(TO_AppCustomData.Channel[ChannelID].Mode == TO_CHANNEL_ENABLED, - "TO_Custom_Init() did not set correct mode"); - //UtAssert_EventSent(TO_TLMOUTENA_INF_EID, CFE_EVS_INFORMATION, returnString, - // "TO_Custom_Init() failed to raise an event"); -} - - -/************************************************************************** - * Tests for TO_OutputChannel_CustomBuildupAll() - **************************************************************************/ -/** - * Test TO_OutputChannel_CustomBuildupAll() nominal - * NOTE: Function is not currently implemented. - */ -void Test_TO_OutputChannel_CustomBuildupAll_Nominal(void) -{ - int32 result = -1; - int32 expected = 0; - uint32 index = 0; - - /* Execute the function being tested */ - result = TO_OutputChannel_CustomBuildupAll(index); - - /* Verify results */ - UtAssert_True (result == expected, - "TO_OutputChannel_CustomBuildupAll() failed nominal"); -} - - -/************************************************************************** - * Tests for TO_OutputChannel_Enable() - **************************************************************************/ -/** - * Test TO_OutputChannel_Enable() null destination address - */ -void Test_TO_OutputChannel_Enable_NullDestinationAddress(void) -{ - int32 result = 0; - int32 expected = -1; - uint8 ChannelID = 0; - /* Null destination address */ - char *DestinationAddress = 0; - uint16 DestinationPort = 0; - - char returnString[128]; - snprintf(returnString, 128, "Destination address for channel %u is null.", 0); - - - /* Execute the function being tested */ - result = TO_OutputChannel_Enable(ChannelID, DestinationAddress, DestinationPort); - - /* Verify results */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_True (result == expected, - "TO_OutputChannel_Enable() did not return the correct value"); - UtAssert_EventSent(TO_TLMOUTENA_ERR_EID, CFE_EVS_ERROR, returnString, - "TO_OutputChannel_Enable() failed to raise an event"); -} - - -/** - * Test TO_OutputChannel_Enable() invalid channel id - */ -void Test_TO_OutputChannel_Enable_InvalidID(void) -{ - int32 result = 0; - int32 expected = -1; - /* Set invalid channel ID */ - uint8 ChannelID = (TO_MAX_CHANNELS); - /* Set test destination address */ - char *DestinationAddress = "test"; - uint16 DestinationPort = 0; - - char returnString[128]; - snprintf(returnString, 128, "ChannelID (%u) invalid.", (TO_MAX_CHANNELS)); - - - /* Execute the function being tested */ - result = TO_OutputChannel_Enable(ChannelID, DestinationAddress, DestinationPort); - - /* Verify results */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_True (result == expected, - "TO_OutputChannel_Enable() did not return the correct value"); - UtAssert_EventSent(TO_TLMOUTENA_ERR_EID, CFE_EVS_ERROR, returnString, - "TO_OutputChannel_Enable() failed to raise an event"); -} - - -/** - * Test TO_OutputChannel_Enable() fail socket creation - */ -void Test_TO_OutputChannel_Enable_SocketFail(void) -{ - int32 result = 0; - int32 expected = -1; - int32 expectedErrno = 5; - uint8 ChannelID = 0; - /* Set test destination address */ - char *DestinationAddress = "test"; - uint16 DestinationPort = 0; - - char returnString[128]; - snprintf(returnString, 128, "TLM socket errno: %i on channel %u", expectedErrno, ChannelID); - - /* Set socket call to fail */ - TO_Platform_Stubs_Returns.TO_Wrap_Socket_Return = -1; - - /* Set errno for socket call */ - TO_Platform_Stubs_Returns.TO_Wrap_Socket_Errno = 1; - TO_Platform_Stubs_Returns.TO_Wrap_Socket_Errno_Value = expectedErrno; - - /* Execute the function being tested */ - result = TO_OutputChannel_Enable(ChannelID, DestinationAddress, DestinationPort); - - /* Verify results */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_True (result == expected, - "TO_OutputChannel_Enable() did not return the correct value"); - UtAssert_True(TO_AppCustomData.Channel[ChannelID].Socket == -1, - "TO_OutputChannel_Enable() failed to return an error"); - UtAssert_True(TO_AppCustomData.Channel[ChannelID].Mode == TO_CHANNEL_DISABLED, - "TO_OutputChannel_Enable() did not set correct mode"); - UtAssert_EventSent(TO_TLMOUTSOCKET_ERR_EID, CFE_EVS_ERROR, returnString, - "TO_OutputChannel_Enable() failed to raise an event"); -} - - -/** - * Test TO_OutputChannel_Enable() fail bind - */ -void Test_TO_OutputChannel_Enable_BindFail(void) -{ - int32 result = 0; - int32 expected = -1; - int32 expectedErrno = 5; - uint8 ChannelID = 0; - /* Set test destination address */ - char *DestinationAddress = "test"; - uint16 DestinationPort = 0; - - char returnString[128]; - snprintf(returnString, 128, "TLM bind errno: %i on channel %u", expectedErrno, ChannelID); - - /* Set socket call to pass */ - TO_Platform_Stubs_Returns.TO_Wrap_Socket_Return = 1; - - /* Set bind call to fail */ - TO_Platform_Stubs_Returns.TO_Wrap_Bind_Return = -1; - - /* Set errno for bind call */ - TO_Platform_Stubs_Returns.TO_Wrap_Bind_Errno = 1; - TO_Platform_Stubs_Returns.TO_Wrap_Bind_Errno_Value = expectedErrno; - - /* Execute the function being tested */ - result = TO_OutputChannel_Enable(ChannelID, DestinationAddress, DestinationPort); - - /* Verify results */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_True (result == expected, - "TO_OutputChannel_Enable() did not return the correct value"); - UtAssert_True(TO_AppCustomData.Channel[ChannelID].Mode == TO_CHANNEL_DISABLED, - "TO_OutputChannel_Enable() did not set correct mode"); - UtAssert_EventSent(TO_TLMOUTSOCKET_ERR_EID, CFE_EVS_ERROR, returnString, - "TO_OutputChannel_Enable() failed to raise an event"); -} - - -/** - * Test TO_OutputChannel_Enable() fail create child task - */ -void Test_TO_OutputChannel_Enable_CreateChildTaskFail(void) -{ - int32 result = 0; - int32 expected = -1; - uint8 ChannelID = 0; - /* Set test destination address */ - char *DestinationAddress = "test"; - uint16 DestinationPort = 0; - - /* Set create child task to fail */ - Ut_CFE_ES_SetReturnCode(UT_CFE_ES_CREATECHILDTASK_INDEX, -1, 1); - - /* Set socket call to pass */ - TO_Platform_Stubs_Returns.TO_Wrap_Socket_Return = 1; - - /* Execute the function being tested */ - result = TO_OutputChannel_Enable(ChannelID, DestinationAddress, DestinationPort); - - /* Verify results */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==0,"Event Count = 0"); - UtAssert_True (result == expected, - "TO_OutputChannel_Enable() did not return the correct value"); - UtAssert_True(TO_AppCustomData.Channel[ChannelID].Mode == TO_CHANNEL_ENABLED, - "TO_OutputChannel_Enable() did not set correct mode"); -} - - -/** - * Test TO_OutputChannel_Enable() nominal - */ -void Test_TO_OutputChannel_Enable_Nominal(void) -{ - int32 result = -1; - int32 expected = CFE_SUCCESS; - uint8 ChannelID = 0; - /* Set test destination address */ - char *DestinationAddress = "test"; - uint16 DestinationPort = 0; - - /* Set create child task to return success */ - Ut_CFE_ES_SetReturnCode(UT_CFE_ES_CREATECHILDTASK_INDEX, CFE_SUCCESS, 1); - - /* Set socket call to pass */ - TO_Platform_Stubs_Returns.TO_Wrap_Socket_Return = 1; - - /* Execute the function being tested */ - result = TO_OutputChannel_Enable(ChannelID, DestinationAddress, DestinationPort); - - /* Verify results */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==0,"Event Count = 0"); - UtAssert_True (result == expected, - "TO_OutputChannel_Enable() did not return the correct value"); - UtAssert_True(TO_AppCustomData.Channel[ChannelID].Mode == TO_CHANNEL_ENABLED, - "TO_OutputChannel_Enable() did not set correct mode"); -} - - -/************************************************************************** - * Tests for TO_OutputChannel_Send() - **************************************************************************/ -/** - * Test TO_OutputChannel_Send() invalid channel id - */ -void Test_TO_OutputChannel_Send_InvalidID(void) -{ - int32 result = -1; - int32 expected = 0; - uint8 ChannelID = (TO_MAX_CHANNELS); - char *testBuffer = "test"; - - /* Execute the function being tested */ - result = TO_OutputChannel_Send(ChannelID, testBuffer, sizeof(testBuffer)); - - /* Verify results */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==0,"Event Count = 0"); - UtAssert_True (result == expected, - "TO_OutputChannel_Enable() did not return the correct value"); -} - - -/** - * Test TO_OutputChannel_Send() sendto fail - */ -void Test_TO_OutputChannel_Send_SendToFail(void) -{ - int32 result = 0; - int32 expected = -1; - uint8 ChannelID = 0; - char *testBuffer = "test"; - - /* Set test channel to enabled */ - TO_AppCustomData.Channel[ChannelID].Mode = TO_CHANNEL_ENABLED; - - /* Set sendto call to fail */ - TO_Platform_Stubs_Returns.TO_Wrap_SendTo_Return = -1; - /* Set errno for sendto call */ - TO_Platform_Stubs_Returns.TO_Wrap_SendTo_Errno = 1; - TO_Platform_Stubs_Returns.TO_Wrap_SendTo_Errno_Value = 8; - - /* Call the function under test */ - result = TO_OutputChannel_Send(ChannelID, testBuffer, sizeof(testBuffer)); - - /* Verify results */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_True(TO_AppCustomData.Channel[ChannelID].Mode == TO_CHANNEL_DISABLED, - "TO_OutputChannel_Send() did not set mode to disabled"); - UtAssert_True(result == expected, - "TO_OutputChannel_Send() did not return the correct value"); - UtAssert_EventSent(TO_TLMOUTSTOP_ERR_EID, CFE_EVS_ERROR, "", - "TO_OutputChannel_Send() failed to raise an event"); -} - - -/** - * Test TO_OutputChannel_Send() sendto fail message too long - */ -void Test_TO_OutputChannel_Send_SendToTooLong(void) -{ - int32 result = 0; - int32 expected = -1; - uint8 ChannelID = 0; - char *testBuffer = "test"; - - /* Set test channel to enabled */ - TO_AppCustomData.Channel[ChannelID].Mode = TO_CHANNEL_ENABLED; - - /* Set sendto call to fail */ - TO_Platform_Stubs_Returns.TO_Wrap_SendTo_Return = -1; - /* Set errno for sendto call */ - TO_Platform_Stubs_Returns.TO_Wrap_SendTo_Errno = 1; - /* Set errno message too long */ - TO_Platform_Stubs_Returns.TO_Wrap_SendTo_Errno_Value = 90; - - /* Call the function under test */ - result = TO_OutputChannel_Send(ChannelID, testBuffer, sizeof(testBuffer)); - - /* Verify results */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_True(result == expected, - "TO_OutputChannel_Send() did not return the correct value"); - UtAssert_EventSent(TO_TLMOUTSTOP_ERR_EID, CFE_EVS_ERROR, "", - "TO_OutputChannel_Send() failed to raise an event"); -} - - -/** - * Test TO_OutputChannel_Send() nominal - */ -void Test_TO_OutputChannel_Send_Nominal(void) -{ - int32 result = -1; - int32 expected = 0; - uint8 ChannelID = 0; - char *testBuffer = "test"; - - /* Set test channel to enabled */ - TO_AppCustomData.Channel[ChannelID].Mode = TO_CHANNEL_ENABLED; - - /* Call the function under test */ - result = TO_OutputChannel_Send(ChannelID, testBuffer, sizeof(testBuffer)); - - UtAssert_True(result == expected, - "TO_OutputChannel_Send() did not return the correct value"); -} - - - /************************************************************************** - * Tests for TO_OutputChannel_ChannelHandler() - **************************************************************************/ -/** - * Test TO_OutputChannel_ChannelHandler() fail OS_QueueGet - */ -void TO_OutputChannel_ChannelHandle_QueueGetFail(void) -{ - uint8 ChannelID = 0; - - /* Set test channel to enabled */ - TO_AppCustomData.Channel[ChannelID].Mode = TO_CHANNEL_ENABLED; - - /* Set all status returns after the first call to disabled - * NOTE: calls to TO_Channel_State sets the channel mode to - * TO_CHANNEL_DISABLED disabled after the first call - */ - TO_App_Return.TO_Channel_State_Return = TO_CHANNEL_OPENED; - TO_App_Return.TO_Channel_State_Return1 = TO_CHANNEL_CLOSED; - - /* Set OS_QueueGet to fail with OS_ERROR */ - Ut_OSAPI_SetReturnCode(UT_OSAPI_QUEUEGET_INDEX, OS_ERROR, 1); - - /* Call the function under test */ - TO_OutputChannel_ChannelHandler(ChannelID); - - /* Verify results */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_EventSent(TO_OSQUEUE_GET_ERROR_EID, CFE_EVS_ERROR, "", - "TO_OutputChannel_Send() failed to raise an event"); -} - - -/** - * Test TO_OutputChannel_ChannelHandler() fail sendto - */ -void TO_OutputChannel_ChannelHandle_SendToFail(void) -{ - uint8 ChannelID = 0; - - /* Set test channel to enabled */ - TO_AppCustomData.Channel[ChannelID].Mode = TO_CHANNEL_ENABLED; - - /* Set sendto call to fail */ - TO_Platform_Stubs_Returns.TO_Wrap_SendTo_Return = -1; - - /* Set all status returns after the first call to disabled - * NOTE: calls to TO_Channel_State sets the channel mode to - * TO_CHANNEL_DISABLED disabled after the first call - */ - TO_App_Return.TO_Channel_State_Return = TO_CHANNEL_OPENED; - TO_App_Return.TO_Channel_State_Return1 = TO_CHANNEL_CLOSED; - - /* Call the function under test */ - TO_OutputChannel_ChannelHandler(ChannelID); - - /* Verify results */ - /* Events sendto error and disable channel info message */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==2,"Event Count = 2"); - UtAssert_EventSent(TO_TLMOUTSTOP_ERR_EID, CFE_EVS_ERROR, "", - "TO_OutputChannel_Send() failed to raise an event"); - UtAssert_EventSent(TO_CMD_INF_EID, CFE_EVS_INFORMATION, "", - "TO_OutputChannel_Send() failed to raise an event"); -} - - -/** - * Test TO_OutputChannel_ChannelHandler() fail CFE_ES_PutPoolBuf() - */ -void TO_OutputChannel_ChannelHandle_PutPoolBufFail(void) -{ - uint8 ChannelID = 0; - - /* Set CFE_ES_PutPoolBuf to fail */ - Ut_CFE_ES_SetReturnCode(UT_CFE_ES_PUTPOOLBUF_INDEX, -1, 1); - - /* Set test channel to enabled */ - TO_AppCustomData.Channel[ChannelID].Mode = TO_CHANNEL_ENABLED; - - /* Set all status returns after the first call to disabled - * NOTE: calls to TO_Channel_State sets the channel mode to - * TO_CHANNEL_DISABLED disabled after the first call - */ - TO_App_Return.TO_Channel_State_Return = TO_CHANNEL_OPENED; - TO_App_Return.TO_Channel_State_Return1 = TO_CHANNEL_CLOSED; - - /* Call the function under test */ - TO_OutputChannel_ChannelHandler(ChannelID); - - /* Verify results */ - /* Events sendto error and disable channel info message */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_EventSent(TO_PUT_POOL_ERR_EID, CFE_EVS_ERROR, "", - "TO_OutputChannel_Send() failed to raise an event"); -} - -/** - * Test TO_OutputChannel_ChannelHandler() OS_QUEUE_TIMEOUT - */ -void TO_OutputChannel_ChannelHandle_OSQueueTimeout(void) -{ - uint8 ChannelID = 0; - - /* Set OS_QueueGet to fail with OS_QUEUE_TIMEOUT */ - Ut_OSAPI_SetReturnCode(UT_OSAPI_QUEUEGET_INDEX, OS_QUEUE_TIMEOUT, 1); - - /* Set test channel to enabled */ - TO_AppCustomData.Channel[ChannelID].Mode = TO_CHANNEL_ENABLED; - - /* Set all status returns after the first call to disabled - * NOTE: calls to TO_Channel_State sets the channel mode to - * TO_CHANNEL_DISABLED disabled after the first call - */ - TO_App_Return.TO_Channel_State_Return = TO_CHANNEL_OPENED; - TO_App_Return.TO_Channel_State_Return1 = TO_CHANNEL_CLOSED; - - /* Call the function under test */ - TO_OutputChannel_ChannelHandler(ChannelID); - - /* Verify results */ - /* Events sendto error and disable channel info message */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==0,"Event Count = 0"); -} - - - /************************************************************************** - * Tests for TO_OutputChannel_ProcessNewCustomCmds() - **************************************************************************/ -/** - * Test TO_OutputChannel_ProcessNewCustomCmds() invalid message length - * enable channel command code - */ -void TO_OutputChannel_ProcessNewCustomCmds_EnableInvalidMessageLength(void) -{ - /* Wrong type to create incorrect size condition */ - TO_DisableChannelCmd_t InMsg; - - CFE_SB_InitMsg(&InMsg, TO_CMD_MID, sizeof(InMsg), TRUE); - - CFE_SB_SetCmdCode((CFE_SB_MsgPtr_t)&InMsg, TO_ENABLE_CHANNEL_CC); - - /* Set get command code function hook */ - Ut_CFE_SB_SetFunctionHook(UT_CFE_SB_GETCMDCODE_INDEX, &Ut_CFE_SB_GetCmdCodeHook); - - /* Call the function under test */ - TO_OutputChannel_ProcessNewCustomCmds((CFE_SB_Msg_t*)&InMsg); - - /* Verify results */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_True(TO_AppData.HkTlm.usCmdErrCnt == 1,"CmdErrCnt not incremented"); - UtAssert_EventSent(TO_MSG_LEN_ERR_EID, CFE_EVS_ERROR, "", - "TO_OutputChannel_ProcessNewCustomCmds() failed to raise an event"); -} - - -/** - * Test TO_OutputChannel_ProcessNewCustomCmds() invalid message length - * disable channel command code - */ -void TO_OutputChannel_ProcessNewCustomCmds_DisableInvalidMessageLength(void) -{ - /* Wrong type to create incorrect size condition */ - TO_EnableChannelCmd_t InMsg; - - CFE_SB_InitMsg(&InMsg, TO_CMD_MID, sizeof(InMsg), TRUE); - - CFE_SB_SetCmdCode((CFE_SB_MsgPtr_t)&InMsg, TO_DISABLE_CHANNEL_CC); - - /* Set get command code function hook */ - Ut_CFE_SB_SetFunctionHook(UT_CFE_SB_GETCMDCODE_INDEX, &Ut_CFE_SB_GetCmdCodeHook); - - /* Call the function under test */ - TO_OutputChannel_ProcessNewCustomCmds((CFE_SB_Msg_t*)&InMsg); - - /* Verify results */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_True(TO_AppData.HkTlm.usCmdErrCnt == 1,"CmdErrCnt not incremented"); - UtAssert_EventSent(TO_MSG_LEN_ERR_EID, CFE_EVS_ERROR, "", - "TO_OutputChannel_ProcessNewCustomCmds() failed to raise an event"); -} - - -/** - * Test TO_OutputChannel_ProcessNewCustomCmds() invalid command code - */ -void TO_OutputChannel_ProcessNewCustomCmds_InvalidCommandCode(void) -{ - /* Create an invalid command code */ - uint8 InvalidCommandCode = 100; - - /* Wrong type to create incorrect size condition */ - TO_EnableChannelCmd_t InMsg; - - CFE_SB_InitMsg(&InMsg, TO_CMD_MID, sizeof(InMsg), TRUE); - - /* Set invalid command code */ - CFE_SB_SetCmdCode((CFE_SB_MsgPtr_t)&InMsg, InvalidCommandCode); - - /* Set get command code function hook */ - Ut_CFE_SB_SetFunctionHook(UT_CFE_SB_GETCMDCODE_INDEX, &Ut_CFE_SB_GetCmdCodeHook); - - /* Call the function under test */ - TO_OutputChannel_ProcessNewCustomCmds((CFE_SB_Msg_t*)&InMsg); - - /* Verify results */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_True(TO_AppData.HkTlm.usCmdErrCnt == 1,"CmdErrCnt not incremented"); - UtAssert_EventSent(TO_CC_ERR_EID, CFE_EVS_ERROR, "", - "TO_OutputChannel_ProcessNewCustomCmds() failed to raise an event"); -} - - -/** - * Test TO_OutputChannel_ProcessNewCustomCmds() enable fail - */ -void TO_OutputChannel_ProcessNewCustomCmds_EnableFail(void) -{ - TO_EnableChannelCmd_t InMsg; - - CFE_SB_InitMsg(&InMsg, TO_CMD_MID, sizeof(InMsg), TRUE); - - /* Set command code */ - CFE_SB_SetCmdCode((CFE_SB_MsgPtr_t)&InMsg, TO_ENABLE_CHANNEL_CC); - - /* Set get command code function hook */ - Ut_CFE_SB_SetFunctionHook(UT_CFE_SB_GETCMDCODE_INDEX, &Ut_CFE_SB_GetCmdCodeHook); - - /* Set socket create to fail */ - TO_Platform_Stubs_Returns.TO_Wrap_Socket_Return = -1; - - /* Call the function under test */ - TO_OutputChannel_ProcessNewCustomCmds((CFE_SB_Msg_t*)&InMsg); - - /* Verify results */ - UtAssert_True(TO_AppData.HkTlm.usCmdErrCnt == 1,"CmdErrCnt not incremented"); - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_EventSent(TO_TLMOUTSOCKET_ERR_EID, CFE_EVS_ERROR, "", - "TO_OutputChannel_Enable() failed to raise an event"); -} - - -/** - * Test TO_OutputChannel_ProcessNewCustomCmds() disable fail - */ -void TO_OutputChannel_ProcessNewCustomCmds_DisableFail(void) -{ - TO_DisableChannelCmd_t InMsg; - - CFE_SB_InitMsg(&InMsg, TO_CMD_MID, sizeof(InMsg), TRUE); - - /* Set command code */ - CFE_SB_SetCmdCode((CFE_SB_MsgPtr_t)&InMsg, TO_DISABLE_CHANNEL_CC); - - /* Set get command code function hook */ - Ut_CFE_SB_SetFunctionHook(UT_CFE_SB_GETCMDCODE_INDEX, &Ut_CFE_SB_GetCmdCodeHook); - - - /* Call the function under test */ - TO_OutputChannel_ProcessNewCustomCmds((CFE_SB_Msg_t*)&InMsg); - - /* Verify results */ - UtAssert_True(TO_AppData.HkTlm.usCmdErrCnt == 1,"CmdErrCnt not incremented"); - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_EventSent(TO_TLMOUTDIS_ERR_EID, CFE_EVS_ERROR, "", - "TO_OutputChannel_Disable() failed to raise an event"); -} - - -/** - * Test TO_OutputChannel_ProcessNewCustomCmds() enable nominal - */ -void TO_OutputChannel_ProcessNewCustomCmds_EnableNominal(void) -{ - TO_EnableChannelCmd_t InMsg; - - CFE_SB_InitMsg(&InMsg, TO_CMD_MID, sizeof(InMsg), TRUE); - - /* Set command code */ - CFE_SB_SetCmdCode((CFE_SB_MsgPtr_t)&InMsg, TO_ENABLE_CHANNEL_CC); - - /* Set get command code function hook */ - Ut_CFE_SB_SetFunctionHook(UT_CFE_SB_GETCMDCODE_INDEX, &Ut_CFE_SB_GetCmdCodeHook); - - /* Call the function under test */ - TO_OutputChannel_ProcessNewCustomCmds((CFE_SB_Msg_t*)&InMsg); - - /* Verify results */ - UtAssert_True(TO_AppData.HkTlm.usCmdCnt == 1,"usCmdCnt not incremented"); - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_EventSent(TO_TLMOUTENA_INF_EID, CFE_EVS_INFORMATION, "", - "TO_OutputChannel_Enable() failed to raise an event"); -} - - -/** - * Test TO_OutputChannel_ProcessNewCustomCmds() disable nominal - */ -void TO_OutputChannel_ProcessNewCustomCmds_DisableNominal(void) -{ - uint8 ChannelID = 0; - TO_DisableChannelCmd_t InMsg; - - /* Set to enabled for TO_OutputChannel_Disable can set to - * disabled - */ - TO_AppCustomData.Channel[ChannelID].Mode = TO_CHANNEL_ENABLED; - - CFE_SB_InitMsg(&InMsg, TO_CMD_MID, sizeof(InMsg), TRUE); - - /* Set command code */ - CFE_SB_SetCmdCode((CFE_SB_MsgPtr_t)&InMsg, TO_DISABLE_CHANNEL_CC); - - /* Set get command code function hook */ - Ut_CFE_SB_SetFunctionHook(UT_CFE_SB_GETCMDCODE_INDEX, &Ut_CFE_SB_GetCmdCodeHook); - - - /* Call the function under test */ - TO_OutputChannel_ProcessNewCustomCmds((CFE_SB_Msg_t*)&InMsg); - - /* Verify results */ - UtAssert_True(TO_AppData.HkTlm.usCmdCnt == 1,"usCmdCnt not incremented"); - UtAssert_True(TO_AppCustomData.Channel[ChannelID].Mode == TO_CHANNEL_DISABLED, - "TO_OutputChannel_Disable did not set correct mode"); - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_EventSent(TO_TLMOUTDIS_INF_EID, CFE_EVS_INFORMATION, "", - "TO_OutputChannel_Disable() failed to raise an event"); -} - - /************************************************************************** - * Tests for TO_OutputChannel_UDPChannelTask() - **************************************************************************/ -/** - * Test TO_OutputChannel_UDPChannelTask() - * Note: currently there is no way to fail this function - */ -void TO_OutputChannel_UDPChannelTask_Nominal(void) -{ - TO_OutputChannel_UDPChannelTask(); -} - - - /************************************************************************** - * Tests for TO_OutputChannel_CustomCleanupAll() - **************************************************************************/ -/** - * Test TO_OutputChannel_CustomCleanupAll() nominal - * Note: currently there is no way to fail this function - */ -void TO_OutputChannel_CustomCleanupAll_Nominal(void) -{ - uint8 ChannelID = 0; - TO_AppCustomData.Channel[ChannelID].Mode = TO_CHANNEL_ENABLED; - - /* Call the function under test */ - TO_OutputChannel_CustomCleanupAll(); - - /* Verify results */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_EventSent(TO_TLMOUTDIS_INF_EID, CFE_EVS_INFORMATION, "", - "TO_OutputChannel_Disable() failed to raise an event"); -} - - - /************************************************************************** - * Tests for TO_OutputChannel_Disable() - **************************************************************************/ - -/** - * Test TO_OutputChannel_Disable() nominal - */ -void TO_OutputChannel_Disable_Fail(void) -{ - int32 result = 0; - int32 expected = -1; - uint8 ChannelID = 0; - - /* Call the function under test */ - result = TO_OutputChannel_Disable(ChannelID); - - /* Verify results */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_EventSent(TO_TLMOUTDIS_ERR_EID, CFE_EVS_ERROR, "", - "TO_OutputChannel_Disable() failed to raise an event"); - UtAssert_True(result == expected, - "TO_OutputChannel_Disable() did not return the correct value"); - -} - - -/** - * Test TO_OutputChannel_Disable() nominal - */ -void TO_OutputChannel_Disable_Nominal(void) -{ - int32 result = -1; - int32 expected = 0; - uint8 ChannelID = 0; - - TO_AppCustomData.Channel[ChannelID].Mode = TO_CHANNEL_ENABLED; - - /* Call the function under test */ - result = TO_OutputChannel_Disable(ChannelID); - - /* Verify results */ - UtAssert_True(Ut_CFE_EVS_GetEventQueueDepth()==1,"Event Count = 1"); - UtAssert_EventSent(TO_TLMOUTDIS_INF_EID, CFE_EVS_INFORMATION, "", - "TO_OutputChannel_Disable() failed to raise an event"); - UtAssert_True(result == expected, - "TO_OutputChannel_Disable() did not return the correct value"); - -} - - - /************************************************************************** - * Test Rollup - **************************************************************************/ -void TO_Custom_App_Test_AddTestCases(void) -{ - UtTest_Add(TO_Custom_Init_OpenChannelFail, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "TO_Custom_Init_OpenChannelFail"); - UtTest_Add(TO_Custom_Init_EnableChannelFail, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "TO_Custom_Init_EnableChannelFail"); - UtTest_Add(TO_Custom_Init_Nominal, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "TO_Custom_Init_Nominal"); - UtTest_Add(TO_Custom_Init_NothingEnabled, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "TO_Custom_Init_NothingEnabled"); - UtTest_Add(Test_TO_OutputChannel_CustomBuildupAll_Nominal, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "Test_TO_OutputChannel_CustomBuildupAll_Nominal"); - UtTest_Add(Test_TO_OutputChannel_Enable_NullDestinationAddress, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "Test_TO_OutputChannel_Enable_NullDestinationAddress"); - UtTest_Add(Test_TO_OutputChannel_Enable_InvalidID, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "Test_TO_OutputChannel_Enable_InvalidID"); - UtTest_Add(Test_TO_OutputChannel_Enable_SocketFail, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "Test_TO_OutputChannel_Enable_SocketFail"); - UtTest_Add(Test_TO_OutputChannel_Enable_BindFail, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "Test_TO_OutputChannel_Enable_BindFail"); - UtTest_Add(Test_TO_OutputChannel_Enable_CreateChildTaskFail, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "Test_TO_OutputChannel_Enable_CreateChildTaskFail"); - UtTest_Add(Test_TO_OutputChannel_Enable_Nominal, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "Test_TO_OutputChannel_Enable_Nominal"); - UtTest_Add(Test_TO_OutputChannel_Send_InvalidID, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "Test_TO_OutputChannel_Send_InvalidID"); - UtTest_Add(Test_TO_OutputChannel_Send_SendToFail, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "Test_TO_OutputChannel_Send_SendToFail"); - UtTest_Add(Test_TO_OutputChannel_Send_SendToTooLong, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "Test_TO_OutputChannel_Send_SendToTooLong"); - UtTest_Add(Test_TO_OutputChannel_Send_Nominal, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "Test_TO_OutputChannel_Send_Nominal"); - UtTest_Add(TO_OutputChannel_ChannelHandle_QueueGetFail, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "TO_OutputChannel_ChannelHandle_QueueGetFail"); - //UtTest_Add(TO_OutputChannel_ChannelHandle_SendToFail, - // TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - // "TO_OutputChannel_ChannelHandle_SendToFail"); - //UtTest_Add(TO_OutputChannel_ChannelHandle_PutPoolBufFail, - // TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - // "TO_OutputChannel_ChannelHandle_PutPoolBufFail"); - UtTest_Add(TO_OutputChannel_ChannelHandle_OSQueueTimeout, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "TO_OutputChannel_ChannelHandle_OSQueueTimeout"); - UtTest_Add(TO_OutputChannel_ProcessNewCustomCmds_EnableInvalidMessageLength, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "TO_OutputChannel_ProcessNewCustomCmds_EnableInvalidMessageLength"); - UtTest_Add(TO_OutputChannel_ProcessNewCustomCmds_DisableInvalidMessageLength, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "TO_OutputChannel_ProcessNewCustomCmds_DisableInvalidMessageLength"); - UtTest_Add(TO_OutputChannel_ProcessNewCustomCmds_InvalidCommandCode, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "TO_OutputChannel_ProcessNewCustomCmds_InvalidCommandCode"); - UtTest_Add(TO_OutputChannel_ProcessNewCustomCmds_EnableFail, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "TO_OutputChannel_ProcessNewCustomCmds_EnableFail"); - UtTest_Add(TO_OutputChannel_ProcessNewCustomCmds_DisableFail, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "TO_OutputChannel_ProcessNewCustomCmds_DisableFail"); - UtTest_Add(TO_OutputChannel_ProcessNewCustomCmds_EnableNominal, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "TO_OutputChannel_ProcessNewCustomCmds_EnableNominal"); - UtTest_Add(TO_OutputChannel_ProcessNewCustomCmds_DisableNominal, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "TO_OutputChannel_ProcessNewCustomCmds_DisableNominal"); - UtTest_Add(TO_OutputChannel_UDPChannelTask_Nominal, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "TO_OutputChannel_UDPChannelTask_Nominal"); - UtTest_Add(TO_OutputChannel_CustomCleanupAll_Nominal, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "TO_OutputChannel_CustomCleanupAll_Nominal"); - UtTest_Add(TO_OutputChannel_Disable_Fail, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "TO_OutputChannel_Disable_Fail"); - UtTest_Add(TO_OutputChannel_Disable_Nominal, - TO_Custom_Test_Setup, TO_Custom_Test_TearDown, - "TO_OutputChannel_Disable_Nominal"); -} diff --git a/config/obc/sitl/target/apps/to/unit_test/to_app_custom_test.h b/config/obc/sitl/target/apps/to/unit_test/to_app_custom_test.h deleted file mode 100644 index 941bef57d..000000000 --- a/config/obc/sitl/target/apps/to/unit_test/to_app_custom_test.h +++ /dev/null @@ -1,55 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#ifndef TO_APP_CUSTOM_TEST_H -#define TO_APP_CUSTOM_TEST_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* - * Includes - */ - -#include "to_custom_test_utils.h" - - -void TO_Custom_App_Test_AddTestCases(void); - - -#ifdef __cplusplus -} -#endif - -#endif /* TO_APP_CUSTOM_TEST_H */ diff --git a/config/obc/sitl/target/apps/to/unit_test/to_app_stubs.c b/config/obc/sitl/target/apps/to/unit_test/to_app_stubs.c deleted file mode 100644 index a43055280..000000000 --- a/config/obc/sitl/target/apps/to/unit_test/to_app_stubs.c +++ /dev/null @@ -1,75 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#include "to_app_stubs.h" - -TO_App_Returns_t TO_App_Return = {0}; - -int32 TO_Channel_OpenChannel(uint32 index, const char *ChannelName, - const char *ConfigTableName, const char *ConfigTableFileName, - TO_ChannelTbl_t *BackupTblPtr, const char *DumpTableName, - const uint32 CfCntSemMax, const char *CfCntSemName) -{ - return TO_App_Return.TO_Channel_OpenChannel_Return; -} - - -void TO_Channel_LockByIndex(uint16 index) -{ - -} - - -void TO_Channel_UnlockByIndex(uint16 index) -{ - -} - - -uint8 TO_Channel_State(uint16 index) -{ - uint8 returnCode = 0; - - if(0 == TO_App_Return.TO_Channel_State_CallCount) - { - returnCode = TO_App_Return.TO_Channel_State_Return; - } - else - { - TO_AppCustomData.Channel[0].Mode = TO_CHANNEL_DISABLED; - returnCode = TO_App_Return.TO_Channel_State_Return1; - } - TO_App_Return.TO_Channel_State_CallCount++; - return returnCode; -} - diff --git a/config/obc/sitl/target/apps/to/unit_test/to_app_stubs.h b/config/obc/sitl/target/apps/to/unit_test/to_app_stubs.h deleted file mode 100644 index 8ee03bf3c..000000000 --- a/config/obc/sitl/target/apps/to/unit_test/to_app_stubs.h +++ /dev/null @@ -1,82 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#ifndef TO_APP_STUBS_H -#define TO_APP_STUBS_H - -#ifdef __cplusplus -extern "C" { -#endif - -/************************************************************************ -** Includes -*************************************************************************/ -#include "cfe.h" -#include "to_custom_test_utils.h" - -/************************************************************************ -** Structure Declarations -*************************************************************************/ -typedef struct -{ - int32 TO_Channel_OpenChannel_Return; - uint8 TO_Channel_State_Return; - uint8 TO_Channel_State_Return1; - uint8 TO_Channel_State_CallCount; -} TO_App_Returns_t; - -/************************************************************************ -** External Global Variables -*************************************************************************/ -extern TO_App_Returns_t TO_App_Return; - -/************************************************************************ -** Function Prototypes (Stubs) -*************************************************************************/ -int32 TO_Channel_OpenChannel(uint32 index, const char *ChannelName, - const char *ConfigTableName, const char *ConfigTableFileName, - TO_ChannelTbl_t *BackupTblPtr, const char *DumpTableName, - const uint32 CfCntSemMax, const char *CfCntSemName); - -void TO_Channel_LockByIndex(uint16 index); - -void TO_Channel_UnlockByIndex(uint16 index); - -uint8 TO_Channel_State(uint16 index); - - -#ifdef __cplusplus -} -#endif - -#endif /* TO_APP_STUBS_H */ diff --git a/config/obc/sitl/target/apps/to/unit_test/to_custom_test_utils.c b/config/obc/sitl/target/apps/to/unit_test/to_custom_test_utils.c deleted file mode 100644 index 8f5c59fc0..000000000 --- a/config/obc/sitl/target/apps/to/unit_test/to_custom_test_utils.c +++ /dev/null @@ -1,77 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#include "to_custom_test_utils.h" -#include "to_platform_stubs.h" - -#include "ut_cfe_evs_hooks.h" -#include "ut_cfe_time_stubs.h" -#include "ut_cfe_psp_memutils_stubs.h" -#include "ut_cfe_tbl_stubs.h" -#include "ut_cfe_tbl_hooks.h" -#include "ut_cfe_fs_stubs.h" -#include "ut_cfe_time_stubs.h" -#include "ut_osapi_stubs.h" -#include "ut_osfileapi_stubs.h" -#include "ut_cfe_sb_stubs.h" -#include "ut_cfe_es_stubs.h" -#include "ut_cfe_evs_stubs.h" - -#include - -/* - * Function Definitions - */ - -void TO_Custom_Test_Setup(void) -{ - /* initialize test environment to default state for every test */ - CFE_PSP_MemSet(&TO_AppData, 0x00, sizeof(TO_AppData)); - CFE_PSP_MemSet(&TO_AppCustomData, 0x00, sizeof(TO_AppCustomData_t)); - CFE_PSP_MemSet(&TO_App_Return, 0x00, sizeof(TO_App_Return)); - CFE_PSP_MemSet(&TO_Platform_Stubs_Returns, 0x00, sizeof(TO_Platform_Stubs_Returns)); - - Ut_CFE_EVS_Reset(); - Ut_CFE_FS_Reset(); - Ut_CFE_TIME_Reset(); - Ut_CFE_TBL_Reset(); - Ut_CFE_SB_Reset(); - Ut_CFE_ES_Reset(); - Ut_OSAPI_Reset(); - Ut_OSFILEAPI_Reset(); -} - -void TO_Custom_Test_TearDown(void) -{ - -} diff --git a/config/obc/sitl/target/apps/to/unit_test/to_custom_test_utils.h b/config/obc/sitl/target/apps/to/unit_test/to_custom_test_utils.h deleted file mode 100644 index f86f57d06..000000000 --- a/config/obc/sitl/target/apps/to/unit_test/to_custom_test_utils.h +++ /dev/null @@ -1,63 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#ifndef TO_CUSTOM_TEST_UTILS_H -#define TO_CUSTOM_TEST_UTILS_H - -/* - * Includes - */ - -#include "to_custom_udp.h" -#include "to_app_stubs.h" - - -extern TO_AppCustomData_t TO_AppCustomData; - -#ifdef __cplusplus -extern "C" { -#endif - -/* - * Function Definitions - */ - -void TO_Custom_Test_Setup(void); -void TO_Custom_Test_TearDown(void); - - -#ifdef __cplusplus -} -#endif - -#endif /* TO_CUSTOM_TEST_UTILS_H */ diff --git a/config/obc/sitl/target/apps/to/unit_test/to_custom_testrunner.c b/config/obc/sitl/target/apps/to/unit_test/to_custom_testrunner.c deleted file mode 100644 index 021ae11bc..000000000 --- a/config/obc/sitl/target/apps/to/unit_test/to_custom_testrunner.c +++ /dev/null @@ -1,52 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#include "uttest.h" - -#include "to_app_custom_test.h" - -TO_AppData_t TO_AppData; - -extern int enable_wrappers; - -int main(void) -{ - int testResults = 0; - enable_wrappers = 1; - TO_Custom_App_Test_AddTestCases(); - testResults = UtTest_Run(); - - enable_wrappers = 0; - - return testResults; -} diff --git a/config/obc/sitl/target/apps/to/unit_test/to_platform_stubs.c b/config/obc/sitl/target/apps/to/unit_test/to_platform_stubs.c deleted file mode 100644 index db2ffbec7..000000000 --- a/config/obc/sitl/target/apps/to/unit_test/to_platform_stubs.c +++ /dev/null @@ -1,105 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#include -#include - -#include "to_platform_stubs.h" - - -int enable_wrappers = 0; - -int __real_socket(int domain, int type, int protocol); -int __real_bind(int sockfd, const struct sockaddr *addr, socklen_t addrlen); -int __real_sendto(int sockfd, const void *buf, size_t len, int flags, - const struct sockaddr *dest_addr, socklen_t addrlen); - -TO_Platform_Stubs_Returns_t TO_Platform_Stubs_Returns = {0}; - - -int __wrap_socket(int domain, int type, int protocol) -{ - int returnCode = 0; - if(enable_wrappers == 0) - { - returnCode = __real_socket(domain, type, protocol); - } - else - { - if (TO_Platform_Stubs_Returns.TO_Wrap_Socket_Errno) - { - errno = TO_Platform_Stubs_Returns.TO_Wrap_Socket_Errno_Value; - } - returnCode = TO_Platform_Stubs_Returns.TO_Wrap_Socket_Return; - } - return returnCode; -} - - -int __wrap_bind(int sockfd, const struct sockaddr *addr, socklen_t addrlen) -{ - int returnCode = 0; - if(enable_wrappers == 0) - { - returnCode = __real_bind(sockfd, addr, addrlen); - } - else - { - if (TO_Platform_Stubs_Returns.TO_Wrap_Bind_Errno) - { - errno = TO_Platform_Stubs_Returns.TO_Wrap_Bind_Errno_Value; - } - returnCode = TO_Platform_Stubs_Returns.TO_Wrap_Bind_Return; - } - return returnCode; -} - - -int __wrap_sendto(int sockfd, const void *buf, size_t len, int flags, - const struct sockaddr *dest_addr, socklen_t addrlen) -{ - int returnCode = 0; - if(enable_wrappers == 0) - { - returnCode = __real_sendto(sockfd, buf, len, flags, dest_addr, addrlen); - } - else - { - if (TO_Platform_Stubs_Returns.TO_Wrap_SendTo_Errno) - { - errno = TO_Platform_Stubs_Returns.TO_Wrap_SendTo_Errno_Value; - } - returnCode = TO_Platform_Stubs_Returns.TO_Wrap_SendTo_Return; - } - return returnCode; -} diff --git a/config/obc/sitl/target/apps/to/unit_test/to_platform_stubs.h b/config/obc/sitl/target/apps/to/unit_test/to_platform_stubs.h deleted file mode 100644 index 923c5cd38..000000000 --- a/config/obc/sitl/target/apps/to/unit_test/to_platform_stubs.h +++ /dev/null @@ -1,61 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2017 Windhover Labs, L.L.C. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name Windhover Labs nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -*****************************************************************************/ - -#ifndef TO_PLATFORM_STUBS_H -#define TO_PLATFORM_STUBS_H - -#ifdef __cplusplus -extern "C" { -#endif - -typedef struct -{ - int TO_Wrap_Socket_Return; - int TO_Wrap_Socket_Errno; - int TO_Wrap_Socket_Errno_Value; - int TO_Wrap_Bind_Return; - int TO_Wrap_Bind_Errno; - int TO_Wrap_Bind_Errno_Value; - int TO_Wrap_SendTo_Return; - int TO_Wrap_SendTo_Errno; - int TO_Wrap_SendTo_Errno_Value; -} TO_Platform_Stubs_Returns_t; - -extern TO_Platform_Stubs_Returns_t TO_Platform_Stubs_Returns; - - -#ifdef __cplusplus -} -#endif - -#endif /* TO_PLATFORM_STUBS_H */ diff --git a/config/obc/sitl/target/apps/to/user_doxy.in b/config/obc/sitl/target/apps/to/user_doxy.in deleted file mode 100644 index 506ec63b3..000000000 --- a/config/obc/sitl/target/apps/to/user_doxy.in +++ /dev/null @@ -1,265 +0,0 @@ -# Doxyfile 1.5.4 -@INCLUDE_PATH=@PROJECT_SOURCE_DIR@/apps/to/docs/dox_src/mnem_maps -@INCLUDE=cfs_to_cmd_mnem_map -@INCLUDE=cfs_to_tlm_mnem_map -#--------------------------------------------------------------------------- -# Project related configuration options -#--------------------------------------------------------------------------- -#DOXYFILE_ENCODING = UTF-8 -PROJECT_NAME = "Telemetry Output (TO) Application on @BUILD_CONFIG_NAME@ User's Guide" -PROJECT_NUMBER = -OUTPUT_DIRECTORY = @CFS_DOCS_HTML_DIR@/users_guide/apps/to -CREATE_SUBDIRS = NO -OUTPUT_LANGUAGE = English -BRIEF_MEMBER_DESC = YES -REPEAT_BRIEF = YES -ABBREVIATE_BRIEF = -ALWAYS_DETAILED_SEC = NO -INLINE_INHERITED_MEMB = NO -FULL_PATH_NAMES = YES -STRIP_FROM_PATH = @PROJECT_SOURCE_DIR@ -STRIP_FROM_INC_PATH = -SHORT_NAMES = NO -JAVADOC_AUTOBRIEF = NO -#QT_AUTOBRIEF = NO -MULTILINE_CPP_IS_BRIEF = NO -DETAILS_AT_TOP = NO -INHERIT_DOCS = YES -SEPARATE_MEMBER_PAGES = NO -TAB_SIZE = 8 -ALIASES += "event=\xrefitem cfstoevents \"Event Message\" \"Telemetry Output Event Message Cross Reference\" " -ALIASES += "retdesc= " -ALIASES += "retcode= " -ALIASES += endcode= -ALIASES += "returns=\return " -ALIASES += endreturns=
-ALIASES += "retstmt= " -ALIASES += endstmt= -ALIASES += "tocmd=\xrefitem cfstocmds \"Name\" \"Telemetry Output Commands\" " -ALIASES += "totlm=\xrefitem cfstotlm \"Name\" \"Telemetry Output Telemetry\" " -ALIASES += "tocmdmnemonic=\xrefitem cfstocmdmnems \"Command Mnemonic(s)\" \"Telemetry Output Command Mnemonic Cross Reference\" \b \c " -ALIASES += "totlmmnemonic=\xrefitem cfstotlmmnems \"Telemetry Mnemonic(s)\" \"Telemetry Output Telemetry Mnemonic Cross Reference\" \b \c " -ALIASES += "tocfg=\xrefitem cfstocfg \"Purpose\" \"Telemetry Output Configuration Parameters\" " -OPTIMIZE_OUTPUT_FOR_C = YES -OPTIMIZE_OUTPUT_JAVA = NO -BUILTIN_STL_SUPPORT = NO -#CPP_CLI_SUPPORT = NO -#SIP_SUPPORT = NO -DISTRIBUTE_GROUP_DOC = NO -SUBGROUPING = YES -#TYPEDEF_HIDES_STRUCT = NO -#--------------------------------------------------------------------------- -# Build related configuration options -#--------------------------------------------------------------------------- -EXTRACT_ALL = YES -EXTRACT_PRIVATE = YES -EXTRACT_STATIC = YES -EXTRACT_LOCAL_CLASSES = YES -EXTRACT_LOCAL_METHODS = NO -#EXTRACT_ANON_NSPACES = NO -HIDE_UNDOC_MEMBERS = NO -HIDE_UNDOC_CLASSES = NO -HIDE_FRIEND_COMPOUNDS = NO -HIDE_IN_BODY_DOCS = NO -INTERNAL_DOCS = NO -CASE_SENSE_NAMES = NO -HIDE_SCOPE_NAMES = NO -SHOW_INCLUDE_FILES = YES -INLINE_INFO = YES -SORT_MEMBER_DOCS = YES -SORT_BRIEF_DOCS = NO -SORT_BY_SCOPE_NAME = NO -GENERATE_TODOLIST = NO -GENERATE_TESTLIST = YES -GENERATE_BUGLIST = YES -GENERATE_DEPRECATEDLIST= YES -ENABLED_SECTIONS = -MAX_INITIALIZER_LINES = 30 -SHOW_USED_FILES = YES -SHOW_DIRECTORIES = YES -FILE_VERSION_FILTER = -#--------------------------------------------------------------------------- -# configuration options related to warning and progress messages -#--------------------------------------------------------------------------- -QUIET = NO -WARNINGS = YES -WARN_IF_UNDOCUMENTED = YES -WARN_IF_DOC_ERROR = YES -WARN_NO_PARAMDOC = YES -WARN_FORMAT = "$file:$line: $text " -WARN_LOGFILE = -#--------------------------------------------------------------------------- -# configuration options related to the input files -#--------------------------------------------------------------------------- -INPUT = @PROJECT_SOURCE_DIR@/apps/to/docs/dox_src/users_guide/cfs_to.dox -INPUT += @PROJECT_SOURCE_DIR@/config/shared/inc/to_mission_cfg.h -INPUT += @PROJECT_SOURCE_DIR@/config/shared/inc/to_perfids.h -INPUT += @PROJECT_SOURCE_DIR@/config/shared/inc/to_msgids.h -INPUT += @PROJECT_SOURCE_DIR@/config/@BUILD_CONFIG_NAME@/inc/to_platform_cfg.h -INPUT += @PROJECT_SOURCE_DIR@/apps/to/fsw/src/to_app.h -INPUT += @PROJECT_SOURCE_DIR@/apps/to/fsw/src/to_cds_utils.h -INPUT += @PROJECT_SOURCE_DIR@/apps/to/fsw/src/to_config_utils.h -INPUT += @PROJECT_SOURCE_DIR@/apps/to/fsw/src/to_events.h -INPUT += @PROJECT_SOURCE_DIR@/apps/to/fsw/src/to_msg.h -INPUT += @PROJECT_SOURCE_DIR@/apps/to/fsw/src/to_tbldefs.h -INPUT += @PROJECT_SOURCE_DIR@/apps/to/fsw/src/to_version.h - -#INPUT_ENCODING = UTF-8 -FILE_PATTERNS = *.c \ - *.h -RECURSIVE = YES -EXCLUDE = -EXCLUDE_SYMLINKS = NO -EXCLUDE_PATTERNS = -#EXCLUDE_SYMBOLS = -EXAMPLE_PATH = -EXAMPLE_PATTERNS = * -EXAMPLE_RECURSIVE = NO -IMAGE_PATH = "./" -IMAGE_PATH += "@PROJECT_SOURCE_DIR@/apps/to/docs/dox_src/users_guide/" -INPUT_FILTER = -FILTER_PATTERNS = -FILTER_SOURCE_FILES = NO -#--------------------------------------------------------------------------- -# configuration options related to source browsing -#--------------------------------------------------------------------------- -SOURCE_BROWSER = YES -INLINE_SOURCES = NO -STRIP_CODE_COMMENTS = YES -REFERENCED_BY_RELATION = YES -REFERENCES_RELATION = YES -REFERENCES_LINK_SOURCE = YES -USE_HTAGS = NO -VERBATIM_HEADERS = YES -#--------------------------------------------------------------------------- -# configuration options related to the alphabetical class index -#--------------------------------------------------------------------------- -ALPHABETICAL_INDEX = YES -COLS_IN_ALPHA_INDEX = 5 -IGNORE_PREFIX = -#--------------------------------------------------------------------------- -# configuration options related to the HTML output -#--------------------------------------------------------------------------- -GENERATE_HTML = YES -HTML_OUTPUT = @CFS_DOCS_HTML_DIR@/users_guide/apps/to -HTML_FILE_EXTENSION = .html -HTML_HEADER = -HTML_FOOTER = -HTML_STYLESHEET = -HTML_ALIGN_MEMBERS = YES -GENERATE_HTMLHELP = NO -#HTML_DYNAMIC_SECTIONS = NO -CHM_FILE = CFS_Help.chm -HHC_LOCATION = "C:/Program Files/HTML Help Workshop/hhc.exe" -GENERATE_CHI = NO -BINARY_TOC = NO -TOC_EXPAND = NO -DISABLE_INDEX = NO -ENUM_VALUES_PER_LINE = 4 -GENERATE_TREEVIEW = NO -TREEVIEW_WIDTH = 250 -#--------------------------------------------------------------------------- -# configuration options related to the LaTeX output -#--------------------------------------------------------------------------- -GENERATE_LATEX = YES -LATEX_OUTPUT = @CFS_DOCS_LATEX_DIR@/users_guide/apps/to -LATEX_CMD_NAME = latex -MAKEINDEX_CMD_NAME = makeindex -COMPACT_LATEX = YES -PAPER_TYPE = letter -EXTRA_PACKAGES = -LATEX_HEADER = -PDF_HYPERLINKS = YES -USE_PDFLATEX = YES -LATEX_BATCHMODE = NO -LATEX_HIDE_INDICES = NO -#--------------------------------------------------------------------------- -# configuration options related to the RTF output -#--------------------------------------------------------------------------- -GENERATE_RTF = NO -RTF_OUTPUT = @CFS_DOCS_DIR@/users_guide/rtf/apps/to -COMPACT_RTF = YES -RTF_HYPERLINKS = NO -RTF_STYLESHEET_FILE = -RTF_EXTENSIONS_FILE = -#--------------------------------------------------------------------------- -# configuration options related to the man page output -#--------------------------------------------------------------------------- -GENERATE_MAN = NO -MAN_OUTPUT = man -MAN_EXTENSION = .3 -MAN_LINKS = NO -#--------------------------------------------------------------------------- -# configuration options related to the XML output -#--------------------------------------------------------------------------- -GENERATE_XML = NO -XML_OUTPUT = xml -XML_SCHEMA = -XML_DTD = -XML_PROGRAMLISTING = YES -#--------------------------------------------------------------------------- -# configuration options for the AutoGen Definitions output -#--------------------------------------------------------------------------- -GENERATE_AUTOGEN_DEF = NO -#--------------------------------------------------------------------------- -# configuration options related to the Perl module output -#--------------------------------------------------------------------------- -GENERATE_PERLMOD = NO -PERLMOD_LATEX = NO -PERLMOD_PRETTY = YES -PERLMOD_MAKEVAR_PREFIX = -#--------------------------------------------------------------------------- -# Configuration options related to the preprocessor -#--------------------------------------------------------------------------- -ENABLE_PREPROCESSING = YES -MACRO_EXPANSION = NO -EXPAND_ONLY_PREDEF = NO -SEARCH_INCLUDES = YES -INCLUDE_PATH = -INCLUDE_FILE_PATTERNS = -PREDEFINED = __PPC__ \ - MESSAGE_FORMAT_IS_CCSDS \ - CFE_TIME_CFG_SRC_TIME \ - CFE_TIME_CFG_SRC_GPS \ - CFE_TIME_CFG_SRC_MET -EXPAND_AS_DEFINED = -SKIP_FUNCTION_MACROS = YES -#--------------------------------------------------------------------------- -# Configuration::additions related to external references -#--------------------------------------------------------------------------- -TAGFILES = @CFS_DOCS_HTML_DIR@/detailed_design/cfe/cfe.tag=../../../cfe/detailed_design/ -GENERATE_TAGFILE = @CFS_DOCS_HTML_DIR@/users_guide/apps/to/to.tag -ALLEXTERNALS = NO -EXTERNAL_GROUPS = YES -PERL_PATH = /usr/bin/perl -#--------------------------------------------------------------------------- -# Configuration options related to the dot tool -#--------------------------------------------------------------------------- -CLASS_DIAGRAMS = NO -#MSCGEN_PATH = -HIDE_UNDOC_RELATIONS = YES -HAVE_DOT = YES -CLASS_GRAPH = NO -COLLABORATION_GRAPH = NO -GROUP_GRAPHS = YES -UML_LOOK = NO -TEMPLATE_RELATIONS = NO -INCLUDE_GRAPH = NO -INCLUDED_BY_GRAPH = NO -CALL_GRAPH = YES -CALLER_GRAPH = NO -GRAPHICAL_HIERARCHY = NO -DIRECTORY_GRAPH = YES -DOT_IMAGE_FORMAT = png -DOT_PATH = -DOTFILE_DIRS = -#DOT_GRAPH_MAX_NODES = 50 -MAX_DOT_GRAPH_DEPTH = 1000 -DOT_TRANSPARENT = NO -DOT_MULTI_TARGETS = NO -GENERATE_LEGEND = YES -DOT_CLEANUP = YES -#--------------------------------------------------------------------------- -# Configuration::additions related to the search engine -#--------------------------------------------------------------------------- -SEARCHENGINE = NO diff --git a/config/obc/sitl/target/cfe_es_startup.scr b/config/obc/sitl/target/cfe_es_startup.scr deleted file mode 100644 index 82d0a04b0..000000000 --- a/config/obc/sitl/target/cfe_es_startup.scr +++ /dev/null @@ -1,48 +0,0 @@ -CFE_LIB, /cf/apps/CFS_LIB.so, CFS_LibInit, CFS_LIB, 0, 0, 0x0, 0, 2; -CFE_LIB, /cf/apps/PRMLIB.so, PRMLIB_LibInit, PRMLIB, 0, 0, 0x0, 0, 2; -CFE_LIB, /cf/apps/PX4LIB.so, PX4LIB_LibInit, PX4LIB, 0, 0, 0x0, 0, 2; -CFE_LIB, /cf/apps/PQ_LIB.so, PQ_LibInit, PQ_LIB, 0, 0, 0x0, 0, 2; -CFE_APP, /cf/apps/CF.so, CF_AppMain, CF, 157, 327680, 0x0, 0, 2; -CFE_APP, /cf/apps/DS.so, DS_AppMain, DS, 190, 327680, 0x0, 0, 2; -CFE_APP, /cf/apps/FM.so, FM_AppMain, FM, 163, 327680, 0x0, 0, 2; -CFE_APP, /cf/apps/HK.so, HK_AppMain, HK, 166, 327680, 0x0, 0, 2; -CFE_APP, /cf/apps/LC.so, LC_AppMain, LC, 178, 327680, 0x0, 0, 2; -CFE_APP, /cf/apps/MM.so, MM_AppMain, MM, 172, 327680, 0x0, 0, 2; -CFE_APP, /cf/apps/SC.so, SC_AppMain, SC, 175, 327680, 0x0, 0, 2; -CFE_APP, /cf/apps/MD.so, MD_AppMain, MD, 169, 327680, 0x0, 0, 2; -CFE_APP, /cf/apps/EA.so, EA_AppMain, EA, 184, 327680, 0x0, 0, 2; -CFE_APP, /cf/apps/CS.so, CS_AppMain, CS, 160, 327680, 0x0, 0, 2; -CFE_APP, /cf/apps/SBN.so, SBN_AppMain, SBN, 37, 327680, 0x0, 0, 2; -CFE_APP, /cf/apps/SCH.so, SCH_AppMain, SCH, 34, 40960, 0x0, 0, 2; -!CFE_LIB, /cf/apps/schlib.so, SCH_LibInit, SCH_LIB, 0, 0, 0x0, 0, 2; -CFE_APP, /cf/apps/LC.so, LC_AppMain, LC, 178, 327680, 0x0, 0, 2; -CFE_APP, /cf/apps/SC.so, SC_AppMain, SC, 175, 327680, 0x0, 0, 2; -CFE_APP, /cf/apps/FLOW.so, FLOW_AppMain, FLOW, 80, 327680, 0x0, 0, 2; -CFE_APP, /cf/apps/MAVLINK.so, MAVLINK_AppMain, MAVLINK, 90, 32768, 0x0, 0, 2; -CFE_APP, /cf/apps/HS.so, HS_AppMain, HS, 123, 32768, 0x0, 0, 2; -!CFE_APP, /cf/apps/ETA.so, ETA_AppMain, ETA, 100, 32768, 0x0, 0, 2; -!CFE_APP, /cf/apps/SBN.so, SBN_AppMain, SBN, 37, 32768, 0x0, 0, 2; -! -! Startup script fields: -! 1. Object Type -- CFE_APP for an Application, or CFE_LIB for a library. -! 2. Path/Filename -- This is a cFE Virtual filename, not a vxWorks device/pathname -! 3. Entry Point -- This is the "main" function for Apps. -! 4. CFE Name -- The cFE name for the the APP or Library -! 5. Priority -- This is the Priority of the App, not used for Library -! 6. Stack Size -- This is the Stack size for the App, not used for the Library -! 7. Load Address -- This is the Optional Load Address for the App or Library. Currently not implemented -! so keep it at 0x0. -! 8. Exception Action -- This is the Action the cFE should take if the App has an exception. -! 0 = Just restart the Application -! Non-Zero = Do a cFE Processor Reset -! -! Other Notes: -! 1. The software will not try to parse anything after the first '!' character it sees. That -! is the End of File marker. -! 2. Common Application file extensions: -! Linux = .so ( ci.so ) -! OS X = .bundle ( ci.bundle ) -! Cygwin = .dll ( ci.dll ) -! vxWorks = .o ( ci.o ) -! RTEMS with S-record Loader = .s3r ( ci.s3r ) -! RTEMS with CEXP Loader = .o ( ci.o ) diff --git a/config/obc/sitl/target/unit_test_wrapper b/config/obc/sitl/target/unit_test_wrapper deleted file mode 100755 index 1f8dde316..000000000 --- a/config/obc/sitl/target/unit_test_wrapper +++ /dev/null @@ -1,22 +0,0 @@ -#!/bin/bash -HOST_PATH=$1 -FULL_COMMAND=${*:2} -TARGET_DIR="/var/lib/jenkins/workspace/Airliner/OcPoC/Release_1.0.0" -TARGET_GCOV_PREFIX="${TARGET_DIR}" -TARGET_USER="root" -TARGET_ADDRESS="10.10.0.80" -HOST_DIR_DEPTH=$(find $1 -type d -printf '%d\n' | sort -n | tail -1) - -echo "*****************************" -echo "HOST_PATH = ${HOST_PATH}" -echo "FULL_COMMAND = ${FULL_COMMAND}" -echo "TARGET_DIR = ${TARGET_DIR}" -echo "TARGET_GCOV_PREFIX = ${TARGET_GCOV_PREFIX}" -echo "TARGET_USER = ${TARGET_USER}" -echo "TARGET_ADDRESS = ${TARGET_ADDRESS}" -echo "HOST_DIR_DEPTH = ${HOST_DIR_DEPTH}" -ssh ${TARGET_USER}@${TARGET_ADDRESS} "cd ${HOST_PATH}; ${FULL_COMMAND}" -RETURN_CODE=$? -echo "*****************************" - -exit ${RETURN_CODE} diff --git a/config/obc/sitl/target/unit_test_wrapper2 b/config/obc/sitl/target/unit_test_wrapper2 deleted file mode 100755 index e484c4af0..000000000 --- a/config/obc/sitl/target/unit_test_wrapper2 +++ /dev/null @@ -1,18 +0,0 @@ -#!/bin/bash -HOST_PATH=$1 -FULL_COMMAND=${*:2} -TARGET_DIR="/root/unit-test" -TARGET_GCOV_PREFIX="${TARGET_DIR}" -TARGET_USER="root" -TARGET_ADDRESS="vehicle1.windhoverlabs.lan" -HOST_DIR_DEPTH=$(find $1 -type d -printf '%d\n' | sort -n | tail -1) - -ssh ${TARGET_USER}@${TARGET_ADDRESS} "mkdir -p ${TARGET_DIR}" || /bin/true -ssh ${TARGET_USER}@${TARGET_ADDRESS} "mkdir -p ${TARGET_GCOV_PREFIX}" || /bin/true -rsync -a -z ${HOST_PATH}/* ${TARGET_USER}@${TARGET_ADDRESS}:${TARGET_DIR}/ -ssh ${TARGET_USER}@${TARGET_ADDRESS} "cd ${TARGET_DIR}; GCOV_PREFIX=${TARGET_GCOV_PREFIX} GCOV_PREFIX_STRIP=${HOST_DIR_DEPTH} ${FULL_COMMAND}" -RETURN_CODE=$? -rsync -a -z ${TARGET_USER}@${TARGET_ADDRESS}:${TARGET_DIR}/* ${HOST_PATH}/ -ssh ${TARGET_USER}@${TARGET_ADDRESS} "rm -Rf ${TARGET_DIR}" || /bin/true - -exit ${RETURN_CODE} diff --git a/config/obc/sitl/wh_config.yaml b/config/obc/sitl/wh_config.yaml deleted file mode 100644 index f0fc32106..000000000 --- a/config/obc/sitl/wh_config.yaml +++ /dev/null @@ -1,5 +0,0 @@ ---- -config_base: ${PROJECT_SOURCE_DIR} - -modules: - sch: \ No newline at end of file diff --git a/config/obc/wh_config.yaml b/config/obc/wh_config.yaml index 1d3904e56..25349a46a 100644 --- a/config/obc/wh_config.yaml +++ b/config/obc/wh_config.yaml @@ -3,4 +3,9 @@ config_base: ${PROJECT_SOURCE_DIR} modules: core: + modules: + osal: + definition: ${PROJECT_SOURCE_DIR}/core/osal/fsw/posix-fast/wh_design.yaml + psp: + definition: ${PROJECT_SOURCE_DIR}/core/psp/fsw/pc-linux/wh_design.yaml diff --git a/config/shared/apps/sed/CMakeLists.txt b/config/shared/apps/sed/CMakeLists.txt new file mode 100644 index 000000000..5e202b3ff --- /dev/null +++ b/config/shared/apps/sed/CMakeLists.txt @@ -0,0 +1,7 @@ +set(APP_NAME sed) + +buildliner_add_table( + ${APP_NAME} + NAME sed_config + SOURCES ${CMAKE_CURRENT_SOURCE_DIR}/tables/sed_config.c +) diff --git a/config/obc/sitl/target/apps/prm/tables/prm_config.c b/config/shared/apps/sed/tables/sed_config.c similarity index 51% rename from config/obc/sitl/target/apps/prm/tables/prm_config.c rename to config/shared/apps/sed/tables/sed_config.c index c275bb0dd..44faf2e2b 100644 --- a/config/obc/sitl/target/apps/prm/tables/prm_config.c +++ b/config/shared/apps/sed/tables/sed_config.c @@ -6,7 +6,7 @@ ** Include Files */ #include "cfe_tbl_filedef.h" -#include "prm_tbldefs.h" +#include "sed_tbldefs.h" /* ** Local Defines @@ -27,8 +27,8 @@ static OS_USED CFE_TBL_FileDef_t CFE_TBL_FileDef = ** ObjSize - size of the entire table */ - "PRM_ConfigTbl", "PRM.CONFIG_TBL", "PRM default config table", - "prm_config.tbl", (sizeof(PRM_ConfigTbl_t)) + "SED_ConfigTbl", "SED.CONFIG_TBL", "SED default config table", + "sed_config.tbl", (sizeof(SED_ConfigTbl_t)) }; /* @@ -39,10 +39,50 @@ static OS_USED CFE_TBL_FileDef_t CFE_TBL_FileDef = ** Global Variables */ -/* Default PRM config table data */ -PRM_ConfigTbl_t PRM_ConfigTbl = +/* Default SED config table data */ +SED_ConfigTbl_t SED_ConfigTbl = { - 1 + /* User calibration. */ + /* AccXScale */ + 1.0f, + /* AccYScale */ + 1.0f, + /* AccZScale */ + 1.0f, + /* AccXOffset */ + 1.0f, + /* AccYOffset */ + 0.0f, + /* AccZOffset */ + 0.0f, + /* GyroXScale */ + 1.0f, + /* GyroYScale */ + 1.0f, + /* GyroZScale */ + 1.0f, + /* GyroXOffset */ + 0.0f, + /* GyroYOffset */ + 0.0f, + /* GyroZOffset */ + 0.0f, + /* TempOffset */ + 25.0f, + /* TempSensitivity */ + 326.8f, + /* AccUnit */ + 9.80665f, + /* GyroUnit */ + 0.0174532f, + /* AccDivider */ + 2048, + /* GyroDivider */ + 16.4, + /* AccScale */ + 16, + /* GyroScale */ + 2000 }; /* @@ -58,6 +98,5 @@ PRM_ConfigTbl_t PRM_ConfigTbl = */ /*======================================================================================= -** End of file prm_config.c +** End of file sed_config.c **=====================================================================================*/ - diff --git a/config/shared/inc/msg_ids.h b/config/shared/inc/msg_ids.h index 1ddcc3c1b..fd7139d66 100644 --- a/config/shared/inc/msg_ids.h +++ b/config/shared/inc/msg_ids.h @@ -437,7 +437,8 @@ #define SBN_SUB_MID TLM_MSG( 433 ) - CFE_MSG_CPU_BASE #define SBN_ALLSUB_MID TLM_MSG( 434 ) - CFE_MSG_CPU_BASE #define SBN_UNSUB_MID TLM_MSG( 435 ) - CFE_MSG_CPU_BASE -#define SBN_MODULE_HK_MID TLM_MSG( 436 ) + +#define SBN_MODULE_HK_TLM_MID TLM_MSG( 436 ) /* SENS */ diff --git a/config/shared/inc/sed_mission_cfg.h b/config/shared/inc/sed_mission_cfg.h new file mode 100644 index 000000000..97d323331 --- /dev/null +++ b/config/shared/inc/sed_mission_cfg.h @@ -0,0 +1,24 @@ +#ifndef SED_MISSION_CFG_H +#define SED_MISSION_CFG_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* +** SED Mission Configuration Parameter Definitions +*/ + +/* TODO: Add mission configuration parameter definitions here, if necessary. */ + +#define SED_SB_TIMEOUT CFE_SB_PEND_FOREVER /* Can be a value in milliseconds */ + +#ifdef __cplusplus +} +#endif + +#endif /* SED_MISSION_CFG_H */ + +/************************/ +/* End of File Comment */ +/************************/ diff --git a/config/shared/inc/sed_msgids.h b/config/shared/inc/sed_msgids.h new file mode 100644 index 000000000..758a93df6 --- /dev/null +++ b/config/shared/inc/sed_msgids.h @@ -0,0 +1,24 @@ +#ifndef SED_MSGIDS_H +#define SED_MSGIDS_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "msg_ids.h" + +#define SED_SEND_HK_MID MPU9250_SEND_HK_MID +#define SED_HK_TLM_MID MPU9250_HK_TLM_MID +#define SED_DIAG_TLM_MID MPU9250_DIAG_TLM_MID +#define SED_CMD_MID MPU9250_CMD_MID +#define SED_MEASURE_MID MPU9250_MEASURE_MID + +#ifdef __cplusplus +} +#endif + +#endif /* SED_MSGIDS_H */ + +/************************/ +/* End of File Comment */ +/************************/ diff --git a/config/shared/inc/sed_perfids.h b/config/shared/inc/sed_perfids.h new file mode 100644 index 000000000..97e96f987 --- /dev/null +++ b/config/shared/inc/sed_perfids.h @@ -0,0 +1,18 @@ +#ifndef SED_PERFIDS_H +#define SED_PERFIDS_H + +#ifdef __cplusplus +extern "C" { +#endif + +#define SED_MAIN_TASK_PERF_ID (83) + +#ifdef __cplusplus +} +#endif + +#endif /* SED_PERFIDS_H */ + +/************************/ +/* End of File Comment */ +/************************/ diff --git a/config/shared/inc/sed_platform_cfg.h b/config/shared/inc/sed_platform_cfg.h new file mode 100644 index 000000000..0b4d5a6ee --- /dev/null +++ b/config/shared/inc/sed_platform_cfg.h @@ -0,0 +1,136 @@ +#ifndef SED_PLATFORM_CFG_H +#define SED_PLATFORM_CFG_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "math.h" + +/* +** SED Platform Configuration Parameter Definitions +*/ + +/** \brief Mission specific version number for SED application +** +** \par Description: +** An application version number consists of four parts: +** major version number, minor version number, revision +** number and mission specific revision number. The mission +** specific revision number is defined here and the other +** parts are defined in "sed_version.h". +** +** \par Limits: +** Must be defined as a numeric value that is greater than +** or equal to zero. +*/ +#define SED_MISSION_REV (0) + +/** \brief Pipe depth for the Scheduler pipe +** +** \par Limits: +** minimum of 1, max of CFE_SB_MAX_PIPE_DEPTH. +*/ +#define SED_SCH_PIPE_DEPTH (2) + +/** \brief Pipe name for the Scheduler pipe +** +** \par Limits: +** Note, this name must fit in OS_MAX_API_NAME. +*/ +#define SED_SCH_PIPE_NAME ("SED_SCH_PIPE") + +/** \brief The SB pend behavior type for the Scheduler pipe. +** +** \par Limits: +** One of: CFE_SB_POLL, CFE_SB_PEND_FOREVER, or the +** number of milliseconds to wait for a new message (recommended). +** Note, using CFE_SB_PEND_FOREVER may cause an unresponsive +** application if no messages arrive on this pipe. +*/ +#define SED_SCH_PIPE_PEND_TIME (2000) + +/** \brief Pipe depth for the params pipe +** +** \par Limits: +** minimum of 1, max of CFE_SB_MAX_PIPE_DEPTH. +*/ +#define SED_PARAM_PIPE_DEPTH (4) + +/** \brief Pipe name for the params pipe +** +** \par Limits: +** Note, this name must fit in OS_MAX_API_NAME. +*/ +#define SED_PARAM_PIPE_NAME ("SED_PARAM_PIPE") + +/** \brief The number of WAKEUP messages to reserve on the Scheduler pipe. +** +** \par Limits: +** minimum of 1, max limited to CFE_SB_MAX_PIPE_DEPTH-1. Note the +** SED_MEASURE_MID_MAX_MSG_COUNT and SED_SEND_HK_MID_MAX_MSG_COUNT +** must be less than SED_SCH_PIPE_DEPTH. +*/ +#define SED_MEASURE_MID_MAX_MSG_COUNT (1) + +/** \brief The number of SEND_HK messages to reserve on the Scheduler pipe. +** +** \par Limits: +** minimum of 1, max of CFE_SB_MAX_PIPE_DEPTH. Note the +** SED_MEASURE_MID_MAX_MSG_COUNT and SED_SEND_HK_MID_MAX_MSG_COUNT +** must be less than SED_SCH_PIPE_DEPTH. +*/ +#define SED_SEND_HK_MID_MAX_MSG_COUNT (1) + +/** \brief Pipe depth for the command pipe +** +** \par Limits: +** minimum of 1, max of CFE_SB_MAX_PIPE_DEPTH. +*/ +#define SED_CMD_PIPE_DEPTH (4) + +/** \brief Pipe name for the Scheduler pipe +** +** \par Limits: +** Note, this name must fit in OS_MAX_API_NAME. +*/ +#define SED_CMD_PIPE_NAME ("SED_CMD_PIPE") + +/** \brief Pipe depth for the data pipe +** +** \par Limits: +** minimum of 1, max of CFE_SB_MAX_PIPE_DEPTH. +*/ +#define SED_DATA_PIPE_DEPTH (4) + +/** \brief Pipe name for the Scheduler pipe +** +** \par Limits: +** Note, this name must fit in OS_MAX_API_NAME. +*/ +#define SED_DATA_PIPE_NAME ("SED_DATA_PIPE") + +/** \brief The config table default filename +** +** \par Limits: +** The length of each string, including the NULL terminator cannot exceed +** the #OS_MAX_PATH_LEN value. +*/ +#define SED_CONFIG_TABLE_FILENAME ("/cf/apps/sed_config.tbl") + +/** \brief The timeout value, in milliseconds, to wait for ES application startup sync. +** +** \par Limits: +** This parameter must be at least 1000 (ms). +*/ +#define SED_STARTUP_TIMEOUT_MSEC (1000) + +#ifdef __cplusplus +} +#endif + +#endif /* SED_PLATFORM_CFG_H */ + +/************************/ +/* End of File Comment */ +/************************/ diff --git a/config/wh_config.yaml b/config/wh_config.yaml index 8a8f0ba37..9233bf7c7 100644 --- a/config/wh_config.yaml +++ b/config/wh_config.yaml @@ -51,7 +51,7 @@ modules: cfe_tbl: telemetry: CFE_TBL_HK_TLM_MID: - msgID: 0x1802 + msgID: 0x0804 CFE_TBL_REG_TLM_MID: msgID: 0x0818 commands: @@ -367,17 +367,14 @@ modules: commands: TO_CMD_MID: msgID: 0x189f - TO_SEND_HK_MID: - msgID: 0x18a0 - TO_SEND_TLM_MID: - msgID: 0x18a1 - perfids: - TO_MAIN_TASK_PERF_ID: - id: 61 - TO_SOCKET_SEND_PERF_ID: - id: 62 - - + commands: + EnableChannel: + cc: 10 + struct: TO_EnableChannelCmd_t + DisableChannel: + cc: 11 + struct: TO_DisableChannelCmd_t + px4lib: definition: ${PROJECT_SOURCE_DIR}/apps/px4lib/wh_design.yaml telemetry: @@ -1081,5 +1078,15 @@ modules: VM_MAIN_TASK_PERF_ID: id: 110 - - + sbn: + definition: ${PROJECT_SOURCE_DIR}/apps/sbn/wh_design.yaml + telemetry: + SBN_TLM_MID: + msgID: 0x09ae + SBN_MODULE_HK_TLM_MID: + msgID: 0x09b4 + commands: + SBN_CMD_MID: + msgID: 0x19af + SBN_WAKEUP_MID: + msgID: 0x19b0 diff --git a/core/base/psp/make/build-functions.cmake b/core/base/psp/make/build-functions.cmake index 543ed496c..f62533602 100644 --- a/core/base/psp/make/build-functions.cmake +++ b/core/base/psp/make/build-functions.cmake @@ -52,7 +52,7 @@ include(${PROJECT_SOURCE_DIR}/core/tools/auto-yamcs/build-functions.cmake) #) function(psp_buildliner_initialize) # Define the function arguments. - cmake_parse_arguments(PARSED_ARGS "REFERENCE;APPS_ONLY" "CORE_BINARY;OSAL;STARTUP_SCRIPT" "CONFIG;CONFIG_SOURCES;FILESYS;CONFIG_DEFINITION" ${ARGN}) + cmake_parse_arguments(PARSED_ARGS "REFERENCE;APPS_ONLY" "CORE_BINARY;OSAL;STARTUP_SCRIPT;CPU_ID;COMMANDER_WORKSPACE;COMMANDER_WORKSPACE_OVERLAY" "CONFIG;CONFIG_SOURCES;FILESYS;CONFIG_DEFINITION" ${ARGN}) # Create all the target directories the caller requested. foreach(dir ${PARSED_ARGS_FILESYS}) @@ -64,21 +64,39 @@ function(psp_buildliner_initialize) message("This is a reference build.") set_property(GLOBAL PROPERTY IS_REFERENCE_BUILD true) endif() - + + if(NOT PARSED_ARGS_COMMANDER_WORKSPACE) + set(PARSED_ARGS_COMMANDER_WORKSPACE ${CMAKE_BINARY_DIR}/commander_workspace) + endif() + + if(NOT PARSED_ARGS_CPU_ID) + set(PARSED_ARGS_CPU_ID cfs) + endif() + # Generate the XTCE file - commander_initialize_workspace(commander_workspace + add_custom_target(ground-tools) + commander_initialize_workspace(commander-workspace CONFIG_FILE ${CMAKE_BINARY_DIR}/wh_defs.yaml XTCE_CONFIG_FILE ${PROJECT_SOURCE_DIR}/core/base/tools/commander/xtce_config.yaml WORKSPACE_TEMPLATE ${PROJECT_SOURCE_DIR}/core/base/tools/commander/workspace_template - WORKSPACE_OUTPUT_PATH ${CMAKE_BINARY_DIR}/commander_workspace + WORKSPACE_OUTPUT_PATH ${PARSED_ARGS_COMMANDER_WORKSPACE} OUTPUT_DB_FILE wh_defs.db - OUTPUT_XTCE_FILE mdb/cfs.xml + OUTPUT_XTCE_FILE mdb/${PARSED_ARGS_CPU_ID}.xml ) - set_target_properties(commander_workspace PROPERTIES EXCLUDE_FROM_ALL TRUE) + set_target_properties(commander-workspace PROPERTIES EXCLUDE_FROM_ALL TRUE) + add_dependencies(ground-tools commander-workspace) + + if(PARSED_ARGS_COMMANDER_WORKSPACE_OVERLAY) + add_custom_target(commander_workspace_overlay + COMMAND cp -R -f ${PARSED_ARGS_COMMANDER_WORKSPACE_OVERLAY}/* ${PARSED_ARGS_COMMANDER_WORKSPACE}/ + ) + add_dependencies(ground-tools commander_workspace_overlay) + add_dependencies(commander_workspace_overlay commander-workspace) + endif() # Add a build target to launch YAMCS with our newly created workspace. add_custom_target(start-yamcs - COMMAND ${CMAKE_BINARY_DIR}/commander_workspace/bin/yamcs-start /opt/yamcs/ ${CMAKE_BINARY_DIR}/commander_workspace + COMMAND ${PARSED_ARGS_COMMANDER_WORKSPACE}/bin/yamcs-start /opt/yamcs/ ${PARSED_ARGS_COMMANDER_WORKSPACE} ) # Add the 'build-file-system' target. This is used to trigger the steps to embed the initial ramdisk @@ -141,7 +159,7 @@ function(psp_buildliner_initialize) # Add the executable to the combined design+configuration yaml file commander_add_module(core - TARGET_WORKSPACE commander_workspace + TARGET_WORKSPACE commander-workspace TARGET_NAME core-binary ) @@ -557,13 +575,13 @@ function(psp_buildliner_add_app_def) if(IS_EMBEDDED) # Add the core binary file to the combined design+configuration yaml file commander_add_module(${PARSED_ARGS_TARGET} - TARGET_WORKSPACE commander_workspace + TARGET_WORKSPACE commander-workspace TARGET_NAME core-binary ) else() # Add the binary file to the combined design+configuration yaml file commander_add_module(${PARSED_ARGS_TARGET} - TARGET_WORKSPACE commander_workspace + TARGET_WORKSPACE commander-workspace TARGET_NAME ${PARSED_ARGS_TARGET} ) endif() diff --git a/core/base/tools/commander/workspace_template/Displays/.project b/core/base/tools/commander/workspace_template/Displays/.project index 2f1f77372..659d284a4 100644 --- a/core/base/tools/commander/workspace_template/Displays/.project +++ b/core/base/tools/commander/workspace_template/Displays/.project @@ -11,7 +11,7 @@ YAML_PATH - $%7BPROJECT_LOC%7D/Resources/definitions.yaml + $%7BPROJECT_LOC%7D/Resources/config_registry.yaml diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/Abandon.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/Abandon.opi index 4202f74d7..772958857 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/Abandon.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/Abandon.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Abandon + ($(CPUID)) CF - Abandon true @@ -28,7 +28,7 @@ true true Display - 260 + 280 31ffe3bf:150a7259bb9:-6563 -1 -1 @@ -139,7 +139,7 @@ importPackage(Packages.org.yamcs.studio.data); var Transaction =VTypeHelper.getString(display.getWidget('Transaction').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cf/Abandon', {'Trans': Transaction}); +Yamcs.issueCommand('/cfs/$(CPUID)/cf/Abandon', {'Trans': Transaction}); ]]> true @@ -217,16 +217,16 @@ $(pv_value) false - Abandon Transaction + ($(CPUID)) CF - Abandon Transaction true 1 true Label - 168 + 271 false 6c5e5e62:1775b7b9abc:-7122 - 46 + 6 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/Application.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/Application.opi index 15cbfb9a4..2c5a31bd9 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/Application.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/Application.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Application + ($(CPUID)) CF - Application true @@ -60,7 +60,7 @@ Text Update 0 false - /cfs/cf/CF_HkPacket_t.CmdCounter + /cfs/$(CPUID)/cf/CF_HkPacket_t.CmdCounter 0.0 @@ -81,8 +81,8 @@ $(pv_value) 100 false 45ea5983:1502a6e6386:-7f01 - 169 - 55 + 168 + 30 @@ -121,8 +121,8 @@ $(pv_value) 100 false 2b4f25d5:1502b5812fe:-7ff9 - 52 - 55 + 51 + 30 @@ -161,8 +161,8 @@ $(pv_value) 100 false 2b4f25d5:1502b5812fe:-7fef - 52 - 74 + 51 + 49 @@ -192,7 +192,7 @@ $(pv_value) Text Update_1 0 false - /cfs/cf/CF_HkPacket_t.ErrCounter + /cfs/$(CPUID)/cf/CF_HkPacket_t.ErrCounter 0.0 @@ -213,8 +213,8 @@ $(pv_value) 100 false 2b4f25d5:1502b5812fe:-7d06 - 169 - 74 + 168 + 49 @@ -223,7 +223,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cf/Noop', {});]]> true @@ -269,8 +269,8 @@ $(pv_value) Action Button 85 39deb42:1504a4eb8cc:-7de2 - 282 - 55 + 281 + 30 @@ -300,7 +300,7 @@ $(pv_value) false - Application + ($(CPUID)) CF - Application true 1 @@ -340,7 +340,7 @@ $(pv_value) Text Update_2 0 false - /cfs/cf/CF_HkPacket_t.App.WakeupForFileProc + /cfs/$(CPUID)/cf/CF_HkPacket_t.App.WakeupForFileProc 0.0 @@ -361,8 +361,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-7f5b - 180 - 121 + 179 + 96 @@ -392,7 +392,7 @@ $(pv_value) Text Update_3 0 false - /cfs/cf/CF_HkPacket_t.App.EngineCycleCount + /cfs/$(CPUID)/cf/CF_HkPacket_t.App.EngineCycleCount 0.0 @@ -413,8 +413,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-7f5a - 180 - 140 + 179 + 115 @@ -444,7 +444,7 @@ $(pv_value) Text Update_4 0 false - /cfs/cf/CF_HkPacket_t.App.MemInUse + /cfs/$(CPUID)/cf/CF_HkPacket_t.App.MemInUse 0.0 @@ -465,8 +465,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-7f59 - 180 - 159 + 179 + 134 @@ -496,7 +496,7 @@ $(pv_value) Text Update_5 0 false - /cfs/cf/CF_HkPacket_t.App.PeakMemInUse + /cfs/$(CPUID)/cf/CF_HkPacket_t.App.PeakMemInUse 0.0 @@ -517,8 +517,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-7f58 - 180 - 178 + 179 + 153 @@ -548,7 +548,7 @@ $(pv_value) Text Update_6 0 false - /cfs/cf/CF_HkPacket_t.App.LowMemoryMark + /cfs/$(CPUID)/cf/CF_HkPacket_t.App.LowMemoryMark 0.0 @@ -569,8 +569,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-7f57 - 180 - 197 + 179 + 172 @@ -600,7 +600,7 @@ $(pv_value) Text Update_7 0 false - /cfs/cf/CF_HkPacket_t.App.MaxMemNeeded + /cfs/$(CPUID)/cf/CF_HkPacket_t.App.MaxMemNeeded 0.0 @@ -621,8 +621,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-7f56 - 180 - 216 + 179 + 191 @@ -652,7 +652,7 @@ $(pv_value) Text Update_8 0 false - /cfs/cf/CF_HkPacket_t.App.MemAllocated + /cfs/$(CPUID)/cf/CF_HkPacket_t.App.MemAllocated 0.0 @@ -673,8 +673,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-7f55 - 180 - 235 + 179 + 210 @@ -704,7 +704,7 @@ $(pv_value) Text Update_9 0 false - /cfs/cf/CF_HkPacket_t.App.BufferPoolHandle + /cfs/$(CPUID)/cf/CF_HkPacket_t.App.BufferPoolHandle 0.0 @@ -725,8 +725,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-7f54 - 180 - 254 + 179 + 229 @@ -756,7 +756,7 @@ $(pv_value) Text Update_10 0 false - /cfs/cf/CF_HkPacket_t.App.QNodesAllocated + /cfs/$(CPUID)/cf/CF_HkPacket_t.App.QNodesAllocated 0.0 @@ -777,8 +777,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-7f53 - 180 - 273 + 179 + 248 @@ -808,7 +808,7 @@ $(pv_value) Text Update_11 0 false - /cfs/cf/CF_HkPacket_t.App.QNodesDeallocated + /cfs/$(CPUID)/cf/CF_HkPacket_t.App.QNodesDeallocated 0.0 @@ -829,8 +829,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-7f52 - 180 - 292 + 179 + 267 @@ -860,7 +860,7 @@ $(pv_value) Text Update_12 0 false - /cfs/cf/CF_HkPacket_t.App.PDUsReceived + /cfs/$(CPUID)/cf/CF_HkPacket_t.App.PDUsReceived 0.0 @@ -881,8 +881,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-7f51 - 180 - 311 + 179 + 286 @@ -912,7 +912,7 @@ $(pv_value) Text Update_13 0 false - /cfs/cf/CF_HkPacket_t.App.PDUsRejected + /cfs/$(CPUID)/cf/CF_HkPacket_t.App.PDUsRejected 0.0 @@ -933,8 +933,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-7f50 - 180 - 330 + 179 + 305 @@ -964,7 +964,7 @@ $(pv_value) Text Update_14 0 false - /cfs/cf/CF_HkPacket_t.App.TotalInProgTrans + /cfs/$(CPUID)/cf/CF_HkPacket_t.App.TotalInProgTrans 0.0 @@ -985,8 +985,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-7f4f - 180 - 349 + 179 + 324 @@ -1016,7 +1016,7 @@ $(pv_value) Text Update_15 0 false - /cfs/cf/CF_HkPacket_t.App.TotalFailedTrans + /cfs/$(CPUID)/cf/CF_HkPacket_t.App.TotalFailedTrans 0.0 @@ -1037,8 +1037,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-7f4e - 180 - 368 + 179 + 343 @@ -1068,7 +1068,7 @@ $(pv_value) Text Update_16 0 false - /cfs/cf/CF_HkPacket_t.App.TotalAbandonTrans + /cfs/$(CPUID)/cf/CF_HkPacket_t.App.TotalAbandonTrans 0.0 @@ -1089,8 +1089,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-7f4d - 180 - 387 + 179 + 362 @@ -1120,7 +1120,7 @@ $(pv_value) Text Update_17 0 false - /cfs/cf/CF_HkPacket_t.App.TotalSuccessTrans + /cfs/$(CPUID)/cf/CF_HkPacket_t.App.TotalSuccessTrans 0.0 @@ -1141,8 +1141,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-7f4c - 180 - 406 + 179 + 381 @@ -1172,7 +1172,7 @@ $(pv_value) Text Update_18 0 false - /cfs/cf/CF_HkPacket_t.App.TotalCompletedTrans + /cfs/$(CPUID)/cf/CF_HkPacket_t.App.TotalCompletedTrans 0.0 @@ -1193,8 +1193,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-7f4b - 180 - 425 + 179 + 400 @@ -1222,7 +1222,7 @@ $(pv_value) 20 Text Update_20 - /cfs/cf/CF_HkPacket_t.AutoSuspend.EnFlag + /cfs/$(CPUID)/cf/CF_HkPacket_t.AutoSuspend.EnFlag @@ -1240,8 +1240,8 @@ $(pv_value) Check Box 32 31ffe3bf:150a7259bb9:-7f49 - 164 - 492 + 163 + 467 @@ -1271,7 +1271,7 @@ $(pv_value) Text Update_21 0 false - /cfs/cf/CF_HkPacket_t.AutoSuspend.LowFreeMark + /cfs/$(CPUID)/cf/CF_HkPacket_t.AutoSuspend.LowFreeMark 0.0 @@ -1292,8 +1292,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-7f48 - 180 - 463 + 179 + 438 @@ -1332,8 +1332,8 @@ $(pv_value) 142 false 31ffe3bf:150a7259bb9:-7e9f - 28 - 121 + 27 + 96 @@ -1372,8 +1372,8 @@ $(pv_value) 129 false 31ffe3bf:150a7259bb9:-7e95 - 41 - 140 + 40 + 115 @@ -1412,8 +1412,8 @@ $(pv_value) 129 false 31ffe3bf:150a7259bb9:-7e90 - 41 - 159 + 40 + 134 @@ -1452,8 +1452,8 @@ $(pv_value) 129 false 31ffe3bf:150a7259bb9:-7e8b - 41 - 178 + 40 + 153 @@ -1492,8 +1492,8 @@ $(pv_value) 129 false 31ffe3bf:150a7259bb9:-7e86 - 41 - 197 + 40 + 172 @@ -1532,8 +1532,8 @@ $(pv_value) 129 false 31ffe3bf:150a7259bb9:-7e81 - 41 - 216 + 40 + 191 @@ -1572,8 +1572,8 @@ $(pv_value) 129 false 31ffe3bf:150a7259bb9:-7e7c - 41 - 235 + 40 + 210 @@ -1612,8 +1612,8 @@ $(pv_value) 129 false 31ffe3bf:150a7259bb9:-7e77 - 41 - 254 + 40 + 229 @@ -1652,8 +1652,8 @@ $(pv_value) 129 false 31ffe3bf:150a7259bb9:-7e72 - 41 - 273 + 40 + 248 @@ -1692,8 +1692,8 @@ $(pv_value) 160 false 31ffe3bf:150a7259bb9:-7e6d - 10 - 292 + 9 + 267 @@ -1732,8 +1732,8 @@ $(pv_value) 129 false 31ffe3bf:150a7259bb9:-7e68 - 41 - 311 + 40 + 286 @@ -1772,8 +1772,8 @@ $(pv_value) 129 false 31ffe3bf:150a7259bb9:-7e63 - 41 - 330 + 40 + 305 @@ -1812,8 +1812,8 @@ $(pv_value) 129 false 31ffe3bf:150a7259bb9:-7e5e - 41 - 349 + 40 + 324 @@ -1852,8 +1852,8 @@ $(pv_value) 129 false 31ffe3bf:150a7259bb9:-7e59 - 41 - 368 + 40 + 343 @@ -1892,8 +1892,8 @@ $(pv_value) 129 false 31ffe3bf:150a7259bb9:-7e54 - 41 - 387 + 40 + 362 @@ -1932,8 +1932,8 @@ $(pv_value) 129 false 31ffe3bf:150a7259bb9:-7e4f - 41 - 406 + 40 + 381 @@ -1972,8 +1972,8 @@ $(pv_value) 142 false 31ffe3bf:150a7259bb9:-7e4a - 28 - 425 + 27 + 400 @@ -2012,8 +2012,8 @@ $(pv_value) 129 false 31ffe3bf:150a7259bb9:-7e45 - 41 - 444 + 40 + 419 @@ -2052,8 +2052,8 @@ $(pv_value) 142 false 31ffe3bf:150a7259bb9:-7e40 - 8 - 492 + 7 + 467 @@ -2092,8 +2092,8 @@ $(pv_value) 116 false 31ffe3bf:150a7259bb9:-7e3b - 54 - 463 + 53 + 438 @@ -2102,7 +2102,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cf/AutoSuspendEn', {'EnableDisable': 'ENABLE'});]]> true @@ -2148,8 +2148,8 @@ $(pv_value) Action Button 87 31ffe3bf:150a7259bb9:-6aa2 - 195 - 492 + 194 + 467 @@ -2158,7 +2158,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cf/AutoSuspendEn', {'EnableDisable': 'DISABLE'});]]> true @@ -2204,8 +2204,8 @@ $(pv_value) Action Button 87 31ffe3bf:150a7259bb9:-6a98 - 281 - 492 + 280 + 467 @@ -2235,7 +2235,7 @@ $(pv_value) Text Update_19 0 false - /cfs/cf/CF_HkPacket_t.App.LastFailedTrans + /cfs/$(CPUID)/cf/CF_HkPacket_t.App.LastFailedTrans 0.0 @@ -2256,8 +2256,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-7f4a - 180 - 444 + 179 + 419 @@ -2311,8 +2311,8 @@ $(pv_value) Action Button 67 6c5e5e62:1775b7b9abc:-7bdc - 288 - 159 + 287 + 134 @@ -2322,7 +2322,7 @@ $(pv_value) importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); -Yamcs.issueCommand('/cfs/cf/ResetCounters', {'Value': 'CMD', 'Spare_0_': 0, 'Spare_1_': 0, 'Spare_2_': 0}); +Yamcs.issueCommand('/cfs/$(CPUID)/cf/ResetCounters', {'Value': 'CMD', 'Spare_0_': 0, 'Spare_1_': 0, 'Spare_2_': 0}); ]]> true @@ -2369,7 +2369,7 @@ $(pv_value) Action Button 85 6c5e5e62:1775b7b9abc:-7b99 - 282 - 74 + 281 + 49 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/Cancel.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/Cancel.opi index fc0eece1e..7b89b1b64 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/Cancel.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/Cancel.opi @@ -19,7 +19,7 @@ true - CF - Cancel + ($(CPUID)) CF - Cancel true @@ -28,7 +28,7 @@ true true Display - 260 + 270 31ffe3bf:150a7259bb9:-6563 -1 -1 @@ -139,7 +139,7 @@ importPackage(Packages.org.yamcs.studio.data); var Transaction = VTypeHelper.getString(display.getWidget('Transaction').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cf/Cancel', {'Trans': Transaction}); +Yamcs.issueCommand('/cfs/$(CPUID)/cf/Cancel', {'Trans': Transaction}); ]]> true @@ -217,16 +217,16 @@ $(pv_value) false - Cancel Transaction + ($(CPUID)) CF - Cancel Transaction true 1 true Label - 168 + 259 false 6c5e5e62:1775b7b9abc:-70f2 - 52 + 6 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/DeleteQueueNode.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/DeleteQueueNode.opi index 6ee07d150..05846d334 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/DeleteQueueNode.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/DeleteQueueNode.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Dequeue Node + ($(CPUID)) CF - Dequeue Node true @@ -139,7 +139,7 @@ importPackage(Packages.org.yamcs.studio.data); var Transaction = VTypeHelper.getString(display.getWidget('Transaction').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cf/DequeueNode', {'Trans': Transaction}); +Yamcs.issueCommand('/cfs/$(CPUID)/cf/DequeueNode', {'Trans': Transaction}); ]]> true @@ -217,16 +217,16 @@ $(pv_value) false - Dequeue Node + ($(CPUID)) CF - Dequeue Node true 1 true Label - 190 + 235 false 6c5e5e62:1775b7b9abc:-715c - 36 + 12 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/DisableDequeue.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/DisableDequeue.opi index 1e5066de2..7e944a840 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/DisableDequeue.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/DisableDequeue.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Disable Dequeue + ($(CPUID)) CF - Disable Dequeue true @@ -50,7 +50,7 @@ if( Channel == 'Channel 1' ) { pChannel = 2; } -Yamcs.issueCommand('/cfs/cf/DisableDequeue', { +Yamcs.issueCommand('/cfs/$(CPUID)/cf/DisableDequeue', { 'Chan': pChannel, 'Spare_0_': 0, 'Spare_1_': 0, @@ -223,16 +223,16 @@ $(pv_value) false - Disable Dequeue + ($(CPUID)) CF - Disable Dequeue true 1 true Label - 199 + 269 false 6c5e5e62:1775b7b9abc:-7231 - 48 + 14 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/DisablePollingDirectory.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/DisablePollingDirectory.opi index 407becd7d..a43cd0819 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/DisablePollingDirectory.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/DisablePollingDirectory.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Disable Polling Directory + ($(CPUID)) CF - Disable Polling Directory true @@ -51,7 +51,7 @@ if( Channel == 'Channel 1' ) { pChannel = 2; } -Yamcs.issueCommand('/cfs/cf/DisableDirPolling', { +Yamcs.issueCommand('/cfs/$(CPUID)/cf/DisableDirPolling', { 'Chan': pChannel, 'Dir': Dir, 'Spare_0_': 0, @@ -319,16 +319,16 @@ $(pv_value) false - Disable Polling Directory + ($(CPUID)) CF - Disable Polling Directory true 1 true Label - 186 + 305 false 6c5e5e62:1775b7b9abc:-71f0 - 84 + 26 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/Downlink.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/Downlink.opi index ebe5eb4f1..a3790a84e 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/Downlink.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/Downlink.opi @@ -10,16 +10,16 @@ - 1.5.3 + 1.5.5.202103012118 6 - 610 + 550 true - CF - Downlink + ($(CPUID)) CF - Downlink true @@ -100,7 +100,7 @@ Text Update_47 0 false - /cfs/cf/CF_HkPacket_t.Chan_0_.PDUsSent + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_0_.PDUsSent 0.0 @@ -152,7 +152,7 @@ $(pv_value) Text Update_48 0 false - /cfs/cf/CF_HkPacket_t.Chan_0_.FilesSent + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_0_.FilesSent 0.0 @@ -204,7 +204,7 @@ $(pv_value) Text Update_49 0 false - /cfs/cf/CF_HkPacket_t.Chan_0_.SuccessCounter + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_0_.SuccessCounter 0.0 @@ -256,7 +256,7 @@ $(pv_value) Text Update_50 0 false - /cfs/cf/CF_HkPacket_t.Chan_0_.FailedCounter + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_0_.FailedCounter 0.0 @@ -308,7 +308,7 @@ $(pv_value) Text Update_51 0 false - /cfs/cf/CF_HkPacket_t.Chan_0_.PendingQFileCnt + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_0_.PendingQFileCnt 0.0 @@ -360,7 +360,7 @@ $(pv_value) Text Update_52 0 false - /cfs/cf/CF_HkPacket_t.Chan_0_.ActiveQFileCnt + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_0_.ActiveQFileCnt 0.0 @@ -412,7 +412,7 @@ $(pv_value) Text Update_53 0 false - /cfs/cf/CF_HkPacket_t.Chan_0_.HistoryQFileCnt + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_0_.HistoryQFileCnt 0.0 @@ -462,7 +462,7 @@ $(pv_value) 20 Text Update_54 - /cfs/cf/CF_HkPacket_t.Chan_0_.Flags + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_0_.Flags @@ -509,7 +509,7 @@ $(pv_value) 20 Text Update_55 - /cfs/cf/CF_HkPacket_t.Chan_1_.Flags + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_1_.Flags @@ -558,7 +558,7 @@ $(pv_value) Text Update_56 0 false - /cfs/cf/CF_HkPacket_t.Chan_0_.RedLightCntr + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_0_.RedLightCntr 0.0 @@ -610,7 +610,7 @@ $(pv_value) Text Update_57 0 false - /cfs/cf/CF_HkPacket_t.Chan_0_.GreenLightCntr + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_0_.GreenLightCntr 0.0 @@ -662,7 +662,7 @@ $(pv_value) Text Update_58 0 false - /cfs/cf/CF_HkPacket_t.Chan_0_.PollDirsChecked + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_0_.PollDirsChecked 0.0 @@ -714,7 +714,7 @@ $(pv_value) Text Update_59 0 false - /cfs/cf/CF_HkPacket_t.Chan_0_.PendingQChecked + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_0_.PendingQChecked 0.0 @@ -766,7 +766,7 @@ $(pv_value) Text Update_60 0 false - /cfs/cf/CF_HkPacket_t.Chan_0_.SemValue + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_0_.SemValue 0.0 @@ -1378,7 +1378,7 @@ $(pv_value) Text Update_61 0 false - /cfs/cf/CF_HkPacket_t.Chan_1_.PDUsSent + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_1_.PDUsSent 0.0 @@ -1430,7 +1430,7 @@ $(pv_value) Text Update_62 0 false - /cfs/cf/CF_HkPacket_t.Chan_1_.FilesSent + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_1_.FilesSent 0.0 @@ -1482,7 +1482,7 @@ $(pv_value) Text Update_63 0 false - /cfs/cf/CF_HkPacket_t.Chan_1_.SuccessCounter + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_1_.SuccessCounter 0.0 @@ -1534,7 +1534,7 @@ $(pv_value) Text Update_64 0 false - /cfs/cf/CF_HkPacket_t.Chan_1_.FailedCounter + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_1_.FailedCounter 0.0 @@ -1586,7 +1586,7 @@ $(pv_value) Text Update_65 0 false - /cfs/cf/CF_HkPacket_t.Chan_1_.PendingQFileCnt + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_1_.PendingQFileCnt 0.0 @@ -1638,7 +1638,7 @@ $(pv_value) Text Update_66 0 false - /cfs/cf/CF_HkPacket_t.Chan_1_.ActiveQFileCnt + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_1_.ActiveQFileCnt 0.0 @@ -1690,7 +1690,7 @@ $(pv_value) Text Update_67 0 false - /cfs/cf/CF_HkPacket_t.Chan_1_.HistoryQFileCnt + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_1_.HistoryQFileCnt 0.0 @@ -1740,7 +1740,7 @@ $(pv_value) 20 Text Update_68 - /cfs/cf/CF_HkPacket_t.Chan_1_.Flags + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_1_.Flags @@ -1787,7 +1787,7 @@ $(pv_value) 20 Text Update_69 - /cfs/cf/CF_HkPacket_t.Chan_1_.Flags + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_1_.Flags @@ -1836,7 +1836,7 @@ $(pv_value) Text Update_70 0 false - /cfs/cf/CF_HkPacket_t.Chan_1_.RedLightCntr + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_1_.RedLightCntr 0.0 @@ -1888,7 +1888,7 @@ $(pv_value) Text Update_71 0 false - /cfs/cf/CF_HkPacket_t.Chan_1_.GreenLightCntr + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_1_.GreenLightCntr 0.0 @@ -1940,7 +1940,7 @@ $(pv_value) Text Update_72 0 false - /cfs/cf/CF_HkPacket_t.Chan_1_.PollDirsChecked + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_1_.PollDirsChecked 0.0 @@ -1992,7 +1992,7 @@ $(pv_value) Text Update_73 0 false - /cfs/cf/CF_HkPacket_t.Chan_1_.PendingQChecked + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_1_.PendingQChecked 0.0 @@ -2044,7 +2044,7 @@ $(pv_value) Text Update_74 0 false - /cfs/cf/CF_HkPacket_t.Chan_1_.SemValue + /cfs/$(CPUID)/cf/CF_HkPacket_t.Chan_1_.SemValue 0.0 @@ -2156,7 +2156,7 @@ $(pv_value) importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); -Yamcs.issueCommand('/cfs/cf/ResetCounters', {'Value': 'DOWN', 'Spare_0_': 0, 'Spare_1_': 0, 'Spare_2_': 0}); +Yamcs.issueCommand('/cfs/$(CPUID)/cf/ResetCounters', {'Value': 'DOWN', 'Spare_0_': 0, 'Spare_1_': 0, 'Spare_2_': 0}); ]]> true @@ -2234,16 +2234,16 @@ $(pv_value) false - Downlink + ($(CPUID)) CF - Downlink true 1 true Label - 164 + 246 false 6c5e5e62:1775b7b9abc:-7b77 - 113 + 66 12 diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/EnableDequeue.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/EnableDequeue.opi index c41d65460..b7d58d131 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/EnableDequeue.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/EnableDequeue.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Enable Dequeue + ($(CPUID)) CF - Enable Dequeue true @@ -50,7 +50,7 @@ if( Channel == 'Channel 1' ) { pChannel = 2; } -Yamcs.issueCommand('/cfs/cf/EnableDequeue', { +Yamcs.issueCommand('/cfs/$(CPUID)/cf/EnableDequeue', { 'Chan': pChannel, 'Spare_0_': 0, 'Spare_1_': 0, @@ -223,16 +223,16 @@ $(pv_value) false - Enable Dequeue + ($(CPUID)) CF - Enable Dequeue true 1 true Label - 199 + 241 false 6c5e5e62:1775b7b9abc:-724e - 42 + 24 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/EnablePollingDirectory.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/EnablePollingDirectory.opi index cfeaacf10..15ed10548 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/EnablePollingDirectory.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/EnablePollingDirectory.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Enable Poll Dir + ($(CPUID)) CF - Enable Poll Dir true @@ -51,7 +51,7 @@ if( Channel == 'Channel 1' ) { pChannel = 2; } -Yamcs.issueCommand('/cfs/cf/EnableDirPolling', { +Yamcs.issueCommand('/cfs/$(CPUID)/cf/EnableDirPolling', { 'Chan': pChannel, 'Dir': Dir, 'Spare_0_': 0, @@ -319,16 +319,16 @@ $(pv_value) false - Enable Polling Directory + ($(CPUID)) CF - Enable Polling Directory true 1 true Label - 186 + 307 false 6c5e5e62:1775b7b9abc:-7255 - 76 + 18 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/Engine.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/Engine.opi index 0ac555cbc..842a43ecc 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/Engine.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/Engine.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Engine + ($(CPUID)) CF - Engine true @@ -60,16 +60,16 @@ false - Engine + ($(CPUID)) CF - Engine true 1 true Label - 175 + 298 false 763e00b7:150973f1dd8:-7cf4 - 72 + 12 12 @@ -100,7 +100,7 @@ Text Update_30 0 false - /cfs/cf/CF_HkPacket_t.Eng.FlightEngineEntityId + /cfs/$(CPUID)/cf/CF_HkPacket_t.Eng.FlightEngineEntityId 0.0 @@ -190,7 +190,7 @@ $(pv_value) 20 Check Box - /cfs/cf/CF_HkPacket_t.Eng.Flags + /cfs/$(CPUID)/cf/CF_HkPacket_t.Eng.Flags @@ -237,7 +237,7 @@ $(pv_value) 20 Check Box_1 - /cfs/cf/CF_HkPacket_t.Eng.Flags + /cfs/$(CPUID)/cf/CF_HkPacket_t.Eng.Flags @@ -284,7 +284,7 @@ $(pv_value) 20 Check Box_2 - /cfs/cf/CF_HkPacket_t.Eng.Flags + /cfs/$(CPUID)/cf/CF_HkPacket_t.Eng.Flags @@ -331,7 +331,7 @@ $(pv_value) 20 Check Box_3 - /cfs/cf/CF_HkPacket_t.Eng.Flags + /cfs/$(CPUID)/cf/CF_HkPacket_t.Eng.Flags @@ -378,7 +378,7 @@ $(pv_value) 20 Check Box_5 - /cfs/cf/CF_HkPacket_t.Eng.Flags + /cfs/$(CPUID)/cf/CF_HkPacket_t.Eng.Flags @@ -425,7 +425,7 @@ $(pv_value) 20 Check Box_4 - /cfs/cf/CF_HkPacket_t.Eng.Flags + /cfs/$(CPUID)/cf/CF_HkPacket_t.Eng.Flags @@ -472,7 +472,7 @@ $(pv_value) 20 Check Box_6 - /cfs/cf/CF_HkPacket_t.Eng.Flags + /cfs/$(CPUID)/cf/CF_HkPacket_t.Eng.Flags @@ -519,7 +519,7 @@ $(pv_value) 20 Check Box_7 - /cfs/cf/CF_HkPacket_t.Eng.Flags + /cfs/$(CPUID)/cf/CF_HkPacket_t.Eng.Flags @@ -566,7 +566,7 @@ $(pv_value) 20 Check Box_8 - /cfs/cf/CF_HkPacket_t.Eng.Flags + /cfs/$(CPUID)/cf/CF_HkPacket_t.Eng.Flags @@ -975,7 +975,7 @@ $(pv_value) Text Update_31 0 false - /cfs/cf/CF_HkPacket_t.Eng.MachinesAllocated + /cfs/$(CPUID)/cf/CF_HkPacket_t.Eng.MachinesAllocated 0.0 @@ -1027,7 +1027,7 @@ $(pv_value) Text Update_32 0 false - /cfs/cf/CF_HkPacket_t.Eng.MachinesDeallocated + /cfs/$(CPUID)/cf/CF_HkPacket_t.Eng.MachinesDeallocated 0.0 @@ -1079,7 +1079,7 @@ $(pv_value) Text Update_33 0 false - /cfs/cf/CF_HkPacket_t.Eng.are_any_partners_frozen + /cfs/$(CPUID)/cf/CF_HkPacket_t.Eng.are_any_partners_frozen 0.0 @@ -1131,7 +1131,7 @@ $(pv_value) Text Update_34 0 false - /cfs/cf/CF_HkPacket_t.Eng.how_many_senders + /cfs/$(CPUID)/cf/CF_HkPacket_t.Eng.how_many_senders 0.0 @@ -1183,7 +1183,7 @@ $(pv_value) Text Update_35 0 false - /cfs/cf/CF_HkPacket_t.Eng.how_many_receivers + /cfs/$(CPUID)/cf/CF_HkPacket_t.Eng.how_many_receivers 0.0 @@ -1235,7 +1235,7 @@ $(pv_value) Text Update_36 0 false - /cfs/cf/CF_HkPacket_t.Eng.how_many_frozen + /cfs/$(CPUID)/cf/CF_HkPacket_t.Eng.how_many_frozen 0.0 @@ -1287,7 +1287,7 @@ $(pv_value) Text Update_37 0 false - /cfs/cf/CF_HkPacket_t.Eng.how_many_suspended + /cfs/$(CPUID)/cf/CF_HkPacket_t.Eng.how_many_suspended 0.0 @@ -1339,7 +1339,7 @@ $(pv_value) Text Update_38 0 false - /cfs/cf/CF_HkPacket_t.Eng.total_files_sent + /cfs/$(CPUID)/cf/CF_HkPacket_t.Eng.total_files_sent 0.0 @@ -1391,7 +1391,7 @@ $(pv_value) Text Update_39 0 false - /cfs/cf/CF_HkPacket_t.Eng.total_files_received + /cfs/$(CPUID)/cf/CF_HkPacket_t.Eng.total_files_received 0.0 @@ -1443,7 +1443,7 @@ $(pv_value) Text Update_40 0 false - /cfs/cf/CF_HkPacket_t.Eng.total_unsuccessful_senders + /cfs/$(CPUID)/cf/CF_HkPacket_t.Eng.total_unsuccessful_senders 0.0 @@ -1495,7 +1495,7 @@ $(pv_value) Text Update_41 0 false - /cfs/cf/CF_HkPacket_t.Eng.total_unsuccessful_receivers + /cfs/$(CPUID)/cf/CF_HkPacket_t.Eng.total_unsuccessful_receivers 0.0 @@ -1967,7 +1967,7 @@ $(pv_value) importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); -Yamcs.issueCommand('/cfs/cf/Freeze', {}); +Yamcs.issueCommand('/cfs/$(CPUID)/cf/Freeze', {}); ]]> true @@ -2025,7 +2025,7 @@ $(pv_value) importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); -Yamcs.issueCommand('/cfs/cf/Thaw', {});]]> +Yamcs.issueCommand('/cfs/$(CPUID)/cf/Thaw', {});]]> true diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/Faults.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/Faults.opi index d0cca8b43..5da7f2058 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/Faults.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/Faults.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Faults + ($(CPUID)) CF - Faults true @@ -60,7 +60,7 @@ false - Faults + ($(CPUID)) CF - Faults true 1 @@ -100,7 +100,7 @@ Text Update_22 0 false - /cfs/cf/CF_HkPacket_t.Cond.PosAckNum + /cfs/$(CPUID)/cf/CF_HkPacket_t.Cond.PosAckNum 0.0 @@ -152,7 +152,7 @@ $(pv_value) Text Update_23 0 false - /cfs/cf/CF_HkPacket_t.Cond.FileStoreRejNum + /cfs/$(CPUID)/cf/CF_HkPacket_t.Cond.FileStoreRejNum 0.0 @@ -204,7 +204,7 @@ $(pv_value) Text Update_24 0 false - /cfs/cf/CF_HkPacket_t.Cond.FileChecksumNum + /cfs/$(CPUID)/cf/CF_HkPacket_t.Cond.FileChecksumNum 0.0 @@ -256,7 +256,7 @@ $(pv_value) Text Update_25 0 false - /cfs/cf/CF_HkPacket_t.Cond.FileSizeNum + /cfs/$(CPUID)/cf/CF_HkPacket_t.Cond.FileSizeNum 0.0 @@ -308,7 +308,7 @@ $(pv_value) Text Update_26 0 false - /cfs/cf/CF_HkPacket_t.Cond.NakLimitNum + /cfs/$(CPUID)/cf/CF_HkPacket_t.Cond.NakLimitNum 0.0 @@ -360,7 +360,7 @@ $(pv_value) Text Update_27 0 false - /cfs/cf/CF_HkPacket_t.Cond.InactiveNum + /cfs/$(CPUID)/cf/CF_HkPacket_t.Cond.InactiveNum 0.0 @@ -412,7 +412,7 @@ $(pv_value) Text Update_28 0 false - /cfs/cf/CF_HkPacket_t.Cond.SuspendNum + /cfs/$(CPUID)/cf/CF_HkPacket_t.Cond.SuspendNum 0.0 @@ -464,7 +464,7 @@ $(pv_value) Text Update_29 0 false - /cfs/cf/CF_HkPacket_t.Cond.CancelNum + /cfs/$(CPUID)/cf/CF_HkPacket_t.Cond.CancelNum 0.0 @@ -816,7 +816,7 @@ $(pv_value) importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); -Yamcs.issueCommand('/cfs/cf/ResetCounters', {'Value': 'FAULT', 'Spare_0_': 0, 'Spare_1_': 0, 'Spare_2_': 0}); +Yamcs.issueCommand('/cfs/$(CPUID)/cf/ResetCounters', {'Value': 'FAULT', 'Spare_0_': 0, 'Spare_1_': 0, 'Spare_2_': 0}); ]]> true diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/GetMIBParam.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/GetMIBParam.opi index 548344c08..609731189 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/GetMIBParam.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/GetMIBParam.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Get MIB Param + ($(CPUID)) CF - Get MIB Param true @@ -28,7 +28,7 @@ true true Display - 250 + 260 31ffe3bf:150a7259bb9:-673d -1 -1 @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var Parameter =VTypeHelper.getString(display.getWidget('Parameter').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cf/GetMIBParameter', {'Param': Parameter}); +Yamcs.issueCommand('/cfs/$(CPUID)/cf/GetMIBParameter', {'Param': Parameter}); ]]> true @@ -218,16 +218,16 @@ $(pv_value) false - Get MIB Parameter + ($(CPUID)) CF - Get MIB Parameter true 1 true Label - 157 + 247 false 6c5e5e62:1775b7b9abc:-7260 - 51 + 6 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/GiveTake.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/GiveTake.opi index 76f2e494e..b6cd7a892 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/GiveTake.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/GiveTake.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Give/Take + ($(CPUID)) CF - Give/Take true @@ -50,7 +50,7 @@ if( Channel == 'Channel 1' ) { pChannel = 1; } -Yamcs.issueCommand('/cfs/cf/GiveTake', { +Yamcs.issueCommand('/cfs/$(CPUID)/cf/GiveTake', { 'Chan': pChannel, 'GiveOrTakeSemaphore': 'GIVE'}); @@ -211,7 +211,7 @@ if( Channel == 'Channel 1' ) { pChannel = 1; } -Yamcs.issueCommand('/cfs/cf/GiveTake', { +Yamcs.issueCommand('/cfs/$(CPUID)/cf/GiveTake', { 'Chan': pChannel, 'GiveOrTakeSemaphore': 'TAKE'}); @@ -292,16 +292,16 @@ $(pv_value) false - Give / Take Semaphore + ($(CPUID)) CF - Give / Take Semaphore true 1 true Label - 229 + 283 false 6c5e5e62:1775b7b9abc:-7267 - 30 + 6 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/Kickstart.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/Kickstart.opi index 7b1532508..75954ddd6 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/Kickstart.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/Kickstart.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Kickstart + ($(CPUID)) CF - Kickstart true @@ -50,7 +50,7 @@ if( Channel == 'Channel 1' ) { pChannel = 1; } -Yamcs.issueCommand('/cfs/cf/Kickstart', { +Yamcs.issueCommand('/cfs/$(CPUID)/cf/Kickstart', { 'Chan': pChannel, 'Spare_0_': 0, 'Spare_1_': 0, @@ -222,16 +222,16 @@ $(pv_value) false - Kickstart + ($(CPUID)) CF - Kickstart true 1 true Label - 113 + 272 false 6c5e5e62:1775b7b9abc:-728c - 88 + 17 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/Main.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/Main.opi index bfce8a380..f3920f7ef 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/Main.opi @@ -10,7 +10,7 @@ - 1.5.5.202103152011 + 1.6.2.202104092231 @@ -23,7 +23,7 @@ Displays /modules/cf - CF + ($(CPUID)) CF true @@ -32,7 +32,7 @@ true true Display - 500 + 340 45ea5983:1502a6e6386:-7f06 -1 -1 @@ -64,16 +64,16 @@ false - CCSDS File Transfer Application + ($(CPUID)) CCSDS File Transfer Application true 1 true Label - 229 + 325 false 763e00b7:150973f1dd8:-7cf4 - 42 + 12 12 @@ -128,7 +128,7 @@ $(pv_value) Action Button 113 31ffe3bf:150a7259bb9:-75f0 - 18 + 60 42 @@ -183,7 +183,7 @@ $(pv_value) Action Button 113 31ffe3bf:150a7259bb9:-75dd - 18 + 60 66 @@ -238,7 +238,7 @@ $(pv_value) Action Button 113 31ffe3bf:150a7259bb9:-75d6 - 18 + 60 89 @@ -293,7 +293,7 @@ $(pv_value) Action Button 113 31ffe3bf:150a7259bb9:-75cf - 18 + 60 112 @@ -348,7 +348,7 @@ $(pv_value) Action Button 113 31ffe3bf:150a7259bb9:-6f00 - 18 + 60 135 @@ -358,7 +358,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cf/SendHK', {});]]> true @@ -404,7 +404,7 @@ $(pv_value) Action Button 127 5e28a52b:177681d8a5c:-7a51 - 144 + 186 114 @@ -414,7 +414,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cf/WakeUp', {});]]> true @@ -460,7 +460,7 @@ $(pv_value) Action Button 127 5e28a52b:177681d8a5c:-7a49 - 144 + 186 133 @@ -521,7 +521,68 @@ $(pv_value) Action Button 127 -19107c2b:177da1db5df:-e22 - 144 + 186 42 + + + + + + true + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 25 + + AppControl + 0 + + + + + true + true + false + + + + App Control + false + $(pv_name) +$(pv_value) + true + Action Button + 127 + 49c9ccd0:178c6a335db:-6ed1 + 186 + 64 + \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/PlaybackDirectory.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/PlaybackDirectory.opi index 47b2af314..a58e26df8 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/PlaybackDirectory.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/PlaybackDirectory.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Playback Dir + ($(CPUID)) CF - Playback Dir true @@ -71,7 +71,7 @@ if( Preserve == 'Delete' ) { pPreserve = 'KEEP'; } -Yamcs.issueCommand('/cfs/cf/PlaybackDirectory', { +Yamcs.issueCommand('/cfs/$(CPUID)/cf/PlaybackDirectory', { 'Class': pTransferClass, 'Chan': pChannel, 'Priority': Priority, @@ -812,16 +812,16 @@ $(pv_value) false - Playback Directory + ($(CPUID)) CF - Playback Directory true 1 true Label - 145 + 397 false 6c5e5e62:1775b7b9abc:-72c1 - 129 + 12 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/PlaybackFile.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/PlaybackFile.opi index 5b844c5d3..83749f4f5 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/PlaybackFile.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/PlaybackFile.opi @@ -10,16 +10,16 @@ - 1.5.3 + 1.5.5.202103012118 6 - 270 + 260 true - CF - Playback File + ($(CPUID)) CF - Playback File true @@ -70,7 +70,7 @@ if( Preserve == 'Delete' ) { pPreserve = 'KEEP'; } -Yamcs.issueCommand('/cfs/cf/PlaybackFile', { +Yamcs.issueCommand('/cfs/$(CPUID)/cf/PlaybackFile', { 'Class': pTransferClass, 'Channel': pChannel, 'Priority': Priority, @@ -124,8 +124,8 @@ $(pv_value) Action Button 80 31ffe3bf:150a7259bb9:-670a - 169 - 228 + 168 + 222 @@ -811,16 +811,16 @@ $(pv_value) false - Playback File + ($(CPUID)) CF - Playback File true 1 true Label - 113 + 391 false 6c5e5e62:1775b7b9abc:-72ee - 152 + 12 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/PurgeQueue.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/PurgeQueue.opi index 9ae1ac521..c4f714ad7 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/PurgeQueue.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/PurgeQueue.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Purge Queue + ($(CPUID)) CF - Purge Queue true @@ -68,7 +68,7 @@ if( Queue == 'Pending' ) { pQueue = 'HISTORY'; } -Yamcs.issueCommand('/cfs/cf/PurgeQueue', { +Yamcs.issueCommand('/cfs/$(CPUID)/cf/PurgeQueue', { 'Type': pTransferType, 'Chan': pChannel, 'Queue': pQueue, @@ -518,16 +518,16 @@ $(pv_value) false - Purge Queue + ($(CPUID)) CF - Purge Queue true 1 true Label - 113 + 307 false 6c5e5e62:1775b7b9abc:-732c - 109 + 12 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/QuickStatus.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/QuickStatus.opi index a4a8ea127..5d49786ae 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/QuickStatus.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/QuickStatus.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Quick Status + ($(CPUID)) CF - Quick Status true @@ -139,7 +139,7 @@ importPackage(Packages.org.yamcs.studio.data); var Transaction =VTypeHelper.getString(display.getWidget('Transaction').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cf/QuickStat', {'Trans': Transaction}); +Yamcs.issueCommand('/cfs/$(CPUID)/cf/QuickStat', {'Trans': Transaction}); ]]> true @@ -218,16 +218,16 @@ $(pv_value) false - Quick Status + ($(CPUID)) CF - Quick Status true 1 true Label - 104 + 231 false 6c5e5e62:1775b7b9abc:-7348 - 72 + 10 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/ResetCounters.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/ResetCounters.opi index a653996b2..7a94c1fa5 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/ResetCounters.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/ResetCounters.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Reset Counters + ($(CPUID)) CF - Reset Counters true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var counters =VTypeHelper.getString(display.getWidget('Counters').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cf/ResetCounters', {'Value': counters, 'Spare_0_': 0, 'Spare_1_': 0, 'Spare_2_': 0}); +Yamcs.issueCommand('/cfs/$(CPUID)/cf/ResetCounters', {'Value': counters, 'Spare_0_': 0, 'Spare_1_': 0, 'Spare_2_': 0}); ]]> true @@ -153,7 +153,7 @@ $(pv_value) - 32 + 30 ALL CMD @@ -209,16 +209,16 @@ $(pv_value) false - Reset Counters + ($(CPUID)) CF - Reset Counters true 1 true Label - 137 + 253 false 6c5e5e62:1775b7b9abc:-7bca - 67 + 12 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/Resume.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/Resume.opi index 82eae11a1..faa87590f 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/Resume.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/Resume.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Resume Transaction + ($(CPUID)) CF - Resume Transaction true @@ -28,7 +28,7 @@ true true Display - 250 + 280 31ffe3bf:150a7259bb9:-6563 -1 -1 @@ -139,7 +139,7 @@ importPackage(Packages.org.yamcs.studio.data); var Transaction =VTypeHelper.getString(display.getWidget('Transaction').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cf/Resume', {'Trans': Transaction}); +Yamcs.issueCommand('/cfs/$(CPUID)/cf/Resume', {'Trans': Transaction}); ]]> true @@ -218,16 +218,16 @@ $(pv_value) false - Resume Transaction + ($(CPUID)) CF -Resume Transaction true 1 true Label - 151 + 259 false 6c5e5e62:1775b7b9abc:-7362 - 48 + 12 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/SetCyclesPerWakeup.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/SetCyclesPerWakeup.opi index 5784c5878..7d8a1a5e2 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/SetCyclesPerWakeup.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/SetCyclesPerWakeup.opi @@ -15,11 +15,11 @@ 6 - 600 + 120 true - CF - Set Cycles + ($(CPUID)) CF - Set Cycles true @@ -28,7 +28,7 @@ true true Display - 800 + 300 -10965483:1776e5e5496:-5786 -1 -1 @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var cycles = VTypeHelper.getDouble(display.getWidget('Spinner').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cf/SetCyclesPerWakeup', {'NumCyclesPerWakeup': cycles}); +Yamcs.issueCommand('/cfs/$(CPUID)/cf/SetCyclesPerWakeup', {'NumCyclesPerWakeup': cycles}); ]]> true @@ -160,7 +160,7 @@ $(pv_value) false - NumCyclesPerWakeup + Num Cycles Per Wakeup true 1 @@ -224,7 +224,7 @@ $(pv_value) Spinner 85 -10965483:1776e5e5496:-56b2 - 186 + 192 45 @@ -255,16 +255,16 @@ $(pv_value) false - Set Cycles + ($(CPUID)) CF - Set Cycles Per Wakeup true 1 true Label - 151 + 283 false -10965483:1776e5e5496:-54db - 42 + 12 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/SetMIBParam.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/SetMIBParam.opi index 8f4957871..891718759 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/SetMIBParam.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/SetMIBParam.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Set MIB Param + ($(CPUID)) CF - Set MIB Param true @@ -28,7 +28,7 @@ true true Display - 250 + 270 31ffe3bf:150a7259bb9:-673d -1 -1 @@ -43,7 +43,7 @@ importPackage(Packages.org.yamcs.studio.data); var Parameter =VTypeHelper.getString(display.getWidget('Parameter').getPropertyValue('pv_value')); var Value =VTypeHelper.getString(display.getWidget('Value').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cf/SetMIBParameter', { +Yamcs.issueCommand('/cfs/$(CPUID)/cf/SetMIBParameter', { 'Param': Parameter, 'Value': Value}); ]]> @@ -308,7 +308,7 @@ $(pv_value) 20 - 2 + 1 Label_2 @@ -317,16 +317,16 @@ $(pv_value) false - Set MIB Parameter + ($(CPUID)) CF - Set MIB Parameter true 1 true Label - 131 + 265 false 6c5e5e62:1775b7b9abc:-7378 - 60 + 6 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/SetPollParam.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/SetPollParam.opi index 3c898512a..a9f5b7bad 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/SetPollParam.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/SetPollParam.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Set Poll Params + ($(CPUID)) CF - Set Poll Params true @@ -71,7 +71,7 @@ if( Preserve == 'Delete' ) { pPreserve = 'KEEP'; } -Yamcs.issueCommand('/cfs/cf/SetPollParameter', { +Yamcs.issueCommand('/cfs/$(CPUID)/cf/SetPollParameter', { 'Chan': pChannel, 'Dir': Dir, 'Class': pTransferClass, @@ -911,16 +911,16 @@ $(pv_value) false - Set Polling Parameters + ($(CPUID)) CF - Set Polling Parameters true 1 true Label - 189 + 283 false 6c5e5e62:1775b7b9abc:-7388 - 106 + 60 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/Suspend.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/Suspend.opi index 66158e174..b1435a847 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/Suspend.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/Suspend.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Suspend + ($(CPUID)) CF - Suspend true @@ -28,7 +28,7 @@ true true Display - 250 + 280 31ffe3bf:150a7259bb9:-6563 -1 -1 @@ -66,7 +66,7 @@ 1 true Label - 95 + 83 false 31ffe3bf:150a7259bb9:-6541 6 @@ -124,9 +124,9 @@ $(pv_value) false true Text Input - 121 + 163 31ffe3bf:150a7259bb9:-6540 - 114 + 102 42 @@ -139,7 +139,7 @@ importPackage(Packages.org.yamcs.studio.data); var Transaction =VTypeHelper.getString(display.getWidget('Transaction').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cf/Suspend', {'Trans': Transaction}); +Yamcs.issueCommand('/cfs/$(CPUID)/cf/Suspend', {'Trans': Transaction}); ]]> true @@ -187,7 +187,7 @@ $(pv_value) Action Button 80 31ffe3bf:150a7259bb9:-652c - 82 + 88 72 @@ -209,7 +209,7 @@ $(pv_value) 20 - 2 + 1 Label_1 @@ -218,16 +218,16 @@ $(pv_value) false - Suspend Transaction + ($(CPUID)) CF - Suspend Transaction true 1 true Label - 147 + 277 false 6c5e5e62:1775b7b9abc:-739a - 48 + 6 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/Uplink.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/Uplink.opi index b0470f3fe..a4d09970a 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/Uplink.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/Uplink.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Uplink + ($(CPUID)) CF - Uplink true @@ -40,7 +40,7 @@ importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); -Yamcs.issueCommand('/cfs/cf/ResetCounters', {'Value': 'UP', 'Spare_0_': 0, 'Spare_1_': 0, 'Spare_2_': 0}); +Yamcs.issueCommand('/cfs/$(CPUID)/cf/ResetCounters', {'Value': 'UP', 'Spare_0_': 0, 'Spare_1_': 0, 'Spare_2_': 0}); ]]> true @@ -118,7 +118,7 @@ $(pv_value) false - Uplink + ($(CPUID)) CF - Uplink true 1 @@ -158,7 +158,7 @@ $(pv_value) Text Update_42 0 false - /cfs/cf/CF_HkPacket_t.Up.MetaCount + /cfs/$(CPUID)/cf/CF_HkPacket_t.Up.MetaCount 0.0 @@ -210,7 +210,7 @@ $(pv_value) Text Update_43 0 false - /cfs/cf/CF_HkPacket_t.Up.UplinkActiveQFileCnt + /cfs/$(CPUID)/cf/CF_HkPacket_t.Up.UplinkActiveQFileCnt 0.0 @@ -262,7 +262,7 @@ $(pv_value) Text Update_44 0 false - /cfs/cf/CF_HkPacket_t.Up.SuccessCounter + /cfs/$(CPUID)/cf/CF_HkPacket_t.Up.SuccessCounter 0.0 @@ -314,7 +314,7 @@ $(pv_value) Text Update_45 0 false - /cfs/cf/CF_HkPacket_t.Up.FailedCounter + /cfs/$(CPUID)/cf/CF_HkPacket_t.Up.FailedCounter 0.0 @@ -366,7 +366,7 @@ $(pv_value) Text Update_46 0 false - /cfs/cf/CF_HkPacket_t.Up.LastFileUplinked + /cfs/$(CPUID)/cf/CF_HkPacket_t.Up.LastFileUplinked 0.0 diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/ViewConfig.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/ViewConfig.opi index b3795a17e..32ab80cbb 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/ViewConfig.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/ViewConfig.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Config Data + ($(CPUID)) CF - Config Data true @@ -39,7 +39,7 @@ true @@ -118,7 +118,7 @@ $(pv_value) Text Update 0 false - /cfs/cf/CF_ConfigPacket_t.EngCycPerWakeup + /cfs/$(CPUID)/cf/CF_ConfigPacket_t.EngCycPerWakeup 0.0 @@ -170,7 +170,7 @@ $(pv_value) Text Update_1 0 false - /cfs/cf/CF_ConfigPacket_t.AckLimit + /cfs/$(CPUID)/cf/CF_ConfigPacket_t.AckLimit 0.0 @@ -222,7 +222,7 @@ $(pv_value) Text Update_2 0 false - /cfs/cf/CF_ConfigPacket_t.AckTimeout + /cfs/$(CPUID)/cf/CF_ConfigPacket_t.AckTimeout 0.0 @@ -274,7 +274,7 @@ $(pv_value) Text Update_3 0 false - /cfs/cf/CF_ConfigPacket_t.NakLimit + /cfs/$(CPUID)/cf/CF_ConfigPacket_t.NakLimit 0.0 @@ -326,7 +326,7 @@ $(pv_value) Text Update_4 0 false - /cfs/cf/CF_ConfigPacket_t.NakTimeout + /cfs/$(CPUID)/cf/CF_ConfigPacket_t.NakTimeout 0.0 @@ -378,7 +378,7 @@ $(pv_value) Text Update_5 0 false - /cfs/cf/CF_ConfigPacket_t.InactTimeout + /cfs/$(CPUID)/cf/CF_ConfigPacket_t.InactTimeout 0.0 @@ -430,7 +430,7 @@ $(pv_value) Text Update_6 0 false - /cfs/cf/CF_ConfigPacket_t.DefOutgoingChunkSize + /cfs/$(CPUID)/cf/CF_ConfigPacket_t.DefOutgoingChunkSize 0.0 @@ -482,7 +482,7 @@ $(pv_value) Text Update_7 0 false - /cfs/cf/CF_ConfigPacket_t.PipeDepth + /cfs/$(CPUID)/cf/CF_ConfigPacket_t.PipeDepth 0.0 @@ -534,7 +534,7 @@ $(pv_value) Text Update_8 0 false - /cfs/cf/CF_ConfigPacket_t.MaxSimultaneousTrans + /cfs/$(CPUID)/cf/CF_ConfigPacket_t.MaxSimultaneousTrans 0.0 @@ -586,7 +586,7 @@ $(pv_value) Text Update_9 0 false - /cfs/cf/CF_ConfigPacket_t.IncomingPduBufSize + /cfs/$(CPUID)/cf/CF_ConfigPacket_t.IncomingPduBufSize 0.0 @@ -638,7 +638,7 @@ $(pv_value) Text Update_10 0 false - /cfs/cf/CF_ConfigPacket_t.OutgoingPduBufSize + /cfs/$(CPUID)/cf/CF_ConfigPacket_t.OutgoingPduBufSize 0.0 @@ -690,7 +690,7 @@ $(pv_value) Text Update_11 0 false - /cfs/cf/CF_ConfigPacket_t.NumInputChannels + /cfs/$(CPUID)/cf/CF_ConfigPacket_t.NumInputChannels 0.0 @@ -742,7 +742,7 @@ $(pv_value) Text Update_12 0 false - /cfs/cf/CF_ConfigPacket_t.MaxPlaybackChans + /cfs/$(CPUID)/cf/CF_ConfigPacket_t.MaxPlaybackChans 0.0 @@ -794,7 +794,7 @@ $(pv_value) Text Update_13 0 false - /cfs/cf/CF_ConfigPacket_t.MaxPollingDirsPerChan + /cfs/$(CPUID)/cf/CF_ConfigPacket_t.MaxPollingDirsPerChan 0.0 @@ -846,7 +846,7 @@ $(pv_value) Text Update_14 0 false - /cfs/cf/CF_ConfigPacket_t.MemPoolBytes + /cfs/$(CPUID)/cf/CF_ConfigPacket_t.MemPoolBytes 0.0 @@ -898,7 +898,7 @@ $(pv_value) Text Update_15 0 false - /cfs/cf/CF_ConfigPacket_t.DebugCompiledIn + /cfs/$(CPUID)/cf/CF_ConfigPacket_t.DebugCompiledIn 0.0 @@ -950,7 +950,7 @@ $(pv_value) Text Update_16 0 false - /cfs/cf/CF_ConfigPacket_t.SaveIncompleteFiles + /cfs/$(CPUID)/cf/CF_ConfigPacket_t.SaveIncompleteFiles 0.0 @@ -1002,7 +1002,7 @@ $(pv_value) Text Update_17 0 false - /cfs/cf/CF_ConfigPacket_t.PipeName + /cfs/$(CPUID)/cf/CF_ConfigPacket_t.PipeName 0.0 @@ -1054,7 +1054,7 @@ $(pv_value) Text Update_18 0 false - /cfs/cf/CF_ConfigPacket_t.TmpFilePrefix + /cfs/$(CPUID)/cf/CF_ConfigPacket_t.TmpFilePrefix 0.0 @@ -1106,7 +1106,7 @@ $(pv_value) Text Update_19 0 false - /cfs/cf/CF_ConfigPacket_t.CfgTblName + /cfs/$(CPUID)/cf/CF_ConfigPacket_t.CfgTblName 0.0 @@ -1158,7 +1158,7 @@ $(pv_value) Text Update_20 0 false - /cfs/cf/CF_ConfigPacket_t.CfgTbleFilename + /cfs/$(CPUID)/cf/CF_ConfigPacket_t.CfgTbleFilename 0.0 @@ -1210,7 +1210,7 @@ $(pv_value) Text Update_21 0 false - /cfs/cf/CF_ConfigPacket_t.DefQInfoFilename + /cfs/$(CPUID)/cf/CF_ConfigPacket_t.DefQInfoFilename 0.0 @@ -2142,16 +2142,16 @@ $(pv_value) false - Config Data + ($(CPUID)) CF - Config Data true 1 true Label - 142 + 265 false 6c5e5e62:1775b7b9abc:-73d1 - 131 + 60 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/ViewTransDiag.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/ViewTransDiag.opi index ab5fefaf5..4055ca12f 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/ViewTransDiag.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/ViewTransDiag.opi @@ -10,16 +10,16 @@ - 1.5.3 + 1.5.5.202103012118 6 - 840 + 600 true - CF - View Transaction + ($(CPUID)) CF - View Transaction true @@ -28,7 +28,7 @@ true true Display - 265 + 500 31ffe3bf:150a7259bb9:-64b0 -1 -1 @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var Transfer =VTypeHelper.getString(display.getWidget('Transfer').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cf/SendTransaction', {'Trans': Transfer}); +Yamcs.issueCommand('/cfs/$(CPUID)/cf/SendTransaction', {'Trans': Transfer}); ]]> true @@ -90,7 +90,7 @@ $(pv_value) Action Button 91 31ffe3bf:150a7259bb9:-6429 - 97 + 204 78 @@ -121,7 +121,7 @@ $(pv_value) Text Update 0 false - /cfs/cf/CF_TransPacket_t.Eng.TransLen + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.TransLen 0.0 @@ -142,8 +142,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63da - 150 - 390 + 136 + 144 @@ -173,7 +173,7 @@ $(pv_value) Text Update_1 0 false - /cfs/cf/CF_TransPacket_t.Eng.TransVal + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.TransVal 0.0 @@ -194,8 +194,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63d9 - 150 - 409 + 136 + 163 @@ -225,7 +225,7 @@ $(pv_value) Text Update_2 0 false - /cfs/cf/CF_TransPacket_t.Eng.Naks + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.Naks 0.0 @@ -246,8 +246,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63d8 - 150 - 428 + 136 + 182 @@ -277,7 +277,7 @@ $(pv_value) Text Update_3 0 false - /cfs/cf/CF_TransPacket_t.Eng.PartLen + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.PartLen 0.0 @@ -298,8 +298,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63d7 - 150 - 447 + 136 + 201 @@ -329,7 +329,7 @@ $(pv_value) Text Update_4 0 false - /cfs/cf/CF_TransPacket_t.Eng.PartVal + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.PartVal 0.0 @@ -350,8 +350,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63d6 - 150 - 466 + 136 + 220 @@ -381,7 +381,7 @@ $(pv_value) Text Update_5 0 false - /cfs/cf/CF_TransPacket_t.Eng.Phase + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.Phase 0.0 @@ -402,8 +402,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63d5 - 150 - 485 + 136 + 239 @@ -431,7 +431,7 @@ $(pv_value) 20 Text Update_6 - /cfs/cf/CF_TransPacket_t.Eng.Flags + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.Flags @@ -449,8 +449,8 @@ $(pv_value) Check Box 100 31ffe3bf:150a7259bb9:-63d4 - 150 - 504 + 136 + 258 @@ -480,7 +480,7 @@ $(pv_value) Text Update_7 0 false - /cfs/cf/CF_TransPacket_t.Eng.TransNum + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.TransNum 0.0 @@ -501,8 +501,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63d3 - 150 - 523 + 136 + 277 @@ -532,7 +532,7 @@ $(pv_value) Text Update_8 0 false - /cfs/cf/CF_TransPacket_t.Eng.Attempts + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.Attempts 0.0 @@ -553,8 +553,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63d2 - 150 - 542 + 136 + 296 @@ -584,7 +584,7 @@ $(pv_value) Text Update_9 0 false - /cfs/cf/CF_TransPacket_t.Eng.CondCode + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.CondCode 0.0 @@ -605,8 +605,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63d1 - 150 - 561 + 136 + 315 @@ -636,7 +636,7 @@ $(pv_value) Text Update_10 0 false - /cfs/cf/CF_TransPacket_t.Eng.DeliCode + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.DeliCode 0.0 @@ -657,8 +657,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63d0 - 150 - 580 + 136 + 334 @@ -688,7 +688,7 @@ $(pv_value) Text Update_11 0 false - /cfs/cf/CF_TransPacket_t.Eng.FdOffset + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.FdOffset 0.0 @@ -709,8 +709,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63cf - 150 - 599 + 136 + 353 @@ -740,7 +740,7 @@ $(pv_value) Text Update_12 0 false - /cfs/cf/CF_TransPacket_t.Eng.FdLength + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.FdLength 0.0 @@ -761,8 +761,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63ce - 150 - 618 + 136 + 372 @@ -792,7 +792,7 @@ $(pv_value) Text Update_13 0 false - /cfs/cf/CF_TransPacket_t.Eng.Checksum + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.Checksum 0.0 @@ -813,8 +813,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63cd - 150 - 637 + 136 + 391 @@ -844,7 +844,7 @@ $(pv_value) Text Update_14 0 false - /cfs/cf/CF_TransPacket_t.Eng.FinalStat + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.FinalStat 0.0 @@ -865,8 +865,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63cc - 150 - 656 + 136 + 410 @@ -896,7 +896,7 @@ $(pv_value) Text Update_15 0 false - /cfs/cf/CF_TransPacket_t.Eng.FileSize + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.FileSize 0.0 @@ -917,8 +917,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63cb - 150 - 675 + 136 + 429 @@ -948,7 +948,7 @@ $(pv_value) Text Update_16 0 false - /cfs/cf/CF_TransPacket_t.Eng.RcvdFileSize + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.RcvdFileSize 0.0 @@ -969,8 +969,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63ca - 150 - 694 + 136 + 448 @@ -1000,7 +1000,7 @@ $(pv_value) Text Update_17 0 false - /cfs/cf/CF_TransPacket_t.Eng.Role + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.Role 0.0 @@ -1021,8 +1021,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63c9 - 150 - 713 + 136 + 467 @@ -1052,7 +1052,7 @@ $(pv_value) Text Update_18 0 false - /cfs/cf/CF_TransPacket_t.Eng.State + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.State 0.0 @@ -1073,8 +1073,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63c8 - 150 - 732 + 136 + 486 @@ -1104,7 +1104,7 @@ $(pv_value) Text Update_19 0 false - /cfs/cf/CF_TransPacket_t.Eng.StartTime + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.StartTime 0.0 @@ -1125,8 +1125,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63c7 - 150 - 751 + 136 + 505 @@ -1156,7 +1156,7 @@ $(pv_value) Text Update_20 0 false - /cfs/cf/CF_TransPacket_t.Eng.SrcFile + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.SrcFile 0.0 @@ -1177,8 +1177,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63c6 - 150 - 770 + 136 + 524 @@ -1208,7 +1208,7 @@ $(pv_value) Text Update_21 0 false - /cfs/cf/CF_TransPacket_t.Eng.DstFile + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.DstFile 0.0 @@ -1229,8 +1229,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63c5 - 150 - 789 + 136 + 543 @@ -1260,7 +1260,7 @@ $(pv_value) Text Update_22 0 false - /cfs/cf/CF_TransPacket_t.Eng.TmpFile + /cfs/$(CPUID)/cf/CF_TransPacket_t.Eng.TmpFile 0.0 @@ -1281,8 +1281,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63c4 - 150 - 808 + 136 + 562 @@ -1312,7 +1312,7 @@ $(pv_value) Text Update_23 0 false - /cfs/cf/CF_TransPacket_t.App.Status + /cfs/$(CPUID)/cf/CF_TransPacket_t.App.Status 0.0 @@ -1333,8 +1333,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63c3 - 150 - 138 + 378 + 144 @@ -1364,7 +1364,7 @@ $(pv_value) Text Update_24 0 false - /cfs/cf/CF_TransPacket_t.App.CondCode + /cfs/$(CPUID)/cf/CF_TransPacket_t.App.CondCode 0.0 @@ -1385,8 +1385,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63c2 - 150 - 157 + 378 + 163 @@ -1416,7 +1416,7 @@ $(pv_value) Text Update_25 0 false - /cfs/cf/CF_TransPacket_t.App.Priority + /cfs/$(CPUID)/cf/CF_TransPacket_t.App.Priority 0.0 @@ -1437,8 +1437,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63c1 - 150 - 176 + 378 + 182 @@ -1468,7 +1468,7 @@ $(pv_value) Text Update_26 0 false - /cfs/cf/CF_TransPacket_t.App.Class + /cfs/$(CPUID)/cf/CF_TransPacket_t.App.Class 0.0 @@ -1489,8 +1489,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63c0 - 150 - 195 + 378 + 201 @@ -1520,7 +1520,7 @@ $(pv_value) Text Update_27 0 false - /cfs/cf/CF_TransPacket_t.App.ChanNum + /cfs/$(CPUID)/cf/CF_TransPacket_t.App.ChanNum 0.0 @@ -1541,8 +1541,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63bf - 150 - 214 + 378 + 220 @@ -1572,7 +1572,7 @@ $(pv_value) Text Update_28 0 false - /cfs/cf/CF_TransPacket_t.App.Source + /cfs/$(CPUID)/cf/CF_TransPacket_t.App.Source 0.0 @@ -1593,8 +1593,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63be - 150 - 233 + 378 + 239 @@ -1624,7 +1624,7 @@ $(pv_value) Text Update_29 0 false - /cfs/cf/CF_TransPacket_t.App.NodeType + /cfs/$(CPUID)/cf/CF_TransPacket_t.App.NodeType 0.0 @@ -1645,8 +1645,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63bd - 150 - 252 + 378 + 258 @@ -1676,7 +1676,7 @@ $(pv_value) Text Update_30 0 false - /cfs/cf/CF_TransPacket_t.App.TransNum + /cfs/$(CPUID)/cf/CF_TransPacket_t.App.TransNum 0.0 @@ -1697,8 +1697,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63bc - 150 - 271 + 378 + 277 @@ -1728,7 +1728,7 @@ $(pv_value) Text Update_31 0 false - /cfs/cf/CF_TransPacket_t.App.Source + /cfs/$(CPUID)/cf/CF_TransPacket_t.App.Source 0.0 @@ -1749,8 +1749,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63bb - 150 - 290 + 378 + 296 @@ -1780,7 +1780,7 @@ $(pv_value) Text Update_32 0 false - /cfs/cf/CF_TransPacket_t.App.SrcFile + /cfs/$(CPUID)/cf/CF_TransPacket_t.App.SrcFile 0.0 @@ -1801,8 +1801,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63ba - 150 - 309 + 378 + 315 @@ -1832,7 +1832,7 @@ $(pv_value) Text Update_33 0 false - /cfs/cf/CF_TransPacket_t.App.DstFile + /cfs/$(CPUID)/cf/CF_TransPacket_t.App.DstFile 0.0 @@ -1853,8 +1853,8 @@ $(pv_value) 100 false 31ffe3bf:150a7259bb9:-63b9 - 150 - 328 + 378 + 334 @@ -1893,8 +1893,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-636f - 36 - 390 + 22 + 144 @@ -1933,8 +1933,8 @@ $(pv_value) 80 false 31ffe3bf:150a7259bb9:-6346 - 108 - 114 + 336 + 120 @@ -1973,8 +1973,8 @@ $(pv_value) 80 false 31ffe3bf:150a7259bb9:-633e - 108 - 366 + 94 + 120 @@ -2013,8 +2013,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-6332 - 36 - 409 + 22 + 163 @@ -2053,8 +2053,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-632d - 36 - 428 + 22 + 182 @@ -2093,8 +2093,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-6328 - 36 - 447 + 22 + 201 @@ -2133,8 +2133,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-6323 - 36 - 466 + 22 + 220 @@ -2173,8 +2173,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-631e - 36 - 485 + 22 + 239 @@ -2213,8 +2213,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-6307 - 36 - 504 + 22 + 258 @@ -2253,8 +2253,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-6306 - 36 - 523 + 22 + 277 @@ -2293,8 +2293,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-6305 - 36 - 542 + 22 + 296 @@ -2333,8 +2333,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-6304 - 36 - 561 + 22 + 315 @@ -2373,8 +2373,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-6303 - 36 - 580 + 22 + 334 @@ -2413,8 +2413,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-6302 - 36 - 599 + 22 + 353 @@ -2453,8 +2453,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-62d9 - 36 - 618 + 22 + 372 @@ -2493,8 +2493,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-62d8 - 36 - 637 + 22 + 391 @@ -2533,8 +2533,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-62d7 - 36 - 656 + 22 + 410 @@ -2573,8 +2573,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-62d6 - 36 - 675 + 22 + 429 @@ -2613,8 +2613,8 @@ $(pv_value) 127 false 31ffe3bf:150a7259bb9:-62d5 - 18 - 694 + 4 + 448 @@ -2653,8 +2653,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-62d4 - 36 - 713 + 22 + 467 @@ -2693,8 +2693,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-62d3 - 36 - 732 + 22 + 486 @@ -2733,8 +2733,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-62d2 - 36 - 751 + 22 + 505 @@ -2773,8 +2773,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-62d1 - 36 - 770 + 22 + 524 @@ -2813,8 +2813,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-62d0 - 36 - 789 + 22 + 543 @@ -2853,8 +2853,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-62cf - 36 - 808 + 22 + 562 @@ -2893,8 +2893,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-619b - 36 - 138 + 264 + 144 @@ -2933,8 +2933,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-6193 - 36 - 157 + 264 + 163 @@ -2973,8 +2973,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-6188 - 36 - 176 + 264 + 182 @@ -3013,8 +3013,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-6187 - 36 - 195 + 264 + 201 @@ -3053,8 +3053,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-6176 - 36 - 214 + 264 + 220 @@ -3093,8 +3093,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-6175 - 36 - 233 + 264 + 239 @@ -3133,8 +3133,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-6174 - 36 - 252 + 264 + 258 @@ -3173,8 +3173,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-613c - 36 - 271 + 264 + 277 @@ -3213,8 +3213,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-613b - 36 - 290 + 264 + 296 @@ -3253,8 +3253,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-613a - 36 - 309 + 264 + 315 @@ -3293,8 +3293,8 @@ $(pv_value) 109 false 31ffe3bf:150a7259bb9:-6139 - 36 - 328 + 264 + 334 @@ -3333,7 +3333,7 @@ $(pv_value) 78 false 31ffe3bf:150a7259bb9:-60d3 - 17 + 94 42 @@ -3388,9 +3388,9 @@ $(pv_value) false true Text Input - 135 + 199 31ffe3bf:150a7259bb9:-60d2 - 108 + 185 42 @@ -3421,16 +3421,16 @@ $(pv_value) false - View Transaction Diag + ($(CPUID)) CF - View Transaction Diag true 1 true Label - 188 + 284 false 6c5e5e62:1775b7b9abc:-73e2 - 36 + 94 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/WriteActiveTrans.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/WriteActiveTrans.opi index a701ae3a2..fe9dc2ba7 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/WriteActiveTrans.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/WriteActiveTrans.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CF - Write Active Trans + ($(CPUID)) CF - Write Active Trans true @@ -53,7 +53,7 @@ if( TransferType == 'All' ) { pTransferType = 'DOWN'; } -Yamcs.issueCommand('/cfs/cf/WriteActiveTrans', { +Yamcs.issueCommand('/cfs/$(CPUID)/cf/WriteActiveTrans', { 'Type': pTransferType, 'Spare': 0, 'Filename': Destination}); @@ -322,16 +322,16 @@ $(pv_value) false - Write Active Transaction + ($(CPUID)) CF - Write Active Transaction true 1 true Label - 201 + 307 false 6c5e5e62:1775b7b9abc:-73fa - 68 + 12 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CF/WriteQueueInfo.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CF/WriteQueueInfo.opi index 309d066d0..58bccd198 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CF/WriteQueueInfo.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CF/WriteQueueInfo.opi @@ -19,7 +19,7 @@ true - CF - Write Queue Info + ($(CPUID)) CF - Write Queue Info true @@ -69,7 +69,7 @@ if( Queue == 'Pending' ) { pQueue = 'HISTORY'; } -Yamcs.issueCommand('/cfs/cf/WriteQueue', { +Yamcs.issueCommand('/cfs/$(CPUID)/cf/WriteQueue', { 'Type': pTransferType, 'Chan': pChannel, 'Queue': pQueue, @@ -521,16 +521,16 @@ $(pv_value) false - Write Queue Information + ($(CPUID)) CF - Write Queue Information true 1 true Label - 201 + 283 false 6c5e5e62:1775b7b9abc:-6369 - 60 + 12 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CI/AuthorizeCommand.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CI/AuthorizeCommand.opi index d515243c4..5838e8048 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CI/AuthorizeCommand.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CI/AuthorizeCommand.opi @@ -15,11 +15,11 @@ 6 - 300 + 150 true - CI - Auth + ($(CPUID)) CI - Auth true @@ -87,7 +87,7 @@ $(pv_value) 100 4d40612f:17772f0c845:-7fc5 120 - 60 + 36 @@ -117,16 +117,16 @@ $(pv_value) false - Authorize Command + ($(CPUID)) CI - Authorize Command true 1 true Label - 192 + 265 false 4d40612f:17772f0c845:-7fb9 - 62 + 6 12 @@ -157,7 +157,7 @@ $(pv_value) false - msgID + MsgID true 1 @@ -167,7 +167,7 @@ $(pv_value) false 4d40612f:17772f0c845:-7fad 36 - 63 + 39 @@ -224,7 +224,7 @@ $(pv_value) 100 4d40612f:17772f0c845:-7f9d 120 - 96 + 72 @@ -254,7 +254,7 @@ $(pv_value) false - cmdCode + Cmd Code true 1 @@ -264,7 +264,7 @@ $(pv_value) false 4d40612f:17772f0c845:-7f9c 36 - 99 + 75 @@ -277,7 +277,7 @@ importPackage(Packages.org.yamcs.studio.data); var msgID =VTypeHelper.getString(display.getWidget('msgIdInput').getPropertyValue('pv_value')); var cmdCode =VTypeHelper.getString(display.getWidget('cmdCodeInput').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/ci/AuthorizeCmd', +Yamcs.issueCommand('/cfs/$(CPUID)/ci/AuthorizeCmd', {'msgID': msgID, 'cmdCode': cmdCode } @@ -327,7 +327,7 @@ $(pv_value) Action Button 105 4d40612f:17772f0c845:-7f4c - 105 - 144 + 108 + 114 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CI/DeauthorizeCommand.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CI/DeauthorizeCommand.opi index 2bb2dda89..b7db6d6de 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CI/DeauthorizeCommand.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CI/DeauthorizeCommand.opi @@ -15,11 +15,11 @@ 6 - 300 + 160 true - CI - Deauth + ($(CPUID)) CI - Deauth true @@ -86,8 +86,8 @@ $(pv_value) Text Input 100 4d40612f:17772f0c845:-7eef - 106 - 72 + 114 + 42 @@ -117,17 +117,17 @@ $(pv_value) false - Deauthorize Command + ($(CPUID)) CI - Deauthorize Command true 1 true Label - 192 + 271 false 4d40612f:17772f0c845:-7eee - 48 - 24 + 12 + 12 @@ -157,7 +157,7 @@ $(pv_value) false - msgID + MsgID true 1 @@ -166,8 +166,8 @@ $(pv_value) 80 false 4d40612f:17772f0c845:-7eed - 22 - 75 + 30 + 45 @@ -223,8 +223,8 @@ $(pv_value) Text Input 100 4d40612f:17772f0c845:-7eec - 106 - 108 + 114 + 78 @@ -254,7 +254,7 @@ $(pv_value) false - cmdCode + Cmd Code true 1 @@ -263,8 +263,8 @@ $(pv_value) 80 false 4d40612f:17772f0c845:-7eeb - 22 - 111 + 30 + 81 @@ -277,7 +277,7 @@ importPackage(Packages.org.yamcs.studio.data); var msgID =VTypeHelper.getString(display.getWidget('msgIdInput').getPropertyValue('pv_value')); var cmdCode =VTypeHelper.getString(display.getWidget('cmdCodeInput').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/ci/DeauthorizeCmd', +Yamcs.issueCommand('/cfs/$(CPUID)/ci/DeauthorizeCmd', {'msgID': msgID, 'cmdCode': cmdCode } @@ -327,7 +327,7 @@ $(pv_value) Action Button 105 4d40612f:17772f0c845:-7eea - 91 - 156 + 95 + 120 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CI/DeregisterCommand.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CI/DeregisterCommand.opi index 0ed22230d..498152eab 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CI/DeregisterCommand.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CI/DeregisterCommand.opi @@ -15,11 +15,11 @@ 6 - 600 + 240 true - CI - Dereg + ($(CPUID)) CI - Dereg true @@ -28,7 +28,7 @@ true true Display - 800 + 300 4d40612f:17772f0c845:-7d45 -1 -1 @@ -86,8 +86,8 @@ $(pv_value) Text Input 134 4d40612f:17772f0c845:-7d17 - 112 - 78 + 108 + 42 @@ -117,17 +117,17 @@ $(pv_value) false - Deregister Command + ($(CPUID)) CI - Deregister Command true 1 true Label - 192 + 267 false 4d40612f:17772f0c845:-7d16 - 54 - 30 + 16 + 12 @@ -157,7 +157,7 @@ $(pv_value) false - msgID + MsgID true 1 @@ -166,8 +166,8 @@ $(pv_value) 80 false 4d40612f:17772f0c845:-7d15 - 28 - 81 + 24 + 45 @@ -223,8 +223,8 @@ $(pv_value) Text Input 134 4d40612f:17772f0c845:-7d14 - 112 - 114 + 108 + 78 @@ -254,7 +254,7 @@ $(pv_value) false - cmdCode + Cmd Code true 1 @@ -263,8 +263,8 @@ $(pv_value) 80 false 4d40612f:17772f0c845:-7d13 - 28 - 117 + 24 + 81 @@ -308,7 +308,7 @@ else if(Log == 'LOG') } -Yamcs.issueCommand('/cfs/ci/DeregisterCmd', +Yamcs.issueCommand('/cfs/$(CPUID)/ci/DeregisterCmd', {'msgID': msgID, 'cmdCode': cmdCode, 'step': StepVal, @@ -360,8 +360,8 @@ $(pv_value) Action Button 105 4d40612f:17772f0c845:-7d12 - 97 - 234 + 93 + 198 @@ -406,8 +406,8 @@ $(pv_value) Combo 134 4d40612f:17772f0c845:-7d11 - 112 - 150 + 108 + 114 @@ -446,8 +446,8 @@ $(pv_value) 80 false 4d40612f:17772f0c845:-7d10 - 28 - 153 + 24 + 117 @@ -486,8 +486,8 @@ $(pv_value) 80 false 4d40612f:17772f0c845:-7d0f - 28 - 189 + 24 + 153 @@ -532,7 +532,7 @@ $(pv_value) Combo 134 4d40612f:17772f0c845:-7d0e - 112 - 189 + 108 + 153 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CI/Main.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CI/Main.opi index 519dc6af9..af43038a7 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CI/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CI/Main.opi @@ -10,7 +10,7 @@ - 1.5.5.202103162101 + 1.6.2.202104092231 @@ -23,7 +23,7 @@ Displays /modules/ci - CI + ($(CPUID)) CI true @@ -64,7 +64,7 @@ Text Update 0 false - /cfs/ci/CI_HkTlm_t.usCmdCnt + /cfs/$(CPUID)/ci/CI_HkTlm_t.usCmdCnt 0.0 @@ -196,7 +196,7 @@ $(pv_value) Text Update_1 0 false - /cfs/ci/CI_HkTlm_t.usCmdErrCnt + /cfs/$(CPUID)/ci/CI_HkTlm_t.usCmdErrCnt 0.0 @@ -227,7 +227,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/ci/Noop', {});]]> true @@ -251,7 +251,7 @@ Yamcs.issueCommand('/cfs/ci/Noop', {});]]> - 18 + 20 ../../Resources/send.png NoOp 0 @@ -274,7 +274,7 @@ $(pv_value) 74 -33cb7c72:150aa4c347f:-75fa 223 - 37 + 36 @@ -283,7 +283,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/ci/Reset', {});]]> true @@ -307,7 +307,7 @@ Yamcs.issueCommand('/cfs/ci/Reset', {});]]> - 17 + 20 ../../Resources/send.png NoOp_1 0 @@ -330,7 +330,7 @@ $(pv_value) 74 -33cb7c72:150aa4c347f:-75f9 223 - 58 + 55 @@ -360,16 +360,16 @@ $(pv_value) false - Command Ingest + ($(CPUID)) Command Ingest true 1 true Label - 192 + 270 false -33cb7c72:150aa4c347f:-75c9 - 72 + 37 6 @@ -480,7 +480,7 @@ $(pv_value) Text Update_2 0 false - /cfs/ci/CI_HkTlm_t.IngestMsgCount + /cfs/$(CPUID)/ci/CI_HkTlm_t.IngestMsgCount 0.0 @@ -532,7 +532,7 @@ $(pv_value) Text Update_3 0 false - /cfs/ci/CI_HkTlm_t.IngestErrorCount + /cfs/$(CPUID)/ci/CI_HkTlm_t.IngestErrorCount 0.0 @@ -624,7 +624,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/ci/ProcessTimeouts', {});]]> true @@ -680,7 +680,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/ci/WakeUp', {});]]> true @@ -729,4 +729,65 @@ $(pv_value) 198 181 + + + + + + true + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 27 + + AppControl + 0 + + + + + true + true + false + + + + App Control + false + $(pv_name) +$(pv_value) + true + Action Button + 156 + 49c9ccd0:178c6a335db:-733d + 18 + 180 + \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CI/RegisterCommand.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CI/RegisterCommand.opi index 9e2d6a6d3..174880c0f 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CI/RegisterCommand.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CI/RegisterCommand.opi @@ -15,11 +15,11 @@ 6 - 300 + 240 true - CI - Reg + ($(CPUID)) CI - Reg true @@ -86,8 +86,8 @@ $(pv_value) Text Input 134 4d40612f:17772f0c845:-7e8b - 106 - 72 + 108 + 42 @@ -117,17 +117,17 @@ $(pv_value) false - Register Command + ($(CPUID)) CI - Register Command true 1 true Label - 192 + 277 false 4d40612f:17772f0c845:-7e8a - 48 - 24 + 12 + 12 @@ -157,7 +157,7 @@ $(pv_value) false - msgID + MsgID true 1 @@ -166,8 +166,8 @@ $(pv_value) 80 false 4d40612f:17772f0c845:-7e89 - 22 - 75 + 24 + 45 @@ -223,8 +223,8 @@ $(pv_value) Text Input 134 4d40612f:17772f0c845:-7e88 - 106 - 108 + 108 + 78 @@ -254,7 +254,7 @@ $(pv_value) false - cmdCode + Cmd Code true 1 @@ -263,8 +263,8 @@ $(pv_value) 80 false 4d40612f:17772f0c845:-7e87 - 22 - 111 + 24 + 81 @@ -308,7 +308,7 @@ else if(Log == 'LOG') } -Yamcs.issueCommand('/cfs/ci/RegisterCmd', +Yamcs.issueCommand('/cfs/$(CPUID)/ci/RegisterCmd', {'msgID': msgID, 'cmdCode': cmdCode, 'step': StepVal, @@ -360,8 +360,8 @@ $(pv_value) Action Button 105 4d40612f:17772f0c845:-7e86 - 91 - 228 + 93 + 198 @@ -406,8 +406,8 @@ $(pv_value) Combo 134 4d40612f:17772f0c845:-7e59 - 106 - 144 + 108 + 114 @@ -446,8 +446,8 @@ $(pv_value) 80 false 4d40612f:17772f0c845:-7e58 - 22 - 147 + 24 + 117 @@ -486,8 +486,8 @@ $(pv_value) 80 false 4d40612f:17772f0c845:-7e56 - 22 - 183 + 24 + 153 @@ -532,7 +532,7 @@ $(pv_value) Combo 134 4d40612f:17772f0c845:-7da1 - 106 - 183 + 108 + 153 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CI/UpdateCommand.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CI/UpdateCommand.opi index 3c13d862a..ac6831b9a 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CI/UpdateCommand.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CI/UpdateCommand.opi @@ -15,11 +15,11 @@ 6 - 300 + 240 true - CI - Update + ($(CPUID)) CI - Update true @@ -86,8 +86,8 @@ $(pv_value) Text Input 134 4d40612f:17772f0c845:-7e8b - 106 - 72 + 108 + 42 @@ -117,17 +117,17 @@ $(pv_value) false - Update Command + ($(CPUID)) CI - Update Command true 1 true Label - 192 + 271 false 4d40612f:17772f0c845:-7e8a - 48 - 24 + 12 + 12 @@ -157,7 +157,7 @@ $(pv_value) false - msgID + MsgID true 1 @@ -166,8 +166,8 @@ $(pv_value) 80 false 4d40612f:17772f0c845:-7e89 - 22 - 75 + 24 + 45 @@ -223,8 +223,8 @@ $(pv_value) Text Input 134 4d40612f:17772f0c845:-7e88 - 106 - 108 + 108 + 78 @@ -254,7 +254,7 @@ $(pv_value) false - cmdCode + Cmd Code true 1 @@ -263,8 +263,8 @@ $(pv_value) 80 false 4d40612f:17772f0c845:-7e87 - 22 - 111 + 24 + 81 @@ -308,7 +308,7 @@ else if(Log == 'LOG') } -Yamcs.issueCommand('/cfs/ci/UpdateCmd', +Yamcs.issueCommand('/cfs/$(CPUID)/ci/UpdateCmd', {'msgID': msgID, 'cmdCode': cmdCode, 'step': StepVal, @@ -360,8 +360,8 @@ $(pv_value) Action Button 105 4d40612f:17772f0c845:-7e86 - 91 - 228 + 93 + 198 @@ -406,8 +406,8 @@ $(pv_value) Combo 134 4d40612f:17772f0c845:-7e59 - 106 - 144 + 108 + 114 @@ -446,8 +446,8 @@ $(pv_value) 80 false 4d40612f:17772f0c845:-7e58 - 22 - 147 + 24 + 117 @@ -486,8 +486,8 @@ $(pv_value) 80 false 4d40612f:17772f0c845:-7e56 - 22 - 183 + 24 + 153 @@ -532,7 +532,7 @@ $(pv_value) Combo 134 4d40612f:17772f0c845:-7da1 - 106 - 183 + 108 + 153 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CI/scripts/NoOp.js b/core/base/tools/commander/workspace_template/Displays/Apps/CI/scripts/NoOp.js index 98a044a29..fbcabbe33 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CI/scripts/NoOp.js +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CI/scripts/NoOp.js @@ -1,4 +1,4 @@ importPackage(Packages.org.csstudio.opibuilder.scriptUtil); importPackage(Packages.org.yamcs.studio.script); -Yamcs.issueCommand('/cfs/ci/Noop', {}); \ No newline at end of file +Yamcs.issueCommand('/cfs/$(CPUID)/ci/Noop', {}); \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CI/scripts/ResetCounters.js b/core/base/tools/commander/workspace_template/Displays/Apps/CI/scripts/ResetCounters.js index edfff03e3..abafcbca3 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CI/scripts/ResetCounters.js +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CI/scripts/ResetCounters.js @@ -1,4 +1,4 @@ importPackage(Packages.org.csstudio.opibuilder.scriptUtil); importPackage(Packages.org.yamcs.studio.script); -Yamcs.issueCommand('/cfs/ci/Reset(arg: none)'); \ No newline at end of file +Yamcs.issueCommand('/cfs/$(CPUID)/ci/Reset(arg: none)'); \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/DisableApplication.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CS/DisableApplication.opi index ad4def0be..fadabac84 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/DisableApplication.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/DisableApplication.opi @@ -15,11 +15,11 @@ 6 - 150 + 130 true - CS - Disable App + ($(CPUID)) CS - Disable App true @@ -39,7 +39,7 @@ true @@ -87,8 +87,8 @@ $(pv_value) Action Button 109 -736e4684:150ac3c95a1:-7e12 - 144 - 78 + 159 + 90 @@ -100,7 +100,7 @@ importPackage(Packages.org.yamcs.studio.data); var app_name = VTypeHelper.getString(display.getWidget('DisableApplicationName').getPropertyValue('pv_value')); -var cmd = '/cfs/cs/DisableNameApp(Name: ' + app_name + ')'; +var cmd = '/cfs/$(CPUID)/cs/DisableNameApp(Name: ' + app_name + ')'; Yamcs.issueCommand(cmd);]]> true @@ -148,8 +148,8 @@ $(pv_value) Action Button 109 -736e4684:150ac3c95a1:-7e06 - 6 - 78 + 21 + 90 @@ -188,8 +188,8 @@ $(pv_value) 50 false -736e4684:150ac3c95a1:-76ae - 12 - 35 + 27 + 47 @@ -250,7 +250,47 @@ $(pv_value) Combo 115 -736e4684:150ac3c95a1:-76ad - 72 - 30 + 87 + 42 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) CS - Disable App + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5f1d + 12 + 11 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/DisableEEPROM.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CS/DisableEEPROM.opi index 207e338d1..ca7948848 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/DisableEEPROM.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/DisableEEPROM.opi @@ -19,7 +19,7 @@ true - CS - Disable EEPROM + ($(CPUID)) CS - Disable EEPROM true @@ -39,7 +39,7 @@ true @@ -100,7 +100,7 @@ importPackage(Packages.org.yamcs.studio.data); var EntryID =VTypeHelper.getDouble(display.getWidget('EntryID').getPropertyValue('pv_value')); -var cmd = '/cfs/cs/DisableEntryEEPROM'; +var cmd = '/cfs/$(CPUID)/cs/DisableEntryEEPROM'; Yamcs.issueCommand(cmd, {'EntryID': EntryID });]]> true @@ -189,7 +189,7 @@ $(pv_value) false -736e4684:150ac3c95a1:-7de8 60 - 36 + 42 @@ -244,6 +244,46 @@ $(pv_value) 100 -736e4684:150ac3c95a1:-7de7 120 - 36 + 42 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) CS - Disable EEPROM + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5f2b + 11 + 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/DisableMemory.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CS/DisableMemory.opi index a0d40c48d..3fed96ca8 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/DisableMemory.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/DisableMemory.opi @@ -15,11 +15,11 @@ 6 - 150 + 110 true - CS - Disable Mem + ($(CPUID)) CS - Disable Mem true @@ -39,7 +39,7 @@ true @@ -100,7 +100,7 @@ importPackage(Packages.org.yamcs.studio.data); var EntryID =VTypeHelper.getDouble(display.getWidget('EntryID').getPropertyValue('pv_value')); -var cmd = '/cfs/cs/DisableEntryMemory'; +var cmd = '/cfs/$(CPUID)/cs/DisableEntryMemory'; Yamcs.issueCommand(cmd, {'EntryID': EntryID });]]> true @@ -188,8 +188,8 @@ $(pv_value) 55 false -736e4684:150ac3c95a1:-7de8 - 36 - 36 + 60 + 42 @@ -243,7 +243,47 @@ $(pv_value) Spinner 100 -736e4684:150ac3c95a1:-7de7 - 96 - 36 + 120 + 42 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) CS - Disable Memory + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5f32 + 13 + 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/DisableTable.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CS/DisableTable.opi index f31e9f2f2..6b69882a2 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/DisableTable.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/DisableTable.opi @@ -15,11 +15,11 @@ 6 - 150 + 120 true - CS - Disable Table + ($(CPUID)) CS - Disable Table true @@ -40,7 +40,7 @@ importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); -var cmd = '/cfs/cs/DisableTables'; +var cmd = '/cfs/$(CPUID)/cs/DisableTables'; Yamcs.issueCommand(cmd, {});]]> true @@ -89,7 +89,7 @@ $(pv_value) 120 -736e4684:150ac3c95a1:-7e12 168 - 90 + 84 @@ -101,7 +101,7 @@ importPackage(Packages.org.yamcs.studio.data); var Name =VTypeHelper.getString(display.getWidget('Name').getPropertyValue('pv_value')); -var cmd = '/cfs/cs/DisableNameTable'; +var cmd = '/cfs/$(CPUID)/cs/DisableNameTable'; Yamcs.issueCommand(cmd, {'Name': Name});]]> true @@ -150,7 +150,7 @@ $(pv_value) 120 -736e4684:150ac3c95a1:-7e06 18 - 90 + 84 @@ -190,7 +190,7 @@ $(pv_value) false -736e4684:150ac3c95a1:-76ae 48 - 41 + 47 @@ -252,6 +252,46 @@ $(pv_value) 115 -736e4684:150ac3c95a1:-76ad 108 - 36 + 42 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) CS - Disable Table + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5f39 + 12 + 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/EnableApplication.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CS/EnableApplication.opi index 92c1fd08b..5baa59fe8 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/EnableApplication.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/EnableApplication.opi @@ -15,11 +15,11 @@ 6 - 150 + 120 true - CS - Enable App + ($(CPUID)) CS - Enable App true @@ -40,7 +40,7 @@ importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); -var cmd = '/cfs/cs/EnableApps'; +var cmd = '/cfs/$(CPUID)/cs/EnableApps'; Yamcs.issueCommand(cmd, {});]]> true @@ -88,7 +88,7 @@ $(pv_value) Action Button 120 -736e4684:150ac3c95a1:-7e12 - 144 + 157 78 @@ -102,7 +102,7 @@ importPackage(Packages.org.yamcs.studio.data); var Name =VTypeHelper.getString(display.getWidget('Name').getPropertyValue('pv_value')); -var cmd = '/cfs/cs/EnableNameApp'; +var cmd = '/cfs/$(CPUID)/cs/EnableNameApp'; Yamcs.issueCommand(cmd, {'Name': Name});]]> true @@ -150,7 +150,7 @@ $(pv_value) Action Button 120 -736e4684:150ac3c95a1:-7e06 - 6 + 19 78 @@ -190,8 +190,8 @@ $(pv_value) 50 false -736e4684:150ac3c95a1:-76ae - 18 - 35 + 27 + 41 @@ -252,7 +252,47 @@ $(pv_value) Combo 115 -736e4684:150ac3c95a1:-76ad - 78 - 30 + 87 + 36 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) CS - Enable App + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5f40 + 12 + 11 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/EnableEEPROM.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CS/EnableEEPROM.opi index 7b72bfd22..a9443b672 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/EnableEEPROM.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/EnableEEPROM.opi @@ -15,11 +15,11 @@ 6 - 150 + 120 true - CS - Enable EEPROM + ($(CPUID)) CS - Enable EEPROM true @@ -40,7 +40,7 @@ importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.csstudio.opibuilder.scriptUtil); -var cmd = '/cfs/cs/EnableEEPROM'; +var cmd = '/cfs/$(CPUID)/cs/EnableEEPROM'; Yamcs.issueCommand(cmd, {});]]> true @@ -88,8 +88,8 @@ $(pv_value) Action Button 120 -736e4684:150ac3c95a1:-7e12 - 144 - 84 + 150 + 78 @@ -101,7 +101,7 @@ importPackage(Packages.org.yamcs.studio.data); var EntryID =VTypeHelper.getDouble(display.getWidget('EntryID').getPropertyValue('pv_value')); -var cmd = '/cfs/cs/EnableEntryEEPROM'; +var cmd = '/cfs/$(CPUID)/cs/EnableEntryEEPROM'; Yamcs.issueCommand(cmd, {'EntryID': EntryID });]]> true @@ -149,8 +149,8 @@ $(pv_value) Action Button 120 -736e4684:150ac3c95a1:-7e06 - 9 - 84 + 15 + 78 @@ -189,8 +189,8 @@ $(pv_value) 55 false -736e4684:150ac3c95a1:-7de8 - 36 - 48 + 42 + 42 @@ -244,7 +244,47 @@ $(pv_value) Spinner 100 -736e4684:150ac3c95a1:-7de7 - 96 - 48 + 102 + 42 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) CS - Enable EEPROM + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5f47 + 9 + 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/EnableMemory.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CS/EnableMemory.opi index 07bfe19de..6ad3cab69 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/EnableMemory.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/EnableMemory.opi @@ -40,7 +40,7 @@ importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); -var cmd = '/cfs/cs/EnableMemory'; +var cmd = '/cfs/$(CPUID)/cs/EnableMemory'; Yamcs.issueCommand(cmd, {});]]> true @@ -101,7 +101,7 @@ importPackage(Packages.org.yamcs.studio.data); var EntryID =VTypeHelper.getDouble(display.getWidget('EntryID').getPropertyValue('pv_value')); -var cmd = '/cfs/cs/EnableEntryMemory'; +var cmd = '/cfs/$(CPUID)/cs/EnableEntryMemory'; Yamcs.issueCommand(cmd, {'EntryID': EntryID});]]> true diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/EnableTable.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CS/EnableTable.opi index f32a51abc..2f991897a 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/EnableTable.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/EnableTable.opi @@ -15,11 +15,11 @@ 6 - 150 + 130 true - CS - Enable Table + ($(CPUID)) CS - Enable Table true @@ -40,7 +40,7 @@ importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); -var cmd = '/cfs/cs/EnableTables'; +var cmd = '/cfs/$(CPUID)/cs/EnableTables'; Yamcs.issueCommand(cmd, {});]]> true @@ -88,8 +88,8 @@ $(pv_value) Action Button 120 -736e4684:150ac3c95a1:-7e12 - 174 - 84 + 162 + 90 @@ -101,7 +101,7 @@ importPackage(Packages.org.yamcs.studio.data); var Name =VTypeHelper.getString(display.getWidget('Name').getPropertyValue('pv_value')); -var cmd = '/cfs/cs/EnableNameTable'; +var cmd = '/cfs/$(CPUID)/cs/EnableNameTable'; Yamcs.issueCommand(cmd, {'Name': Name});]]> true @@ -149,8 +149,8 @@ $(pv_value) Action Button 120 -736e4684:150ac3c95a1:-7e06 - 36 - 84 + 24 + 90 @@ -189,8 +189,8 @@ $(pv_value) 50 false -736e4684:150ac3c95a1:-76ae - 48 - 41 + 36 + 47 @@ -251,7 +251,47 @@ $(pv_value) Combo 115 -736e4684:150ac3c95a1:-76ad - 108 - 36 + 96 + 42 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) CS - Enable Table + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5f4e + 12 + 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/GetEntryIDEEPROM.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CS/GetEntryIDEEPROM.opi index 81a6b5238..a669d8748 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/GetEntryIDEEPROM.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/GetEntryIDEEPROM.opi @@ -15,11 +15,11 @@ 6 - 90 + 110 true - CS - Get EID EEPROM + ($(CPUID)) CS - Get EID EEPROM true @@ -28,7 +28,7 @@ true true Display - 200 + 290 -33cb7c72:150aa4c347f:-6fed -1 -1 @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var Address =VTypeHelper.getDouble(display.getWidget('Address').getPropertyValue('pv_value')); -var cmd = '/cfs/cs/GetEntryIDEEPROM'; +var cmd = '/cfs/$(CPUID)/cs/GetEntryIDEEPROM'; Yamcs.issueCommand(cmd, {'Address': Address});]]> true @@ -90,8 +90,8 @@ $(pv_value) Action Button 120 -736e4684:150ac3c95a1:-7e80 - 48 - 48 + 78 + 78 @@ -130,8 +130,8 @@ $(pv_value) 55 false -736e4684:150ac3c95a1:-7e7f - 18 - 12 + 48 + 42 @@ -187,7 +187,47 @@ $(pv_value) Text Input 100 -736e4684:150ac3c95a1:-7e7e - 78 + 108 + 42 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) CS - Get EEPROM Entry ID + + true + 1 + true + Label + 278 + false + -c05c465:1785c72c4a1:-5f64 + 5 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/GetEntryIDMemory.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CS/GetEntryIDMemory.opi index 46a15493a..5a8eff21a 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/GetEntryIDMemory.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/GetEntryIDMemory.opi @@ -15,11 +15,11 @@ 6 - 90 + 110 true - CS - Get EID Memory + ($(CPUID)) CS - Get EID Memory true @@ -28,7 +28,7 @@ true true Display - 200 + 280 -33cb7c72:150aa4c347f:-6fed -1 -1 @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var Address =VTypeHelper.getDouble(display.getWidget('Address').getPropertyValue('pv_value')); -var cmd = '/cfs/cs/GetEntryIDMemory'; +var cmd = '/cfs/$(CPUID)/cs/GetEntryIDMemory'; Yamcs.issueCommand(cmd, {'Address':Address});]]> true @@ -90,8 +90,8 @@ $(pv_value) Action Button 120 -736e4684:150ac3c95a1:-7e80 - 48 - 48 + 84 + 72 @@ -130,8 +130,8 @@ $(pv_value) 55 false -736e4684:150ac3c95a1:-7e7f - 18 - 12 + 54 + 36 @@ -187,7 +187,47 @@ $(pv_value) Text Input 100 -736e4684:150ac3c95a1:-7e7e - 78 - 12 + 114 + 36 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) CS - Get Memory Entry ID + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5f6b + 6 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/Main.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CS/Main.opi index 91c0a8463..f9d87c2bb 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/Main.opi @@ -10,7 +10,7 @@ - 1.5.5.202103162101 + 1.6.2.202104092231 @@ -23,7 +23,7 @@ Displays /modules/cs - CS + ($(CPUID)) CS true @@ -64,7 +64,7 @@ Text Update 0 false - /cfs/cs/CS_HkPacket_t.CmdCounter + /cfs/$(CPUID)/cs/CS_HkPacket_t.CmdCounter 0.0 @@ -236,7 +236,7 @@ $(pv_value) Text Update_1 0 false - /cfs/cs/CS_HkPacket_t.CmdErrCounter + /cfs/$(CPUID)/cs/CS_HkPacket_t.CmdErrCounter 0.0 @@ -267,7 +267,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cs/Noop', {});]]> true @@ -323,7 +323,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cs/Reset', {});]]> true @@ -400,7 +400,7 @@ $(pv_value) false - Checksum Services + ($(CPUID)) Checksum Services true 1 @@ -440,7 +440,7 @@ $(pv_value) Text Update_2 0 false - /cfs/cs/CS_HkPacket_t.ChecksumState + /cfs/$(CPUID)/cs/CS_HkPacket_t.ChecksumState 0.0 @@ -492,7 +492,7 @@ $(pv_value) Text Update_3 0 false - /cfs/cs/CS_HkPacket_t.EepromCSState + /cfs/$(CPUID)/cs/CS_HkPacket_t.EepromCSState 0.0 @@ -544,7 +544,7 @@ $(pv_value) Text Update_4 0 false - /cfs/cs/CS_HkPacket_t.MemoryCSState + /cfs/$(CPUID)/cs/CS_HkPacket_t.MemoryCSState 0.0 @@ -596,7 +596,7 @@ $(pv_value) Text Update_5 0 false - /cfs/cs/CS_HkPacket_t.AppCSState + /cfs/$(CPUID)/cs/CS_HkPacket_t.AppCSState 0.0 @@ -648,7 +648,7 @@ $(pv_value) Text Update_6 0 false - /cfs/cs/CS_HkPacket_t.TablesCSState + /cfs/$(CPUID)/cs/CS_HkPacket_t.TablesCSState 0.0 @@ -700,7 +700,7 @@ $(pv_value) Text Update_7 0 false - /cfs/cs/CS_HkPacket_t.OSCSState + /cfs/$(CPUID)/cs/CS_HkPacket_t.OSCSState 0.0 @@ -752,7 +752,7 @@ $(pv_value) Text Update_8 0 false - /cfs/cs/CS_HkPacket_t.CfeCoreCSState + /cfs/$(CPUID)/cs/CS_HkPacket_t.CfeCoreCSState 0.0 @@ -802,7 +802,7 @@ $(pv_value) 20 Text Update_9 - /cfs/cs/CS_HkPacket_t. + /cfs/$(CPUID)/cs/CS_HkPacket_t. @@ -849,7 +849,7 @@ $(pv_value) 20 Text Update_10 - /cfs/cs/CS_HkPacket_t.OneShotInProgress + /cfs/$(CPUID)/cs/CS_HkPacket_t.OneShotInProgress @@ -898,7 +898,7 @@ $(pv_value) Text Update_11 0 false - /cfs/cs/CS_HkPacket_t.EepromCSErrCounter + /cfs/$(CPUID)/cs/CS_HkPacket_t.EepromCSErrCounter 0.0 @@ -950,7 +950,7 @@ $(pv_value) Text Update_12 0 false - /cfs/cs/CS_HkPacket_t.MemoryCSErrCounter + /cfs/$(CPUID)/cs/CS_HkPacket_t.MemoryCSErrCounter 0.0 @@ -1002,7 +1002,7 @@ $(pv_value) Text Update_13 0 false - /cfs/cs/CS_HkPacket_t.AppCSErrCounter + /cfs/$(CPUID)/cs/CS_HkPacket_t.AppCSErrCounter 0.0 @@ -1054,7 +1054,7 @@ $(pv_value) Text Update_14 0 false - /cfs/cs/CS_HkPacket_t.TablesCSErrCounter + /cfs/$(CPUID)/cs/CS_HkPacket_t.TablesCSErrCounter 0.0 @@ -1106,7 +1106,7 @@ $(pv_value) Text Update_15 0 false - /cfs/cs/CS_HkPacket_t.CfeCoreCSErrCounter + /cfs/$(CPUID)/cs/CS_HkPacket_t.CfeCoreCSErrCounter 0.0 @@ -1158,7 +1158,7 @@ $(pv_value) Text Update_16 0 false - /cfs/cs/CS_HkPacket_t.OSCSErrCounter + /cfs/$(CPUID)/cs/CS_HkPacket_t.OSCSErrCounter 0.0 @@ -1210,7 +1210,7 @@ $(pv_value) Text Update_17 0 false - /cfs/cs/CS_HkPacket_t.CurrentCSTable + /cfs/$(CPUID)/cs/CS_HkPacket_t.CurrentCSTable 0.0 @@ -1262,7 +1262,7 @@ $(pv_value) Text Update_18 0 false - /cfs/cs/CS_HkPacket_t.CurrentEntryInTable + /cfs/$(CPUID)/cs/CS_HkPacket_t.CurrentEntryInTable 0.0 @@ -1314,7 +1314,7 @@ $(pv_value) Text Update_19 0 false - /cfs/cs/CS_HkPacket_t.EepromBaseline + /cfs/$(CPUID)/cs/CS_HkPacket_t.EepromBaseline 0.0 @@ -1366,7 +1366,7 @@ $(pv_value) Text Update_20 0 false - /cfs/cs/CS_HkPacket_t.OSBaseline + /cfs/$(CPUID)/cs/CS_HkPacket_t.OSBaseline 0.0 @@ -1418,7 +1418,7 @@ $(pv_value) Text Update_21 0 false - /cfs/cs/CS_HkPacket_t.CfeCoreBaseline + /cfs/$(CPUID)/cs/CS_HkPacket_t.CfeCoreBaseline 0.0 @@ -1470,7 +1470,7 @@ $(pv_value) Text Update_22 0 false - /cfs/cs/CS_HkPacket_t.LastOneShotAddress + /cfs/$(CPUID)/cs/CS_HkPacket_t.LastOneShotAddress 0.0 @@ -1522,7 +1522,7 @@ $(pv_value) Text Update_23 0 false - /cfs/cs/CS_HkPacket_t.LastOneShotSize + /cfs/$(CPUID)/cs/CS_HkPacket_t.LastOneShotSize 0.0 @@ -1574,7 +1574,7 @@ $(pv_value) Text Update_24 0 false - /cfs/cs/CS_HkPacket_t.LastOneShotChecksum + /cfs/$(CPUID)/cs/CS_HkPacket_t.LastOneShotChecksum 0.0 @@ -1626,7 +1626,7 @@ $(pv_value) Text Update_25 0 false - /cfs/cs/CS_HkPacket_t.AppCSState + /cfs/$(CPUID)/cs/CS_HkPacket_t.AppCSState 0.0 @@ -2478,7 +2478,7 @@ $(pv_value) Text Update_26 0 true - /cfs/cs/CS_HkPacket_t.PassCounter + /cfs/$(CPUID)/cs/CS_HkPacket_t.PassCounter 0.0 @@ -2549,7 +2549,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cs/EnableAllCS', {});]]> true @@ -2605,7 +2605,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cs/DisableAllCS', {});]]> true @@ -3101,7 +3101,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cs/ReportBaselineOS', {});]]> true @@ -3157,7 +3157,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cs/RecomputeBaselineOS', {});]]> true @@ -3213,7 +3213,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cs/ReportBaselineCfeCore', {});]]> true @@ -3269,7 +3269,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cs/RecomputeBaselineCfeCore', {});]]> true @@ -3875,7 +3875,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cs/EnableOS', {});]]> true @@ -3931,7 +3931,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cs/DisableOS', {});]]> true @@ -3987,7 +3987,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cs/EnableCfeCore', {});]]> true @@ -4043,7 +4043,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cs/DisableCfeCore', {});]]> true @@ -4154,7 +4154,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cs/CancelOneShot', {});]]> true @@ -4239,7 +4239,7 @@ ScriptUtil.openOPI(display.getWidget("Events"), opi_to_open_path, RunModeService - 26 + 25 Events 0 @@ -4261,8 +4261,8 @@ $(pv_value) Action Button 171 -69f8bd78:177f094d5fe:-24f4 - 47 - 414 + 267 + 450 @@ -4271,7 +4271,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cs/SendHK', {});]]> true @@ -4327,7 +4327,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cs/BackgroundCycle', {});]]> true @@ -4376,4 +4376,65 @@ $(pv_value) 47 474 + + + + + + true + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 25 + + AppControl + 0 + + + + + true + true + false + + + + App Control + false + $(pv_name) +$(pv_value) + true + Action Button + 171 + 49c9ccd0:178c6a335db:-6d55 + 267 + 475 + \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/OneShot.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CS/OneShot.opi index 023de821a..ca7186e8d 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/OneShot.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/OneShot.opi @@ -19,7 +19,7 @@ true - CS - One Shot + ($(CPUID)) CS - One Shot true @@ -28,7 +28,7 @@ true true Display - 250 + 270 72a2bf2b:1508717c835:-7d33 -1 -1 @@ -44,7 +44,7 @@ var Address =VTypeHelper.getDouble(display.getWidget('Address').getPropertyValue var Size =VTypeHelper.getDouble(display.getWidget('Size').getPropertyValue('pv_value')); var MaxBytesPerCycle =VTypeHelper.getDouble(display.getWidget('MaxBytesPerCycle').getPropertyValue('pv_value')); -var cmd = '/cfs/cs/OneShot'; +var cmd = '/cfs/$(CPUID)/cs/OneShot'; Yamcs.issueCommand(cmd, {'Address': Address, @@ -97,8 +97,8 @@ $(pv_value) Action Button 125 72a2bf2b:1508717c835:-7cf7 - 47 - 96 + 68 + 114 @@ -138,7 +138,7 @@ $(pv_value) false 72a2bf2b:1508717c835:-7c63 12 - 19 + 36 @@ -195,7 +195,7 @@ $(pv_value) 100 -33cb7c72:150aa4c347f:-72cb 150 - 19 + 36 @@ -235,7 +235,7 @@ $(pv_value) false -33cb7c72:150aa4c347f:-72bb 12 - 38 + 55 @@ -290,7 +290,7 @@ $(pv_value) 100 -33cb7c72:150aa4c347f:-72b3 150 - 38 + 55 @@ -330,7 +330,7 @@ $(pv_value) false 4d40612f:17772f0c845:-73cc 12 - 56 + 73 @@ -385,6 +385,46 @@ $(pv_value) 100 4d40612f:17772f0c845:-73cb 150 - 56 + 73 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) CS - One Shot + + true + 1 + true + Label + 238 + false + -c05c465:1785c72c4a1:-5f78 + 12 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/RecomputeBaselineApp.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CS/RecomputeBaselineApp.opi index a9e4e6404..69bc1bb14 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/RecomputeBaselineApp.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/RecomputeBaselineApp.opi @@ -15,11 +15,11 @@ 6 - 80 + 100 true - CS - Rebase App + ($(CPUID)) CS - Rebase App true @@ -28,7 +28,7 @@ true true Display - 200 + 230 -736e4684:150ac3c95a1:-7e23 -1 -1 @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var Name =VTypeHelper.getString(display.getWidget('Name').getPropertyValue('pv_value')); -var cmd = '/cfs/cs/RecomputeBaselineApp'; +var cmd = '/cfs/$(CPUID)/cs/RecomputeBaselineApp'; Yamcs.issueCommand(cmd, {'Name': Name}); ]]> @@ -91,8 +91,8 @@ $(pv_value) Action Button 160 -736e4684:150ac3c95a1:-7e06 - 30 - 48 + 42 + 66 @@ -131,8 +131,8 @@ $(pv_value) 50 false -736e4684:150ac3c95a1:-76ae - 12 - 17 + 24 + 35 @@ -193,7 +193,47 @@ $(pv_value) Combo 115 -736e4684:150ac3c95a1:-76ad - 72 - 12 + 84 + 30 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) CS - Rebase App + + true + 1 + true + Label + 229 + false + -c05c465:1785c72c4a1:-5f7f + 6 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/RecomputeBaselineEEPROM.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CS/RecomputeBaselineEEPROM.opi index 3ae7fb8b1..07c11fae6 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/RecomputeBaselineEEPROM.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/RecomputeBaselineEEPROM.opi @@ -15,11 +15,11 @@ 6 - 90 + 110 true - CS - Rebase EEPROM + ($(CPUID)) CS - Rebase EEPROM true @@ -28,7 +28,7 @@ true true Display - 186 + 270 -736e4684:150ac3c95a1:-7e23 -1 -1 @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var EntryID =VTypeHelper.getDouble(display.getWidget('EntryID').getPropertyValue('pv_value')); -var cmd = '/cfs/cs/RecomputeBaselineEEPROM'; +var cmd = '/cfs/$(CPUID)/cs/RecomputeBaselineEEPROM'; Yamcs.issueCommand(cmd, {'EntryID': EntryID });]]> true @@ -90,8 +90,8 @@ $(pv_value) Action Button 160 -736e4684:150ac3c95a1:-7e06 - 24 - 54 + 59 + 78 @@ -130,8 +130,8 @@ $(pv_value) 55 false -736e4684:150ac3c95a1:-7de8 - 12 - 18 + 59 + 42 @@ -185,7 +185,47 @@ $(pv_value) Spinner 100 -736e4684:150ac3c95a1:-7de7 - 72 - 18 + 119 + 42 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) CS - Rebase EEPROM + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5f86 + 6 + 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/RecomputeBaselineMemory.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CS/RecomputeBaselineMemory.opi index c48b47f34..4d6bfc520 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/RecomputeBaselineMemory.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/RecomputeBaselineMemory.opi @@ -15,11 +15,11 @@ 6 - 90 + 110 true - CS - Rebase Memory + ($(CPUID)) CS - Rebase Memory true @@ -28,7 +28,7 @@ true true Display - 184 + 270 -736e4684:150ac3c95a1:-7e23 -1 -1 @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var EntryID =VTypeHelper.getDouble(display.getWidget('EntryID').getPropertyValue('pv_value')); -var cmd = '/cfs/cs/RecomputeBaselineMemory'; +var cmd = '/cfs/$(CPUID)/cs/RecomputeBaselineMemory'; Yamcs.issueCommand(cmd, {'EntryID': EntryID}); @@ -93,8 +93,8 @@ $(pv_value) Action Button 160 -736e4684:150ac3c95a1:-7e06 - 12 - 54 + 59 + 72 @@ -133,8 +133,8 @@ $(pv_value) 52 false -736e4684:150ac3c95a1:-7de8 - 12 - 18 + 54 + 42 @@ -188,7 +188,47 @@ $(pv_value) Spinner 100 -736e4684:150ac3c95a1:-7de7 - 72 - 18 + 114 + 42 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) CS - Rebase Memory + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5f9e + 6 + 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/RecomputeBaselineTable.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CS/RecomputeBaselineTable.opi index 547897b67..ff79d2684 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/RecomputeBaselineTable.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/RecomputeBaselineTable.opi @@ -15,11 +15,11 @@ 6 - 80 + 110 true - CS - Rebase Table + ($(CPUID)) CS - Rebase Table true @@ -28,7 +28,7 @@ true true Display - 200 + 290 -736e4684:150ac3c95a1:-7e23 -1 -1 @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var Name =VTypeHelper.getString(display.getWidget('Name').getPropertyValue('pv_value')); -var cmd = '/cfs/cs/RecomputeBaselineTable'; +var cmd = '/cfs/$(CPUID)/cs/RecomputeBaselineTable'; Yamcs.issueCommand(cmd , {'Name': Name});]]> true @@ -90,8 +90,8 @@ $(pv_value) Action Button 160 -736e4684:150ac3c95a1:-7e06 - 30 - 48 + 45 + 78 @@ -130,8 +130,8 @@ $(pv_value) 50 false -736e4684:150ac3c95a1:-76ae - 12 - 17 + 27 + 47 @@ -192,7 +192,47 @@ $(pv_value) Combo 115 -736e4684:150ac3c95a1:-76ad - 72 + 87 + 42 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) CS - Rebase Table + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5fa5 + 12 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/ReportBaselineApp.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CS/ReportBaselineApp.opi index df781f770..a69d90e0d 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/ReportBaselineApp.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/ReportBaselineApp.opi @@ -15,11 +15,11 @@ 6 - 80 + 110 true - CS - Report App Base + ($(CPUID)) CS - Report App Base true @@ -28,7 +28,7 @@ true true Display - 200 + 290 -736e4684:150ac3c95a1:-7e23 -1 -1 @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var Name =VTypeHelper.getString(display.getWidget('Name').getPropertyValue('pv_value')); -var cmd = '/cfs/cs/ReportBaselineApp'; +var cmd = '/cfs/$(CPUID)/cs/ReportBaselineApp'; Yamcs.issueCommand(cmd, {'Name': Name});]]> true @@ -90,8 +90,8 @@ $(pv_value) Action Button 130 -736e4684:150ac3c95a1:-7e06 - 42 - 48 + 72 + 78 @@ -130,8 +130,8 @@ $(pv_value) 50 false -736e4684:150ac3c95a1:-76ae - 12 - 17 + 42 + 47 @@ -192,7 +192,47 @@ $(pv_value) Combo 115 -736e4684:150ac3c95a1:-76ad - 72 + 102 + 42 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) CS - Report App Baseline + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5fac + 12 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/ReportBaselineEEPROM.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CS/ReportBaselineEEPROM.opi index 91b45d9e6..28f25ee38 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/ReportBaselineEEPROM.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/ReportBaselineEEPROM.opi @@ -15,11 +15,11 @@ 6 - 90 + 110 true - CS - Report EEPROM Base + ($(CPUID)) CS - Report EEPROM Base true @@ -28,7 +28,7 @@ true true Display - 180 + 320 -736e4684:150ac3c95a1:-7e23 -1 -1 @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var EntryID =VTypeHelper.getDouble(display.getWidget('EntryID').getPropertyValue('pv_value')); -var cmd = '/cfs/cs/ReportBaselineEEPROM'; +var cmd = '/cfs/$(CPUID)/cs/ReportBaselineEEPROM'; Yamcs.issueCommand(cmd, {'EntryID': EntryID});]]> true @@ -90,8 +90,8 @@ $(pv_value) Action Button 130 -736e4684:150ac3c95a1:-7e06 - 36 - 54 + 97 + 72 @@ -130,8 +130,8 @@ $(pv_value) 52 false -736e4684:150ac3c95a1:-7de8 - 12 - 18 + 72 + 42 @@ -185,7 +185,47 @@ $(pv_value) Spinner 100 -736e4684:150ac3c95a1:-7de7 - 72 - 18 + 132 + 42 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) CS - Report EEPROM Baseline + + true + 1 + true + Label + 312 + false + -c05c465:1785c72c4a1:-5fb3 + 6 + 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/ReportBaselineMemory.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CS/ReportBaselineMemory.opi index bf8fe30bc..2a0c41fed 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/ReportBaselineMemory.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/ReportBaselineMemory.opi @@ -15,11 +15,11 @@ 6 - 90 + 110 true - CS - Report Mem Base + ($(CPUID)) CS - Report Mem Base true @@ -28,7 +28,7 @@ true true Display - 180 + 310 -736e4684:150ac3c95a1:-7e23 -1 -1 @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var EntryID =VTypeHelper.getDouble(display.getWidget('EntryID').getPropertyValue('pv_value')); -var cmd = '/cfs/cs/ReportBaselineMemory'; +var cmd = '/cfs/$(CPUID)/cs/ReportBaselineMemory'; Yamcs.issueCommand(cmd, {'EntryID': EntryID});]]> true @@ -90,8 +90,8 @@ $(pv_value) Action Button 130 -736e4684:150ac3c95a1:-7e06 - 36 - 54 + 88 + 72 @@ -130,8 +130,8 @@ $(pv_value) 52 false -736e4684:150ac3c95a1:-7de8 - 12 - 18 + 60 + 42 @@ -185,7 +185,47 @@ $(pv_value) Spinner 100 -736e4684:150ac3c95a1:-7de7 - 72 - 18 + 120 + 42 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) CS - Report Memory Baseline + + true + 1 + true + Label + 293 + false + -c05c465:1785c72c4a1:-5fba + 6 + 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/ReportBaselineTable.opi b/core/base/tools/commander/workspace_template/Displays/Apps/CS/ReportBaselineTable.opi index 3b2c1e8cb..796cbab31 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/ReportBaselineTable.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/ReportBaselineTable.opi @@ -15,11 +15,11 @@ 6 - 80 + 110 true - CS - Report Table Base + ($(CPUID)) CS - Report Table Base true @@ -28,7 +28,7 @@ true true Display - 200 + 280 -736e4684:150ac3c95a1:-7e23 -1 -1 @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var Name =VTypeHelper.getString(display.getWidget('Name').getPropertyValue('pv_value')); -var cmd = '/cfs/cs/ReportBaselineTable'; +var cmd = '/cfs/$(CPUID)/cs/ReportBaselineTable'; Yamcs.issueCommand(cmd, {'Name': Name});]]> true @@ -90,8 +90,8 @@ $(pv_value) Action Button 130 -736e4684:150ac3c95a1:-7e06 - 42 - 48 + 75 + 66 @@ -130,8 +130,8 @@ $(pv_value) 50 false -736e4684:150ac3c95a1:-76ae - 12 - 17 + 36 + 35 @@ -192,7 +192,47 @@ $(pv_value) Combo 115 -736e4684:150ac3c95a1:-76ad - 72 - 12 + 96 + 30 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) CS - Report Table Baseline + + true + 1 + true + Label + 274 + false + -c05c465:1785c72c4a1:-5fc8 + 3 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/CancelOneShot.js b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/CancelOneShot.js index afd2fc055..d42bfeafc 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/CancelOneShot.js +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/CancelOneShot.js @@ -1,4 +1,4 @@ importPackage(Packages.org.csstudio.opibuilder.scriptUtil); importPackage(Packages.org.yamcs.studio.script); -Yamcs.issueCommand('/cfs/cs/CancelOneShot', {}); \ No newline at end of file +Yamcs.issueCommand('/cfs/$(CPUID)/cs/CancelOneShot', {}); \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/DisableAll.js b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/DisableAll.js index f25a51ae8..6b9a82290 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/DisableAll.js +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/DisableAll.js @@ -1,4 +1,4 @@ importPackage(Packages.org.csstudio.opibuilder.scriptUtil); importPackage(Packages.org.yamcs.studio.script); -Yamcs.issueCommand('/cfs/cs/DisableApps', {}); \ No newline at end of file +Yamcs.issueCommand('/cfs/$(CPUID)/cs/DisableApps', {}); \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/DisableCFECore.js b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/DisableCFECore.js index 5e292dc09..b8c60729d 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/DisableCFECore.js +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/DisableCFECore.js @@ -1,4 +1,4 @@ importPackage(Packages.org.csstudio.opibuilder.scriptUtil); importPackage(Packages.org.yamcs.studio.script); -Yamcs.issueCommand('/cfs/cs/DisableCFECore', {}); \ No newline at end of file +Yamcs.issueCommand('/cfs/$(CPUID)/cs/DisableCFECore', {}); \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/DisableEEPROM.js b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/DisableEEPROM.js index 787db5ce1..88ef7b1dc 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/DisableEEPROM.js +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/DisableEEPROM.js @@ -1,4 +1,4 @@ importPackage(Packages.org.csstudio.opibuilder.scriptUtil); importPackage(Packages.org.yamcs.studio.script); -Yamcs.issueCommand('/cfs/cs/DisableEEPROM', {}); \ No newline at end of file +Yamcs.issueCommand('/cfs/$(CPUID)/cs/DisableEEPROM', {}); \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/DisableOS.js b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/DisableOS.js index c08cc56ed..e1372194a 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/DisableOS.js +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/DisableOS.js @@ -1,4 +1,4 @@ importPackage(Packages.org.csstudio.opibuilder.scriptUtil); importPackage(Packages.org.yamcs.studio.script); -Yamcs.issueCommand('/cfs/cs/DisableOS', {}); \ No newline at end of file +Yamcs.issueCommand('/cfs/$(CPUID)/cs/DisableOS', {}); \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/EnableAll.js b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/EnableAll.js index 9990d1ff2..72c42712e 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/EnableAll.js +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/EnableAll.js @@ -1,4 +1,4 @@ importPackage(Packages.org.csstudio.opibuilder.scriptUtil); importPackage(Packages.org.yamcs.studio.script); -Yamcs.issueCommand('/cfs/cfs/EnableApps', {}); \ No newline at end of file +Yamcs.issueCommand('/cfs/$(CPUID)/cfs/EnableApps', {}); \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/EnableCFECore.js b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/EnableCFECore.js index ac1d23111..525f79f9b 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/EnableCFECore.js +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/EnableCFECore.js @@ -1,4 +1,4 @@ importPackage(Packages.org.csstudio.opibuilder.scriptUtil); importPackage(Packages.org.yamcs.studio.script); -Yamcs.issueCommand('/cfs/cs/EnableCfeCore', {}); \ No newline at end of file +Yamcs.issueCommand('/cfs/$(CPUID)/cs/EnableCfeCore', {}); \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/EnableEEPROM.js b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/EnableEEPROM.js index aa04757c2..003736cc3 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/EnableEEPROM.js +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/EnableEEPROM.js @@ -1,4 +1,4 @@ importPackage(Packages.org.csstudio.opibuilder.scriptUtil); importPackage(Packages.org.yamcs.studio.script); -Yamcs.issueCommand('/cfs/cs/EnableEntryEEPROM', {}); \ No newline at end of file +Yamcs.issueCommand('/cfs/$(CPUID)/cs/EnableEntryEEPROM', {}); \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/EnableOS.js b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/EnableOS.js index da0f22f49..b2141ed3a 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/EnableOS.js +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/EnableOS.js @@ -1,4 +1,4 @@ importPackage(Packages.org.csstudio.opibuilder.scriptUtil); importPackage(Packages.org.yamcs.studio.script); -Yamcs.issueCommand('/cfs/cs/EnableOS', {}); \ No newline at end of file +Yamcs.issueCommand('/cfs/$(CPUID)/cs/EnableOS', {}); \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/NoOp.js b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/NoOp.js index 262742834..84202ad5e 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/NoOp.js +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/NoOp.js @@ -1,4 +1,4 @@ importPackage(Packages.org.csstudio.opibuilder.scriptUtil); importPackage(Packages.org.yamcs.studio.script); -Yamcs.issueCommand('/cfs/cs/Noop', {}); \ No newline at end of file +Yamcs.issueCommand('/cfs/$(CPUID)/cs/Noop', {}); \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/RecomputeBaseCFECore.js b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/RecomputeBaseCFECore.js index a893c5dcf..40c1d9f0b 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/RecomputeBaseCFECore.js +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/RecomputeBaseCFECore.js @@ -1,4 +1,4 @@ importPackage(Packages.org.csstudio.opibuilder.scriptUtil); importPackage(Packages.org.yamcs.studio.script); -Yamcs.issueCommand('/cfs/cs/RecomputeBaselineCfeCore', {}); \ No newline at end of file +Yamcs.issueCommand('/cfs/$(CPUID)/cs/RecomputeBaselineCfeCore', {}); \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/RecomputeBaselineOS.js b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/RecomputeBaselineOS.js index fb876929b..ebe67c461 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/RecomputeBaselineOS.js +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/RecomputeBaselineOS.js @@ -1,4 +1,4 @@ importPackage(Packages.org.csstudio.opibuilder.scriptUtil); importPackage(Packages.org.yamcs.studio.script); -Yamcs.issueCommand('/cfs/cs/RecomputeBaselineOS', {}); \ No newline at end of file +Yamcs.issueCommand('/cfs/$(CPUID)/cs/RecomputeBaselineOS', {}); \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/ReportBaseCFECore.js b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/ReportBaseCFECore.js index c41d56253..67f2b1ea9 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/ReportBaseCFECore.js +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/ReportBaseCFECore.js @@ -1,4 +1,4 @@ importPackage(Packages.org.csstudio.opibuilder.scriptUtil); importPackage(Packages.org.yamcs.studio.script); -Yamcs.issueCommand('/cfs/cs/ReportBaselineCfeCore', {}); \ No newline at end of file +Yamcs.issueCommand('/cfs/$(CPUID)/cs/ReportBaselineCfeCore', {}); \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/ReportBaselineOS.js b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/ReportBaselineOS.js index ce18e1ac0..baa9cc286 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/ReportBaselineOS.js +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/ReportBaselineOS.js @@ -1,4 +1,4 @@ importPackage(Packages.org.csstudio.opibuilder.scriptUtil); importPackage(Packages.org.yamcs.studio.script); -Yamcs.issueCommand('/cfs/cs/ReportBaselineOS', {}); \ No newline at end of file +Yamcs.issueCommand('/cfs/$(CPUID)/cs/ReportBaselineOS', {}); \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/ResetCounters.js b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/ResetCounters.js index 542c054d6..3c6fe82d1 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/ResetCounters.js +++ b/core/base/tools/commander/workspace_template/Displays/Apps/CS/scripts/ResetCounters.js @@ -1,4 +1,4 @@ importPackage(Packages.org.csstudio.opibuilder.scriptUtil); importPackage(Packages.org.yamcs.studio.script); -Yamcs.issueCommand('/cfs/cs/Reset', {}); \ No newline at end of file +Yamcs.issueCommand('/cfs/$(CPUID)/cs/Reset', {}); \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/DS/AddMid.opi b/core/base/tools/commander/workspace_template/Displays/Apps/DS/AddMid.opi index cfdb251b5..629b56196 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/DS/AddMid.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/DS/AddMid.opi @@ -15,11 +15,11 @@ 6 - 400 + 120 true - DS - Add MID + ($(CPUID)) DS - Add MID true @@ -28,7 +28,7 @@ true true Display - 400 + 220 -736e4684:150ac3c95a1:-720f -1 -1 @@ -86,8 +86,8 @@ $(pv_value) Text Input 100 -1c861553:17787873ea6:-7feb - 144 - 37 + 96 + 36 @@ -117,7 +117,7 @@ $(pv_value) false - MessageID + MsgID true 1 @@ -126,8 +126,8 @@ $(pv_value) 80 false -1c861553:17787873ea6:-7fe8 - 54 - 40 + 6 + 39 @@ -139,7 +139,7 @@ importPackage(Packages.org.yamcs.studio.data); var msgID = VTypeHelper.getDouble(display.getWidget('AddMidMessaeIDInput').getPropertyValue('pv_value')); -var cmd = '/cfs/ds/AddMessage'; +var cmd = '/cfs/$(CPUID)/ds/AddMessage'; Yamcs.issueCommand(cmd, {'MessageID': msgID, @@ -189,7 +189,47 @@ $(pv_value) Action Button 163 -1c861553:17787873ea6:-7fde - 90 - 84 + 27 + 78 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) DS - Add Msg ID + + true + 1 + true + Label + 205 + false + -c05c465:1785c72c4a1:-5d6f + 6 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/DS/CloseAll.opi b/core/base/tools/commander/workspace_template/Displays/Apps/DS/CloseAll.opi deleted file mode 100644 index 4f41fd34b..000000000 --- a/core/base/tools/commander/workspace_template/Displays/Apps/DS/CloseAll.opi +++ /dev/null @@ -1,94 +0,0 @@ - - - - - false - -1 - -1 - - false - - - - 1.5.5.202103012118 - - - - 6 - 300 - - true - - DS - Close All - - - true - true - true - true - true - Display - 300 - -736e4684:150ac3c95a1:-720b - -1 - -1 - - - - - - true - - - - false - false - - - - false - - - - 0 - 1 - true - - Default - - false - - - - 24 - ../../Resources/send.png - Action Button_1 - 0 - - - - - true - true - false - - - - Colse All - false - $(pv_name) -$(pv_value) - true - Action Button - 163 - -1c861553:17787873ea6:-7f8c - 60 - 90 - - \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/DS/CloseFile.opi b/core/base/tools/commander/workspace_template/Displays/Apps/DS/CloseFile.opi index 365aa3a52..9f09688c4 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/DS/CloseFile.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/DS/CloseFile.opi @@ -15,11 +15,11 @@ 6 - 400 + 110 true - DS - Close File + ($(CPUID)) DS - Close File true @@ -28,7 +28,7 @@ true true Display - 400 + 300 -736e4684:150ac3c95a1:-7217 -1 -1 @@ -40,7 +40,7 @@ importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); -var cmd = '/cfs/ds/CloseAll'; +var cmd = '/cfs/$(CPUID)/ds/CloseAll'; Yamcs.issueCommand(cmd, {});]]> true @@ -80,16 +80,16 @@ Yamcs.issueCommand(cmd, {});]]> - Colse All + Close All false $(pv_name) $(pv_value) true Action Button - 163 + 127 -1c861553:17787873ea6:-7f73 - 198 - 108 + 150 + 72 @@ -143,8 +143,8 @@ $(pv_value) Spinner 85 -1c861553:17787873ea6:-7f6f - 156 - 54 + 150 + 33 @@ -174,7 +174,7 @@ $(pv_value) false - FileTableIndex + File Table Index true 1 @@ -183,8 +183,8 @@ $(pv_value) 121 false -1c861553:17787873ea6:-7f6b - 30 - 57 + 24 + 36 @@ -196,7 +196,7 @@ importPackage(Packages.org.yamcs.studio.data); var file_index = VTypeHelper.getDouble(display.getWidget('EntryID').getPropertyValue('pv_value')); -var cmd = '/cfs/ds/CloseFile'; +var cmd = '/cfs/$(CPUID)/ds/CloseFile'; Yamcs.issueCommand(cmd, {'FileTableIndex': file_index, @@ -239,15 +239,55 @@ Yamcs.issueCommand(cmd, - Colse File + Close File false $(pv_name) $(pv_value) true Action Button - 163 + 127 -1c861553:17787873ea6:-7f4b - 18 - 108 + 12 + 72 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) DS - Close File + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5c58 + 6 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/DS/GetFileInfo.opi b/core/base/tools/commander/workspace_template/Displays/Apps/DS/GetFileInfo.opi index a3707e5bb..ef6ea01ba 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/DS/GetFileInfo.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/DS/GetFileInfo.opi @@ -19,7 +19,7 @@ true - DS - Get File Info + ($(CPUID)) DS - Get File Info true @@ -40,7 +40,7 @@ importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); -var cmd = '/cfs/ds/GetFileInfo'; +var cmd = '/cfs/$(CPUID)/ds/GetFileInfo'; Yamcs.issueCommand(cmd, {});]]> true @@ -80,7 +80,7 @@ Yamcs.issueCommand(cmd, {});]]> - GetFileInfo + Get File Info false $(pv_name) $(pv_value) @@ -88,8 +88,8 @@ $(pv_value) Action Button 163 -1c861553:17787873ea6:-7f22 - 96 - 30 + 63 + 36 @@ -128,8 +128,8 @@ $(pv_value) 80 false -1c861553:17787873ea6:-7e6c - 173 - 96 + 191 + 78 @@ -168,8 +168,8 @@ $(pv_value) 80 false -1c861553:17787873ea6:-7e69 - 252 - 96 + 270 + 78 @@ -208,8 +208,8 @@ $(pv_value) 80 false -1c861553:17787873ea6:-7e66 - 348 - 96 + 366 + 78 @@ -248,8 +248,8 @@ $(pv_value) 139 false -1c861553:17787873ea6:-7e63 - 427 - 96 + 445 + 78 @@ -288,8 +288,8 @@ $(pv_value) 80 false -1c861553:17787873ea6:-7e60 - 565 - 96 + 583 + 78 @@ -328,8 +328,8 @@ $(pv_value) 80 false -1c861553:17787873ea6:-7e56 - 654 - 96 + 672 + 78 @@ -368,8 +368,8 @@ $(pv_value) 80 false -1c861553:17787873ea6:-7e4c - 17 - 96 + 35 + 78 @@ -399,7 +399,7 @@ $(pv_value) Text Update 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_0_.FileName + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_0_.FileName 0.0 @@ -420,8 +420,8 @@ $(pv_value) 157 false -1c861553:17787873ea6:-7e46 - 17 - 138 + 35 + 103 @@ -451,7 +451,7 @@ $(pv_value) Text Update_1 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_0_.FileAge + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_0_.FileAge 0.0 @@ -472,8 +472,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-7e43 - 188 - 138 + 206 + 103 @@ -503,7 +503,7 @@ $(pv_value) Text Update_2 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_0_.FileSize + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_0_.FileSize 0.0 @@ -524,8 +524,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-7e39 - 267 - 138 + 285 + 103 @@ -555,7 +555,7 @@ $(pv_value) Text Update_3 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_0_.FileRate + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_0_.FileRate 0.0 @@ -576,8 +576,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-7e34 - 355 - 138 + 373 + 103 @@ -607,7 +607,7 @@ $(pv_value) Text Update_4 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_0_.SequenceCount + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_0_.SequenceCount 0.0 @@ -628,8 +628,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-7e2f - 450 - 138 + 468 + 103 @@ -657,7 +657,7 @@ $(pv_value) 20 Check Box - /cfs/ds/DS_FileInfoPkt_t.FileInfo_0_.EnableState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_0_.EnableState @@ -675,8 +675,8 @@ $(pv_value) Check Box 18 -1c861553:17787873ea6:-7cdf - 588 - 138 + 606 + 103 @@ -704,7 +704,7 @@ $(pv_value) 20 Check Box_1 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_0_.OpenState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_0_.OpenState @@ -722,8 +722,8 @@ $(pv_value) Check Box 19 -1c861553:17787873ea6:-7cd7 - 684 - 138 + 702 + 103 @@ -753,7 +753,7 @@ $(pv_value) Text Update_5 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_1_.FileName + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_1_.FileName 0.0 @@ -774,8 +774,8 @@ $(pv_value) 157 false -1c861553:17787873ea6:-7bf5 - 17 - 162 + 35 + 127 @@ -805,7 +805,7 @@ $(pv_value) Text Update_6 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_1_.FileAge + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_1_.FileAge 0.0 @@ -826,8 +826,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-7bf4 - 188 - 162 + 206 + 127 @@ -857,7 +857,7 @@ $(pv_value) Text Update_7 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_1_.FileSize + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_1_.FileSize 0.0 @@ -878,8 +878,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-7bf3 - 267 - 162 + 285 + 127 @@ -909,7 +909,7 @@ $(pv_value) Text Update_8 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_1_.FileRate + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_1_.FileRate 0.0 @@ -930,8 +930,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-7bf2 - 355 - 162 + 373 + 127 @@ -961,7 +961,7 @@ $(pv_value) Text Update_9 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_1_.SequenceCount + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_1_.SequenceCount 0.0 @@ -982,8 +982,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-7bf1 - 450 - 162 + 468 + 127 @@ -1011,7 +1011,7 @@ $(pv_value) 20 Check Box_3 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_1_.OpenState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_1_.OpenState @@ -1029,8 +1029,8 @@ $(pv_value) Check Box 19 -1c861553:17787873ea6:-7bef - 684 - 162 + 702 + 127 @@ -1058,7 +1058,7 @@ $(pv_value) 20 Check Box_4 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_1_.EnableState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_1_.EnableState @@ -1076,8 +1076,8 @@ $(pv_value) Check Box 18 -1c861553:17787873ea6:-7b83 - 588 - 162 + 606 + 127 @@ -1116,8 +1116,8 @@ $(pv_value) 18 false -1c861553:17787873ea6:-7b16 - 0 - 138 + 18 + 103 @@ -1156,8 +1156,8 @@ $(pv_value) 18 false -1c861553:17787873ea6:-7ada - 0 - 162 + 18 + 127 @@ -1187,7 +1187,7 @@ $(pv_value) Text Update_10 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_2_.FileName + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_2_.FileName 0.0 @@ -1208,8 +1208,8 @@ $(pv_value) 157 false -1c861553:17787873ea6:-7a4a - 17 - 186 + 35 + 151 @@ -1239,7 +1239,7 @@ $(pv_value) Text Update_11 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_2_.FileAge + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_2_.FileAge 0.0 @@ -1260,8 +1260,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-7a49 - 188 - 186 + 206 + 151 @@ -1291,7 +1291,7 @@ $(pv_value) Text Update_12 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_2_.FileSize + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_2_.FileSize 0.0 @@ -1312,8 +1312,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-7a48 - 267 - 186 + 285 + 151 @@ -1343,7 +1343,7 @@ $(pv_value) Text Update_13 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_1_.FileRate + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_1_.FileRate 0.0 @@ -1364,8 +1364,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-7a47 - 355 - 186 + 373 + 151 @@ -1395,7 +1395,7 @@ $(pv_value) Text Update_14 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_2_.SequenceCount + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_2_.SequenceCount 0.0 @@ -1416,8 +1416,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-7a46 - 450 - 186 + 468 + 151 @@ -1445,7 +1445,7 @@ $(pv_value) 20 Check Box_5 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_2_.OpenState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_2_.OpenState @@ -1463,8 +1463,8 @@ $(pv_value) Check Box 19 -1c861553:17787873ea6:-7a45 - 684 - 186 + 702 + 151 @@ -1492,7 +1492,7 @@ $(pv_value) 20 Check Box_6 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_2_.EnableState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_2_.EnableState @@ -1510,8 +1510,8 @@ $(pv_value) Check Box 18 -1c861553:17787873ea6:-7a44 - 588 - 186 + 606 + 151 @@ -1550,8 +1550,8 @@ $(pv_value) 18 false -1c861553:17787873ea6:-7a43 - 0 - 186 + 18 + 151 @@ -1581,7 +1581,7 @@ $(pv_value) Text Update_15 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_3_.FileName + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_3_.FileName 0.0 @@ -1602,8 +1602,8 @@ $(pv_value) 157 false -1c861553:17787873ea6:-79b7 - 17 - 210 + 35 + 175 @@ -1633,7 +1633,7 @@ $(pv_value) Text Update_16 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_3_.FileAge + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_3_.FileAge 0.0 @@ -1654,8 +1654,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-79b6 - 188 - 210 + 206 + 175 @@ -1685,7 +1685,7 @@ $(pv_value) Text Update_17 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_3_.FileSize + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_3_.FileSize 0.0 @@ -1706,8 +1706,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-79b5 - 267 - 210 + 285 + 175 @@ -1737,7 +1737,7 @@ $(pv_value) Text Update_18 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_3_.FileRate + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_3_.FileRate 0.0 @@ -1758,8 +1758,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-79b4 - 355 - 210 + 373 + 175 @@ -1789,7 +1789,7 @@ $(pv_value) Text Update_19 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_3_.SequenceCount + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_3_.SequenceCount 0.0 @@ -1810,8 +1810,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-79b3 - 450 - 210 + 468 + 175 @@ -1839,7 +1839,7 @@ $(pv_value) 20 Check Box_7 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_3_.OpenState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_3_.OpenState @@ -1857,8 +1857,8 @@ $(pv_value) Check Box 19 -1c861553:17787873ea6:-79b2 - 684 - 210 + 702 + 175 @@ -1886,7 +1886,7 @@ $(pv_value) 20 Check Box_8 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_3_.EnableState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_3_.EnableState @@ -1904,8 +1904,8 @@ $(pv_value) Check Box 18 -1c861553:17787873ea6:-79b1 - 588 - 210 + 606 + 175 @@ -1944,8 +1944,8 @@ $(pv_value) 18 false -1c861553:17787873ea6:-79b0 - 0 - 210 + 18 + 175 @@ -1975,7 +1975,7 @@ $(pv_value) Text Update_20 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_4_.FileName + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_4_.FileName 0.0 @@ -1996,8 +1996,8 @@ $(pv_value) 157 false -1c861553:17787873ea6:-78f9 - 17 - 234 + 35 + 199 @@ -2027,7 +2027,7 @@ $(pv_value) Text Update_21 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_4_.FileAge + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_4_.FileAge 0.0 @@ -2048,8 +2048,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-78f8 - 188 - 234 + 206 + 199 @@ -2079,7 +2079,7 @@ $(pv_value) Text Update_22 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_4_.FileSize + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_4_.FileSize 0.0 @@ -2100,8 +2100,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-78f7 - 267 - 234 + 285 + 199 @@ -2131,7 +2131,7 @@ $(pv_value) Text Update_23 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_4_.FileRate + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_4_.FileRate 0.0 @@ -2152,8 +2152,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-78f6 - 355 - 234 + 373 + 199 @@ -2183,7 +2183,7 @@ $(pv_value) Text Update_24 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_4_.SequenceCount + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_4_.SequenceCount 0.0 @@ -2204,8 +2204,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-78f5 - 450 - 234 + 468 + 199 @@ -2233,7 +2233,7 @@ $(pv_value) 20 Check Box_9 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_4_.OpenState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_4_.OpenState @@ -2251,8 +2251,8 @@ $(pv_value) Check Box 19 -1c861553:17787873ea6:-78f4 - 684 - 234 + 702 + 199 @@ -2280,7 +2280,7 @@ $(pv_value) 20 Check Box_10 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_4_.EnableState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_4_.EnableState @@ -2298,8 +2298,8 @@ $(pv_value) Check Box 18 -1c861553:17787873ea6:-78f3 - 588 - 234 + 606 + 199 @@ -2338,8 +2338,8 @@ $(pv_value) 18 false -1c861553:17787873ea6:-78f2 - 0 - 234 + 18 + 199 @@ -2369,7 +2369,7 @@ $(pv_value) Text Update_25 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_4_.FileName + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_4_.FileName 0.0 @@ -2390,8 +2390,8 @@ $(pv_value) 157 false -1c861553:17787873ea6:-7897 - 17 - 258 + 35 + 223 @@ -2421,7 +2421,7 @@ $(pv_value) Text Update_26 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_4_.FileAge + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_4_.FileAge 0.0 @@ -2442,8 +2442,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-7896 - 188 - 258 + 206 + 223 @@ -2473,7 +2473,7 @@ $(pv_value) Text Update_27 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_4_.FileSize + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_4_.FileSize 0.0 @@ -2494,8 +2494,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-7895 - 267 - 258 + 285 + 223 @@ -2525,7 +2525,7 @@ $(pv_value) Text Update_28 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_4_.FileRate + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_4_.FileRate 0.0 @@ -2546,8 +2546,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-7894 - 355 - 258 + 373 + 223 @@ -2577,7 +2577,7 @@ $(pv_value) Text Update_29 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_4_.SequenceCount + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_4_.SequenceCount 0.0 @@ -2598,8 +2598,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-7893 - 450 - 258 + 468 + 223 @@ -2627,7 +2627,7 @@ $(pv_value) 20 Check Box_11 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_4_.OpenState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_4_.OpenState @@ -2645,8 +2645,8 @@ $(pv_value) Check Box 19 -1c861553:17787873ea6:-7892 - 684 - 258 + 702 + 223 @@ -2674,7 +2674,7 @@ $(pv_value) 20 Check Box_12 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_4_.EnableState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_4_.EnableState @@ -2692,8 +2692,8 @@ $(pv_value) Check Box 18 -1c861553:17787873ea6:-7891 - 588 - 258 + 606 + 223 @@ -2732,8 +2732,8 @@ $(pv_value) 18 false -1c861553:17787873ea6:-7890 - 0 - 258 + 18 + 223 @@ -2763,7 +2763,7 @@ $(pv_value) Text Update_30 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_5_.FileName + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_5_.FileName 0.0 @@ -2784,8 +2784,8 @@ $(pv_value) 157 false -1c861553:17787873ea6:-77c3 - 17 - 282 + 35 + 247 @@ -2815,7 +2815,7 @@ $(pv_value) Text Update_31 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_5_.FileAge + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_5_.FileAge 0.0 @@ -2836,8 +2836,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-77c2 - 188 - 282 + 206 + 247 @@ -2867,7 +2867,7 @@ $(pv_value) Text Update_32 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_5_.FileSize + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_5_.FileSize 0.0 @@ -2888,8 +2888,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-77c1 - 267 - 282 + 285 + 247 @@ -2919,7 +2919,7 @@ $(pv_value) Text Update_33 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_5_.FileRate + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_5_.FileRate 0.0 @@ -2940,8 +2940,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-77c0 - 355 - 282 + 373 + 247 @@ -2971,7 +2971,7 @@ $(pv_value) Text Update_34 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_5_.SequenceCount + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_5_.SequenceCount 0.0 @@ -2992,8 +2992,8 @@ $(pv_value) 65 false -1c861553:17787873ea6:-77bf - 450 - 282 + 468 + 247 @@ -3021,7 +3021,7 @@ $(pv_value) 20 Check Box_13 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_5_.OpenState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_5_.OpenState @@ -3039,8 +3039,8 @@ $(pv_value) Check Box 19 -1c861553:17787873ea6:-77be - 684 - 282 + 702 + 247 @@ -3068,7 +3068,7 @@ $(pv_value) 20 Check Box_14 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_5_.EnableState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_5_.EnableState @@ -3086,8 +3086,8 @@ $(pv_value) Check Box 18 -1c861553:17787873ea6:-77bd - 588 - 282 + 606 + 247 @@ -3126,8 +3126,8 @@ $(pv_value) 18 false -1c861553:17787873ea6:-77bc - 0 - 282 + 18 + 247 @@ -3157,7 +3157,7 @@ $(pv_value) Text Update_35 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_6_.FileName + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_6_.FileName 0.0 @@ -3178,8 +3178,8 @@ $(pv_value) 157 false a22d448:177887d8135:-7f21 - 17 - 306 + 35 + 271 @@ -3209,7 +3209,7 @@ $(pv_value) Text Update_36 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_6_.FileAge + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_6_.FileAge 0.0 @@ -3230,8 +3230,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7f20 - 188 - 306 + 206 + 271 @@ -3261,7 +3261,7 @@ $(pv_value) Text Update_37 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_6_.FileSize + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_6_.FileSize 0.0 @@ -3282,8 +3282,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7f1f - 267 - 306 + 285 + 271 @@ -3313,7 +3313,7 @@ $(pv_value) Text Update_38 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_6_.FileRate + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_6_.FileRate 0.0 @@ -3334,8 +3334,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7f1e - 355 - 306 + 373 + 271 @@ -3365,7 +3365,7 @@ $(pv_value) Text Update_39 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_6_.SequenceCount + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_6_.SequenceCount 0.0 @@ -3386,8 +3386,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7f1d - 450 - 306 + 468 + 271 @@ -3415,7 +3415,7 @@ $(pv_value) 20 Check Box_15 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_6_.OpenState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_6_.OpenState @@ -3433,8 +3433,8 @@ $(pv_value) Check Box 19 a22d448:177887d8135:-7f1c - 684 - 306 + 702 + 271 @@ -3462,7 +3462,7 @@ $(pv_value) 20 Check Box_16 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_6_.EnableState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_6_.EnableState @@ -3480,8 +3480,8 @@ $(pv_value) Check Box 18 a22d448:177887d8135:-7f1b - 588 - 306 + 606 + 271 @@ -3520,8 +3520,8 @@ $(pv_value) 18 false a22d448:177887d8135:-7f1a - 0 - 306 + 18 + 271 @@ -3551,7 +3551,7 @@ $(pv_value) Text Update_40 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_6_.FileName + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_6_.FileName 0.0 @@ -3572,8 +3572,8 @@ $(pv_value) 157 false a22d448:177887d8135:-7e6b - 17 - 330 + 35 + 295 @@ -3603,7 +3603,7 @@ $(pv_value) Text Update_41 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_6_.FileAge + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_6_.FileAge 0.0 @@ -3624,8 +3624,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7e6a - 188 - 330 + 206 + 295 @@ -3655,7 +3655,7 @@ $(pv_value) Text Update_42 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_6_.FileSize + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_6_.FileSize 0.0 @@ -3676,8 +3676,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7e69 - 267 - 330 + 285 + 295 @@ -3707,7 +3707,7 @@ $(pv_value) Text Update_43 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_6_.FileRate + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_6_.FileRate 0.0 @@ -3728,8 +3728,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7e68 - 355 - 330 + 373 + 295 @@ -3759,7 +3759,7 @@ $(pv_value) Text Update_44 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_6_.SequenceCount + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_6_.SequenceCount 0.0 @@ -3780,8 +3780,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7e67 - 450 - 330 + 468 + 295 @@ -3809,7 +3809,7 @@ $(pv_value) 20 Check Box_17 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_6_.OpenState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_6_.OpenState @@ -3827,8 +3827,8 @@ $(pv_value) Check Box 19 a22d448:177887d8135:-7e66 - 684 - 330 + 702 + 295 @@ -3856,7 +3856,7 @@ $(pv_value) 20 Check Box_18 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_6_.EnableState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_6_.EnableState @@ -3874,8 +3874,8 @@ $(pv_value) Check Box 18 a22d448:177887d8135:-7e65 - 588 - 330 + 606 + 295 @@ -3914,8 +3914,8 @@ $(pv_value) 18 false a22d448:177887d8135:-7e64 - 0 - 330 + 18 + 295 @@ -3945,7 +3945,7 @@ $(pv_value) Text Update_45 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_7_.FileName + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_7_.FileName 0.0 @@ -3966,8 +3966,8 @@ $(pv_value) 157 false a22d448:177887d8135:-7e09 - 17 - 354 + 35 + 319 @@ -3997,7 +3997,7 @@ $(pv_value) Text Update_46 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_7_.FileAge + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_7_.FileAge 0.0 @@ -4018,8 +4018,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7e08 - 188 - 354 + 206 + 319 @@ -4049,7 +4049,7 @@ $(pv_value) Text Update_47 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_7_.FileSize + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_7_.FileSize 0.0 @@ -4070,8 +4070,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7e07 - 267 - 354 + 285 + 319 @@ -4101,7 +4101,7 @@ $(pv_value) Text Update_48 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_7_.FileRate + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_7_.FileRate 0.0 @@ -4122,8 +4122,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7e06 - 355 - 354 + 373 + 319 @@ -4153,7 +4153,7 @@ $(pv_value) Text Update_49 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_7_.SequenceCount + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_7_.SequenceCount 0.0 @@ -4174,8 +4174,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7e05 - 450 - 354 + 468 + 319 @@ -4214,8 +4214,8 @@ $(pv_value) 18 false a22d448:177887d8135:-7e02 - 0 - 354 + 18 + 319 @@ -4245,7 +4245,7 @@ $(pv_value) Text Update_65 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_8_.FileName + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_8_.FileName 0.0 @@ -4266,8 +4266,8 @@ $(pv_value) 157 false a22d448:177887d8135:-7da1 - 17 - 378 + 35 + 343 @@ -4297,7 +4297,7 @@ $(pv_value) Text Update_66 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_8_.FileAge + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_8_.FileAge 0.0 @@ -4318,8 +4318,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7da0 - 188 - 378 + 206 + 343 @@ -4349,7 +4349,7 @@ $(pv_value) Text Update_67 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_8_.FileSize + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_8_.FileSize 0.0 @@ -4370,8 +4370,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d9f - 267 - 378 + 285 + 343 @@ -4401,7 +4401,7 @@ $(pv_value) Text Update_68 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_8_.FileRate + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_8_.FileRate 0.0 @@ -4422,8 +4422,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d9e - 355 - 378 + 373 + 343 @@ -4453,7 +4453,7 @@ $(pv_value) Text Update_69 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_8_.SequenceCount + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_8_.SequenceCount 0.0 @@ -4474,8 +4474,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d9d - 450 - 378 + 468 + 343 @@ -4503,7 +4503,7 @@ $(pv_value) 20 Check Box_27 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_8_.OpenState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_8_.OpenState @@ -4521,8 +4521,8 @@ $(pv_value) Check Box 19 a22d448:177887d8135:-7d9c - 684 - 378 + 702 + 343 @@ -4550,7 +4550,7 @@ $(pv_value) 20 Check Box_28 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_8_.EnableState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_8_.EnableState @@ -4568,8 +4568,8 @@ $(pv_value) Check Box 18 a22d448:177887d8135:-7d9b - 588 - 378 + 606 + 343 @@ -4608,8 +4608,8 @@ $(pv_value) 18 false a22d448:177887d8135:-7d9a - 0 - 378 + 18 + 343 @@ -4637,7 +4637,7 @@ $(pv_value) 20 Check Box_29 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_7_.EnableState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_7_.EnableState @@ -4655,8 +4655,8 @@ $(pv_value) Check Box 18 a22d448:177887d8135:-7d92 - 588 - 354 + 606 + 319 @@ -4684,7 +4684,7 @@ $(pv_value) 20 Check Box_30 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_7_.OpenState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_7_.OpenState @@ -4702,8 +4702,8 @@ $(pv_value) Check Box 19 a22d448:177887d8135:-7d8a - 684 - 354 + 702 + 319 @@ -4733,7 +4733,7 @@ $(pv_value) Text Update_70 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_9_.FileName + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_9_.FileName 0.0 @@ -4754,8 +4754,8 @@ $(pv_value) 157 false a22d448:177887d8135:-7d6d - 17 - 402 + 35 + 367 @@ -4785,7 +4785,7 @@ $(pv_value) Text Update_71 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_9_.FileAge + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_9_.FileAge 0.0 @@ -4806,8 +4806,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d6c - 188 - 402 + 206 + 367 @@ -4837,7 +4837,7 @@ $(pv_value) Text Update_72 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_9_.FileSize + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_9_.FileSize 0.0 @@ -4858,8 +4858,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d6b - 267 - 402 + 285 + 367 @@ -4889,7 +4889,7 @@ $(pv_value) Text Update_73 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_9_.FileRate + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_9_.FileRate 0.0 @@ -4910,8 +4910,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d6a - 355 - 402 + 373 + 367 @@ -4941,7 +4941,7 @@ $(pv_value) Text Update_74 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_9_.SequenceCount + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_9_.SequenceCount 0.0 @@ -4962,8 +4962,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d69 - 450 - 402 + 468 + 367 @@ -4991,7 +4991,7 @@ $(pv_value) 20 Check Box_31 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_9_.OpenState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_9_.OpenState @@ -5009,8 +5009,8 @@ $(pv_value) Check Box 19 a22d448:177887d8135:-7d68 - 684 - 402 + 702 + 367 @@ -5038,7 +5038,7 @@ $(pv_value) 20 Check Box_32 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_9_.EnableState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_9_.EnableState @@ -5056,8 +5056,8 @@ $(pv_value) Check Box 18 a22d448:177887d8135:-7d67 - 588 - 402 + 606 + 367 @@ -5096,8 +5096,8 @@ $(pv_value) 18 false a22d448:177887d8135:-7d66 - 0 - 402 + 18 + 367 @@ -5127,7 +5127,7 @@ $(pv_value) Text Update_75 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_10_.FileName + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_10_.FileName 0.0 @@ -5148,8 +5148,8 @@ $(pv_value) 157 false a22d448:177887d8135:-7d53 - 17 - 426 + 35 + 391 @@ -5179,7 +5179,7 @@ $(pv_value) Text Update_76 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_10_.FileAge + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_10_.FileAge 0.0 @@ -5200,8 +5200,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d52 - 188 - 426 + 206 + 391 @@ -5231,7 +5231,7 @@ $(pv_value) Text Update_77 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_10_.FileSize + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_10_.FileSize 0.0 @@ -5252,8 +5252,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d51 - 267 - 426 + 285 + 391 @@ -5283,7 +5283,7 @@ $(pv_value) Text Update_78 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_10_.FileRate + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_10_.FileRate 0.0 @@ -5304,8 +5304,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d50 - 355 - 426 + 373 + 391 @@ -5335,7 +5335,7 @@ $(pv_value) Text Update_79 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_10_.SequenceCount + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_10_.SequenceCount 0.0 @@ -5356,8 +5356,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d4f - 450 - 426 + 468 + 391 @@ -5385,7 +5385,7 @@ $(pv_value) 20 Check Box_33 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_10_.OpenState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_10_.OpenState @@ -5403,8 +5403,8 @@ $(pv_value) Check Box 19 a22d448:177887d8135:-7d4e - 684 - 426 + 702 + 391 @@ -5432,7 +5432,7 @@ $(pv_value) 20 Check Box_34 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_10_.EnableState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_10_.EnableState @@ -5450,8 +5450,8 @@ $(pv_value) Check Box 18 a22d448:177887d8135:-7d4d - 588 - 426 + 606 + 391 @@ -5490,8 +5490,8 @@ $(pv_value) 18 false a22d448:177887d8135:-7d4c - 0 - 426 + 18 + 391 @@ -5521,7 +5521,7 @@ $(pv_value) Text Update_80 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_11_.FileName + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_11_.FileName 0.0 @@ -5542,8 +5542,8 @@ $(pv_value) 157 false a22d448:177887d8135:-7d39 - 17 - 450 + 35 + 415 @@ -5573,7 +5573,7 @@ $(pv_value) Text Update_81 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_11_.FileAge + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_11_.FileAge 0.0 @@ -5594,8 +5594,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d38 - 188 - 450 + 206 + 415 @@ -5625,7 +5625,7 @@ $(pv_value) Text Update_82 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_11_.FileSize + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_11_.FileSize 0.0 @@ -5646,8 +5646,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d37 - 267 - 450 + 285 + 415 @@ -5677,7 +5677,7 @@ $(pv_value) Text Update_83 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_11_.FileRate + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_11_.FileRate 0.0 @@ -5698,8 +5698,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d36 - 355 - 450 + 373 + 415 @@ -5729,7 +5729,7 @@ $(pv_value) Text Update_84 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_11_.SequenceCount + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_11_.SequenceCount 0.0 @@ -5750,8 +5750,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d35 - 450 - 450 + 468 + 415 @@ -5779,7 +5779,7 @@ $(pv_value) 20 Check Box_35 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_11_.OpenState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_11_.OpenState @@ -5797,8 +5797,8 @@ $(pv_value) Check Box 19 a22d448:177887d8135:-7d34 - 684 - 450 + 702 + 415 @@ -5826,7 +5826,7 @@ $(pv_value) 20 Check Box_36 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_11_.EnableState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_11_.EnableState @@ -5844,8 +5844,8 @@ $(pv_value) Check Box 18 a22d448:177887d8135:-7d33 - 588 - 450 + 606 + 415 @@ -5884,8 +5884,8 @@ $(pv_value) 18 false a22d448:177887d8135:-7d32 - 0 - 450 + 18 + 415 @@ -5915,7 +5915,7 @@ $(pv_value) Text Update_85 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_12_.FileName + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_12_.FileName 0.0 @@ -5936,8 +5936,8 @@ $(pv_value) 157 false a22d448:177887d8135:-7d1f - 17 - 474 + 35 + 439 @@ -5967,7 +5967,7 @@ $(pv_value) Text Update_86 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_12_.FileAge + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_12_.FileAge 0.0 @@ -5988,8 +5988,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d1e - 188 - 474 + 206 + 439 @@ -6019,7 +6019,7 @@ $(pv_value) Text Update_87 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_12_.FileSize + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_12_.FileSize 0.0 @@ -6040,8 +6040,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d1d - 267 - 474 + 285 + 439 @@ -6071,7 +6071,7 @@ $(pv_value) Text Update_88 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_12_.FileRate + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_12_.FileRate 0.0 @@ -6092,8 +6092,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d1c - 355 - 474 + 373 + 439 @@ -6123,7 +6123,7 @@ $(pv_value) Text Update_89 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_12_.SequenceCount + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_12_.SequenceCount 0.0 @@ -6144,8 +6144,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d1b - 450 - 474 + 468 + 439 @@ -6173,7 +6173,7 @@ $(pv_value) 20 Check Box_37 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_12_.OpenState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_12_.OpenState @@ -6191,8 +6191,8 @@ $(pv_value) Check Box 19 a22d448:177887d8135:-7d1a - 684 - 474 + 702 + 439 @@ -6220,7 +6220,7 @@ $(pv_value) 20 Check Box_38 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_12_.EnableState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_12_.EnableState @@ -6238,8 +6238,8 @@ $(pv_value) Check Box 18 a22d448:177887d8135:-7d19 - 588 - 474 + 606 + 439 @@ -6278,8 +6278,8 @@ $(pv_value) 18 false a22d448:177887d8135:-7d18 - 0 - 474 + 18 + 439 @@ -6309,7 +6309,7 @@ $(pv_value) Text Update_90 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_13_.FileName + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_13_.FileName 0.0 @@ -6330,8 +6330,8 @@ $(pv_value) 157 false a22d448:177887d8135:-7d05 - 17 - 498 + 35 + 463 @@ -6361,7 +6361,7 @@ $(pv_value) Text Update_91 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_13_.FileAge + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_13_.FileAge 0.0 @@ -6382,8 +6382,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d04 - 188 - 498 + 206 + 463 @@ -6413,7 +6413,7 @@ $(pv_value) Text Update_92 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_13_.FileSize + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_13_.FileSize 0.0 @@ -6434,8 +6434,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d03 - 267 - 498 + 285 + 463 @@ -6465,7 +6465,7 @@ $(pv_value) Text Update_93 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_13_.FileRate + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_13_.FileRate 0.0 @@ -6486,8 +6486,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d02 - 355 - 498 + 373 + 463 @@ -6517,7 +6517,7 @@ $(pv_value) Text Update_94 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_13_.SequenceCount + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_13_.SequenceCount 0.0 @@ -6538,8 +6538,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7d01 - 450 - 498 + 468 + 463 @@ -6567,7 +6567,7 @@ $(pv_value) 20 Check Box_39 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_13_.OpenState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_13_.OpenState @@ -6585,8 +6585,8 @@ $(pv_value) Check Box 19 a22d448:177887d8135:-7d00 - 684 - 498 + 702 + 463 @@ -6614,7 +6614,7 @@ $(pv_value) 20 Check Box_40 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_13_.EnableState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_13_.EnableState @@ -6632,8 +6632,8 @@ $(pv_value) Check Box 18 a22d448:177887d8135:-7cff - 588 - 498 + 606 + 463 @@ -6672,8 +6672,8 @@ $(pv_value) 18 false a22d448:177887d8135:-7cfe - 0 - 498 + 18 + 463 @@ -6703,7 +6703,7 @@ $(pv_value) Text Update_95 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_15_.FileName + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_15_.FileName 0.0 @@ -6724,8 +6724,8 @@ $(pv_value) 157 false a22d448:177887d8135:-7ceb - 17 - 551 + 35 + 516 @@ -6755,7 +6755,7 @@ $(pv_value) Text Update_96 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_15_.FileAge + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_15_.FileAge 0.0 @@ -6776,8 +6776,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7cea - 188 - 551 + 206 + 516 @@ -6807,7 +6807,7 @@ $(pv_value) Text Update_97 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_15_.FileSize + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_15_.FileSize 0.0 @@ -6828,8 +6828,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7ce9 - 267 - 551 + 285 + 516 @@ -6859,7 +6859,7 @@ $(pv_value) Text Update_98 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_15_.FileRate + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_15_.FileRate 0.0 @@ -6880,8 +6880,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7ce8 - 355 - 551 + 373 + 516 @@ -6911,7 +6911,7 @@ $(pv_value) Text Update_99 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_15_.SequenceCount + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_15_.SequenceCount 0.0 @@ -6932,8 +6932,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7ce7 - 450 - 551 + 468 + 516 @@ -6961,7 +6961,7 @@ $(pv_value) 20 Check Box_41 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_15_.OpenState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_15_.OpenState @@ -6979,8 +6979,8 @@ $(pv_value) Check Box 19 a22d448:177887d8135:-7ce6 - 684 - 551 + 702 + 516 @@ -7008,7 +7008,7 @@ $(pv_value) 20 Check Box_42 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_15_.EnableState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_15_.EnableState @@ -7026,8 +7026,8 @@ $(pv_value) Check Box 18 a22d448:177887d8135:-7ce5 - 588 - 551 + 606 + 516 @@ -7066,8 +7066,8 @@ $(pv_value) 18 false a22d448:177887d8135:-7ce4 - 0 - 551 + 18 + 516 @@ -7097,7 +7097,7 @@ $(pv_value) Text Update_100 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_14_.FileName + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_14_.FileName 0.0 @@ -7118,8 +7118,8 @@ $(pv_value) 157 false a22d448:177887d8135:-7cd1 - 17 - 526 + 35 + 491 @@ -7149,7 +7149,7 @@ $(pv_value) Text Update_101 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_14_.FileAge + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_14_.FileAge 0.0 @@ -7170,8 +7170,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7cd0 - 188 - 526 + 206 + 491 @@ -7201,7 +7201,7 @@ $(pv_value) Text Update_102 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_14_.FileSize + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_14_.FileSize 0.0 @@ -7222,8 +7222,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7ccf - 267 - 526 + 285 + 491 @@ -7253,7 +7253,7 @@ $(pv_value) Text Update_103 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_14_.FileRate + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_14_.FileRate 0.0 @@ -7274,8 +7274,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7cce - 355 - 526 + 373 + 491 @@ -7305,7 +7305,7 @@ $(pv_value) Text Update_104 0 true - /cfs/ds/DS_FileInfoPkt_t.FileInfo_14_.SequenceCount + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_14_.SequenceCount 0.0 @@ -7326,8 +7326,8 @@ $(pv_value) 65 false a22d448:177887d8135:-7ccd - 450 - 526 + 468 + 491 @@ -7355,7 +7355,7 @@ $(pv_value) 20 Check Box_43 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_14_.OpenState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_14_.OpenState @@ -7373,8 +7373,8 @@ $(pv_value) Check Box 19 a22d448:177887d8135:-7ccc - 684 - 526 + 702 + 491 @@ -7402,7 +7402,7 @@ $(pv_value) 20 Check Box_44 - /cfs/ds/DS_FileInfoPkt_t.FileInfo_14_.EnableState + /cfs/$(CPUID)/ds/DS_FileInfoPkt_t.FileInfo_14_.EnableState @@ -7420,8 +7420,8 @@ $(pv_value) Check Box 18 a22d448:177887d8135:-7ccb - 588 - 526 + 606 + 491 @@ -7460,7 +7460,47 @@ $(pv_value) 18 false a22d448:177887d8135:-7cca - 0 - 526 + 18 + 491 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) DS - Get File Info + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5c6c + 12 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/DS/Main.opi b/core/base/tools/commander/workspace_template/Displays/Apps/DS/Main.opi index b4e3825cd..d84f1c272 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/DS/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/DS/Main.opi @@ -10,7 +10,7 @@ - 1.5.5.202103162101 + 1.6.2.202104092231 @@ -23,7 +23,7 @@ /Displays/Core/EVS/Events.opi /modules/ds - DS + ($(CPUID)) DS true @@ -64,7 +64,7 @@ Text Update 0 false - /cfs/ds/DS_HkPacket_t.CmdAcceptedCounter + /cfs/$(CPUID)/ds/DS_HkPacket_t.CmdAcceptedCounter 0.0 @@ -236,7 +236,7 @@ $(pv_value) Text Update_1 0 false - /cfs/ds/DS_HkPacket_t.CmdRejectedCounter + /cfs/$(CPUID)/ds/DS_HkPacket_t.CmdRejectedCounter 0.0 @@ -267,7 +267,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/ds/Noop', {});]]> true @@ -323,7 +323,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/ds/Reset', {});]]> true @@ -400,7 +400,7 @@ $(pv_value) false - Data Storage + ($(CPUID)) Data Storage true 1 @@ -440,7 +440,7 @@ $(pv_value) Text Update_2 0 false - /cfs/ds/DS_HkPacket_t.DestTblLoadCounter + /cfs/$(CPUID)/ds/DS_HkPacket_t.DestTblLoadCounter 0.0 @@ -492,7 +492,7 @@ $(pv_value) Text Update_3 0 false - /cfs/ds/DS_HkPacket_t.DestTblErrCounter + /cfs/$(CPUID)/ds/DS_HkPacket_t.DestTblErrCounter 0.0 @@ -544,7 +544,7 @@ $(pv_value) Text Update_4 0 false - /cfs/ds/DS_HkPacket_t.FilterTblLoadCounter + /cfs/$(CPUID)/ds/DS_HkPacket_t.FilterTblLoadCounter 0.0 @@ -596,7 +596,7 @@ $(pv_value) Text Update_5 0 false - /cfs/ds/DS_HkPacket_t.FilterTblErrCounter + /cfs/$(CPUID)/ds/DS_HkPacket_t.FilterTblErrCounter 0.0 @@ -646,7 +646,7 @@ $(pv_value) 20 Text Update_6 - /cfs/ds/DS_HkPacket_t.AppEnableState + /cfs/$(CPUID)/ds/DS_HkPacket_t.AppEnableState @@ -695,7 +695,7 @@ $(pv_value) Text Update_7 0 false - /cfs/ds/DS_HkPacket_t.FileWriteCounter + /cfs/$(CPUID)/ds/DS_HkPacket_t.FileWriteCounter 0.0 @@ -747,7 +747,7 @@ $(pv_value) Text Update_8 0 false - /cfs/ds/DS_HkPacket_t.FileWriteErrCounter + /cfs/$(CPUID)/ds/DS_HkPacket_t.FileWriteErrCounter 0.0 @@ -799,7 +799,7 @@ $(pv_value) Text Update_9 0 false - /cfs/ds/DS_HkPacket_t.FileUpdateCounter + /cfs/$(CPUID)/ds/DS_HkPacket_t.FileUpdateCounter 0.0 @@ -851,7 +851,7 @@ $(pv_value) Text Update_10 0 false - /cfs/ds/DS_HkPacket_t.DisabledPktCounter + /cfs/$(CPUID)/ds/DS_HkPacket_t.DisabledPktCounter 0.0 @@ -903,7 +903,7 @@ $(pv_value) Text Update_11 0 false - /cfs/ds/DS_HkPacket_t.DisabledPktCounter + /cfs/$(CPUID)/ds/DS_HkPacket_t.DisabledPktCounter 0.0 @@ -955,7 +955,7 @@ $(pv_value) Text Update_12 0 false - /cfs/ds/DS_HkPacket_t.IgnoredPktCounter + /cfs/$(CPUID)/ds/DS_HkPacket_t.IgnoredPktCounter 0.0 @@ -1007,7 +1007,7 @@ $(pv_value) Text Update_13 0 false - /cfs/ds/DS_HkPacket_t.FilteredPktCounter + /cfs/$(CPUID)/ds/DS_HkPacket_t.FilteredPktCounter 0.0 @@ -1059,7 +1059,7 @@ $(pv_value) Text Update_14 0 false - /cfs/ds/DS_HkPacket_t.PassedPktCounter + /cfs/$(CPUID)/ds/DS_HkPacket_t.PassedPktCounter 0.0 @@ -1650,7 +1650,7 @@ $(pv_value) true @@ -2473,19 +2473,22 @@ $(pv_value) - - CloseAll.opi - - true - - 1 + + + + true false false - + false @@ -2499,11 +2502,11 @@ $(pv_value) false - + 19 - - NoOp_17 + ../../Resources/send.png + NoOp_18 0 @@ -2515,16 +2518,16 @@ $(pv_value) - Close All + Dis false $(pv_name) $(pv_value) true Action Button - 155 - -736e4684:150ac3c95a1:-724e - 346 - 328 + 68 + -736e4684:150ac3c95a1:-71f7 + 244 + 239 @@ -2532,10 +2535,11 @@ $(pv_value) +var cmd = '/cfs/$(CPUID)/ds/CloseAll'; + +Yamcs.issueCommand(cmd, {});]]> true @@ -2561,7 +2565,7 @@ Yamcs.issueCommand('/cfs/ds/SetAppState', 19 ../../Resources/send.png - NoOp_18 + Action Button_1 0 @@ -2573,16 +2577,77 @@ Yamcs.issueCommand('/cfs/ds/SetAppState', - Dis + Close All false $(pv_name) $(pv_value) true Action Button - 68 - -736e4684:150ac3c95a1:-71f7 - 244 - 239 + 153 + -c05c465:1785c72c4a1:-5d4e + 347 + 328 + + + + + + + true + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 19 + + Events + 0 + + + + + true + true + false + + + + Event Filters + false + $(pv_name) +$(pv_value) + true + Action Button + 154 + -c05c465:1785c72c4a1:-5d44 + 347 + 346 @@ -2591,7 +2656,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/ds/SendHK', {});]]> true @@ -2615,7 +2680,7 @@ Yamcs.issueCommand('/cfs/ds/SendHK', {});]]> - 20 + 19 ../../Resources/send.png NoOp_19 0 @@ -2635,10 +2700,10 @@ Yamcs.issueCommand('/cfs/ds/SendHK', {});]]> $(pv_value) true Action Button - 82 - 3224b3ef:1778cb22598:-7f83 - 378 - 6 + 155 + -c05c465:1785c72c4a1:-5d3a + 347 + 364 @@ -2649,10 +2714,10 @@ importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); importPackage(org.csstudio.opibuilder.runmode) -var opi_to_open_path = FileUtil.workspacePathToSysPath(display.getMacroValue("EVENTS_OPI")); +var opi_to_open_path = FileUtil.workspacePathToSysPath("Displays/Core/ES/ApplicationControl_App.opi"); var macroInput = DataUtil.createMacrosInput(true); -ScriptUtil.openOPI(display.getWidget("Events"), opi_to_open_path, RunModeService.DisplayMode.REPLACE, macroInput );]]> +ScriptUtil.openOPI(display.getWidget("AppControl"), opi_to_open_path, RunModeService.DisplayMode.REPLACE, macroInput );]]> true @@ -2678,7 +2743,7 @@ ScriptUtil.openOPI(display.getWidget("Events"), opi_to_open_path, RunModeService 19 - Events + AppControl 0 @@ -2690,15 +2755,15 @@ ScriptUtil.openOPI(display.getWidget("Events"), opi_to_open_path, RunModeService - Event Filters + App Control false $(pv_name) $(pv_value) true Action Button - 154 - -19107c2b:177da1db5df:1a4 - 347 - 346 + 153 + 49c9ccd0:178c6a335db:-6b9f + 348 + 58 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestAge.opi b/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestAge.opi index fb18d79e1..ab0dc2866 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestAge.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestAge.opi @@ -15,11 +15,11 @@ 6 - 600 + 150 true - DS - Set Dest Age + ($(CPUID)) DS - Set Dest Age true @@ -28,7 +28,7 @@ true true Display - 800 + 240 -736e4684:150ac3c95a1:-721f -1 -1 @@ -51,7 +51,7 @@ 20 - 1 + 2 Label @@ -60,17 +60,17 @@ false - FileTableIndex + File Table Index true 1 true Label - 139 + 103 false a22d448:177887d8135:-740c 18 - 30 + 39 @@ -124,8 +124,8 @@ $(pv_value) Spinner 85 a22d448:177887d8135:-7408 - 168 - 27 + 132 + 36 @@ -146,7 +146,7 @@ $(pv_value) 20 - 1 + 2 Label_1 @@ -155,17 +155,17 @@ $(pv_value) false - MaxFileAge + Max File Age true 1 true Label - 139 + 85 false a22d448:177887d8135:-7400 - 18 - 60 + 36 + 69 @@ -219,8 +219,8 @@ $(pv_value) Spinner 85 a22d448:177887d8135:-73f8 - 168 - 57 + 132 + 66 @@ -234,7 +234,7 @@ var file_index = VTypeHelper.getDouble(display.getWidget('FileTableIndex').getPr var file_age = VTypeHelper.getDouble(display.getWidget('MaxFileAge').getPropertyValue('pv_value')); -var cmd = '/cfs/ds/SetDestAge'; +var cmd = '/cfs/$(CPUID)/ds/SetDestAge'; Yamcs.issueCommand(cmd, {'FileTableIndex': file_index, @@ -278,15 +278,55 @@ Yamcs.issueCommand(cmd, - SetDestAge + Set false $(pv_name) $(pv_value) true Action Button - 163 + 79 a22d448:177887d8135:-73ea - 72 - 102 + 78 + 108 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) DS - Set Dest Age + + true + 1 + true + Label + 223 + false + -c05c465:1785c72c4a1:-5c89 + 6 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestBase.opi b/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestBase.opi index 72d663042..cb61eb3cc 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestBase.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestBase.opi @@ -15,11 +15,11 @@ 6 - 400 + 150 true - DS - Set Dest Base + ($(CPUID)) DS - Set Dest Base true @@ -28,7 +28,7 @@ true true Display - 400 + 300 -736e4684:150ac3c95a1:-722b -1 -1 @@ -84,8 +84,8 @@ $(pv_value) Spinner 85 a22d448:177887d8135:-6ef2 - 150 - 39 + 138 + 36 @@ -99,7 +99,7 @@ var file_index = VTypeHelper.getDouble(display.getWidget('FileTableIndex').getPr var base_name = VTypeHelper.getString(display.getWidget('Basename').getPropertyValue('pv_value')); -var cmd = '/cfs/ds/SetDestBase'; +var cmd = '/cfs/$(CPUID)/ds/SetDestBase'; Yamcs.issueCommand(cmd, {'FileTableIndex': file_index, @@ -144,16 +144,16 @@ Yamcs.issueCommand(cmd, - SetDestBase + Set false $(pv_name) $(pv_value) true Action Button - 163 + 85 a22d448:177887d8135:-6ef1 - 96 - 126 + 108 + 108 @@ -174,7 +174,7 @@ $(pv_value) 20 - 1 + 2 Label @@ -183,17 +183,17 @@ $(pv_value) false - FileTableIndex + File Table Index true 1 true Label - 97 + 121 false a22d448:177887d8135:-6eea - 24 - 42 + 3 + 39 @@ -214,7 +214,7 @@ $(pv_value) 20 - 1 + 2 Label_1 @@ -223,7 +223,7 @@ $(pv_value) false - Basename + Base Name true 1 @@ -232,8 +232,8 @@ $(pv_value) 103 false a22d448:177887d8135:-6ee2 - 24 - 72 + 21 + 69 @@ -289,7 +289,47 @@ $(pv_value) Text Input 146 a22d448:177887d8135:-6ed6 - 144 - 69 + 138 + 66 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) DS - Set Dest Base + + true + 1 + true + Label + 229 + false + -c05c465:1785c72c4a1:-5ca1 + 36 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestCount.opi b/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestCount.opi index 45abbede1..76d6a065a 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestCount.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestCount.opi @@ -15,11 +15,11 @@ 6 - 600 + 140 true - DS - Set Dest Count + ($(CPUID)) DS - Set Dest Count true @@ -28,7 +28,7 @@ true true Display - 800 + 280 -736e4684:150ac3c95a1:-721b -1 -1 @@ -85,7 +85,7 @@ $(pv_value) 85 a22d448:177887d8135:-6e94 144 - 30 + 36 @@ -99,7 +99,7 @@ var file_index = VTypeHelper.getDouble(display.getWidget('FileTableIndex').getPr var seq_count = VTypeHelper.getDouble(display.getWidget('Basename').getPropertyValue('pv_value')); -var cmd = '/cfs/ds/SetDestCount'; +var cmd = '/cfs/$(CPUID)/ds/SetDestCount'; Yamcs.issueCommand(cmd, {'FileTableIndex': file_index, @@ -144,16 +144,16 @@ Yamcs.issueCommand(cmd, - SetDestCount + Set false $(pv_name) $(pv_value) true Action Button - 163 + 100 a22d448:177887d8135:-6e93 - 90 - 117 + 89 + 96 @@ -174,7 +174,7 @@ $(pv_value) 20 - 1 + 2 Label @@ -183,7 +183,7 @@ $(pv_value) false - FileTableIndex + File Table Index true 1 @@ -193,7 +193,7 @@ $(pv_value) false a22d448:177887d8135:-6e92 18 - 33 + 39 @@ -214,7 +214,7 @@ $(pv_value) 20 - 1 + 2 Label_1 @@ -223,7 +223,7 @@ $(pv_value) false - SequenceCount + Sequence Count true 1 @@ -233,7 +233,7 @@ $(pv_value) false a22d448:177887d8135:-6e91 18 - 63 + 61 @@ -288,6 +288,46 @@ $(pv_value) 85 a22d448:177887d8135:-6e90 144 - 60 + 58 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) DS - Set Dest Count + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5d25 + 6 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestExt.opi b/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestExt.opi index edff40389..7e9224195 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestExt.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestExt.opi @@ -15,11 +15,11 @@ 6 - 600 + 140 true - DS - Set Dest Ext + ($(CPUID)) DS - Set Dest Ext true @@ -28,7 +28,7 @@ true true Display - 800 + 280 -736e4684:150ac3c95a1:-7227 -1 -1 @@ -99,7 +99,7 @@ var file_index = VTypeHelper.getDouble(display.getWidget('FileTableIndex').getPr var extension = VTypeHelper.getString(display.getWidget('Extension').getPropertyValue('pv_value')); -var cmd = '/cfs/ds/SetDestExt'; +var cmd = '/cfs/$(CPUID)/ds/SetDestExt'; Yamcs.issueCommand(cmd, {'FileTableIndex': file_index, @@ -144,16 +144,16 @@ Yamcs.issueCommand(cmd, - SetDestExt + Set false $(pv_name) $(pv_value) true Action Button - 163 + 91 a22d448:177887d8135:-6e25 - 48 - 114 + 93 + 96 @@ -233,7 +233,7 @@ $(pv_value) false a22d448:177887d8135:-6e23 24 - 63 + 60 @@ -290,6 +290,46 @@ $(pv_value) 100 a22d448:177887d8135:-6e0b 150 - 60 + 57 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) DS - Set Dest Extension + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5d05 + 6 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestPath.opi b/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestPath.opi index 406b0947d..30569a137 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestPath.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestPath.opi @@ -15,11 +15,11 @@ 6 - 400 + 140 true - DS - Set Dest Path + ($(CPUID)) DS - Set Dest Path true @@ -28,7 +28,7 @@ true true Display - 400 + 340 -736e4684:150ac3c95a1:-7233 -1 -1 @@ -84,7 +84,7 @@ $(pv_value) Spinner 85 a22d448:177887d8135:-6de4 - 156 + 120 30 @@ -99,7 +99,7 @@ var file_index = VTypeHelper.getDouble(display.getWidget('FileTableIndex').getPr var extension = VTypeHelper.getString(display.getWidget('Path').getPropertyValue('pv_value')); -var cmd = '/cfs/ds/SetDestPath'; +var cmd = '/cfs/$(CPUID)/ds/SetDestPath'; Yamcs.issueCommand(cmd, {'FileTableIndex': file_index, @@ -144,16 +144,16 @@ Yamcs.issueCommand(cmd, - SetDestPath + Set false $(pv_name) $(pv_value) true Action Button - 163 + 79 a22d448:177887d8135:-6de3 - 54 - 114 + 105 + 96 @@ -174,7 +174,7 @@ $(pv_value) 20 - 1 + 2 Label @@ -183,16 +183,16 @@ $(pv_value) false - FileTableIndex + File Table Index true 1 true Label - 115 + 109 false a22d448:177887d8135:-6de2 - 30 + 0 33 @@ -214,7 +214,7 @@ $(pv_value) 20 - 1 + 2 Label_1 @@ -223,16 +223,16 @@ $(pv_value) false - Pathname + Path Name true 1 true Label - 115 + 91 false a22d448:177887d8135:-6de1 - 30 + 18 63 @@ -289,7 +289,47 @@ $(pv_value) Text Input 211 a22d448:177887d8135:-6de0 - 156 + 120 60 + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) DS - Set Dest Path + + true + 1 + true + Label + 229 + false + -c05c465:1785c72c4a1:-5ced + 30 + 6 + \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestSize.opi b/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestSize.opi index 2ecbc2351..cd01f8521 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestSize.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestSize.opi @@ -15,11 +15,11 @@ 6 - 600 + 140 true - DS - Set Dest Size + ($(CPUID)) DS - Set Dest Size true @@ -28,7 +28,7 @@ true true Display - 800 + 260 -736e4684:150ac3c95a1:-7223 -1 -1 @@ -85,7 +85,7 @@ $(pv_value) 85 a22d448:177887d8135:-6db9 156 - 48 + 30 @@ -100,7 +100,7 @@ var file_index = VTypeHelper.getNumber(display.getWidget('FileTableIndex').getPr var size = VTypeHelper.getDouble(display.getWidget('MaxFileSize').getPropertyValue('pv_value')); -var cmd = '/cfs/ds/SetDestSize'; +var cmd = '/cfs/$(CPUID)/ds/SetDestSize'; Yamcs.issueCommand(cmd, {'FileTableIndex': file_index, @@ -153,8 +153,8 @@ $(pv_value) Action Button 163 a22d448:177887d8135:-6db8 - 54 - 132 + 57 + 96 @@ -194,7 +194,7 @@ $(pv_value) false a22d448:177887d8135:-6db7 30 - 51 + 33 @@ -234,7 +234,7 @@ $(pv_value) false a22d448:177887d8135:-6db6 30 - 81 + 63 @@ -289,6 +289,46 @@ $(pv_value) 85 a22d448:177887d8135:-6da7 156 - 78 + 60 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) DS - Set Dest Size + + true + 1 + true + Label + 253 + false + -c05c465:1785c72c4a1:-5d7b + 6 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestState.opi b/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestState.opi index 681788d76..21f682236 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestState.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestState.opi @@ -15,7 +15,7 @@ 6 - 400 + 140 true @@ -28,7 +28,7 @@ true true Display - 400 + 260 -736e4684:150ac3c95a1:-7237 -1 -1 @@ -84,8 +84,8 @@ $(pv_value) Spinner 85 a22d448:177887d8135:-6d80 - 156 - 51 + 138 + 33 @@ -107,7 +107,7 @@ if(enabled == 1) enabled_arg = 1; } -var cmd = '/cfs/ds/SetDestState'; +var cmd = '/cfs/$(CPUID)/ds/SetDestState'; Yamcs.issueCommand(cmd, @@ -152,16 +152,16 @@ Yamcs.issueCommand(cmd, - SetDestState + Set false $(pv_name) $(pv_value) true Action Button - 163 + 85 a22d448:177887d8135:-6d7f - 54 - 135 + 87 + 96 @@ -200,8 +200,8 @@ $(pv_value) 115 false a22d448:177887d8135:-6d7e - 30 - 54 + 12 + 36 @@ -240,8 +240,8 @@ $(pv_value) 115 false a22d448:177887d8135:-6d7d - 30 - 84 + 12 + 66 @@ -287,7 +287,47 @@ $(pv_value) Check Box 19 a22d448:177887d8135:-6d7c - 156 - 81 + 138 + 63 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) DS - Set Dest State + + true + 1 + true + Label + 235 + false + -c05c465:1785c72c4a1:-5d82 + 12 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestType.opi b/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestType.opi index 62a097811..85f784b76 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestType.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetDestType.opi @@ -15,7 +15,7 @@ 6 - 600 + 140 true @@ -28,7 +28,7 @@ true true Display - 800 + 290 -736e4684:150ac3c95a1:-723b -1 -1 @@ -99,7 +99,7 @@ var file_index = VTypeHelper.getDouble(display.getWidget('FileTableIndex').getPr var type = VTypeHelper.getDouble(display.getWidget('FileNameType').getPropertyValue('pv_value')); -var cmd = '/cfs/ds/SetDestType'; +var cmd = '/cfs/$(CPUID)/ds/SetDestType'; Yamcs.issueCommand(cmd, @@ -144,16 +144,16 @@ Yamcs.issueCommand(cmd, - SetDestType + Set false $(pv_name) $(pv_value) true Action Button - 163 + 85 a22d448:177887d8135:-6c9f - 48 - 114 + 102 + 102 @@ -183,7 +183,7 @@ $(pv_value) false - FileTableIndex + File Table Index true 1 @@ -223,7 +223,7 @@ $(pv_value) false - FileNameType + File Name Type true 1 @@ -290,4 +290,44 @@ $(pv_value) 150 60 + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) DS - Set Dest Type + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5d89 + 12 + 6 + \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetFilterFile.opi b/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetFilterFile.opi index 561767f92..7ad133d88 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetFilterFile.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetFilterFile.opi @@ -15,11 +15,11 @@ 6 - 600 + 190 true - DS - Set Filter File + ($(CPUID)) DS - Set Filter File true @@ -28,7 +28,7 @@ true true Display - 800 + 280 -736e4684:150ac3c95a1:-7247 -1 -1 @@ -82,10 +82,10 @@ $(pv_value) 1 true Spinner - 85 + 109 a22d448:177887d8135:-6c00 - 174 - 90 + 150 + 69 @@ -101,7 +101,7 @@ var param_index = VTypeHelper.getDouble(display.getWidget('FilterParmsIndex').ge var msgID = VTypeHelper.getDouble(display.getWidget('MessageID').getPropertyValue('pv_value')); -var cmd = '/cfs/ds/SetFilterFile'; +var cmd = '/cfs/$(CPUID)/ds/SetFilterFile'; Yamcs.issueCommand(cmd, {'MessageID': msgID, @@ -147,16 +147,16 @@ Yamcs.issueCommand(cmd, - SetFilterFile + Set false $(pv_name) $(pv_value) true Action Button - 163 + 85 a22d448:177887d8135:-6bff - 72 - 168 + 101 + 144 @@ -177,7 +177,7 @@ $(pv_value) 20 - 1 + 2 Label @@ -186,7 +186,7 @@ $(pv_value) false - FilterParmsIndex + Filter Parms Index true 1 @@ -195,8 +195,8 @@ $(pv_value) 121 false a22d448:177887d8135:-6bfe - 24 - 93 + 12 + 72 @@ -217,7 +217,7 @@ $(pv_value) 20 - 1 + 2 Label_1 @@ -226,7 +226,7 @@ $(pv_value) false - FileTableIndex + File Table Index true 1 @@ -235,8 +235,8 @@ $(pv_value) 103 false a22d448:177887d8135:-6bfd - 24 - 123 + 30 + 102 @@ -288,10 +288,10 @@ $(pv_value) 1 true Spinner - 85 + 109 a22d448:177887d8135:-6bf1 - 174 - 60 + 150 + 39 @@ -312,7 +312,7 @@ $(pv_value) 20 - 1 + 2 Label_2 @@ -321,7 +321,7 @@ $(pv_value) false - MessageID + MsgID true 1 @@ -330,8 +330,8 @@ $(pv_value) 121 false a22d448:177887d8135:-6bf0 - 24 - 63 + 12 + 42 @@ -383,9 +383,49 @@ $(pv_value) 1 true Spinner - 85 + 109 a22d448:177887d8135:-6718 - 174 - 120 + 150 + 99 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) DS - Set Filter File + + true + 1 + true + Label + 254 + false + -c05c465:1785c72c4a1:-5d90 + 17 + 4 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetFilterParms.opi b/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetFilterParms.opi index a7f13fc72..8561d13d4 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetFilterParms.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetFilterParms.opi @@ -15,11 +15,11 @@ 6 - 600 + 260 true - DS - Set Filter Parms + ($(CPUID)) DS - Set Filter Parms true @@ -28,7 +28,7 @@ true true Display - 800 + 300 -736e4684:150ac3c95a1:-723f -1 -1 @@ -102,7 +102,7 @@ var Algorithm_X = VTypeHelper.getDouble(display.getWidget('Algorithm_X').getP var Algorithm_O = VTypeHelper.getDouble(display.getWidget('Algorithm_O').getPropertyValue('pv_value')); -var cmd = '/cfs/ds/SetFilterParams'; +var cmd = '/cfs/$(CPUID)/ds/SetFilterParams'; Yamcs.issueCommand(cmd, {'MessageID': msgID, @@ -150,16 +150,16 @@ Yamcs.issueCommand(cmd, - SetFilterParams + Set false $(pv_name) $(pv_value) true Action Button - 163 + 91 a22d448:177887d8135:-6b8e - 66 - 252 + 100 + 216 @@ -180,7 +180,7 @@ $(pv_value) 20 - 1 + 2 Label @@ -189,7 +189,7 @@ $(pv_value) false - FilterParmsIndex + Filter Parms Index true 1 @@ -198,7 +198,7 @@ $(pv_value) 121 false a22d448:177887d8135:-6b8d - 30 + 48 69 @@ -220,7 +220,7 @@ $(pv_value) 20 - 1 + 2 Label_1 @@ -229,7 +229,7 @@ $(pv_value) false - Algorithm_N + Algorithm N true 1 @@ -238,7 +238,7 @@ $(pv_value) 103 false a22d448:177887d8135:-6b8c - 30 + 66 99 @@ -315,7 +315,7 @@ $(pv_value) 20 - 1 + 2 Label_2 @@ -324,7 +324,7 @@ $(pv_value) false - MessageID + MsgID true 1 @@ -333,7 +333,7 @@ $(pv_value) 121 false a22d448:177887d8135:-6b8a - 30 + 48 39 @@ -355,7 +355,7 @@ $(pv_value) 20 - 1 + 2 Label_3 @@ -364,7 +364,7 @@ $(pv_value) false - Algorithm_O + Algorithm O true 1 @@ -373,7 +373,7 @@ $(pv_value) 103 false a22d448:177887d8135:-6b5e - 30 + 66 171 @@ -395,7 +395,7 @@ $(pv_value) 20 - 1 + 2 Label_4 @@ -404,7 +404,7 @@ $(pv_value) false - Algorithm_X + Algorithm X true 1 @@ -413,7 +413,7 @@ $(pv_value) 103 false a22d448:177887d8135:-6b56 - 30 + 66 135 @@ -581,4 +581,44 @@ $(pv_value) 180 96 + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) DS - Set Filter Parameters + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5d97 + 13 + 2 + \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetFilterType.opi b/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetFilterType.opi index c271a5315..7470c4e1b 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetFilterType.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/DS/SetFilterType.opi @@ -15,11 +15,11 @@ 6 - 600 + 160 true - DS - Set Filter Type + ($(CPUID)) DS - Set Filter Type true @@ -28,7 +28,7 @@ true true Display - 800 + 290 -736e4684:150ac3c95a1:-7243 -1 -1 @@ -82,10 +82,10 @@ $(pv_value) 1 true Spinner - 85 + 115 a22d448:177887d8135:-6aac - 198 - 93 + 150 + 60 @@ -100,7 +100,7 @@ var param_index = VTypeHelper.getDouble(display.getWidget('FilterParmsIndex'). var filter_type = VTypeHelper.getDouble(display.getWidget('FilterType').getPropertyValue('pv_value')); -var cmd = '/cfs/ds/SetFilterType'; +var cmd = '/cfs/$(CPUID)/ds/SetFilterType'; Yamcs.issueCommand(cmd, {'MessageID': msgID, @@ -146,16 +146,16 @@ Yamcs.issueCommand(cmd, - SetFilterParams + Set false $(pv_name) $(pv_value) true Action Button - 163 + 91 a22d448:177887d8135:-6aab - 84 - 174 + 99 + 126 @@ -176,7 +176,7 @@ $(pv_value) 20 - 1 + 2 Label @@ -185,7 +185,7 @@ $(pv_value) false - FilterParmsIndex + Filter Param Index true 1 @@ -194,8 +194,8 @@ $(pv_value) 121 false a22d448:177887d8135:-6aaa - 48 - 96 + 12 + 63 @@ -216,7 +216,7 @@ $(pv_value) 20 - 1 + 2 Label_1 @@ -225,7 +225,7 @@ $(pv_value) false - FilterType + Filter Type true 1 @@ -234,8 +234,8 @@ $(pv_value) 103 false a22d448:177887d8135:-6aa9 - 48 - 126 + 30 + 87 @@ -287,10 +287,10 @@ $(pv_value) 1 true Spinner - 85 + 115 a22d448:177887d8135:-6aa8 - 198 - 63 + 150 + 36 @@ -311,7 +311,7 @@ $(pv_value) 20 - 1 + 2 Label_2 @@ -320,7 +320,7 @@ $(pv_value) false - MessageID + MsgID true 1 @@ -329,8 +329,8 @@ $(pv_value) 121 false a22d448:177887d8135:-6aa7 - 48 - 66 + 12 + 39 @@ -382,9 +382,49 @@ $(pv_value) 1 true Spinner - 85 + 115 a22d448:177887d8135:-6aa2 - 198 - 123 + 150 + 84 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) DS - Set Filter Type + + true + 1 + true + Label + 229 + false + -c05c465:1785c72c4a1:-5d9e + 30 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/DS/scripts/NoOp.js b/core/base/tools/commander/workspace_template/Displays/Apps/DS/scripts/NoOp.js index c83421048..ec1d14bf8 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/DS/scripts/NoOp.js +++ b/core/base/tools/commander/workspace_template/Displays/Apps/DS/scripts/NoOp.js @@ -1,4 +1,4 @@ importPackage(Packages.org.csstudio.opibuilder.scriptUtil); importPackage(Packages.org.yamcs.studio.script); -Yamcs.issueCommand('/cfs/ds/Noop', {}); \ No newline at end of file +Yamcs.issueCommand('/cfs/$(CPUID)/ds/Noop', {}); \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/DS/scripts/ResetCounters.js b/core/base/tools/commander/workspace_template/Displays/Apps/DS/scripts/ResetCounters.js index ea88615c3..cc2d20ac3 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/DS/scripts/ResetCounters.js +++ b/core/base/tools/commander/workspace_template/Displays/Apps/DS/scripts/ResetCounters.js @@ -1,4 +1,4 @@ importPackage(Packages.org.csstudio.opibuilder.scriptUtil); importPackage(Packages.org.yamcs.studio.script); -Yamcs.issueCommand('/cfs/ds/Reset', {}); \ No newline at end of file +Yamcs.issueCommand('/cfs/$(CPUID)/ds/Reset', {}); \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/FM/Concat.opi b/core/base/tools/commander/workspace_template/Displays/Apps/FM/Concat.opi index 270500240..1d9c30c72 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/FM/Concat.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/FM/Concat.opi @@ -15,11 +15,11 @@ 6 - 400 + 180 true - FM - Concat + ($(CPUID)) FM - Concat true @@ -28,7 +28,7 @@ true true Display - 400 + 380 3224b3ef:1778cb22598:-7c75 -1 -1 @@ -44,7 +44,7 @@ var source1_arg = VTypeHelper.getString(display.getWidget("Source1") .getProper var source2_arg = VTypeHelper.getString(display.getWidget("Source2").getPropertyValue("pv_value")); var target_arg = VTypeHelper.getString(display.getWidget("Target").getPropertyValue("pv_value")); -Yamcs.issueCommand('/cfs/fm/Concat', +Yamcs.issueCommand('/cfs/$(CPUID)/fm/Concat', {"Source1": source1_arg, "Source2": source2_arg, "Target": target_arg}); @@ -72,7 +72,7 @@ Yamcs.issueCommand('/cfs/fm/Concat', - 18 + 25 ../../Resources/send.png NoOp 0 @@ -94,8 +94,8 @@ $(pv_value) Action Button 109 3224b3ef:1778cb22598:-7c6a - 84 - 168 + 85 + 138 @@ -109,7 +109,7 @@ $(pv_value) - 1 + 4 1 true @@ -149,10 +149,10 @@ $(pv_value) false true Text Input - 100 + 265 3224b3ef:1778cb22598:-7c66 - 132 - 81 + 96 + 69 @@ -173,7 +173,7 @@ $(pv_value) 20 - 1 + 2 Label @@ -182,7 +182,7 @@ $(pv_value) false - Source2 + Source 2 true 1 @@ -191,8 +191,8 @@ $(pv_value) 80 false 3224b3ef:1778cb22598:-7c62 - 48 - 84 + 6 + 75 @@ -206,7 +206,7 @@ $(pv_value) - 1 + 4 1 true @@ -246,10 +246,10 @@ $(pv_value) false true Text Input - 100 + 265 3224b3ef:1778cb22598:-7c57 - 132 - 114 + 96 + 102 @@ -270,7 +270,7 @@ $(pv_value) 20 - 1 + 2 Label_1 @@ -288,8 +288,8 @@ $(pv_value) 80 false 3224b3ef:1778cb22598:-7c56 - 48 - 114 + 6 + 105 @@ -310,7 +310,7 @@ $(pv_value) 20 - 1 + 2 Label_2 @@ -319,7 +319,7 @@ $(pv_value) false - Source1 + Source 1 true 1 @@ -328,8 +328,8 @@ $(pv_value) 80 false 3224b3ef:1778cb22598:-7c47 - 48 - 51 + 6 + 42 @@ -343,7 +343,7 @@ $(pv_value) - 1 + 4 1 true @@ -383,9 +383,49 @@ $(pv_value) false true Text Input - 100 + 265 3224b3ef:1778cb22598:-7a20 - 132 - 48 + 96 + 36 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) FM - Concat + + true + 1 + true + Label + 187 + false + -c05c465:1785c72c4a1:-5a98 + 54 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/FM/CopyFile.opi b/core/base/tools/commander/workspace_template/Displays/Apps/FM/CopyFile.opi index 79eee2888..db522fe81 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/FM/CopyFile.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/FM/CopyFile.opi @@ -15,11 +15,11 @@ 6 - 400 + 180 true - FM - Copy + ($(CPUID)) FM - Copy true @@ -28,7 +28,7 @@ true true Display - 400 + 380 3224b3ef:1778cb22598:-7c75 -1 -1 @@ -46,7 +46,7 @@ var overwrite_arg = VTypeHelper.getDouble(display.getWidget("Overwrite") .getPr var source_arg = VTypeHelper.getString(display.getWidget("Source").getPropertyValue("pv_value")); var target_arg = VTypeHelper.getString(display.getWidget("Target").getPropertyValue("pv_value")); -Yamcs.issueCommand('/cfs/fm/CopyFile', +Yamcs.issueCommand('/cfs/$(CPUID)/fm/CopyFile', {"Overwrite": parseInt(overwrite_arg), "Source": source_arg, "Target": target_arg}); @@ -74,7 +74,7 @@ Yamcs.issueCommand('/cfs/fm/CopyFile', - 18 + 25 ../../Resources/send.png NoOp 0 @@ -88,7 +88,7 @@ Yamcs.issueCommand('/cfs/fm/CopyFile', - CopyFile + Copy false $(pv_name) $(pv_value) @@ -96,8 +96,8 @@ $(pv_value) Action Button 109 3224b3ef:1778cb22598:-7c6a - 84 - 168 + 88 + 138 @@ -111,7 +111,7 @@ $(pv_value) - 1 + 4 1 true @@ -151,10 +151,10 @@ $(pv_value) false true Text Input - 100 + 265 3224b3ef:1778cb22598:-7c66 - 132 - 81 + 93 + 69 @@ -193,8 +193,8 @@ $(pv_value) 80 false 3224b3ef:1778cb22598:-7c62 - 48 - 84 + 9 + 72 @@ -208,7 +208,7 @@ $(pv_value) - 1 + 4 1 true @@ -248,10 +248,10 @@ $(pv_value) false true Text Input - 100 + 265 3224b3ef:1778cb22598:-7c57 - 132 - 114 + 93 + 102 @@ -290,8 +290,8 @@ $(pv_value) 80 false 3224b3ef:1778cb22598:-7c56 - 48 - 114 + 9 + 102 @@ -304,7 +304,7 @@ $(pv_value) - 1 + 4 1 false true @@ -345,8 +345,8 @@ $(pv_value) Spinner 100 3224b3ef:1778cb22598:-7c4f - 132 - 48 + 93 + 36 @@ -385,7 +385,47 @@ $(pv_value) 80 false 3224b3ef:1778cb22598:-7c47 - 48 - 51 + 9 + 39 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) FM - Copy + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5ac4 + 6 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/FM/CreateDir.opi b/core/base/tools/commander/workspace_template/Displays/Apps/FM/CreateDir.opi index 5def652fa..683ecc785 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/FM/CreateDir.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/FM/CreateDir.opi @@ -15,11 +15,11 @@ 6 - 400 + 110 true - FM - Create Dir + ($(CPUID)) FM - Create Dir true @@ -28,7 +28,7 @@ true true Display - 400 + 370 3224b3ef:1778cb22598:-7c75 -1 -1 @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var directory_arg = VTypeHelper.getString(display.getWidget("Directory").getPropertyValue("pv_value")); -Yamcs.issueCommand('/cfs/fm/CreateDir', +Yamcs.issueCommand('/cfs/$(CPUID)/fm/CreateDir', {"Directory":directory_arg}); ]]> true @@ -68,7 +68,7 @@ Yamcs.issueCommand('/cfs/fm/CreateDir', - 18 + 25 ../../Resources/send.png NoOp 0 @@ -82,7 +82,7 @@ Yamcs.issueCommand('/cfs/fm/CreateDir', - CreateDir + Create false $(pv_name) $(pv_value) @@ -90,8 +90,8 @@ $(pv_value) Action Button 109 3224b3ef:1778cb22598:-7c6a - 84 - 78 + 117 + 72 @@ -105,7 +105,7 @@ $(pv_value) - 1 + 4 1 true @@ -145,9 +145,9 @@ $(pv_value) false true Text Input - 100 + 265 3224b3ef:1778cb22598:-7c57 - 120 + 84 36 @@ -169,7 +169,7 @@ $(pv_value) 20 - 1 + 2 Label_1 @@ -184,10 +184,50 @@ $(pv_value) 1 true Label - 80 + 62 false 3224b3ef:1778cb22598:-7c56 - 36 + 12 36 + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) FM - Create Directory + + true + 1 + true + Label + 247 + false + -c05c465:1785c72c4a1:-5abd + 48 + 6 + \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/FM/Decompress.opi b/core/base/tools/commander/workspace_template/Displays/Apps/FM/Decompress.opi index 9444ec964..ed8f2a7c4 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/FM/Decompress.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/FM/Decompress.opi @@ -15,11 +15,11 @@ 6 - 400 + 150 true - FM - Decompress + ($(CPUID)) FM - Decompress true @@ -28,7 +28,7 @@ true true Display - 400 + 380 3224b3ef:1778cb22598:-7c75 -1 -1 @@ -43,7 +43,7 @@ importPackage(Packages.org.yamcs.studio.data); var source_arg = VTypeHelper.getString(display.getWidget("Source").getPropertyValue("pv_value")); var target_arg = VTypeHelper.getString(display.getWidget("Target").getPropertyValue("pv_value")); -Yamcs.issueCommand('/cfs/fm/Decompress', +Yamcs.issueCommand('/cfs/$(CPUID)/fm/Decompress', { "Source": source_arg, "Target": target_arg @@ -73,7 +73,7 @@ Yamcs.issueCommand('/cfs/fm/Decompress', - 18 + 24 ../../Resources/send.png NoOp 0 @@ -93,10 +93,10 @@ Yamcs.issueCommand('/cfs/fm/Decompress', $(pv_value) true Action Button - 109 + 133 3224b3ef:1778cb22598:-7c6a - 102 - 132 + 114 + 108 @@ -110,7 +110,7 @@ $(pv_value) - 1 + 4 1 true @@ -150,10 +150,10 @@ $(pv_value) false true Text Input - 100 + 265 3224b3ef:1778cb22598:-7c66 - 138 - 45 + 90 + 36 @@ -192,8 +192,8 @@ $(pv_value) 80 false 3224b3ef:1778cb22598:-7c62 - 54 - 48 + 6 + 39 @@ -207,7 +207,7 @@ $(pv_value) - 1 + 4 1 true @@ -247,10 +247,10 @@ $(pv_value) false true Text Input - 100 + 265 3224b3ef:1778cb22598:-7c57 - 138 - 78 + 90 + 69 @@ -289,7 +289,47 @@ $(pv_value) 80 false 3224b3ef:1778cb22598:-7c56 - 54 - 78 + 6 + 69 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) FM - Decompress + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5ab6 + 48 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/FM/DeleteAllFiles.opi b/core/base/tools/commander/workspace_template/Displays/Apps/FM/DeleteAllFiles.opi index b79c9533a..886d863f9 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/FM/DeleteAllFiles.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/FM/DeleteAllFiles.opi @@ -15,11 +15,11 @@ 6 - 400 + 120 true - FM - Delete All + ($(CPUID)) FM - Delete All true @@ -28,7 +28,7 @@ true true Display - 400 + 370 3224b3ef:1778cb22598:-7c75 -1 -1 @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var directory_arg = VTypeHelper.getString(display.getWidget("Directory").getPropertyValue("pv_value")); -Yamcs.issueCommand('/cfs/fm/DeleteAll', +Yamcs.issueCommand('/cfs/$(CPUID)/fm/DeleteAll', {"Directory":directory_arg}); ]]> true @@ -68,7 +68,7 @@ Yamcs.issueCommand('/cfs/fm/DeleteAll', - 18 + 25 ../../Resources/send.png NoOp 0 @@ -82,7 +82,7 @@ Yamcs.issueCommand('/cfs/fm/DeleteAll', - DeleteAll + Delete All false $(pv_name) $(pv_value) @@ -90,8 +90,8 @@ $(pv_value) Action Button 109 3224b3ef:1778cb22598:-7c6a - 84 - 78 + 120 + 72 @@ -105,7 +105,7 @@ $(pv_value) - 1 + 4 1 true @@ -145,9 +145,9 @@ $(pv_value) false true Text Input - 100 + 265 3224b3ef:1778cb22598:-7c57 - 120 + 84 36 @@ -187,7 +187,47 @@ $(pv_value) 80 false 3224b3ef:1778cb22598:-7c56 - 36 - 36 + 5 + 39 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) FM - Delete All + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5aaf + 42 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/FM/DeleteDir.opi b/core/base/tools/commander/workspace_template/Displays/Apps/FM/DeleteDir.opi index 4fb6c69ab..71103c33a 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/FM/DeleteDir.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/FM/DeleteDir.opi @@ -15,11 +15,11 @@ 6 - 400 + 120 true - FM - Delete Dir + ($(CPUID)) FM - Delete Dir true @@ -28,7 +28,7 @@ true true Display - 400 + 380 3224b3ef:1778cb22598:-7c75 -1 -1 @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var directory_arg = VTypeHelper.getString(display.getWidget("Directory").getPropertyValue("pv_value")); -Yamcs.issueCommand('/cfs/fm/DeleteDir', +Yamcs.issueCommand('/cfs/$(CPUID)/fm/DeleteDir', {"Directory":directory_arg}); ]]> true @@ -68,7 +68,7 @@ Yamcs.issueCommand('/cfs/fm/DeleteDir', - 18 + 25 ../../Resources/send.png NoOp 0 @@ -82,7 +82,7 @@ Yamcs.issueCommand('/cfs/fm/DeleteDir', - DeleteDir + Delete false $(pv_name) $(pv_value) @@ -90,7 +90,7 @@ $(pv_value) Action Button 109 3224b3ef:1778cb22598:-7c6a - 84 + 120 78 @@ -105,7 +105,7 @@ $(pv_value) - 1 + 4 1 true @@ -145,9 +145,9 @@ $(pv_value) false true Text Input - 100 + 265 3224b3ef:1778cb22598:-7c57 - 120 + 90 36 @@ -187,7 +187,47 @@ $(pv_value) 80 false 3224b3ef:1778cb22598:-7c56 - 36 - 36 + 11 + 39 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) FM - Delete Directory + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5aa8 + 42 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/FM/DeleteFile.opi b/core/base/tools/commander/workspace_template/Displays/Apps/FM/DeleteFile.opi index 22671de56..8e68d312b 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/FM/DeleteFile.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/FM/DeleteFile.opi @@ -15,11 +15,11 @@ 6 - 400 + 120 true - FM - Delete File + ($(CPUID)) FM - Delete File true @@ -28,7 +28,7 @@ true true Display - 400 + 380 3224b3ef:1778cb22598:-7c75 -1 -1 @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var filename_arg = VTypeHelper.getString(display.getWidget("Filename").getPropertyValue("pv_value")); -Yamcs.issueCommand('/cfs/fm/DeleteFile', +Yamcs.issueCommand('/cfs/$(CPUID)/fm/DeleteFile', {"Filename":filename_arg}); ]]> true @@ -68,7 +68,7 @@ Yamcs.issueCommand('/cfs/fm/DeleteFile', - 18 + 25 ../../Resources/send.png NoOp 0 @@ -82,7 +82,7 @@ Yamcs.issueCommand('/cfs/fm/DeleteFile', - DeleteFile + Delete false $(pv_name) $(pv_value) @@ -90,8 +90,8 @@ $(pv_value) Action Button 109 3224b3ef:1778cb22598:-7c6a - 84 - 78 + 132 + 72 @@ -105,7 +105,7 @@ $(pv_value) - 1 + 4 1 true @@ -145,9 +145,9 @@ $(pv_value) false true Text Input - 100 + 265 3224b3ef:1778cb22598:-7c57 - 120 + 96 36 @@ -187,7 +187,47 @@ $(pv_value) 80 false 3224b3ef:1778cb22598:-7c56 - 36 - 36 + 17 + 39 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) FM - Delete File + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5a8f + 54 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/FM/GetDir.opi b/core/base/tools/commander/workspace_template/Displays/Apps/FM/GetDir.opi index e908a6fe4..55d785240 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/FM/GetDir.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/FM/GetDir.opi @@ -15,11 +15,11 @@ 6 - 600 + 170 true - FM - Get Dir + ($(CPUID)) FM - Get Dir true @@ -28,7 +28,7 @@ true true Display - 800 + 450 3224b3ef:1778cb22598:-7099 -1 -1 @@ -69,8 +69,8 @@ 91 false 3224b3ef:1778cb22598:-7094 - 54 - 54 + 58 + 39 @@ -84,7 +84,7 @@ - 1 + 4 1 true @@ -124,10 +124,10 @@ $(pv_value) false true Text Input - 100 + 265 3224b3ef:1778cb22598:-7090 - 168 - 51 + 163 + 36 @@ -166,8 +166,8 @@ $(pv_value) 91 false 3224b3ef:1778cb22598:-7085 - 54 - 87 + 58 + 72 @@ -181,7 +181,7 @@ $(pv_value) - 1 + 4 1 true @@ -221,10 +221,10 @@ $(pv_value) false true Text Input - 100 + 265 3224b3ef:1778cb22598:-7084 - 168 - 84 + 163 + 69 @@ -254,17 +254,17 @@ $(pv_value) false - GetSizeTimeMode + Get Size Time Mode true 1 true Label - 121 + 140 false 3224b3ef:1778cb22598:-707d - 24 - 117 + 9 + 102 @@ -279,7 +279,7 @@ var filename_arg = VTypeHelper.getString(display.getWidget("Filename").getProper var timemode_arg = parseInt(VTypeHelper.getDouble(display.getWidget("GetSizeTimeMode").getPropertyValue("pv_value"))); -Yamcs.issueCommand('/cfs/fm/GetDirFile', +Yamcs.issueCommand('/cfs/$(CPUID)/fm/GetDirFile', {"Directory":directory_arg, "Filename": filename_arg, "GetSizeTimeMode": timemode_arg, @@ -310,7 +310,7 @@ Yamcs.issueCommand('/cfs/fm/GetDirFile', - 18 + 25 ../../Resources/send.png NoOp 0 @@ -332,8 +332,8 @@ $(pv_value) Action Button 109 3224b3ef:1778cb22598:-706b - 24 - 162 + 96 + 132 @@ -346,7 +346,7 @@ $(pv_value) - 1 + 4 1 false true @@ -387,8 +387,8 @@ $(pv_value) Spinner 100 3224b3ef:1778cb22598:-705f - 168 - 117 + 163 + 99 @@ -403,7 +403,7 @@ var filename_arg = VTypeHelper.getString(display.getWidget("Filename").getProper var timemode_arg = parseInt(VTypeHelper.getDouble(display.getWidget("GetSizeTimeMode").getPropertyValue("pv_value"))); -Yamcs.issueCommand('/cfs/fm/GetDirFile', +Yamcs.issueCommand('/cfs/$(CPUID)/fm/GetDirFile', {"Directory":directory_arg, "Filename": filename_arg, "GetSizeTimeMode": timemode_arg, @@ -434,7 +434,7 @@ Yamcs.issueCommand('/cfs/fm/GetDirFile', - 18 + 25 ../../Resources/send.png NoOp_1 0 @@ -456,7 +456,47 @@ $(pv_value) Action Button 109 -69f8bd78:177f094d5fe:-2369 - 163 - 162 + 219 + 132 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) FM - Get Directory + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5aa1 + 85 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/FM/GetFileInfo.opi b/core/base/tools/commander/workspace_template/Displays/Apps/FM/GetFileInfo.opi index 46aa6b49c..962f4c9be 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/FM/GetFileInfo.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/FM/GetFileInfo.opi @@ -15,11 +15,11 @@ 6 - 600 + 320 true - FM - Get File Info + ($(CPUID)) FM - Get File Info true @@ -28,7 +28,7 @@ true true Display - 800 + 360 3224b3ef:1778cb22598:-7447 -1 -1 @@ -44,7 +44,7 @@ - 1 + 4 1 true @@ -60,7 +60,7 @@ Text Update 0 true - /cfs/fm/FM_FileInfoPkt_t.FileStatus + /cfs/$(CPUID)/fm/FM_FileInfoPkt_t.FileStatus 0.0 @@ -81,8 +81,8 @@ $(pv_value) 175 false 3224b3ef:1778cb22598:-7442 - 186 - 186 + 156 + 138 @@ -112,7 +112,7 @@ $(pv_value) false - FileStatus: + File Status: true 1 @@ -121,8 +121,8 @@ $(pv_value) 121 false 3224b3ef:1778cb22598:-743e - 54 - 186 + 23 + 138 @@ -136,7 +136,7 @@ $(pv_value) - 1 + 4 1 true @@ -152,7 +152,7 @@ $(pv_value) Text Update_1 0 true - /cfs/fm/FM_FileInfoPkt_t.CRC_Computed + /cfs/$(CPUID)/fm/FM_FileInfoPkt_t.CRC_Computed 0.0 @@ -173,8 +173,8 @@ $(pv_value) 175 false 3224b3ef:1778cb22598:-7433 - 186 - 210 + 156 + 162 @@ -204,7 +204,7 @@ $(pv_value) false - CRC_Computed: + CRC Computed: true 1 @@ -213,8 +213,8 @@ $(pv_value) 121 false 3224b3ef:1778cb22598:-7432 - 48 - 210 + 23 + 162 @@ -228,7 +228,7 @@ $(pv_value) - 1 + 4 1 true @@ -244,7 +244,7 @@ $(pv_value) Text Update_2 0 true - /cfs/fm/FM_FileInfoPkt_t.CRC + /cfs/$(CPUID)/fm/FM_FileInfoPkt_t.CRC 0.0 @@ -265,8 +265,8 @@ $(pv_value) 175 false 3224b3ef:1778cb22598:-7410 - 186 - 234 + 156 + 186 @@ -305,8 +305,8 @@ $(pv_value) 121 false 3224b3ef:1778cb22598:-740f - 48 - 234 + 23 + 186 @@ -320,7 +320,7 @@ $(pv_value) - 1 + 4 1 true @@ -336,7 +336,7 @@ $(pv_value) Text Update_3 0 true - /cfs/fm/FM_FileInfoPkt_t.FileSize + /cfs/$(CPUID)/fm/FM_FileInfoPkt_t.FileSize 0.0 @@ -357,8 +357,8 @@ $(pv_value) 175 false 3224b3ef:1778cb22598:-73e1 - 186 - 258 + 156 + 210 @@ -388,7 +388,7 @@ $(pv_value) false - FileSize: + File Size: true 1 @@ -397,8 +397,8 @@ $(pv_value) 121 false 3224b3ef:1778cb22598:-73e0 - 48 - 258 + 23 + 210 @@ -412,7 +412,7 @@ $(pv_value) - 1 + 4 1 true @@ -428,7 +428,7 @@ $(pv_value) Text Update_4 0 true - /cfs/fm/FM_FileInfoPkt_t.LastModifiedTime + /cfs/$(CPUID)/fm/FM_FileInfoPkt_t.LastModifiedTime 0.0 @@ -449,8 +449,8 @@ $(pv_value) 175 false 3224b3ef:1778cb22598:-73cc - 186 - 282 + 156 + 234 @@ -480,17 +480,17 @@ $(pv_value) false - LastModifiedTime: + Last Modified Time: true 1 true Label - 121 + 131 false 3224b3ef:1778cb22598:-73cb - 48 - 282 + 13 + 234 @@ -504,7 +504,7 @@ $(pv_value) - 1 + 4 1 true @@ -520,7 +520,7 @@ $(pv_value) Text Update_5 0 true - /cfs/fm/FM_FileInfoPkt_t.Mode + /cfs/$(CPUID)/fm/FM_FileInfoPkt_t.Mode 0.0 @@ -541,8 +541,8 @@ $(pv_value) 175 false 3224b3ef:1778cb22598:-73aa - 186 - 306 + 156 + 258 @@ -581,8 +581,8 @@ $(pv_value) 121 false 3224b3ef:1778cb22598:-73a9 - 48 - 306 + 23 + 258 @@ -596,7 +596,7 @@ $(pv_value) - 1 + 4 1 true @@ -612,7 +612,7 @@ $(pv_value) Text Update_6 0 true - /cfs/fm/FM_FileInfoPkt_t.Filename + /cfs/$(CPUID)/fm/FM_FileInfoPkt_t.Filename 0.0 @@ -633,8 +633,8 @@ $(pv_value) 175 false 3224b3ef:1778cb22598:-739c - 186 - 330 + 156 + 282 @@ -673,8 +673,8 @@ $(pv_value) 121 false 3224b3ef:1778cb22598:-739b - 48 - 330 + 23 + 282 @@ -688,7 +688,7 @@ importPackage(Packages.org.yamcs.studio.data); var filename_arg = VTypeHelper.getString(display.getWidget("Filename").getPropertyValue("pv_value")); var crc_arg = parseInt(VTypeHelper.getDouble(display.getWidget("FileInfoCRC").getPropertyValue("pv_value"))); -Yamcs.issueCommand("/cfs/fm/GetFileInfo", +Yamcs.issueCommand("/cfs/$(CPUID)/fm/GetFileInfo", { "Filename": filename_arg, "FileInfoCRC": crc_arg @@ -717,7 +717,7 @@ Yamcs.issueCommand("/cfs/fm/GetFileInfo", - 18 + 25 ../../Resources/send.png NoOp 0 @@ -731,16 +731,16 @@ Yamcs.issueCommand("/cfs/fm/GetFileInfo", - GetFileInfo + Get File Info false $(pv_name) $(pv_value) true Action Button - 175 + 127 3224b3ef:1778cb22598:-736a - 108 - 108 + 72 + 102 @@ -754,7 +754,7 @@ $(pv_value) - 1 + 4 1 true @@ -794,9 +794,9 @@ $(pv_value) false true Text Input - 100 + 217 3224b3ef:1778cb22598:-7360 - 186 + 126 36 @@ -836,7 +836,7 @@ $(pv_value) 80 false 3224b3ef:1778cb22598:-735a - 95 + 42 39 @@ -867,16 +867,16 @@ $(pv_value) false - FileInfoCRC: + File Info CRC true 1 true Label - 80 + 109 false 3224b3ef:1778cb22598:-7352 - 95 + 13 69 @@ -890,7 +890,7 @@ $(pv_value) - 3 + 4 1 false true @@ -931,7 +931,47 @@ $(pv_value) Spinner 85 3224b3ef:1778cb22598:-72d5 - 186 + 126 66 + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) FM - Get File Info + + true + 1 + true + Label + 205 + false + -c05c465:1785c72c4a1:-5ae4 + 54 + 6 + \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/FM/GetFreeSpace.opi b/core/base/tools/commander/workspace_template/Displays/Apps/FM/GetFreeSpace.opi index 508f408b2..e4e1e45b5 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/FM/GetFreeSpace.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/FM/GetFreeSpace.opi @@ -15,11 +15,11 @@ 6 - 1750 + 320 true - FM - Get Free Space + ($(CPUID)) FM - Get Free Space true @@ -28,7 +28,7 @@ true true Display - 800 + 630 3224b3ef:1778cb22598:-7a0f -1 -1 @@ -40,7 +40,7 @@ importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); -Yamcs.issueCommand("/cfs/fm/GetFreeSpace",{}); +Yamcs.issueCommand("/cfs/$(CPUID)/fm/GetFreeSpace",{}); ]]> true @@ -65,7 +65,7 @@ Yamcs.issueCommand("/cfs/fm/GetFreeSpace",{}); - 18 + 25 ../../Resources/send.png NoOp 0 @@ -79,7 +79,7 @@ Yamcs.issueCommand("/cfs/fm/GetFreeSpace",{}); - GetFreeSpace + Get Free Space false $(pv_name) $(pv_value) @@ -87,8 +87,8 @@ $(pv_value) Action Button 175 3224b3ef:1778cb22598:-7a04 - 277 - 30 + 189 + 36 @@ -118,7 +118,7 @@ $(pv_value) false - FreeSpace_A + FreeSpace A true 1 @@ -127,8 +127,8 @@ $(pv_value) 151 false 3224b3ef:1778cb22598:-79e5 - 72 - 120 + 60 + 72 @@ -158,7 +158,7 @@ $(pv_value) false - FreeSpace_B + FreeSpace B true 1 @@ -167,8 +167,8 @@ $(pv_value) 134 false 3224b3ef:1778cb22598:-79e2 - 288 - 120 + 276 + 72 @@ -207,8 +207,8 @@ $(pv_value) 37 false 3224b3ef:1778cb22598:-79df - 24 - 150 + 12 + 102 @@ -222,7 +222,7 @@ $(pv_value) - 1 + 4 1 true @@ -238,7 +238,7 @@ $(pv_value) Text Update_1 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_0_.FreeSpace_A + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_0_.FreeSpace_A 0.0 @@ -259,8 +259,8 @@ $(pv_value) 195 false 3224b3ef:1778cb22598:-79d5 - 71 - 150 + 59 + 102 @@ -274,7 +274,7 @@ $(pv_value) - 1 + 4 1 true @@ -290,7 +290,7 @@ $(pv_value) Text Update_2 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_0_.FreeSpace_B + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_0_.FreeSpace_B 0.0 @@ -311,8 +311,8 @@ $(pv_value) 154 false 3224b3ef:1778cb22598:-79d2 - 288 - 150 + 276 + 102 @@ -351,8 +351,8 @@ $(pv_value) 37 false 3224b3ef:1778cb22598:-79a0 - 24 - 180 + 13 + 126 @@ -366,7 +366,7 @@ $(pv_value) - 1 + 4 1 true @@ -382,7 +382,7 @@ $(pv_value) Text Update_3 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_1_.FreeSpace_A + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_1_.FreeSpace_A 0.0 @@ -403,8 +403,8 @@ $(pv_value) 195 false 3224b3ef:1778cb22598:-799f - 70 - 180 + 59 + 126 @@ -418,7 +418,7 @@ $(pv_value) - 1 + 4 1 true @@ -434,7 +434,7 @@ $(pv_value) Text Update_4 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_1_.FreeSpace_B + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_1_.FreeSpace_B 0.0 @@ -455,8 +455,8 @@ $(pv_value) 154 false 3224b3ef:1778cb22598:-799e - 287 - 180 + 276 + 126 @@ -495,8 +495,8 @@ $(pv_value) 37 false 3224b3ef:1778cb22598:-78ae - 24 - 204 + 13 + 150 @@ -510,7 +510,7 @@ $(pv_value) - 1 + 4 1 true @@ -526,7 +526,7 @@ $(pv_value) Text Update_17 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_2_.FreeSpace_A + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_2_.FreeSpace_A 0.0 @@ -547,8 +547,8 @@ $(pv_value) 195 false 3224b3ef:1778cb22598:-78ad - 71 - 204 + 60 + 150 @@ -562,7 +562,7 @@ $(pv_value) - 1 + 4 1 true @@ -578,7 +578,7 @@ $(pv_value) Text Update_18 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_2_.FreeSpace_B + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_2_.FreeSpace_B 0.0 @@ -599,8 +599,8 @@ $(pv_value) 154 false 3224b3ef:1778cb22598:-78ac - 288 - 204 + 277 + 150 @@ -639,8 +639,8 @@ $(pv_value) 37 false 3224b3ef:1778cb22598:-779d - 24 - 228 + 13 + 174 @@ -654,7 +654,7 @@ $(pv_value) - 1 + 4 1 true @@ -670,7 +670,7 @@ $(pv_value) Text Update_19 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_3_.FreeSpace_A + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_3_.FreeSpace_A 0.0 @@ -691,8 +691,8 @@ $(pv_value) 195 false 3224b3ef:1778cb22598:-779c - 71 - 228 + 60 + 174 @@ -706,7 +706,7 @@ $(pv_value) - 1 + 4 1 true @@ -722,7 +722,7 @@ $(pv_value) Text Update_20 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_3_.FreeSpace_B + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_3_.FreeSpace_B 0.0 @@ -743,8 +743,8 @@ $(pv_value) 154 false 3224b3ef:1778cb22598:-779b - 288 - 228 + 277 + 174 @@ -783,8 +783,8 @@ $(pv_value) 37 false 3224b3ef:1778cb22598:-7762 - 24 - 252 + 13 + 198 @@ -798,7 +798,7 @@ $(pv_value) - 1 + 4 1 true @@ -814,7 +814,7 @@ $(pv_value) Text Update_21 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_4_.FreeSpace_A + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_4_.FreeSpace_A 0.0 @@ -835,8 +835,8 @@ $(pv_value) 195 false 3224b3ef:1778cb22598:-7761 - 71 - 252 + 60 + 198 @@ -850,7 +850,7 @@ $(pv_value) - 1 + 4 1 true @@ -866,7 +866,7 @@ $(pv_value) Text Update_22 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_4_.FreeSpace_B + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_4_.FreeSpace_B 0.0 @@ -887,8 +887,8 @@ $(pv_value) 154 false 3224b3ef:1778cb22598:-7760 - 288 - 252 + 277 + 198 @@ -927,8 +927,8 @@ $(pv_value) 37 false 3224b3ef:1778cb22598:-774b - 24 - 276 + 13 + 222 @@ -942,7 +942,7 @@ $(pv_value) - 1 + 4 1 true @@ -958,7 +958,7 @@ $(pv_value) Text Update_23 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_5_.FreeSpace_A + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_5_.FreeSpace_A 0.0 @@ -979,8 +979,8 @@ $(pv_value) 195 false 3224b3ef:1778cb22598:-774a - 71 - 276 + 60 + 222 @@ -994,7 +994,7 @@ $(pv_value) - 1 + 4 1 true @@ -1010,7 +1010,7 @@ $(pv_value) Text Update_24 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_5_.FreeSpace_B + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_5_.FreeSpace_B 0.0 @@ -1031,8 +1031,8 @@ $(pv_value) 154 false 3224b3ef:1778cb22598:-7749 - 288 - 276 + 277 + 222 @@ -1071,8 +1071,8 @@ $(pv_value) 37 false 3224b3ef:1778cb22598:-7728 - 24 - 300 + 13 + 246 @@ -1086,7 +1086,7 @@ $(pv_value) - 1 + 4 1 true @@ -1102,7 +1102,7 @@ $(pv_value) Text Update_25 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_6_.FreeSpace_A + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_6_.FreeSpace_A 0.0 @@ -1123,8 +1123,8 @@ $(pv_value) 195 false 3224b3ef:1778cb22598:-7727 - 71 - 300 + 60 + 246 @@ -1138,7 +1138,7 @@ $(pv_value) - 1 + 4 1 true @@ -1154,7 +1154,7 @@ $(pv_value) Text Update_26 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_6_.FreeSpace_B + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_6_.FreeSpace_B 0.0 @@ -1175,8 +1175,8 @@ $(pv_value) 154 false 3224b3ef:1778cb22598:-7726 - 288 - 300 + 277 + 246 @@ -1215,8 +1215,8 @@ $(pv_value) 37 false 3224b3ef:1778cb22598:-76eb - 24 - 324 + 13 + 270 @@ -1230,7 +1230,7 @@ $(pv_value) - 1 + 4 1 true @@ -1246,7 +1246,7 @@ $(pv_value) Text Update_27 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_7_.FreeSpace_A + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_7_.FreeSpace_A 0.0 @@ -1267,8 +1267,8 @@ $(pv_value) 195 false 3224b3ef:1778cb22598:-76ea - 71 - 324 + 60 + 270 @@ -1282,7 +1282,7 @@ $(pv_value) - 1 + 4 1 true @@ -1298,7 +1298,7 @@ $(pv_value) Text Update_28 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_7_.FreeSpace_B + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_7_.FreeSpace_B 0.0 @@ -1319,8 +1319,8 @@ $(pv_value) 154 false 3224b3ef:1778cb22598:-76e9 - 288 - 324 + 277 + 270 @@ -1359,8 +1359,8 @@ $(pv_value) 134 false 3224b3ef:1778cb22598:-6f29 - 468 - 120 + 456 + 72 @@ -1374,7 +1374,7 @@ $(pv_value) - 1 + 4 1 true @@ -1390,7 +1390,7 @@ $(pv_value) Text Update_47 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_0_.Name + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_0_.Name 0.0 @@ -1411,8 +1411,8 @@ $(pv_value) 154 false 3224b3ef:1778cb22598:-6f28 - 468 - 150 + 456 + 102 @@ -1426,7 +1426,7 @@ $(pv_value) - 1 + 4 1 true @@ -1442,7 +1442,7 @@ $(pv_value) Text Update_48 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_1_.Name + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_1_.Name 0.0 @@ -1463,8 +1463,8 @@ $(pv_value) 154 false 3224b3ef:1778cb22598:-6f27 - 467 - 180 + 456 + 126 @@ -1478,7 +1478,7 @@ $(pv_value) - 1 + 4 1 true @@ -1494,7 +1494,7 @@ $(pv_value) Text Update_49 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_2_.Name + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_2_.Name 0.0 @@ -1515,8 +1515,8 @@ $(pv_value) 154 false 3224b3ef:1778cb22598:-6f26 - 468 - 204 + 457 + 150 @@ -1530,7 +1530,7 @@ $(pv_value) - 1 + 4 1 true @@ -1546,7 +1546,7 @@ $(pv_value) Text Update_50 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_3_.Name + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_3_.Name 0.0 @@ -1567,8 +1567,8 @@ $(pv_value) 154 false 3224b3ef:1778cb22598:-6f25 - 468 - 228 + 457 + 174 @@ -1582,7 +1582,7 @@ $(pv_value) - 1 + 4 1 true @@ -1598,7 +1598,7 @@ $(pv_value) Text Update_51 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_4_.Name + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_4_.Name 0.0 @@ -1619,8 +1619,8 @@ $(pv_value) 154 false 3224b3ef:1778cb22598:-6f24 - 468 - 252 + 457 + 198 @@ -1634,7 +1634,7 @@ $(pv_value) - 1 + 4 1 true @@ -1650,7 +1650,7 @@ $(pv_value) Text Update_52 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_5_.Name + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_5_.Name 0.0 @@ -1671,8 +1671,8 @@ $(pv_value) 154 false 3224b3ef:1778cb22598:-6f23 - 468 - 276 + 457 + 222 @@ -1686,7 +1686,7 @@ $(pv_value) - 1 + 4 1 true @@ -1702,7 +1702,7 @@ $(pv_value) Text Update_53 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_6_.Name + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_6_.Name 0.0 @@ -1723,8 +1723,8 @@ $(pv_value) 154 false 3224b3ef:1778cb22598:-6f22 - 468 - 300 + 457 + 246 @@ -1738,7 +1738,7 @@ $(pv_value) - 1 + 4 1 true @@ -1754,7 +1754,7 @@ $(pv_value) Text Update_54 0 true - /cfs/fm/FM_FreeSpacePkt_t.FileSys_7_.Name + /cfs/$(CPUID)/fm/FM_FreeSpacePkt_t.FileSys_7_.Name 0.0 @@ -1775,7 +1775,47 @@ $(pv_value) 154 false 3224b3ef:1778cb22598:-6f21 - 468 - 324 + 457 + 270 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) FM - Get Free Space + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5af8 + 144 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/FM/GetOpenFiles.opi b/core/base/tools/commander/workspace_template/Displays/Apps/FM/GetOpenFiles.opi index a49af7425..ac33d09ab 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/FM/GetOpenFiles.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/FM/GetOpenFiles.opi @@ -15,11 +15,11 @@ 6 - 1750 + 550 true - FM - Get Open Files + ($(CPUID)) FM - Get Open Files true @@ -28,7 +28,7 @@ true true Display - 800 + 460 3224b3ef:1778cb22598:-7a0f -1 -1 @@ -40,7 +40,7 @@ importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); -Yamcs.issueCommand("/cfs/fm/GetOpenFiles",{}); +Yamcs.issueCommand("/cfs/$(CPUID)/fm/GetOpenFiles",{}); ]]> true @@ -65,7 +65,7 @@ Yamcs.issueCommand("/cfs/fm/GetOpenFiles",{}); - 18 + 25 ../../Resources/send.png NoOp 0 @@ -79,7 +79,7 @@ Yamcs.issueCommand("/cfs/fm/GetOpenFiles",{}); - GetOpenFiles + Get Open Files false $(pv_name) $(pv_value) @@ -87,8 +87,8 @@ $(pv_value) Action Button 175 3224b3ef:1778cb22598:-7a04 - 174 - 30 + 60 + 36 @@ -109,7 +109,7 @@ $(pv_value) 20 - 1 + 2 Label @@ -118,17 +118,17 @@ $(pv_value) false - NumOpenFiles: + Num Open Files: true 1 true Label - 103 + 121 false 3224b3ef:1778cb22598:-79fe - 174 - 54 + 42 + 71 @@ -158,7 +158,7 @@ $(pv_value) Text Update 0 true - /cfs/fm/FM_OpenFilesPkt_t.NumOpenFiles + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.NumOpenFiles 0.0 @@ -179,8 +179,8 @@ $(pv_value) 61 false 3224b3ef:1778cb22598:-79f4 - 288 - 54 + 174 + 71 @@ -210,7 +210,7 @@ $(pv_value) false - LogicalName + Logical Name true 1 @@ -220,7 +220,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-79e5 72 - 120 + 96 @@ -250,7 +250,7 @@ $(pv_value) false - AppName + App Name true 1 @@ -260,7 +260,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-79e2 288 - 120 + 96 @@ -300,7 +300,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-79df 24 - 150 + 126 @@ -330,7 +330,7 @@ $(pv_value) Text Update_1 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_0_.LogicalName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_0_.LogicalName 0.0 @@ -352,7 +352,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-79d5 71 - 150 + 126 @@ -382,7 +382,7 @@ $(pv_value) Text Update_2 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_0_.AppName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_0_.AppName 0.0 @@ -404,7 +404,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-79d2 288 - 150 + 126 @@ -444,7 +444,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-79a0 23 - 180 + 156 @@ -474,7 +474,7 @@ $(pv_value) Text Update_3 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_1_.LogicalName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_1_.LogicalName 0.0 @@ -496,7 +496,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-799f 70 - 180 + 156 @@ -526,7 +526,7 @@ $(pv_value) Text Update_4 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_1_.AppName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_1_.AppName 0.0 @@ -548,7 +548,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-799e 287 - 180 + 156 @@ -588,7 +588,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-78ae 24 - 204 + 180 @@ -618,7 +618,7 @@ $(pv_value) Text Update_17 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_2_.LogicalName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_2_.LogicalName 0.0 @@ -640,7 +640,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-78ad 71 - 204 + 180 @@ -670,7 +670,7 @@ $(pv_value) Text Update_18 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_2_.AppName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_2_.AppName 0.0 @@ -692,7 +692,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-78ac 288 - 204 + 180 @@ -732,7 +732,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-779d 24 - 228 + 204 @@ -762,7 +762,7 @@ $(pv_value) Text Update_19 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_3_.LogicalName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_3_.LogicalName 0.0 @@ -784,7 +784,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-779c 71 - 228 + 204 @@ -814,7 +814,7 @@ $(pv_value) Text Update_20 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_3_.AppName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_3_.AppName 0.0 @@ -836,7 +836,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-779b 288 - 228 + 204 @@ -876,7 +876,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-7762 24 - 252 + 228 @@ -906,7 +906,7 @@ $(pv_value) Text Update_21 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_4_.LogicalName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_4_.LogicalName 0.0 @@ -928,7 +928,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-7761 71 - 252 + 228 @@ -958,7 +958,7 @@ $(pv_value) Text Update_22 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_4_.AppName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_4_.AppName 0.0 @@ -980,7 +980,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-7760 288 - 252 + 228 @@ -1020,7 +1020,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-774b 24 - 276 + 252 @@ -1050,7 +1050,7 @@ $(pv_value) Text Update_23 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_5_.LogicalName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_5_.LogicalName 0.0 @@ -1072,7 +1072,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-774a 71 - 276 + 252 @@ -1102,7 +1102,7 @@ $(pv_value) Text Update_24 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_5_.AppName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_5_.AppName 0.0 @@ -1124,7 +1124,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-7749 288 - 276 + 252 @@ -1164,7 +1164,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-7728 24 - 300 + 276 @@ -1194,7 +1194,7 @@ $(pv_value) Text Update_25 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_6_.LogicalName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_6_.LogicalName 0.0 @@ -1216,7 +1216,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-7727 71 - 300 + 276 @@ -1246,7 +1246,7 @@ $(pv_value) Text Update_26 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_6_.AppName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_6_.AppName 0.0 @@ -1268,7 +1268,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-7726 288 - 300 + 276 @@ -1308,7 +1308,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-76eb 24 - 324 + 300 @@ -1338,7 +1338,7 @@ $(pv_value) Text Update_27 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_7_.LogicalName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_7_.LogicalName 0.0 @@ -1360,7 +1360,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-76ea 71 - 324 + 300 @@ -1390,7 +1390,7 @@ $(pv_value) Text Update_28 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_7_.AppName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_7_.AppName 0.0 @@ -1412,7 +1412,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-76e9 288 - 324 + 300 @@ -1452,7 +1452,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-76d4 24 - 348 + 324 @@ -1482,7 +1482,7 @@ $(pv_value) Text Update_29 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_8_.LogicalName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_8_.LogicalName 0.0 @@ -1504,7 +1504,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-76d3 71 - 348 + 324 @@ -1534,7 +1534,7 @@ $(pv_value) Text Update_30 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_8_.AppName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_8_.AppName 0.0 @@ -1556,7 +1556,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-76d2 288 - 348 + 324 @@ -1596,7 +1596,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-76bd 23 - 372 + 348 @@ -1626,7 +1626,7 @@ $(pv_value) Text Update_31 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_9_.LogicalName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_9_.LogicalName 0.0 @@ -1648,7 +1648,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-76bc 70 - 372 + 348 @@ -1678,7 +1678,7 @@ $(pv_value) Text Update_32 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_9_.AppName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_9_.AppName 0.0 @@ -1700,7 +1700,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-76bb 287 - 372 + 348 @@ -1740,7 +1740,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-76a6 24 - 396 + 372 @@ -1770,7 +1770,7 @@ $(pv_value) Text Update_33 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_10_.LogicalName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_10_.LogicalName 0.0 @@ -1792,7 +1792,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-76a5 71 - 396 + 372 @@ -1822,7 +1822,7 @@ $(pv_value) Text Update_34 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_10_.AppName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_10_.AppName 0.0 @@ -1844,7 +1844,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-76a4 288 - 396 + 372 @@ -1884,7 +1884,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-7690 23 - 420 + 396 @@ -1914,7 +1914,7 @@ $(pv_value) Text Update_35 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_11_.LogicalName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_11_.LogicalName 0.0 @@ -1936,7 +1936,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-768f 70 - 420 + 396 @@ -1966,7 +1966,7 @@ $(pv_value) Text Update_36 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_11_.AppName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_11_.AppName 0.0 @@ -1988,7 +1988,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-768e 287 - 420 + 396 @@ -2028,7 +2028,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-7685 23 - 450 + 426 @@ -2058,7 +2058,7 @@ $(pv_value) Text Update_37 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_12_.LogicalName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_12_.LogicalName 0.0 @@ -2080,7 +2080,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-7684 70 - 450 + 426 @@ -2110,7 +2110,7 @@ $(pv_value) Text Update_38 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_12_.AppName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_12_.AppName 0.0 @@ -2132,7 +2132,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-7683 287 - 450 + 426 @@ -2172,7 +2172,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-767a 24 - 504 + 480 @@ -2202,7 +2202,7 @@ $(pv_value) Text Update_39 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_14_.LogicalName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_14_.LogicalName 0.0 @@ -2224,7 +2224,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-7679 71 - 504 + 480 @@ -2254,7 +2254,7 @@ $(pv_value) Text Update_40 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_14_.AppName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_14_.AppName 0.0 @@ -2276,7 +2276,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-7678 288 - 504 + 480 @@ -2316,7 +2316,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-7664 23 - 480 + 456 @@ -2346,7 +2346,7 @@ $(pv_value) Text Update_43 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_13_.LogicalName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_13_.LogicalName 0.0 @@ -2368,7 +2368,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-7663 70 - 480 + 456 @@ -2398,7 +2398,7 @@ $(pv_value) Text Update_44 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_13_.AppName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_13_.AppName 0.0 @@ -2420,7 +2420,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-7662 287 - 480 + 456 @@ -2460,7 +2460,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-7659 24 - 534 + 510 @@ -2490,7 +2490,7 @@ $(pv_value) Text Update_45 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_15_.LogicalName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_15_.LogicalName 0.0 @@ -2512,7 +2512,7 @@ $(pv_value) false 3224b3ef:1778cb22598:-7658 71 - 534 + 510 @@ -2542,7 +2542,7 @@ $(pv_value) Text Update_46 0 true - /cfs/fm/FM_OpenFilesPkt_t.OpenFilesList_15_.AppName + /cfs/$(CPUID)/fm/FM_OpenFilesPkt_t.OpenFilesList_15_.AppName 0.0 @@ -2564,6 +2564,46 @@ $(pv_value) false 3224b3ef:1778cb22598:-7657 288 - 534 + 510 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) FM - Get Open Files + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5b39 + 12 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/FM/Main.opi b/core/base/tools/commander/workspace_template/Displays/Apps/FM/Main.opi index 99c5c40d7..c14b7d8e0 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/FM/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/FM/Main.opi @@ -10,12 +10,12 @@ - 1.5.5.202103162101 + 1.6.2.202104092231 6 - 340 + 320 true fm @@ -23,7 +23,7 @@ Displays /modules/fm - FM + ($(CPUID)) FM true @@ -64,7 +64,7 @@ Text Update 0 false - /cfs/fm/FM_HousekeepingPkt_t.CommandCounter + /cfs/$(CPUID)/fm/FM_HousekeepingPkt_t.CommandCounter 0.0 @@ -236,7 +236,7 @@ $(pv_value) Text Update_1 0 false - /cfs/fm/FM_HousekeepingPkt_t.CommandErrCounter + /cfs/$(CPUID)/fm/FM_HousekeepingPkt_t.CommandErrCounter 0.0 @@ -267,7 +267,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/fm/Noop', {});]]> true @@ -323,7 +323,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/fm/Reset', {});]]> true @@ -400,7 +400,7 @@ $(pv_value) false - File Manager + ($(CPUID)) File Manager true 1 @@ -440,7 +440,7 @@ $(pv_value) Text Update_16 0 false - /cfs/fm/FM_HousekeepingPkt_t.NumOpenFiles + /cfs/$(CPUID)/fm/FM_HousekeepingPkt_t.NumOpenFiles 0.0 @@ -462,7 +462,7 @@ $(pv_value) false -736e4684:150ac3c95a1:-6f4b 95 - 144 + 114 @@ -492,7 +492,7 @@ $(pv_value) Text Update_17 0 false - /cfs/fm/FM_HousekeepingPkt_t.ChildCmdCounter + /cfs/$(CPUID)/fm/FM_HousekeepingPkt_t.ChildCmdCounter 0.0 @@ -514,7 +514,7 @@ $(pv_value) false -736e4684:150ac3c95a1:-6f4a 98 - 210 + 180 @@ -544,7 +544,7 @@ $(pv_value) Text Update_18 0 false - /cfs/fm/FM_HousekeepingPkt_t.ChildCmdErrCounter + /cfs/$(CPUID)/fm/FM_HousekeepingPkt_t.ChildCmdErrCounter 0.0 @@ -566,7 +566,7 @@ $(pv_value) false -736e4684:150ac3c95a1:-6f49 98 - 229 + 199 @@ -596,7 +596,7 @@ $(pv_value) Text Update_19 0 false - /cfs/fm/FM_HousekeepingPkt_t.ChildCmdWarnCounter + /cfs/$(CPUID)/fm/FM_HousekeepingPkt_t.ChildCmdWarnCounter 0.0 @@ -618,7 +618,7 @@ $(pv_value) false -736e4684:150ac3c95a1:-6f48 98 - 248 + 218 @@ -648,7 +648,7 @@ $(pv_value) Text Update_20 0 false - /cfs/fm/FM_HousekeepingPkt_t.ChildQueueCount + /cfs/$(CPUID)/fm/FM_HousekeepingPkt_t.ChildQueueCount 0.0 @@ -670,7 +670,7 @@ $(pv_value) false -736e4684:150ac3c95a1:-6f47 98 - 267 + 237 @@ -700,7 +700,7 @@ $(pv_value) Text Update_21 0 false - /cfs/fm/FM_HousekeepingPkt_t.ChildCurrentCC + /cfs/$(CPUID)/fm/FM_HousekeepingPkt_t.ChildCurrentCC 0.0 @@ -722,7 +722,7 @@ $(pv_value) false -736e4684:150ac3c95a1:-6f46 98 - 286 + 256 @@ -752,7 +752,7 @@ $(pv_value) Text Update_22 0 false - /cfs/fm/FM_HousekeepingPkt_t.ChildPreviousCC + /cfs/$(CPUID)/fm/FM_HousekeepingPkt_t.ChildPreviousCC 0.0 @@ -774,7 +774,7 @@ $(pv_value) false -736e4684:150ac3c95a1:-6f45 98 - 305 + 275 @@ -814,7 +814,7 @@ $(pv_value) false -736e4684:150ac3c95a1:-6f3d 18 - 144 + 114 @@ -854,7 +854,7 @@ $(pv_value) false -736e4684:150ac3c95a1:-6f2e 12 - 210 + 180 @@ -894,7 +894,7 @@ $(pv_value) false -736e4684:150ac3c95a1:-6f22 21 - 229 + 199 @@ -934,7 +934,7 @@ $(pv_value) false -736e4684:150ac3c95a1:-6f1d 21 - 248 + 218 @@ -974,7 +974,7 @@ $(pv_value) false -736e4684:150ac3c95a1:-6f18 21 - 267 + 237 @@ -1014,7 +1014,7 @@ $(pv_value) false -736e4684:150ac3c95a1:-6f13 12 - 286 + 256 @@ -1054,7 +1054,7 @@ $(pv_value) false -736e4684:150ac3c95a1:-6f0e 6 - 305 + 275 @@ -1094,7 +1094,7 @@ $(pv_value) false -736e4684:150ac3c95a1:-6f04 66 - 186 + 156 @@ -1149,7 +1149,7 @@ $(pv_value) 153 -69f8bd78:177f094d5fe:-2440 222 - 144 + 114 @@ -1204,7 +1204,7 @@ $(pv_value) 153 -69f8bd78:177f094d5fe:-2428 222 - 163 + 133 @@ -1259,7 +1259,7 @@ $(pv_value) 153 -69f8bd78:177f094d5fe:-2421 222 - 182 + 152 @@ -1314,7 +1314,7 @@ $(pv_value) 153 -69f8bd78:177f094d5fe:-2417 222 - 201 + 171 @@ -1369,7 +1369,7 @@ $(pv_value) 153 -69f8bd78:177f094d5fe:-2410 222 - 220 + 190 @@ -1424,7 +1424,7 @@ $(pv_value) 153 -69f8bd78:177f094d5fe:-2406 222 - 239 + 209 @@ -1479,7 +1479,7 @@ $(pv_value) 153 -69f8bd78:177f094d5fe:-23fc 222 - 258 + 228 @@ -1534,7 +1534,7 @@ $(pv_value) 153 -69f8bd78:177f094d5fe:-23f2 222 - 277 + 247 @@ -1589,7 +1589,7 @@ $(pv_value) 153 -69f8bd78:177f094d5fe:-23de 384 - 144 + 114 @@ -1644,7 +1644,7 @@ $(pv_value) 153 -69f8bd78:177f094d5fe:-23d7 384 - 163 + 133 @@ -1699,7 +1699,7 @@ $(pv_value) 153 -69f8bd78:177f094d5fe:-23d0 384 - 182 + 152 @@ -1754,7 +1754,7 @@ $(pv_value) 153 -69f8bd78:177f094d5fe:-23c9 384 - 201 + 171 @@ -1809,7 +1809,7 @@ $(pv_value) 153 -69f8bd78:177f094d5fe:-23c2 384 - 220 + 190 @@ -1864,7 +1864,7 @@ $(pv_value) 153 -69f8bd78:177f094d5fe:-23b6 384 - 239 + 209 @@ -1919,7 +1919,7 @@ $(pv_value) 153 -69f8bd78:177f094d5fe:-23af 384 - 258 + 228 @@ -1980,7 +1980,7 @@ $(pv_value) 153 -69f8bd78:177f094d5fe:-232d 384 - 277 + 247 @@ -1989,7 +1989,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/fm/SendHK', {});]]> true @@ -2036,6 +2036,67 @@ $(pv_value) 153 -69f8bd78:177f094d5fe:-2325 384 - 296 + 266 + + + + + + + true + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 20 + + AppControl + 0 + + + + + true + true + false + + + + App Control + false + $(pv_name) +$(pv_value) + true + Action Button + 153 + 49c9ccd0:178c6a335db:-4f82 + 222 + 266 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/FM/MoveFile.opi b/core/base/tools/commander/workspace_template/Displays/Apps/FM/MoveFile.opi index 7814b724a..e9864bf34 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/FM/MoveFile.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/FM/MoveFile.opi @@ -15,11 +15,11 @@ 6 - 400 + 180 true - FM - Move + ($(CPUID)) FM - Move true @@ -46,7 +46,7 @@ var overwrite_arg = VTypeHelper.getDouble(display.getWidget("Overwrite") .getPr var source_arg = VTypeHelper.getString(display.getWidget("Source").getPropertyValue("pv_value")); var target_arg = VTypeHelper.getString(display.getWidget("Target").getPropertyValue("pv_value")); -Yamcs.issueCommand('/cfs/fm/MoveFile', +Yamcs.issueCommand('/cfs/$(CPUID)/fm/MoveFile', {"Overwrite": parseInt(overwrite_arg), "Source": source_arg, "Target": target_arg}); @@ -74,7 +74,7 @@ Yamcs.issueCommand('/cfs/fm/MoveFile', - 18 + 25 ../../Resources/send.png NoOp 0 @@ -88,7 +88,7 @@ Yamcs.issueCommand('/cfs/fm/MoveFile', - MoveFile + Move false $(pv_name) $(pv_value) @@ -96,8 +96,8 @@ $(pv_value) Action Button 109 3224b3ef:1778cb22598:-7c6a - 84 - 168 + 132 + 138 @@ -111,7 +111,7 @@ $(pv_value) - 1 + 4 1 true @@ -151,10 +151,10 @@ $(pv_value) false true Text Input - 100 + 265 3224b3ef:1778cb22598:-7c66 - 132 - 81 + 114 + 63 @@ -193,8 +193,8 @@ $(pv_value) 80 false 3224b3ef:1778cb22598:-7c62 - 48 - 84 + 30 + 66 @@ -208,7 +208,7 @@ $(pv_value) - 1 + 4 1 true @@ -248,10 +248,10 @@ $(pv_value) false true Text Input - 100 + 265 3224b3ef:1778cb22598:-7c57 - 132 - 114 + 114 + 96 @@ -290,8 +290,8 @@ $(pv_value) 80 false 3224b3ef:1778cb22598:-7c56 - 48 - 114 + 30 + 96 @@ -304,7 +304,7 @@ $(pv_value) - 1 + 4 1 false true @@ -345,8 +345,8 @@ $(pv_value) Spinner 100 3224b3ef:1778cb22598:-7c4f - 132 - 48 + 114 + 30 @@ -385,7 +385,47 @@ $(pv_value) 80 false 3224b3ef:1778cb22598:-7c47 - 48 - 51 + 30 + 33 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) FM - Move + + true + 1 + true + Label + 241 + false + -c05c465:1785c72c4a1:-5b47 + 72 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/FM/RenameFile.opi b/core/base/tools/commander/workspace_template/Displays/Apps/FM/RenameFile.opi index 509de6f77..107c498a4 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/FM/RenameFile.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/FM/RenameFile.opi @@ -15,11 +15,11 @@ 6 - 400 + 160 true - FM - Rename File + ($(CPUID)) FM - Rename File true @@ -28,7 +28,7 @@ true true Display - 400 + 370 3224b3ef:1778cb22598:-7c75 -1 -1 @@ -43,7 +43,7 @@ importPackage(Packages.org.yamcs.studio.data); var source_arg = VTypeHelper.getString(display.getWidget("Source").getPropertyValue("pv_value")); var target_arg = VTypeHelper.getString(display.getWidget("Target").getPropertyValue("pv_value")); -Yamcs.issueCommand('/cfs/fm/RenameFile', +Yamcs.issueCommand('/cfs/$(CPUID)/fm/RenameFile', { "Source": source_arg, "Target": target_arg @@ -73,7 +73,7 @@ Yamcs.issueCommand('/cfs/fm/RenameFile', - 18 + 28 ../../Resources/send.png NoOp 0 @@ -87,7 +87,7 @@ Yamcs.issueCommand('/cfs/fm/RenameFile', - RenameFile + Rename false $(pv_name) $(pv_value) @@ -95,8 +95,8 @@ $(pv_value) Action Button 109 3224b3ef:1778cb22598:-7c6a - 102 - 138 + 120 + 108 @@ -110,7 +110,7 @@ $(pv_value) - 1 + 4 1 true @@ -150,10 +150,10 @@ $(pv_value) false true Text Input - 100 + 265 3224b3ef:1778cb22598:-7c66 - 150 - 51 + 84 + 36 @@ -174,7 +174,7 @@ $(pv_value) 20 - 1 + 2 Label @@ -189,11 +189,11 @@ $(pv_value) 1 true Label - 80 + 56 false 3224b3ef:1778cb22598:-7c62 - 66 - 54 + 12 + 42 @@ -207,7 +207,7 @@ $(pv_value) - 1 + 4 1 true @@ -247,10 +247,10 @@ $(pv_value) false true Text Input - 100 + 265 3224b3ef:1778cb22598:-7c57 - 150 - 84 + 84 + 69 @@ -271,7 +271,7 @@ $(pv_value) 20 - 1 + 2 Label_1 @@ -286,10 +286,50 @@ $(pv_value) 1 true Label - 80 + 44 false 3224b3ef:1778cb22598:-7c56 - 66 - 84 + 24 + 72 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) FM - Rename + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5b4e + 36 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/FM/SetPerm.opi b/core/base/tools/commander/workspace_template/Displays/Apps/FM/SetPerm.opi index db1b6836d..7193dc764 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/FM/SetPerm.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/FM/SetPerm.opi @@ -15,11 +15,11 @@ 6 - 600 + 150 true - FM - Set Perm + ($(CPUID)) FM - Set Perm true @@ -28,7 +28,7 @@ true true Display - 800 + 380 3224b3ef:1778cb22598:-7447 -1 -1 @@ -44,7 +44,7 @@ importPackage(Packages.org.yamcs.studio.data); var filename_arg = VTypeHelper.getString(display.getWidget("Filename").getPropertyValue("pv_value")); var mode_arg = parseInt(VTypeHelper.getDouble(display.getWidget("Mode").getPropertyValue("pv_value"))); -Yamcs.issueCommand("/cfs/fm/SetPerm", +Yamcs.issueCommand("/cfs/$(CPUID)/fm/SetPerm", { "FileName": filename_arg, "Mode": mode_arg @@ -73,7 +73,7 @@ Yamcs.issueCommand("/cfs/fm/SetPerm", - 18 + 25 ../../Resources/send.png NoOp 0 @@ -87,15 +87,15 @@ Yamcs.issueCommand("/cfs/fm/SetPerm", - SetPerm + Set false $(pv_name) $(pv_value) true Action Button - 175 + 97 3224b3ef:1778cb22598:-736a - 108 + 120 108 @@ -110,7 +110,7 @@ $(pv_value) - 1 + 4 1 true @@ -150,9 +150,9 @@ $(pv_value) false true Text Input - 100 + 265 3224b3ef:1778cb22598:-7360 - 186 + 96 36 @@ -192,7 +192,7 @@ $(pv_value) 80 false 3224b3ef:1778cb22598:-735a - 95 + 5 39 @@ -232,7 +232,7 @@ $(pv_value) 80 false 3224b3ef:1778cb22598:-7352 - 95 + 5 69 @@ -246,7 +246,7 @@ $(pv_value) - 1 + 4 1 false true @@ -287,7 +287,47 @@ $(pv_value) Spinner 85 3224b3ef:1778cb22598:-72d5 - 186 + 96 66 + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) FM - Set Permissions + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5b55 + 36 + 6 + \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/FM/SetTableState.opi b/core/base/tools/commander/workspace_template/Displays/Apps/FM/SetTableState.opi index 3f7706481..8827293cd 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/FM/SetTableState.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/FM/SetTableState.opi @@ -15,11 +15,11 @@ 6 - 600 + 170 true - FM - Set Table State + ($(CPUID)) FM - Set Table State true @@ -28,7 +28,7 @@ true true Display - 800 + 300 3224b3ef:1778cb22598:-7447 -1 -1 @@ -62,7 +62,7 @@ else if(table_state_arg == "UNUSED") table_state_val = "UNUSED"; } -Yamcs.issueCommand("/cfs/fm/SetTableState", +Yamcs.issueCommand("/cfs/$(CPUID)/fm/SetTableState", { "TableEntryIndex": tableindex_arg, "TableEntryState": table_state_val @@ -91,7 +91,7 @@ Yamcs.issueCommand("/cfs/fm/SetTableState", - 18 + 25 ../../Resources/send.png NoOp 0 @@ -105,16 +105,16 @@ Yamcs.issueCommand("/cfs/fm/SetTableState", - SetTableState + Set false $(pv_name) $(pv_value) true Action Button - 175 + 103 3224b3ef:1778cb22598:-736a - 108 - 132 + 78 + 114 @@ -135,7 +135,7 @@ $(pv_value) 20 - 1 + 2 Label_8 @@ -144,16 +144,16 @@ $(pv_value) false - TableEntryIndex + Table Entry Index true 1 true Label - 103 + 121 false 3224b3ef:1778cb22598:-7352 - 66 + 12 39 @@ -167,7 +167,7 @@ $(pv_value) - 3 + 4 1 false true @@ -208,7 +208,7 @@ $(pv_value) Spinner 145 3224b3ef:1778cb22598:-72d5 - 180 + 138 36 @@ -222,7 +222,7 @@ $(pv_value) - 0 + 4 1 true @@ -255,8 +255,8 @@ $(pv_value) Combo 145 3224b3ef:1778cb22598:-6c7c - 180 - 72 + 138 + 66 @@ -277,7 +277,7 @@ $(pv_value) 20 - 1 + 2 Label @@ -286,16 +286,56 @@ $(pv_value) false - TableEntryState + Table Entry State true 1 true Label - 103 + 121 false 3224b3ef:1778cb22598:-6c78 - 66 - 79 + 12 + 73 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_49 + + + true + true + false + + + ($(CPUID)) FM - Set Table State + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-5b61 + 6 + 6 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/HK/Main.opi b/core/base/tools/commander/workspace_template/Displays/Apps/HK/Main.opi index 4b1503284..223d4cc11 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/HK/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/HK/Main.opi @@ -10,12 +10,12 @@ - 1.5.5.202103162101 + 1.6.2.202104092231 6 - 220 + 250 true hk @@ -23,7 +23,7 @@ Displays /modules/hk - HK + ($(CPUID)) HK true @@ -32,7 +32,7 @@ true true Display - 600 + 300 -33cb7c72:150aa4c347f:-76c2 -1 -1 @@ -64,7 +64,7 @@ Text Update 0 false - /cfs/hk/HK_HkPacket_t.CmdCounter + /cfs/$(CPUID)/hk/HK_HkPacket_t.CmdCounter 0.0 @@ -196,7 +196,7 @@ $(pv_value) Text Update_1 0 false - /cfs/hk/HK_HkPacket_t.ErrCounter + /cfs/$(CPUID)/hk/HK_HkPacket_t.ErrCounter 0.0 @@ -227,7 +227,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/hk/Noop', {});]]> true @@ -283,7 +283,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/hk/Reset', {});]]> true @@ -360,7 +360,7 @@ $(pv_value) false - Housekeeping + ($(CPUID)) Housekeeping true 1 @@ -400,7 +400,7 @@ $(pv_value) Text Update_17 0 false - /cfs/hk/HK_HkPacket_t.CombinedPacketsSent + /cfs/$(CPUID)/hk/HK_HkPacket_t.CombinedPacketsSent 0.0 @@ -452,7 +452,7 @@ $(pv_value) Text Update_18 0 false - /cfs/hk/HK_HkPacket_t.MissingDataCtr + /cfs/$(CPUID)/hk/HK_HkPacket_t.MissingDataCtr 0.0 @@ -504,7 +504,7 @@ $(pv_value) Text Update_19 0 false - /cfs/hk/HK_HkPacket_t.MemPoolHandle + /cfs/$(CPUID)/hk/HK_HkPacket_t.MemPoolHandle 0.0 @@ -655,7 +655,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/hk/SendHK', {});]]> true @@ -702,7 +702,7 @@ $(pv_value) 171 689e2ae8:1777f312f88:-7741 62 - 193 + 210 @@ -757,7 +757,7 @@ $(pv_value) 171 689e2ae8:1777f312f88:-7725 62 - 212 + 229 @@ -818,6 +818,67 @@ $(pv_value) 171 -19107c2b:177da1db5df:6d4 62 - 174 + 191 + + + + + + + true + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 20 + + AppControl + 0 + + + + + true + true + false + + + + App Control + false + $(pv_name) +$(pv_value) + true + Action Button + 171 + 49c9ccd0:178c6a335db:-4e0e + 62 + 172 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/HK/SendCombined.opi b/core/base/tools/commander/workspace_template/Displays/Apps/HK/SendCombined.opi index 09b8795e9..4382fbbc7 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/HK/SendCombined.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/HK/SendCombined.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -28,7 +28,7 @@ true true Display - 200 + 260 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,13 +60,13 @@ false - Send Combined + ($(CPUID)) HK - Send Combined true 1 true Label - 175 + 241 false -10b748b0:17773fb054b:-7a20 12 @@ -82,7 +82,7 @@ importPackage(Packages.org.yamcs.studio.data); var OutMsgToSend = VTypeHelper.getString(display.getWidget('OutMsgToSend').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/hk/SendCombinedPkt', { +Yamcs.issueCommand('/cfs/$(CPUID)/hk/SendCombinedPkt', { 'OutMsgToSend': OutMsgToSend});]]> true @@ -129,7 +129,7 @@ $(pv_value) Action Button 92 -10b748b0:17773fb054b:-79c7 - 54 + 81 72 @@ -169,7 +169,7 @@ $(pv_value) 61 false 689e2ae8:1777f312f88:-7891 - 0 + 24 36 @@ -184,7 +184,7 @@ $(pv_value) - 1 + 4 1 true @@ -226,7 +226,7 @@ $(pv_value) Text Input 121 689e2ae8:1777f312f88:-7890 - 66 + 90 36 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/HS/Main.opi b/core/base/tools/commander/workspace_template/Displays/Apps/HS/Main.opi index 262e33024..2ee5c8e35 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/HS/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/HS/Main.opi @@ -10,7 +10,7 @@ - 1.5.5.202103162101 + 1.6.2.202104092231 @@ -23,7 +23,7 @@ /Displays/Core/EVS/Events.opi /modules/hs - HS + ($(CPUID)) HS true @@ -64,7 +64,7 @@ Text Update 0 false - /cfs/hs/HS_HkPacket_t.CmdCount + /cfs/$(CPUID)/hs/HS_HkPacket_t.CmdCount 0.0 @@ -196,7 +196,7 @@ $(pv_value) Text Update_1 0 false - /cfs/hs/HS_HkPacket_t.CmdErrCount + /cfs/$(CPUID)/hs/HS_HkPacket_t.CmdErrCount 0.0 @@ -227,7 +227,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/hs/Noop', {});]]> true @@ -283,7 +283,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/hs/Reset', {});]]> true @@ -360,7 +360,7 @@ $(pv_value) false - Health Services + ($(CPUID)) Health Services true 1 @@ -398,7 +398,7 @@ $(pv_value) 20 Text Update_4 - /cfs/hs/HS_HkPacket_t.CurrentAppMonState + /cfs/$(CPUID)/hs/HS_HkPacket_t.CurrentAppMonState @@ -445,7 +445,7 @@ $(pv_value) 20 Text Update_5 - /cfs/hs/HS_HkPacket_t.CurrentEventMonState + /cfs/$(CPUID)/hs/HS_HkPacket_t.CurrentEventMonState @@ -492,7 +492,7 @@ $(pv_value) 20 Text Update_6 - /cfs/hs/HS_HkPacket_t.CurrentAlivenessState + /cfs/$(CPUID)/hs/HS_HkPacket_t.CurrentAlivenessState @@ -539,7 +539,7 @@ $(pv_value) 20 Text Update_7 - /cfs/hs/HS_HkPacket_t.CurrentCPUHogState + /cfs/$(CPUID)/hs/HS_HkPacket_t.CurrentCPUHogState @@ -586,7 +586,7 @@ $(pv_value) 20 Text Update_9 - /CFS/HS/LoadedEMT + /cfs/$(CPUID)/HS/LoadedEMT @@ -633,7 +633,7 @@ $(pv_value) 20 Text Update_10 - /CFS/HS/LoadedAMT + /cfs/$(CPUID)/HS/LoadedAMT @@ -680,7 +680,7 @@ $(pv_value) 20 Text Update_11 - /CFS/HS/LoadedMAT + /cfs/$(CPUID)/HS/LoadedMAT @@ -727,7 +727,7 @@ $(pv_value) 20 Text Update_12 - /CFS/HS/LoadedXCT + /cfs/$(CPUID)/HS/LoadedXCT @@ -776,7 +776,7 @@ $(pv_value) Text Update_13 0 false - /cfs/hs/HS_HkPacket_t.ResetsPerformed + /cfs/$(CPUID)/hs/HS_HkPacket_t.ResetsPerformed 0.0 @@ -828,7 +828,7 @@ $(pv_value) Text Update_14 0 false - /cfs/hs/HS_HkPacket_t.MaxResets + /cfs/$(CPUID)/hs/HS_HkPacket_t.MaxResets 0.0 @@ -880,7 +880,7 @@ $(pv_value) Text Update_15 0 false - /cfs/hs/HS_HkPacket_t.EventsMonitoredCount + /cfs/$(CPUID)/hs/HS_HkPacket_t.EventsMonitoredCount 0.0 @@ -932,7 +932,7 @@ $(pv_value) Text Update_16 0 false - /cfs/hs/HS_HkPacket_t.InvalidEventMonCount + /cfs/$(CPUID)/hs/HS_HkPacket_t.InvalidEventMonCount 0.0 @@ -1582,7 +1582,7 @@ $(pv_value) 20 Text Update_17 - /CFS/HS/AppMonEnable_0 + /cfs/$(CPUID)/HS/AppMonEnable_0 @@ -1629,7 +1629,7 @@ $(pv_value) 20 Text Update_18 - /CFS/HS/AppMonEnable_1 + /cfs/$(CPUID)/HS/AppMonEnable_1 @@ -1676,7 +1676,7 @@ $(pv_value) 20 Text Update_19 - /CFS/HS/AppMonEnable_2 + /cfs/$(CPUID)/HS/AppMonEnable_2 @@ -1723,7 +1723,7 @@ $(pv_value) 20 Text Update_20 - /CFS/HS/AppMonEnable_3 + /cfs/$(CPUID)/HS/AppMonEnable_3 @@ -1770,7 +1770,7 @@ $(pv_value) 20 Text Update_21 - /CFS/HS/AppMonEnable_4 + /cfs/$(CPUID)/HS/AppMonEnable_4 @@ -1817,7 +1817,7 @@ $(pv_value) 20 Text Update_22 - /CFS/HS/AppMonEnable_5 + /cfs/$(CPUID)/HS/AppMonEnable_5 @@ -1864,7 +1864,7 @@ $(pv_value) 20 Text Update_23 - /CFS/HS/AppMonEnable_6 + /cfs/$(CPUID)/HS/AppMonEnable_6 @@ -1911,7 +1911,7 @@ $(pv_value) 20 Text Update_24 - /CFS/HS/AppMonEnable_7 + /cfs/$(CPUID)/HS/AppMonEnable_7 @@ -1958,7 +1958,7 @@ $(pv_value) 20 Text Update_25 - /CFS/HS/AppMonEnable_8 + /cfs/$(CPUID)/HS/AppMonEnable_8 @@ -2005,7 +2005,7 @@ $(pv_value) 20 Text Update_26 - /CFS/HS/AppMonEnable_9 + /cfs/$(CPUID)/HS/AppMonEnable_9 @@ -2052,7 +2052,7 @@ $(pv_value) 20 Text Update_27 - /CFS/HS/AppMonEnable_10 + /cfs/$(CPUID)/HS/AppMonEnable_10 @@ -2099,7 +2099,7 @@ $(pv_value) 20 Text Update_28 - /CFS/HS/AppMonEnable_11 + /cfs/$(CPUID)/HS/AppMonEnable_11 @@ -2146,7 +2146,7 @@ $(pv_value) 20 Text Update_29 - /CFS/HS/AppMonEnable_12 + /cfs/$(CPUID)/HS/AppMonEnable_12 @@ -2193,7 +2193,7 @@ $(pv_value) 20 Text Update_30 - /CFS/HS/AppMonEnable_13 + /cfs/$(CPUID)/HS/AppMonEnable_13 @@ -2240,7 +2240,7 @@ $(pv_value) 20 Text Update_31 - /CFS/HS/AppMonEnable_14 + /cfs/$(CPUID)/HS/AppMonEnable_14 @@ -2287,7 +2287,7 @@ $(pv_value) 20 Text Update_32 - /CFS/HS/AppMonEnable_15 + /cfs/$(CPUID)/HS/AppMonEnable_15 @@ -2334,7 +2334,7 @@ $(pv_value) 20 Text Update_33 - /CFS/HS/AppMonEnable_16 + /cfs/$(CPUID)/HS/AppMonEnable_16 @@ -2381,7 +2381,7 @@ $(pv_value) 20 Text Update_34 - /CFS/HS/AppMonEnable_17 + /cfs/$(CPUID)/HS/AppMonEnable_17 @@ -2428,7 +2428,7 @@ $(pv_value) 20 Text Update_35 - /CFS/HS/AppMonEnable_18 + /cfs/$(CPUID)/HS/AppMonEnable_18 @@ -2475,7 +2475,7 @@ $(pv_value) 20 Text Update_36 - /CFS/HS/AppMonEnable_19 + /cfs/$(CPUID)/HS/AppMonEnable_19 @@ -2522,7 +2522,7 @@ $(pv_value) 20 Text Update_37 - /CFS/HS/AppMonEnable_20 + /cfs/$(CPUID)/HS/AppMonEnable_20 @@ -2569,7 +2569,7 @@ $(pv_value) 20 Text Update_38 - /CFS/HS/AppMonEnable_21 + /cfs/$(CPUID)/HS/AppMonEnable_21 @@ -2616,7 +2616,7 @@ $(pv_value) 20 Text Update_39 - /CFS/HS/AppMonEnable_22 + /cfs/$(CPUID)/HS/AppMonEnable_22 @@ -2663,7 +2663,7 @@ $(pv_value) 20 Text Update_40 - /CFS/HS/AppMonEnable_23 + /cfs/$(CPUID)/HS/AppMonEnable_23 @@ -2710,7 +2710,7 @@ $(pv_value) 20 Text Update_41 - /CFS/HS/AppMonEnable_24 + /cfs/$(CPUID)/HS/AppMonEnable_24 @@ -2757,7 +2757,7 @@ $(pv_value) 20 Text Update_42 - /CFS/HS/AppMonEnable_25 + /cfs/$(CPUID)/HS/AppMonEnable_25 @@ -2804,7 +2804,7 @@ $(pv_value) 20 Text Update_43 - /CFS/HS/AppMonEnable_26 + /cfs/$(CPUID)/HS/AppMonEnable_26 @@ -2851,7 +2851,7 @@ $(pv_value) 20 Text Update_44 - /CFS/HS/AppMonEnable_27 + /cfs/$(CPUID)/HS/AppMonEnable_27 @@ -2898,7 +2898,7 @@ $(pv_value) 20 Text Update_45 - /CFS/HS/AppMonEnable_28 + /cfs/$(CPUID)/HS/AppMonEnable_28 @@ -2945,7 +2945,7 @@ $(pv_value) 20 Text Update_46 - /CFS/HS/AppMonEnable_29 + /cfs/$(CPUID)/HS/AppMonEnable_29 @@ -2992,7 +2992,7 @@ $(pv_value) 20 Text Update_47 - /CFS/HS/AppMonEnable_30 + /cfs/$(CPUID)/HS/AppMonEnable_30 @@ -3039,7 +3039,7 @@ $(pv_value) 20 Text Update_48 - /CFS/HS/AppMonEnable_31 + /cfs/$(CPUID)/HS/AppMonEnable_31 @@ -3088,7 +3088,7 @@ $(pv_value) Text Update_49 0 false - /cfs/hs/HS_HkPacket_t.MsgActExec + /cfs/$(CPUID)/hs/HS_HkPacket_t.MsgActExec 0.0 @@ -3140,7 +3140,7 @@ $(pv_value) Text Update_50 0 false - /cfs/hs/HS_HkPacket_t.UtilCpuAvg + /cfs/$(CPUID)/hs/HS_HkPacket_t.UtilCpuAvg 0.0 @@ -3192,7 +3192,7 @@ $(pv_value) Text Update_51 0 false - /cfs/hs/HS_HkPacket_t.UtilCpuPeak + /cfs/$(CPUID)/hs/HS_HkPacket_t.UtilCpuPeak 0.0 @@ -4684,7 +4684,7 @@ $(pv_value) Text Update_52 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_0_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_0_ 0.0 @@ -4736,7 +4736,7 @@ $(pv_value) Text Update_53 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_1_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_1_ 0.0 @@ -4788,7 +4788,7 @@ $(pv_value) Text Update_54 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_2_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_2_ 0.0 @@ -4840,7 +4840,7 @@ $(pv_value) Text Update_55 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_3_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_3_ 0.0 @@ -4892,7 +4892,7 @@ $(pv_value) Text Update_56 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_4_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_4_ 0.0 @@ -4944,7 +4944,7 @@ $(pv_value) Text Update_57 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_5_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_5_ 0.0 @@ -4996,7 +4996,7 @@ $(pv_value) Text Update_58 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_6_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_6_ 0.0 @@ -5048,7 +5048,7 @@ $(pv_value) Text Update_59 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_7_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_7_ 0.0 @@ -5100,7 +5100,7 @@ $(pv_value) Text Update_60 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_8_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_8_ 0.0 @@ -5152,7 +5152,7 @@ $(pv_value) Text Update_61 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_9_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_9_ 0.0 @@ -5204,7 +5204,7 @@ $(pv_value) Text Update_62 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_10_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_10_ 0.0 @@ -5256,7 +5256,7 @@ $(pv_value) Text Update_63 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_11_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_11_ 0.0 @@ -5308,7 +5308,7 @@ $(pv_value) Text Update_64 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_12_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_12_ 0.0 @@ -5360,7 +5360,7 @@ $(pv_value) Text Update_65 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_13_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_13_ 0.0 @@ -5412,7 +5412,7 @@ $(pv_value) Text Update_66 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_14_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_14_ 0.0 @@ -5464,7 +5464,7 @@ $(pv_value) Text Update_67 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_15_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_15_ 0.0 @@ -5516,7 +5516,7 @@ $(pv_value) Text Update_68 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_16_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_16_ 0.0 @@ -5568,7 +5568,7 @@ $(pv_value) Text Update_69 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_17_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_17_ 0.0 @@ -5620,7 +5620,7 @@ $(pv_value) Text Update_70 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_18_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_18_ 0.0 @@ -5672,7 +5672,7 @@ $(pv_value) Text Update_71 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_19_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_19_ 0.0 @@ -5724,7 +5724,7 @@ $(pv_value) Text Update_72 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_20_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_20_ 0.0 @@ -5776,7 +5776,7 @@ $(pv_value) Text Update_73 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_21_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_21_ 0.0 @@ -5828,7 +5828,7 @@ $(pv_value) Text Update_74 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_22_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_22_ 0.0 @@ -5880,7 +5880,7 @@ $(pv_value) Text Update_75 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_23_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_23_ 0.0 @@ -5932,7 +5932,7 @@ $(pv_value) Text Update_76 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_24_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_24_ 0.0 @@ -5984,7 +5984,7 @@ $(pv_value) Text Update_77 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_25_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_25_ 0.0 @@ -6036,7 +6036,7 @@ $(pv_value) Text Update_78 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_26_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_26_ 0.0 @@ -6088,7 +6088,7 @@ $(pv_value) Text Update_79 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_27_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_27_ 0.0 @@ -6140,7 +6140,7 @@ $(pv_value) Text Update_80 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_28_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_28_ 0.0 @@ -6192,7 +6192,7 @@ $(pv_value) Text Update_81 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_29_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_29_ 0.0 @@ -6244,7 +6244,7 @@ $(pv_value) Text Update_82 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_30_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_30_ 0.0 @@ -6296,7 +6296,7 @@ $(pv_value) Text Update_83 0 false - /cfs/hs/HS_HkPacket_t.ExeCounts_31_ + /cfs/$(CPUID)/hs/HS_HkPacket_t.ExeCounts_31_ 0.0 @@ -6367,7 +6367,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/hs/EnableAppMon', {});]]> true @@ -6423,7 +6423,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/hs/DisableAppMon', {});]]> true @@ -6479,7 +6479,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/hs/EnableEventMon', {});]]> true @@ -6535,7 +6535,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/hs/EnableAliveness', {});]]> true @@ -6591,7 +6591,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/hs/EnableCpuHog', {});]]> true @@ -6647,7 +6647,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/hs/DisableEventMon', {});]]> true @@ -6703,7 +6703,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/hs/DisableAliveness', {});]]> true @@ -6759,7 +6759,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/hs/DisableCpuHog', {});]]> true @@ -6815,7 +6815,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/hs/ResetResetsPerformed', {});]]> true @@ -6980,4 +6980,65 @@ $(pv_value) 42 384 + + + + + + true + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 20 + + AppControl + 0 + + + + + true + true + false + + + + App Control + false + $(pv_name) +$(pv_value) + true + Action Button + 127 + 49c9ccd0:178c6a335db:-3be9 + 42 + 403 + \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/LC/Main.opi b/core/base/tools/commander/workspace_template/Displays/Apps/LC/Main.opi index db7a4d206..fab8d09ea 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/LC/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/LC/Main.opi @@ -10,7 +10,7 @@ - 1.5.5.202103162101 + 1.6.2.202104092231 @@ -23,7 +23,7 @@ Displays /modules/lc - LC + ($(CPUID)) LC true @@ -64,7 +64,7 @@ Text Update 0 false - /cfs/lc/LC_HkPacket_t.CmdCount + /cfs/$(CPUID)/lc/LC_HkPacket_t.CmdCount 0.0 @@ -196,7 +196,7 @@ $(pv_value) Text Update_1 0 false - /cfs/lc/LC_HkPacket_t.CmdErrCount + /cfs/$(CPUID)/lc/LC_HkPacket_t.CmdErrCount 0.0 @@ -227,7 +227,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/lc/Noop', {});]]> true @@ -283,7 +283,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/lc/Reset', {});]]> true @@ -360,7 +360,7 @@ $(pv_value) false - Limit Checker + ($(CPUID)) Limit Checker true 1 @@ -400,7 +400,7 @@ $(pv_value) Text Update_2 0 false - /cfs/lc/LC_HkPacket_t.PassiveRTSExecCount + /cfs/$(CPUID)/lc/LC_HkPacket_t.PassiveRTSExecCount 0.0 @@ -452,7 +452,7 @@ $(pv_value) Text Update_3 0 false - /cfs/lc/LC_HkPacket_t.WPsInUse + /cfs/$(CPUID)/lc/LC_HkPacket_t.WPsInUse 0.0 @@ -504,7 +504,7 @@ $(pv_value) Text Update_4 0 false - /cfs/lc/LC_HkPacket_t.ActiveAPs + /cfs/$(CPUID)/lc/LC_HkPacket_t.ActiveAPs 0.0 @@ -556,7 +556,7 @@ $(pv_value) Text Update_5 0 false - /cfs/lc/LC_HkPacket_t.APSampleCount + /cfs/$(CPUID)/lc/LC_HkPacket_t.APSampleCount 0.0 @@ -608,7 +608,7 @@ $(pv_value) Text Update_6 0 false - /cfs/lc/LC_HkPacket_t.MonitoredMsgCount + /cfs/$(CPUID)/lc/LC_HkPacket_t.MonitoredMsgCount 0.0 @@ -900,7 +900,7 @@ $(pv_value) Text Update_7 0 false - /cfs/lc/LC_HkPacket_t.RTSExecCount + /cfs/$(CPUID)/lc/LC_HkPacket_t.RTSExecCount 0.0 @@ -1206,7 +1206,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/lc/SendHK', {});]]> true @@ -1283,7 +1283,7 @@ $(pv_value) Text Update_8 0 false - /cfs/lc/LC_HkPacket_t.CurrentLCState + /cfs/$(CPUID)/lc/LC_HkPacket_t.CurrentLCState 0.0 @@ -1408,4 +1408,65 @@ $(pv_value) 147 272 + + + + + + true + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 20 + + AppControl + 0 + + + + + true + true + false + + + + App Control + false + $(pv_name) +$(pv_value) + true + Action Button + 138 + 49c9ccd0:178c6a335db:-486a + 10 + 291 + \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/LC/ResetAPStats.opi b/core/base/tools/commander/workspace_template/Displays/Apps/LC/ResetAPStats.opi index 8455b87a1..f3d57e66a 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/LC/ResetAPStats.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/LC/ResetAPStats.opi @@ -19,7 +19,7 @@ true - LC - Reset AP Stats + ($(CPUID)) LC - Reset AP Stats true @@ -28,7 +28,7 @@ true true Display - 200 + 240 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,16 +60,16 @@ false - Reset AP Stats + ($(CPUID)) LC - Reset AP Stats true 1 true Label - 175 + 235 false -10b748b0:17773fb054b:-7a20 - 12 + 6 6 @@ -82,7 +82,7 @@ importPackage(Packages.org.yamcs.studio.data); var APNumber = VTypeHelper.getString(display.getWidget('APNumber').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/lc/ResetAPStats', { +Yamcs.issueCommand('/cfs/$(CPUID)/lc/ResetAPStats', { 'APNumber': APNumber, 'Padding': 0 });]]> true @@ -130,7 +130,7 @@ $(pv_value) Action Button 92 -10b748b0:17773fb054b:-79c7 - 54 + 72 72 @@ -170,7 +170,7 @@ $(pv_value) 61 false 689e2ae8:1777f312f88:-7891 - 0 + 18 36 @@ -185,7 +185,7 @@ $(pv_value) - 1 + 4 1 true @@ -227,7 +227,7 @@ $(pv_value) Text Input 121 689e2ae8:1777f312f88:-7890 - 66 + 84 36 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/LC/ResetWPStats.opi b/core/base/tools/commander/workspace_template/Displays/Apps/LC/ResetWPStats.opi index 74564f3fb..c08e8f446 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/LC/ResetWPStats.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/LC/ResetWPStats.opi @@ -19,7 +19,7 @@ true - LC - Reset WP Stats + ($(CPUID)) LC - Reset WP Stats true @@ -60,13 +60,13 @@ false - Reset WP Stats + ($(CPUID)) LC - Reset WP Stats true 1 true Label - 175 + 241 false -10b748b0:17773fb054b:-7a20 12 @@ -82,7 +82,7 @@ importPackage(Packages.org.yamcs.studio.data); var WPNumber = VTypeHelper.getString(display.getWidget('WPNumber').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/lc/ResetWPStats', { +Yamcs.issueCommand('/cfs/$(CPUID)/lc/ResetWPStats', { 'WPNumber': WPNumber, 'Padding': 0 });]]> true @@ -130,7 +130,7 @@ $(pv_value) Action Button 92 -10b748b0:17773fb054b:-79c7 - 54 + 72 72 @@ -170,7 +170,7 @@ $(pv_value) 61 false 689e2ae8:1777f312f88:-7891 - 0 + 18 36 @@ -185,7 +185,7 @@ $(pv_value) - 1 + 4 1 true @@ -227,7 +227,7 @@ $(pv_value) Text Input 121 689e2ae8:1777f312f88:-7890 - 66 + 84 36 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/LC/SetAPPermOff.opi b/core/base/tools/commander/workspace_template/Displays/Apps/LC/SetAPPermOff.opi index f0e79c627..d38e634ea 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/LC/SetAPPermOff.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/LC/SetAPPermOff.opi @@ -19,7 +19,7 @@ true - LC - Set AP Perm Off + ($(CPUID)) LC - Set AP Perm Off true @@ -28,7 +28,7 @@ true true Display - 200 + 260 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,13 +60,13 @@ false - Set AP Perm Off + ($(CPUID)) LC - Set AP Perm Off true 1 true Label - 175 + 241 false -10b748b0:17773fb054b:-7a20 12 @@ -82,7 +82,7 @@ importPackage(Packages.org.yamcs.studio.data); var APNumber = VTypeHelper.getString(display.getWidget('APNumber').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/lc/SetAPPermOff', { +Yamcs.issueCommand('/cfs/$(CPUID)/lc/SetAPPermOff', { 'APNumber': APNumber, 'Padding': 0 });]]> true @@ -130,7 +130,7 @@ $(pv_value) Action Button 92 -10b748b0:17773fb054b:-79c7 - 54 + 84 72 @@ -170,7 +170,7 @@ $(pv_value) 61 false 689e2ae8:1777f312f88:-7891 - 0 + 24 36 @@ -185,7 +185,7 @@ $(pv_value) - 1 + 4 1 true @@ -227,7 +227,7 @@ $(pv_value) Text Input 121 689e2ae8:1777f312f88:-7890 - 66 + 96 36 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/LC/SetAPState.opi b/core/base/tools/commander/workspace_template/Displays/Apps/LC/SetAPState.opi index 8a81590b2..e697e8865 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/LC/SetAPState.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/LC/SetAPState.opi @@ -19,7 +19,7 @@ true - LC - Set LC State + ($(CPUID)) LC - Set LC State true @@ -28,7 +28,7 @@ true true Display - 200 + 240 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,13 +60,13 @@ false - Set AP State + ($(CPUID)) LC - Set AP State true 1 true Label - 175 + 217 false -10b748b0:17773fb054b:-7a20 12 @@ -83,7 +83,7 @@ importPackage(Packages.org.yamcs.studio.data); var State = VTypeHelper.getString(display.getWidget('State').getPropertyValue('pv_value')); var APNumber = VTypeHelper.getString(display.getWidget('APNumber').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/lc/SetAPState', { +Yamcs.issueCommand('/cfs/$(CPUID)/lc/SetAPState', { 'NewAPState': State, 'APNumber': APNumber });]]> true @@ -131,7 +131,7 @@ $(pv_value) Action Button 92 -10b748b0:17773fb054b:-79c7 - 54 + 66 108 @@ -171,7 +171,7 @@ $(pv_value) 37 false 54e87698:1777e01a75d:-6f83 - 12 + 24 42 @@ -185,7 +185,7 @@ $(pv_value) - 0 + 4 1 true @@ -219,7 +219,7 @@ $(pv_value) Combo 127 689e2ae8:1777f312f88:-7910 - 60 + 72 36 @@ -259,7 +259,7 @@ $(pv_value) 61 false 689e2ae8:1777f312f88:-7891 - 0 + 12 72 @@ -274,7 +274,7 @@ $(pv_value) - 1 + 4 1 true @@ -316,7 +316,7 @@ $(pv_value) Text Input 121 689e2ae8:1777f312f88:-7890 - 66 + 78 72 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/LC/SetLCState.opi b/core/base/tools/commander/workspace_template/Displays/Apps/LC/SetLCState.opi index 3eeed964d..940df200b 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/LC/SetLCState.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/LC/SetLCState.opi @@ -15,11 +15,11 @@ 6 - 100 + 110 true - LC - Set LC State + ($(CPUID)) LC - Set LC State true @@ -28,7 +28,7 @@ true true Display - 200 + 220 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,16 +60,16 @@ false - Set LC State + ($(CPUID)) LC - Set LC State true 1 true Label - 175 + 211 false -10b748b0:17773fb054b:-7a20 - 12 + 6 6 @@ -82,7 +82,7 @@ importPackage(Packages.org.yamcs.studio.data); var State = VTypeHelper.getString(display.getWidget('State').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/lc/SetLCState', { +Yamcs.issueCommand('/cfs/$(CPUID)/lc/SetLCState', { 'NewLCState': State, 'Padding': 0 });]]> true @@ -108,7 +108,7 @@ Yamcs.issueCommand('/cfs/lc/SetLCState', { - 20 + 25 ../../Resources/send.png NoOp 0 @@ -130,7 +130,7 @@ $(pv_value) Action Button 92 -10b748b0:17773fb054b:-79c7 - 54 + 60 72 @@ -170,7 +170,7 @@ $(pv_value) 37 false 54e87698:1777e01a75d:-6f83 - 12 + 18 36 @@ -217,7 +217,7 @@ $(pv_value) Combo 127 689e2ae8:1777f312f88:-7910 - 60 + 66 30 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/MD/Jam.opi b/core/base/tools/commander/workspace_template/Displays/Apps/MD/Jam.opi index 8c9edbcfe..dddcf94f5 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/MD/Jam.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/MD/Jam.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - MD - Jam + ($(CPUID)) MD - Jam true @@ -60,7 +60,7 @@ false - Jam + ($(CPUID)) MD - Jam true 1 @@ -87,7 +87,7 @@ var DwellDelay = VTypeHelper.getString(display.getWidget('DwellDelay').getProper var SymbolName = VTypeHelper.getString(display.getWidget('SymbolName').getPropertyValue('pv_value')); var Offset = VTypeHelper.getString(display.getWidget('Offset').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/md/Jam', { +Yamcs.issueCommand('/cfs/$(CPUID)/md/Jam', { 'TableId': TableID, 'EntryId': EntryID, 'FieldLength': FieldLength, @@ -194,7 +194,7 @@ $(pv_value) - 1 + 4 1 true @@ -291,7 +291,7 @@ $(pv_value) - 1 + 4 1 true @@ -388,7 +388,7 @@ $(pv_value) - 1 + 4 1 true @@ -485,7 +485,7 @@ $(pv_value) - 1 + 4 1 true @@ -582,7 +582,7 @@ $(pv_value) - 1 + 4 1 true @@ -679,7 +679,7 @@ $(pv_value) - 1 + 4 1 true diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/MD/Main.opi b/core/base/tools/commander/workspace_template/Displays/Apps/MD/Main.opi index 36583a9c7..508b4893a 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/MD/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/MD/Main.opi @@ -10,7 +10,7 @@ - 1.5.5.202103162101 + 1.6.2.202104092231 @@ -23,7 +23,7 @@ Displays /modules/md - MD + ($(CPUID)) MD true @@ -48,7 +48,7 @@ - 1 + 4 1 true @@ -64,7 +64,7 @@ Text Update 0 false - /cfs/md/MD_HkTlm_t.ValidCmdCntr + /cfs/$(CPUID)/md/MD_HkTlm_t.ValidCmdCntr 0.0 @@ -180,7 +180,7 @@ $(pv_value) - 1 + 4 1 true @@ -196,7 +196,7 @@ $(pv_value) Text Update_1 0 false - /cfs/md/MD_HkTlm_t.InvalidCmdCntr + /cfs/$(CPUID)/md/MD_HkTlm_t.InvalidCmdCntr 0.0 @@ -227,7 +227,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/md/Noop', {});]]> true @@ -283,7 +283,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/md/Reset', {});]]> true @@ -360,16 +360,16 @@ $(pv_value) false - Memory Dwell + ($(CPUID)) Memory Dwell true 1 true Label - 155 + 187 false -33cb7c72:150aa4c347f:-75c9 - 194 + 162 6 @@ -424,7 +424,7 @@ $(pv_value) - 1 + 4 1 true @@ -440,7 +440,7 @@ $(pv_value) Text Update_26 0 false - /cfs/md/MD_HkTlm_t.DwellEnabledMask + /cfs/$(CPUID)/md/MD_HkTlm_t.DwellEnabledMask 0.0 @@ -476,7 +476,7 @@ $(pv_value) - 1 + 4 1 true @@ -492,7 +492,7 @@ $(pv_value) Text Update_27 0 false - /cfs/md/MD_HkTlm_t.DwellTblAddrCount_0_ + /cfs/$(CPUID)/md/MD_HkTlm_t.DwellTblAddrCount_0_ 0.0 @@ -528,7 +528,7 @@ $(pv_value) - 1 + 4 1 true @@ -544,7 +544,7 @@ $(pv_value) Text Update_28 0 false - /cfs/md/MD_HkTlm_t.DwellTblAddrCount_1_ + /cfs/$(CPUID)/md/MD_HkTlm_t.DwellTblAddrCount_1_ 0.0 @@ -580,7 +580,7 @@ $(pv_value) - 1 + 4 1 true @@ -596,7 +596,7 @@ $(pv_value) Text Update_29 0 false - /cfs/md/MD_HkTlm_t.DwellTblAddrCount_2_ + /cfs/$(CPUID)/md/MD_HkTlm_t.DwellTblAddrCount_2_ 0.0 @@ -632,7 +632,7 @@ $(pv_value) - 1 + 4 1 true @@ -648,7 +648,7 @@ $(pv_value) Text Update_30 0 false - /cfs/md/MD_HkTlm_t.DwellTblAddrCount_3_ + /cfs/$(CPUID)/md/MD_HkTlm_t.DwellTblAddrCount_3_ 0.0 @@ -684,7 +684,7 @@ $(pv_value) - 1 + 4 1 true @@ -700,7 +700,7 @@ $(pv_value) Text Update_31 0 false - /cfs/md/MD_HkTlm_t.NumWaitsPerPkt_0_ + /cfs/$(CPUID)/md/MD_HkTlm_t.NumWaitsPerPkt_0_ 0.0 @@ -736,7 +736,7 @@ $(pv_value) - 1 + 4 1 true @@ -752,7 +752,7 @@ $(pv_value) Text Update_32 0 false - /cfs/md/MD_HkTlm_t.NumWaitsPerPkt_1_ + /cfs/$(CPUID)/md/MD_HkTlm_t.NumWaitsPerPkt_1_ 0.0 @@ -788,7 +788,7 @@ $(pv_value) - 1 + 4 1 true @@ -804,7 +804,7 @@ $(pv_value) Text Update_33 0 false - /cfs/md/MD_HkTlm_t.NumWaitsPerPkt_2_ + /cfs/$(CPUID)/md/MD_HkTlm_t.NumWaitsPerPkt_2_ 0.0 @@ -840,7 +840,7 @@ $(pv_value) - 1 + 4 1 true @@ -856,7 +856,7 @@ $(pv_value) Text Update_34 0 false - /cfs/md/MD_HkTlm_t.NumWaitsPerPkt_3_ + /cfs/$(CPUID)/md/MD_HkTlm_t.NumWaitsPerPkt_3_ 0.0 @@ -892,7 +892,7 @@ $(pv_value) - 1 + 4 1 true @@ -908,7 +908,7 @@ $(pv_value) Text Update_35 0 false - /cfs/md/MD_HkTlm_t.ByteCount_0_ + /cfs/$(CPUID)/md/MD_HkTlm_t.ByteCount_0_ 0.0 @@ -944,7 +944,7 @@ $(pv_value) - 1 + 4 1 true @@ -960,7 +960,7 @@ $(pv_value) Text Update_36 0 false - /cfs/md/MD_HkTlm_t.ByteCount_1_ + /cfs/$(CPUID)/md/MD_HkTlm_t.ByteCount_1_ 0.0 @@ -996,7 +996,7 @@ $(pv_value) - 1 + 4 1 true @@ -1012,7 +1012,7 @@ $(pv_value) Text Update_37 0 false - /cfs/md/MD_HkTlm_t.ByteCount_2_ + /cfs/$(CPUID)/md/MD_HkTlm_t.ByteCount_2_ 0.0 @@ -1048,7 +1048,7 @@ $(pv_value) - 1 + 4 1 true @@ -1064,7 +1064,7 @@ $(pv_value) Text Update_38 0 false - /cfs/md/MD_HkTlm_t.ByteCount_3_ + /cfs/$(CPUID)/md/MD_HkTlm_t.ByteCount_3_ 0.0 @@ -1100,7 +1100,7 @@ $(pv_value) - 1 + 4 1 true @@ -1116,7 +1116,7 @@ $(pv_value) Text Update_39 0 false - /cfs/md/MD_HkTlm_t.DwellPktOffset_0_ + /cfs/$(CPUID)/md/MD_HkTlm_t.DwellPktOffset_0_ 0.0 @@ -1152,7 +1152,7 @@ $(pv_value) - 1 + 4 1 true @@ -1168,7 +1168,7 @@ $(pv_value) Text Update_40 0 false - /cfs/md/MD_HkTlm_t.DwellPktOffset_1_ + /cfs/$(CPUID)/md/MD_HkTlm_t.DwellPktOffset_1_ 0.0 @@ -1204,7 +1204,7 @@ $(pv_value) - 1 + 4 1 true @@ -1220,7 +1220,7 @@ $(pv_value) Text Update_41 0 false - /cfs/md/MD_HkTlm_t.DwellPktOffset_2_ + /cfs/$(CPUID)/md/MD_HkTlm_t.DwellPktOffset_2_ 0.0 @@ -1256,7 +1256,7 @@ $(pv_value) - 1 + 4 1 true @@ -1272,7 +1272,7 @@ $(pv_value) Text Update_42 0 false - /cfs/md/MD_HkTlm_t.DwellPktOffset_3_ + /cfs/$(CPUID)/md/MD_HkTlm_t.DwellPktOffset_3_ 0.0 @@ -1308,7 +1308,7 @@ $(pv_value) - 1 + 4 1 true @@ -1324,7 +1324,7 @@ $(pv_value) Text Update_43 0 false - /cfs/md/MD_HkTlm_t.DwellTblEntry_0_ + /cfs/$(CPUID)/md/MD_HkTlm_t.DwellTblEntry_0_ 0.0 @@ -1360,7 +1360,7 @@ $(pv_value) - 1 + 4 1 true @@ -1376,7 +1376,7 @@ $(pv_value) Text Update_44 0 false - /cfs/md/MD_HkTlm_t.DwellTblEntry_1_ + /cfs/$(CPUID)/md/MD_HkTlm_t.DwellTblEntry_1_ 0.0 @@ -1412,7 +1412,7 @@ $(pv_value) - 1 + 4 1 true @@ -1428,7 +1428,7 @@ $(pv_value) Text Update_45 0 false - /cfs/md/MD_HkTlm_t.DwellTblEntry_2_ + /cfs/$(CPUID)/md/MD_HkTlm_t.DwellTblEntry_2_ 0.0 @@ -1464,7 +1464,7 @@ $(pv_value) - 1 + 4 1 true @@ -1480,7 +1480,7 @@ $(pv_value) Text Update_46 0 false - /cfs/md/MD_HkTlm_t.DwellTblEntry_3_ + /cfs/$(CPUID)/md/MD_HkTlm_t.DwellTblEntry_3_ 0.0 @@ -1516,7 +1516,7 @@ $(pv_value) - 1 + 4 1 true @@ -1532,7 +1532,7 @@ $(pv_value) Text Update_47 0 false - /cfs/md/MD_HkTlm_t.Countdown_0_ + /cfs/$(CPUID)/md/MD_HkTlm_t.Countdown_0_ 0.0 @@ -1568,7 +1568,7 @@ $(pv_value) - 1 + 4 1 true @@ -1584,7 +1584,7 @@ $(pv_value) Text Update_48 0 false - /cfs/md/MD_HkTlm_t.Countdown_1_ + /cfs/$(CPUID)/md/MD_HkTlm_t.Countdown_1_ 0.0 @@ -1620,7 +1620,7 @@ $(pv_value) - 1 + 4 1 true @@ -1636,7 +1636,7 @@ $(pv_value) Text Update_49 0 false - /cfs/md/MD_HkTlm_t.Countdown_2_ + /cfs/$(CPUID)/md/MD_HkTlm_t.Countdown_2_ 0.0 @@ -1672,7 +1672,7 @@ $(pv_value) - 1 + 4 1 true @@ -1688,7 +1688,7 @@ $(pv_value) Text Update_50 0 false - /cfs/md/MD_HkTlm_t.Countdown_3_ + /cfs/$(CPUID)/md/MD_HkTlm_t.Countdown_3_ 0.0 @@ -2164,8 +2164,8 @@ $(pv_value) Action Button 128 689e2ae8:1777f312f88:-7a71 - 372 - 20 + 366 + 36 @@ -2219,8 +2219,8 @@ $(pv_value) Action Button 128 689e2ae8:1777f312f88:-7a69 - 372 - 39 + 366 + 55 @@ -2274,8 +2274,8 @@ $(pv_value) Action Button 128 689e2ae8:1777f312f88:-7a61 - 372 - 58 + 366 + 74 @@ -2329,8 +2329,8 @@ $(pv_value) Action Button 128 689e2ae8:1777f312f88:-7a59 - 372 - 77 + 366 + 93 @@ -2390,8 +2390,8 @@ $(pv_value) Action Button 128 -19107c2b:177da1db5df:d33 - 372 - 96 + 366 + 112 @@ -2401,7 +2401,7 @@ $(pv_value) importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); -Yamcs.issueCommand('/cfs/md/SendHK', {});]]> +Yamcs.issueCommand('/cfs/$(CPUID)/md/SendHK', {});]]> true @@ -2447,8 +2447,8 @@ $(pv_value) Action Button 128 -69f8bd78:177f094d5fe:-21fa - 372 - 115 + 366 + 131 @@ -2458,7 +2458,7 @@ $(pv_value) importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); -Yamcs.issueCommand('/cfs/md/Wakeup', {});]]> +Yamcs.issueCommand('/cfs/$(CPUID)/md/Wakeup', {});]]> true @@ -2504,7 +2504,68 @@ $(pv_value) Action Button 128 -69f8bd78:177f094d5fe:-21f2 - 372 - 134 + 366 + 150 + + + + + + + true + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 20 + + AppControl + 0 + + + + + true + true + false + + + + App Control + false + $(pv_name) +$(pv_value) + true + Action Button + 128 + 49c9ccd0:178c6a335db:-481f + 366 + 17 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/MD/SetSignature.opi b/core/base/tools/commander/workspace_template/Displays/Apps/MD/SetSignature.opi index e8ea9262c..41f50ca41 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/MD/SetSignature.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/MD/SetSignature.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -60,16 +60,16 @@ false - Set Signature + ($(CPUID)) MD - Set Signature true 1 true Label - 175 + 238 false -10b748b0:17773fb054b:-7a20 - 48 + 12 6 @@ -83,7 +83,7 @@ importPackage(Packages.org.yamcs.studio.data); var TableID = VTypeHelper.getString(display.getWidget('TableID').getPropertyValue('pv_value')); var Signature = VTypeHelper.getString(display.getWidget('Signature').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/md/SetSignature', { +Yamcs.issueCommand('/cfs/$(CPUID)/md/SetSignature', { 'TableId': TableID, 'Signature': Signature, 'Padding': 0});]]> @@ -187,7 +187,7 @@ $(pv_value) - 1 + 4 1 true @@ -284,7 +284,7 @@ $(pv_value) - 1 + 4 1 true diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/MD/Start.opi b/core/base/tools/commander/workspace_template/Displays/Apps/MD/Start.opi index 454564566..58c0d8d42 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/MD/Start.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/MD/Start.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - MD - Start + ($(CPUID)) MD - Start true @@ -60,7 +60,7 @@ false - Start + ($(CPUID)) MD - Start true 1 @@ -82,7 +82,7 @@ importPackage(Packages.org.yamcs.studio.data); var TableMask = VTypeHelper.getString(display.getWidget('TableMask').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/md/Start', { +Yamcs.issueCommand('/cfs/$(CPUID)/md/Start', { 'TableMask': TableMask});]]> true @@ -184,7 +184,7 @@ $(pv_value) - 1 + 4 1 true diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/MD/Stop.opi b/core/base/tools/commander/workspace_template/Displays/Apps/MD/Stop.opi index f4af9b365..f53135110 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/MD/Stop.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/MD/Stop.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - MD - Stop + ($(CPUID)) MD - Stop true @@ -60,7 +60,7 @@ false - Stop + ($(CPUID)) MD - Stop true 1 @@ -82,7 +82,7 @@ importPackage(Packages.org.yamcs.studio.data); var TableMask = VTypeHelper.getString(display.getWidget('TableMask').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/md/Stop', { +Yamcs.issueCommand('/cfs/$(CPUID)/md/Stop', { 'TableMask': TableMask});]]> true @@ -184,7 +184,7 @@ $(pv_value) - 1 + 4 1 true diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/MM/DisableEEPROMWrite.opi b/core/base/tools/commander/workspace_template/Displays/Apps/MM/DisableEEPROMWrite.opi index b88e1f6a1..02cd22cbd 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/MM/DisableEEPROMWrite.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/MM/DisableEEPROMWrite.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - MM - Disable EEPROM + ($(CPUID)) MM - Disable EEPROM true @@ -28,7 +28,7 @@ true true Display - 190 + 310 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,13 +60,13 @@ false - Disable EEPROM Write + ($(CPUID)) MM - Disable EEPROM Write true 1 true Label - 175 + 289 false -10b748b0:17773fb054b:-7a20 12 @@ -109,7 +109,7 @@ 61 false -10b748b0:17773fb054b:-7a0f - 0 + 60 36 @@ -122,7 +122,7 @@ importPackage(Packages.org.yamcs.studio.data); var Bank = VTypeHelper.getString(display.getWidget('Bank').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/mm/DisableEEPROMWrite', { +Yamcs.issueCommand('/cfs/$(CPUID)/mm/DisableEEPROMWrite', { 'Bank': Bank});]]> true @@ -169,7 +169,7 @@ $(pv_value) Action Button 92 -10b748b0:17773fb054b:-79c7 - 48 + 114 66 @@ -184,7 +184,7 @@ $(pv_value) - 1 + 4 1 true @@ -226,7 +226,7 @@ $(pv_value) Text Input 100 -10b748b0:17773fb054b:-78ff - 72 + 132 36 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/MM/DumpMemInEvent.opi b/core/base/tools/commander/workspace_template/Displays/Apps/MM/DumpMemInEvent.opi index 5eb873a7d..19eb4875f 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/MM/DumpMemInEvent.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/MM/DumpMemInEvent.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - MM - Dump Memory In Event + ($(CPUID)) MM - Dump Memory In Event true @@ -28,7 +28,7 @@ true true Display - 260 + 320 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,16 +60,16 @@ false - Dump Memory In Event + ($(CPUID)) MM - Dump Memory In Event true 1 true Label - 175 + 313 false -10b748b0:17773fb054b:-7a20 - 48 + 12 6 @@ -100,7 +100,7 @@ false - MemType + Mem Type true 1 @@ -109,8 +109,8 @@ 73 false -10b748b0:17773fb054b:-7a0f - 36 - 35 + 54 + 34 @@ -125,7 +125,7 @@ var NumofBytes = VTypeHelper.getString(display.getWidget('NumofBytes').getProper var SymbolName = VTypeHelper.getString(display.getWidget('SymbolName').getPropertyValue('pv_value')); var Offset = VTypeHelper.getString(display.getWidget('Offset').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/mm/DumpInEvent', { +Yamcs.issueCommand('/cfs/$(CPUID)/mm/DumpInEvent', { 'MemType': MemType, 'NumOfBytes': NumofBytes, 'Padding': 0, @@ -176,8 +176,8 @@ $(pv_value) Action Button 92 -10b748b0:17773fb054b:-79c7 - 90 - 138 + 108 + 150 @@ -200,7 +200,7 @@ $(pv_value) - 27 + 32 NOMEMTYPE EEPROM @@ -226,8 +226,8 @@ $(pv_value) Combo 136 54e87698:1777e01a75d:-6f8b - 114 - 31 + 132 + 30 @@ -266,8 +266,8 @@ $(pv_value) 97 false 54e87698:1777e01a75d:-6f83 - 12 - 57 + 30 + 69 @@ -281,7 +281,7 @@ $(pv_value) - 1 + 4 1 true @@ -323,8 +323,8 @@ $(pv_value) Text Input 136 54e87698:1777e01a75d:-6f5d - 114 - 57 + 132 + 69 @@ -363,8 +363,8 @@ $(pv_value) 97 false 54e87698:1777e01a75d:-6f53 - 12 - 83 + 30 + 95 @@ -378,7 +378,7 @@ $(pv_value) - 1 + 4 1 true @@ -420,8 +420,8 @@ $(pv_value) Text Input 136 54e87698:1777e01a75d:-6f49 - 114 - 83 + 132 + 95 @@ -460,8 +460,8 @@ $(pv_value) 97 false 54e87698:1777e01a75d:-6f41 - 12 - 107 + 30 + 119 @@ -475,7 +475,7 @@ $(pv_value) - 1 + 4 1 true @@ -517,7 +517,7 @@ $(pv_value) Text Input 136 54e87698:1777e01a75d:-6f37 - 114 - 107 + 132 + 119 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/MM/DumpMemToFile.opi b/core/base/tools/commander/workspace_template/Displays/Apps/MM/DumpMemToFile.opi index 5338f4afe..4946bb107 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/MM/DumpMemToFile.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/MM/DumpMemToFile.opi @@ -10,16 +10,16 @@ - 1.5.3 + 1.5.5.202103012118 6 - 200 + 210 true - MM - Dump Memory to File + ($(CPUID)) MM - Dump Memory to File true @@ -28,7 +28,7 @@ true true Display - 260 + 330 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,16 +60,16 @@ false - Dump Memory to File + ($(CPUID)) MM - Dump Memory to File true 1 true Label - 175 + 283 false -10b748b0:17773fb054b:-7a20 - 48 + 12 6 @@ -126,7 +126,7 @@ var SymbolName = VTypeHelper.getString(display.getWidget('SymbolName').getProper var Offset = VTypeHelper.getString(display.getWidget('Offset').getPropertyValue('pv_value')); var FileName = VTypeHelper.getString(display.getWidget('FileName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/mm/DumpMemToFile', { +Yamcs.issueCommand('/cfs/$(CPUID)/mm/DumpMemToFile', { 'MemType': MemType, 'NumOfBytes': NumofBytes, 'Padding_0_': 0, @@ -181,7 +181,7 @@ $(pv_value) 92 -10b748b0:17773fb054b:-79c7 90 - 168 + 180 @@ -204,7 +204,7 @@ $(pv_value) - 27 + 32 NOMEMTYPE EEPROM @@ -271,7 +271,7 @@ $(pv_value) false 54e87698:1777e01a75d:-6f83 12 - 57 + 69 @@ -285,7 +285,7 @@ $(pv_value) - 1 + 4 1 true @@ -328,7 +328,7 @@ $(pv_value) 136 54e87698:1777e01a75d:-6f5d 114 - 57 + 69 @@ -368,7 +368,7 @@ $(pv_value) false 54e87698:1777e01a75d:-6f53 12 - 83 + 95 @@ -382,7 +382,7 @@ $(pv_value) - 1 + 4 1 true @@ -425,7 +425,7 @@ $(pv_value) 136 54e87698:1777e01a75d:-6f49 114 - 83 + 95 @@ -465,7 +465,7 @@ $(pv_value) false 54e87698:1777e01a75d:-6f41 12 - 107 + 119 @@ -479,7 +479,7 @@ $(pv_value) - 1 + 4 1 true @@ -522,7 +522,7 @@ $(pv_value) 136 54e87698:1777e01a75d:-6f37 114 - 107 + 119 @@ -562,7 +562,7 @@ $(pv_value) false 54e87698:1777e01a75d:-6ef6 12 - 132 + 144 @@ -576,7 +576,7 @@ $(pv_value) - 1 + 4 1 true @@ -616,9 +616,9 @@ $(pv_value) false true Text Input - 136 + 200 54e87698:1777e01a75d:-6ef5 114 - 132 + 144 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/MM/EnableEEPROMWrite.opi b/core/base/tools/commander/workspace_template/Displays/Apps/MM/EnableEEPROMWrite.opi index 51522d881..73d086210 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/MM/EnableEEPROMWrite.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/MM/EnableEEPROMWrite.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - MM - Enable EEPROM + ($(CPUID)) MM - Enable EEPROM true @@ -28,7 +28,7 @@ true true Display - 190 + 310 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,17 +60,17 @@ false - Enable EEPROM Write + ($(CPUID)) MM - Enable EEPROM Write true 1 true Label - 175 + 283 false -10b748b0:17773fb054b:-7a20 - 12 - 12 + 6 + 6 @@ -109,7 +109,7 @@ 61 false -10b748b0:17773fb054b:-7a0f - 0 + 36 36 @@ -122,7 +122,7 @@ importPackage(Packages.org.yamcs.studio.data); var Bank = VTypeHelper.getString(display.getWidget('Bank').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/mm/EnableEEPROMWrite', { +Yamcs.issueCommand('/cfs/$(CPUID)/mm/EnableEEPROMWrite', { 'Bank': Bank});]]> true @@ -169,7 +169,7 @@ $(pv_value) Action Button 92 -10b748b0:17773fb054b:-79c7 - 48 + 102 66 @@ -184,7 +184,7 @@ $(pv_value) - 1 + 4 1 true @@ -226,7 +226,7 @@ $(pv_value) Text Input 100 -10b748b0:17773fb054b:-78ff - 72 + 108 36 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/MM/FillMem.opi b/core/base/tools/commander/workspace_template/Displays/Apps/MM/FillMem.opi index 048ab38b3..cbde8f78a 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/MM/FillMem.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/MM/FillMem.opi @@ -10,16 +10,16 @@ - 1.5.3 + 1.5.5.202103012118 6 - 200 + 220 true - MM - Fill Memory + ($(CPUID)) MM - Fill Memory true @@ -60,16 +60,16 @@ false - Fill Memory + ($(CPUID)) MM - Fill Memory true 1 true Label - 175 + 238 false -10b748b0:17773fb054b:-7a20 - 48 + 12 6 @@ -126,7 +126,7 @@ var FillPattern = VTypeHelper.getString(display.getWidget('FillPattern').getProp var SymbolName = VTypeHelper.getString(display.getWidget('SymbolName').getPropertyValue('pv_value')); var Offset = VTypeHelper.getString(display.getWidget('Offset').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/mm/FillMem', { +Yamcs.issueCommand('/cfs/$(CPUID)/mm/FillMem', { 'MemType': MemType, 'NumOfBytes': NumofBytes, 'FillPattern': NumofBytes, @@ -158,7 +158,7 @@ Yamcs.issueCommand('/cfs/mm/FillMem', { - 20 + 25 ../../Resources/send.png NoOp 0 @@ -181,7 +181,7 @@ $(pv_value) 92 -10b748b0:17773fb054b:-79c7 90 - 162 + 174 @@ -204,7 +204,7 @@ $(pv_value) - 27 + 32 NOMEMTYPE EEPROM @@ -271,7 +271,7 @@ $(pv_value) false 54e87698:1777e01a75d:-6f83 12 - 57 + 69 @@ -285,7 +285,7 @@ $(pv_value) - 1 + 4 1 true @@ -328,7 +328,7 @@ $(pv_value) 136 54e87698:1777e01a75d:-6f5d 114 - 57 + 69 @@ -368,7 +368,7 @@ $(pv_value) false 54e87698:1777e01a75d:-6f53 12 - 108 + 120 @@ -382,7 +382,7 @@ $(pv_value) - 1 + 4 1 true @@ -425,7 +425,7 @@ $(pv_value) 136 54e87698:1777e01a75d:-6f49 114 - 108 + 120 @@ -465,7 +465,7 @@ $(pv_value) false 54e87698:1777e01a75d:-6f41 12 - 132 + 144 @@ -479,7 +479,7 @@ $(pv_value) - 1 + 4 1 true @@ -522,7 +522,7 @@ $(pv_value) 136 54e87698:1777e01a75d:-6f37 114 - 132 + 144 @@ -562,7 +562,7 @@ $(pv_value) false 54e87698:1777e01a75d:-6ec0 12 - 84 + 96 @@ -576,7 +576,7 @@ $(pv_value) - 1 + 4 1 true @@ -619,6 +619,6 @@ $(pv_value) 136 54e87698:1777e01a75d:-6ebf 114 - 84 + 96 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/MM/LoadMemFromFile.opi b/core/base/tools/commander/workspace_template/Displays/Apps/MM/LoadMemFromFile.opi index 3ebd0e51e..799d25db9 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/MM/LoadMemFromFile.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/MM/LoadMemFromFile.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - MM - Dump Memory to File + ($(CPUID)) MM - Dump Memory to File true @@ -28,7 +28,7 @@ true true Display - 260 + 370 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,16 +60,16 @@ false - Load Memory from File + ($(CPUID)) MM - Load Memory from File true 1 true Label - 175 + 301 false -10b748b0:17773fb054b:-7a20 - 48 + 24 6 @@ -82,7 +82,7 @@ importPackage(Packages.org.yamcs.studio.data); var FileName = VTypeHelper.getString(display.getWidget('FileName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/mm/LoadMemFromFile', { +Yamcs.issueCommand('/cfs/$(CPUID)/mm/LoadMemFromFile', { 'FileName': FileName});]]> true @@ -129,7 +129,7 @@ $(pv_value) Action Button 92 -10b748b0:17773fb054b:-79c7 - 90 + 120 66 @@ -166,7 +166,7 @@ $(pv_value) 1 true Label - 97 + 73 false 54e87698:1777e01a75d:-6ef6 12 @@ -184,7 +184,7 @@ $(pv_value) - 1 + 4 1 true @@ -224,9 +224,9 @@ $(pv_value) false true Text Input - 136 + 265 54e87698:1777e01a75d:-6ef5 - 114 + 90 36 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/MM/LookupSymbol.opi b/core/base/tools/commander/workspace_template/Displays/Apps/MM/LookupSymbol.opi index b2ece6fd9..a85314234 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/MM/LookupSymbol.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/MM/LookupSymbol.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - MM - Lookup Symbol + ($(CPUID)) MM - Lookup Symbol true @@ -60,16 +60,16 @@ false - Lookup Symbol + ($(CPUID)) Lookup Symbol true 1 true Label - 175 + 217 false -10b748b0:17773fb054b:-7a20 - 48 + 18 6 @@ -82,7 +82,7 @@ importPackage(Packages.org.yamcs.studio.data); var SymbolName = VTypeHelper.getString(display.getWidget('SymbolName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/mm/LookupSymbol', { +Yamcs.issueCommand('/cfs/$(CPUID)/mm/LookupSymbol', { 'SymName': SymbolName});]]> true @@ -184,7 +184,7 @@ $(pv_value) - 1 + 4 1 true diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/MM/Main.opi b/core/base/tools/commander/workspace_template/Displays/Apps/MM/Main.opi index 845f91955..8d0a7b90e 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/MM/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/MM/Main.opi @@ -10,7 +10,7 @@ - 1.5.5.202103162101 + 1.6.2.202104092231 @@ -23,7 +23,7 @@ Displays /modules/mm - MM + ($(CPUID)) MM true @@ -48,7 +48,7 @@ - 1 + 4 1 true @@ -64,7 +64,7 @@ Text Update 0 false - /cfs/mm/MM_HkPacket_t.CmdCounter + /cfs/$(CPUID)/mm/MM_HkPacket_t.CmdCounter 0.0 @@ -180,7 +180,7 @@ $(pv_value) - 1 + 4 1 true @@ -196,7 +196,7 @@ $(pv_value) Text Update_1 0 false - /cfs/mm/MM_HkPacket_t.ErrCounter + /cfs/$(CPUID)/mm/MM_HkPacket_t.ErrCounter 0.0 @@ -227,7 +227,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/mm/Noop', {});]]> true @@ -283,7 +283,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/mm/Reset', {});]]> true @@ -360,16 +360,16 @@ $(pv_value) false - Memory Manager + ($(CPUID)) Memory Manager true 1 true Label - 166 + 247 false -33cb7c72:150aa4c347f:-75c9 - 102 + 66 6 @@ -384,7 +384,7 @@ $(pv_value) - 1 + 4 1 true @@ -400,7 +400,7 @@ $(pv_value) Text Update_51 0 false - /cfs/mm/MM_HkPacket_t.LastAction + /cfs/$(CPUID)/mm/MM_HkPacket_t.LastAction 0.0 @@ -436,7 +436,7 @@ $(pv_value) - 1 + 4 1 true @@ -452,7 +452,7 @@ $(pv_value) Text Update_52 0 false - /cfs/mm/MM_HkPacket_t.MemType + /cfs/$(CPUID)/mm/MM_HkPacket_t.MemType 0.0 @@ -488,7 +488,7 @@ $(pv_value) - 1 + 4 1 true @@ -504,7 +504,7 @@ $(pv_value) Text Update_53 0 false - /cfs/mm/MM_HkPacket_t.Address + /cfs/$(CPUID)/mm/MM_HkPacket_t.Address 0.0 @@ -540,7 +540,7 @@ $(pv_value) - 1 + 4 1 true @@ -556,7 +556,7 @@ $(pv_value) Text Update_54 0 false - /cfs/mm/MM_HkPacket_t.DataValue + /cfs/$(CPUID)/mm/MM_HkPacket_t.DataValue 0.0 @@ -592,7 +592,7 @@ $(pv_value) - 1 + 4 1 true @@ -608,7 +608,7 @@ $(pv_value) Text Update_55 0 false - /cfs/mm/MM_HkPacket_t.BytesProcessed + /cfs/$(CPUID)/mm/MM_HkPacket_t.BytesProcessed 0.0 @@ -644,7 +644,7 @@ $(pv_value) - 1 + 4 1 true @@ -660,7 +660,7 @@ $(pv_value) Text Update_56 0 false - /cfs/mm/MM_HkPacket_t.FileName + /cfs/$(CPUID)/mm/MM_HkPacket_t.FileName 0.0 @@ -1597,7 +1597,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/mm/SendHK',{});]]> true @@ -1646,4 +1646,65 @@ $(pv_value) 201 342 + + + + + + true + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 20 + + AppControl + 0 + + + + + true + true + false + + + + App Control + false + $(pv_name) +$(pv_value) + true + Action Button + 175 + 49c9ccd0:178c6a335db:-47f5 + 12 + 342 + \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/MM/Peek.opi b/core/base/tools/commander/workspace_template/Displays/Apps/MM/Peek.opi index e6bcd28cb..f6afe674e 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/MM/Peek.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/MM/Peek.opi @@ -10,16 +10,16 @@ - 1.5.3 + 1.5.5.202103012118 6 - 180 + 190 true - MM - Peek + ($(CPUID)) MM - Peek true @@ -60,7 +60,7 @@ false - Peek + ($(CPUID)) MM - Peek true 1 @@ -125,7 +125,7 @@ var NumofBytes = VTypeHelper.getString(display.getWidget('NumofBytes').getProper var SymbolName = VTypeHelper.getString(display.getWidget('SymbolName').getPropertyValue('pv_value')); var Offset = VTypeHelper.getString(display.getWidget('Offset').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/mm/Peek', { +Yamcs.issueCommand('/cfs/$(CPUID)/mm/Peek', { 'MemType': MemType, 'DataSize': NumofBytes, 'Padding_0_': 0, @@ -155,7 +155,7 @@ Yamcs.issueCommand('/cfs/mm/Peek', { - 20 + 28 ../../Resources/send.png NoOp 0 @@ -178,7 +178,7 @@ $(pv_value) 92 -10b748b0:17773fb054b:-79c7 90 - 138 + 147 @@ -191,7 +191,7 @@ $(pv_value) - 0 + 4 1 true @@ -201,7 +201,7 @@ $(pv_value) - 27 + 32 NOMEMTYPE EEPROM @@ -268,7 +268,7 @@ $(pv_value) false 54e87698:1777e01a75d:-6f83 12 - 57 + 66 @@ -282,7 +282,7 @@ $(pv_value) - 1 + 4 1 true @@ -325,7 +325,7 @@ $(pv_value) 136 54e87698:1777e01a75d:-6f5d 114 - 57 + 66 @@ -365,7 +365,7 @@ $(pv_value) false 54e87698:1777e01a75d:-6f53 12 - 83 + 92 @@ -379,7 +379,7 @@ $(pv_value) - 1 + 4 1 true @@ -422,7 +422,7 @@ $(pv_value) 136 54e87698:1777e01a75d:-6f49 114 - 83 + 92 @@ -462,7 +462,7 @@ $(pv_value) false 54e87698:1777e01a75d:-6f41 12 - 107 + 116 @@ -476,7 +476,7 @@ $(pv_value) - 1 + 4 1 true @@ -519,6 +519,6 @@ $(pv_value) 136 54e87698:1777e01a75d:-6f37 114 - 107 + 116 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/MM/Poke.opi b/core/base/tools/commander/workspace_template/Displays/Apps/MM/Poke.opi index 706a2823a..92600b2a6 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/MM/Poke.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/MM/Poke.opi @@ -10,16 +10,16 @@ - 1.5.3 + 1.5.5.202103012118 6 - 190 + 210 true - MM - Poke + ($(CPUID)) MM - Poke true @@ -60,7 +60,7 @@ false - Poke + ($(CPUID)) MM - Poke true 1 @@ -126,7 +126,7 @@ var SymbolName = VTypeHelper.getString(display.getWidget('SymbolName').getProper var Offset = VTypeHelper.getString(display.getWidget('Offset').getPropertyValue('pv_value')); var Data = VTypeHelper.getString(display.getWidget('Data').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/mm/Poke', { +Yamcs.issueCommand('/cfs/$(CPUID)/mm/Poke', { 'MemType': MemType, 'DataSize': NumofBytes, 'Padding_0_': 0, @@ -157,7 +157,7 @@ Yamcs.issueCommand('/cfs/mm/Poke', { - 20 + 28 ../../Resources/send.png NoOp 0 @@ -180,7 +180,7 @@ $(pv_value) 92 -10b748b0:17773fb054b:-79c7 90 - 162 + 171 @@ -203,7 +203,7 @@ $(pv_value) - 27 + 32 NOMEMTYPE EEPROM @@ -270,7 +270,7 @@ $(pv_value) false 54e87698:1777e01a75d:-6f83 12 - 57 + 66 @@ -284,7 +284,7 @@ $(pv_value) - 1 + 4 1 true @@ -327,7 +327,7 @@ $(pv_value) 136 54e87698:1777e01a75d:-6f5d 114 - 57 + 66 @@ -367,7 +367,7 @@ $(pv_value) false 54e87698:1777e01a75d:-6f53 12 - 83 + 92 @@ -381,7 +381,7 @@ $(pv_value) - 1 + 4 1 true @@ -424,7 +424,7 @@ $(pv_value) 136 54e87698:1777e01a75d:-6f49 114 - 83 + 92 @@ -464,7 +464,7 @@ $(pv_value) false 54e87698:1777e01a75d:-6f41 12 - 107 + 116 @@ -478,7 +478,7 @@ $(pv_value) - 1 + 4 1 true @@ -521,7 +521,7 @@ $(pv_value) 136 54e87698:1777e01a75d:-6f37 114 - 107 + 116 @@ -561,7 +561,7 @@ $(pv_value) false 54e87698:1777e01a75d:-6e32 12 - 132 + 141 @@ -575,7 +575,7 @@ $(pv_value) - 1 + 4 1 true @@ -618,6 +618,6 @@ $(pv_value) 136 54e87698:1777e01a75d:-6e31 114 - 132 + 141 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/MM/SymbolTableToFile.opi b/core/base/tools/commander/workspace_template/Displays/Apps/MM/SymbolTableToFile.opi index 6a7eca457..3e835d1bd 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/MM/SymbolTableToFile.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/MM/SymbolTableToFile.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -28,7 +28,7 @@ true true Display - 260 + 360 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,16 +60,16 @@ false - Symbol Table to File + ($(CPUID)) MM - Symbol Table to File true 1 true Label - 175 + 283 false -10b748b0:17773fb054b:-7a20 - 48 + 12 6 @@ -82,7 +82,7 @@ importPackage(Packages.org.yamcs.studio.data); var FileName = VTypeHelper.getString(display.getWidget('FileName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/mm/SymTblToFile', { +Yamcs.issueCommand('/cfs/$(CPUID)/mm/SymTblToFile', { 'FileName': FileName});]]> true @@ -129,7 +129,7 @@ $(pv_value) Action Button 92 -10b748b0:17773fb054b:-79c7 - 90 + 96 66 @@ -166,10 +166,10 @@ $(pv_value) 1 true Label - 97 + 73 false 54e87698:1777e01a75d:-6ef6 - 12 + 6 36 @@ -184,7 +184,7 @@ $(pv_value) - 1 + 4 1 true @@ -224,9 +224,9 @@ $(pv_value) false true Text Input - 136 + 265 54e87698:1777e01a75d:-6ef5 - 114 + 84 36 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/Main.opi b/core/base/tools/commander/workspace_template/Displays/Apps/Main.opi index 1df9285f0..0214820f4 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/Main.opi @@ -60,7 +60,7 @@ Text Update 0 false - /cfs/cs/CS_HkPacket_t.CmdCounter + /cfs/$(CPUID)/cs/CS_HkPacket_t.CmdCounter 0.0 @@ -152,7 +152,7 @@ $(pv_value) Text Update_1 0 false - /cfs/cs/CS_HkPacket_t.CmdErrCounter + /cfs/$(CPUID)/cs/CS_HkPacket_t.CmdErrCounter 0.0 @@ -183,7 +183,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cs/Noop()');]]> true @@ -239,7 +239,7 @@ $(pv_value) true @@ -452,7 +452,7 @@ $(pv_value) Text Update_2 0 false - /cfs/cf/CF_HkPacket_t.CmdCounter + /cfs/$(CPUID)/cf/CF_HkPacket_t.CmdCounter 0.0 @@ -504,7 +504,7 @@ $(pv_value) Text Update_3 0 false - /cfs/cf/CF_HkPacket_t.ErrCounter + /cfs/$(CPUID)/cf/CF_HkPacket_t.ErrCounter 0.0 @@ -534,7 +534,7 @@ $(pv_value) CF/scripts/NoOp.js +Yamcs.issueCommand('/cfs/$(CPUID)/cf/Noop', {});]]> true @@ -761,7 +761,7 @@ $(pv_value) Text Update_4 0 false - /cfs/ds/DS_HkPacket_t.CmdAcceptedCounter + /cfs/$(CPUID)/ds/DS_HkPacket_t.CmdAcceptedCounter 0.0 @@ -813,7 +813,7 @@ $(pv_value) Text Update_5 0 false - /cfs/ds/DS_HkPacket_t.CmdRejectedCounter + /cfs/$(CPUID)/ds/DS_HkPacket_t.CmdRejectedCounter 0.0 @@ -844,7 +844,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/ds/Noop', {});]]> true @@ -900,7 +900,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/ds/Reset', {});]]> true @@ -1072,7 +1072,7 @@ $(pv_value) Text Update_8 0 false - /cfs/fm/FM_HousekeepingPkt_t.CommandCounter + /cfs/$(CPUID)/fm/FM_HousekeepingPkt_t.CommandCounter 0.0 @@ -1124,7 +1124,7 @@ $(pv_value) Text Update_9 0 false - /cfs/hk/HK_HkPacket_t.ErrCounter + /cfs/$(CPUID)/hk/HK_HkPacket_t.ErrCounter 0.0 @@ -1155,7 +1155,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/fm/Noop', {});]]> true @@ -1211,7 +1211,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/fm/Reset', {});]]> true @@ -1383,7 +1383,7 @@ $(pv_value) Text Update_10 0 false - /cfs/hk/HK_HkPacket_t.CmdCounter + /cfs/$(CPUID)/hk/HK_HkPacket_t.CmdCounter 0.0 @@ -1435,7 +1435,7 @@ $(pv_value) Text Update_11 0 false - /cfs/hk/HK_HkPacket_t.ErrCounter + /cfs/$(CPUID)/hk/HK_HkPacket_t.ErrCounter 0.0 @@ -1466,7 +1466,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/hk/Noop', {});]]> true @@ -1522,7 +1522,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/hk/Reset', {});]]> true @@ -1694,7 +1694,7 @@ $(pv_value) Text Update_12 0 false - /cfs/ci/CI_HkTlm_t.usCmdCnt + /cfs/$(CPUID)/ci/CI_HkTlm_t.usCmdCnt 0.0 @@ -1746,7 +1746,7 @@ $(pv_value) Text Update_13 0 false - /cfs/ci/CI_HkTlm_t.usCmdErrCnt + /cfs/$(CPUID)/ci/CI_HkTlm_t.usCmdErrCnt 0.0 @@ -1777,7 +1777,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/ci/Noop(arg: none)');]]> true @@ -1833,7 +1833,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/ci/Reset', {});]]> true @@ -2005,7 +2005,7 @@ $(pv_value) Text Update_14 0 false - /cfs/hs/HS_HkPacket_t.CmdCount + /cfs/$(CPUID)/hs/HS_HkPacket_t.CmdCount 0.0 @@ -2057,7 +2057,7 @@ $(pv_value) Text Update_15 0 false - /cfs/hs/HS_HkPacket_t.CmdErrCount + /cfs/$(CPUID)/hs/HS_HkPacket_t.CmdErrCount 0.0 @@ -2088,7 +2088,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/hs/Noop', {});]]> true @@ -2144,7 +2144,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/hs/Reset', {});]]> true @@ -2316,7 +2316,7 @@ $(pv_value) Text Update_16 0 false - /cfs/lc/LC_HkPacket_t.CmdCount + /cfs/$(CPUID)/lc/LC_HkPacket_t.CmdCount 0.0 @@ -2368,7 +2368,7 @@ $(pv_value) Text Update_17 0 false - /cfs/lc/LC_HkPacket_t.CmdErrCount + /cfs/$(CPUID)/lc/LC_HkPacket_t.CmdErrCount 0.0 @@ -2399,7 +2399,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/lc/Noop', {});]]> true @@ -2455,7 +2455,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/lc/Reset', {});]]> true @@ -2627,7 +2627,7 @@ $(pv_value) Text Update_18 0 false - /cfs/md/MD_HkTlm_t.ValidCmdCntr + /cfs/$(CPUID)/md/MD_HkTlm_t.ValidCmdCntr 0.0 @@ -2679,7 +2679,7 @@ $(pv_value) Text Update_19 0 false - /cfs/md/MD_HkTlm_t.InvalidCmdCntr + /cfs/$(CPUID)/md/MD_HkTlm_t.InvalidCmdCntr 0.0 @@ -2710,7 +2710,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/md/Noop', {});]]> true @@ -2766,7 +2766,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/md/Reset', {});]]> true @@ -2938,7 +2938,7 @@ $(pv_value) Text Update_20 0 false - /cfs/mm/MM_HkPacket_t.CmdCounter + /cfs/$(CPUID)/mm/MM_HkPacket_t.CmdCounter 0.0 @@ -2990,7 +2990,7 @@ $(pv_value) Text Update_21 0 false - /cfs/mm/MM_HkPacket_t.ErrCounter + /cfs/$(CPUID)/mm/MM_HkPacket_t.ErrCounter 0.0 @@ -3021,7 +3021,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/mm/Noop', {});]]> true @@ -3077,7 +3077,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/mm/Reset', {});]]> true @@ -3249,7 +3249,7 @@ $(pv_value) Text Update_22 0 false - /cfs/sc/SC_HkTlm_t.CmdCtr + /cfs/$(CPUID)/sc/SC_HkTlm_t.CmdCtr 0.0 @@ -3301,7 +3301,7 @@ $(pv_value) Text Update_23 0 false - /cfs/sc/SC_HkTlm_t.CmdErrCtr + /cfs/$(CPUID)/sc/SC_HkTlm_t.CmdErrCtr 0.0 @@ -3332,7 +3332,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/sc/Noop',{});]]> true @@ -3388,7 +3388,7 @@ $(pv_value) true @@ -3561,7 +3561,7 @@ $(pv_value) Text Update_24 0 false - /cfs/sch/SCH_HkPacket_t.CmdCounter + /cfs/$(CPUID)/sch/SCH_HkPacket_t.CmdCounter 0.0 @@ -3613,7 +3613,7 @@ $(pv_value) Text Update_25 0 false - /cfs/sch/SCH_HkPacket_t.ErrCounter + /cfs/$(CPUID)/sch/SCH_HkPacket_t.ErrCounter 0.0 @@ -3644,7 +3644,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/sch/Noop', {});]]> true @@ -3700,7 +3700,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/sch/Reset', {});]]> true @@ -3872,7 +3872,7 @@ $(pv_value) Text Update_26 0 false - /cfs/to/TO_HkTlm_t.usCmdCnt + /cfs/$(CPUID)/to/TO_HkTlm_t.usCmdCnt 0.0 @@ -3924,7 +3924,7 @@ $(pv_value) Text Update_27 0 false - /cfs/to/TO_HkTlm_t.usCmdErrCnt + /cfs/$(CPUID)/to/TO_HkTlm_t.usCmdErrCnt 0.0 @@ -3955,7 +3955,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/to/Noop', {});]]> true @@ -4011,7 +4011,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/to/Reset', {});]]> true diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/PE/Baro.opi b/core/base/tools/commander/workspace_template/Displays/Apps/PE/Baro.opi index dccc8c792..8befb067c 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/PE/Baro.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/PE/Baro.opi @@ -100,7 +100,7 @@ Text Update_2 0 false - /cfs/pe/PE_HkTlm_t.TimestampLastBaro.Seconds + /cfs/$(CPUID)/pe/PE_HkTlm_t.TimestampLastBaro.Seconds 0.0 @@ -192,7 +192,7 @@ $(pv_value) Text Update_7 0 false - /cfs/pe/PE_HkTlm_t.TimeLastBaro.Seconds + /cfs/$(CPUID)/pe/PE_HkTlm_t.TimeLastBaro.Seconds 0.0 @@ -284,7 +284,7 @@ $(pv_value) Text Update_11 3 false - /cfs/pe/PE_HkTlm_t.BaroAltOrigin + /cfs/$(CPUID)/pe/PE_HkTlm_t.BaroAltOrigin 0.0 @@ -386,7 +386,7 @@ $(pv_value) ON - /cfs/pe/PE_HkTlm_t.BaroInitialized + /cfs/$(CPUID)/pe/PE_HkTlm_t.BaroInitialized @@ -484,7 +484,7 @@ $(pv_value) ON - /cfs/pe/PE_HkTlm_t.BaroFault + /cfs/$(CPUID)/pe/PE_HkTlm_t.BaroFault @@ -582,7 +582,7 @@ $(pv_value) ON - /cfs/pe/PE_HkTlm_t.BaroTimeout + /cfs/$(CPUID)/pe/PE_HkTlm_t.BaroTimeout @@ -680,7 +680,7 @@ $(pv_value) ON - /cfs/pe/PE_HkTlm_t.BaroFuse + /cfs/$(CPUID)/pe/PE_HkTlm_t.BaroFuse @@ -707,7 +707,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/pe/EnableBaro', {});]]> true @@ -763,7 +763,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/pe/DisableBaro', {});]]> true @@ -880,7 +880,7 @@ $(pv_value) Text Update_26 0 false - /cfs/pe/PE_HkTlm_t.SensorCombinedMsgCount + /cfs/$(CPUID)/pe/PE_HkTlm_t.SensorCombinedMsgCount 0.0 @@ -932,7 +932,7 @@ $(pv_value) Text Update_35 0 false - /cfs/pe/PE_HkTlm_t.TimeLastBaro.Subseconds + /cfs/$(CPUID)/pe/PE_HkTlm_t.TimeLastBaro.Subseconds 0.0 @@ -984,7 +984,7 @@ $(pv_value) Text Update_38 0 false - /cfs/pe/PE_HkTlm_t.TimestampLastBaro.Subseconds + /cfs/$(CPUID)/pe/PE_HkTlm_t.TimestampLastBaro.Subseconds 0.0 diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/PE/Distance.opi b/core/base/tools/commander/workspace_template/Displays/Apps/PE/Distance.opi index d677221a1..2269741be 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/PE/Distance.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/PE/Distance.opi @@ -100,7 +100,7 @@ Text Update_5 0 false - /cfs/pe/PE_HkTlm_t.TimeLastDist.Seconds + /cfs/$(CPUID)/pe/PE_HkTlm_t.TimeLastDist.Seconds 0.0 @@ -192,7 +192,7 @@ $(pv_value) Text Update_13 3 false - /cfs/pe/PE_HkTlm_t.DistAltOrigin + /cfs/$(CPUID)/pe/PE_HkTlm_t.DistAltOrigin 0.0 @@ -294,7 +294,7 @@ $(pv_value) ON - /cfs/pe/PE_HkTlm_t.DistInitialized + /cfs/$(CPUID)/pe/PE_HkTlm_t.DistInitialized @@ -432,7 +432,7 @@ $(pv_value) ON - /cfs/pe/PE_HkTlm_t.DistFuse + /cfs/$(CPUID)/pe/PE_HkTlm_t.DistFuse @@ -499,7 +499,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/pe/EnableDist', {});]]> true @@ -555,7 +555,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/pe/DisableDist', {});]]> true @@ -672,7 +672,7 @@ $(pv_value) Text Update_27 0 false - /cfs/pe/PE_HkTlm_t.DistanceSensorMsgCount + /cfs/$(CPUID)/pe/PE_HkTlm_t.DistanceSensorMsgCount 0.0 @@ -724,7 +724,7 @@ $(pv_value) Text Update_34 0 false - /cfs/pe/PE_HkTlm_t.TimeLastDist.Subseconds + /cfs/$(CPUID)/pe/PE_HkTlm_t.TimeLastDist.Subseconds 0.0 diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/PE/Flow.opi b/core/base/tools/commander/workspace_template/Displays/Apps/PE/Flow.opi index 35addd764..ebe5d81c4 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/PE/Flow.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/PE/Flow.opi @@ -100,7 +100,7 @@ Text Update_6 0 false - /cfs/pe/PE_HkTlm_t.TimeLastFlow.Seconds + /cfs/$(CPUID)/pe/PE_HkTlm_t.TimeLastFlow.Seconds 0.0 @@ -232,7 +232,7 @@ $(pv_value) Text Update_25 0 false - /cfs/pe/PE_HkTlm_t.OpticalFlowMsgCount + /cfs/$(CPUID)/pe/PE_HkTlm_t.OpticalFlowMsgCount 0.0 @@ -263,7 +263,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/pe/EnableFlow', {});]]> true @@ -319,7 +319,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/pe/DisableFlow', {});]]> true @@ -396,7 +396,7 @@ $(pv_value) Text Update_36 0 false - /cfs/pe/PE_HkTlm_t.TimeLastFlow.Subseconds + /cfs/$(CPUID)/pe/PE_HkTlm_t.TimeLastFlow.Subseconds 0.0 diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/PE/GPS.opi b/core/base/tools/commander/workspace_template/Displays/Apps/PE/GPS.opi index c215a97f6..54f824b77 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/PE/GPS.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/PE/GPS.opi @@ -100,7 +100,7 @@ Text Update_3 0 false - /cfs/pe/PE_HkTlm_t.TimeLastGps.Seconds + /cfs/$(CPUID)/pe/PE_HkTlm_t.TimeLastGps.Seconds 0.0 @@ -192,7 +192,7 @@ $(pv_value) Text Update_12 3 false - /cfs/pe/PE_HkTlm_t.GpsAltOrigin + /cfs/$(CPUID)/pe/PE_HkTlm_t.GpsAltOrigin 0.0 @@ -294,7 +294,7 @@ $(pv_value) ON - /cfs/pe/PE_HkTlm_t.GpsInitialized + /cfs/$(CPUID)/pe/PE_HkTlm_t.GpsInitialized @@ -392,7 +392,7 @@ $(pv_value) ON - /cfs/pe/PE_HkTlm_t.GpsFault + /cfs/$(CPUID)/pe/PE_HkTlm_t.GpsFault @@ -490,7 +490,7 @@ $(pv_value) ON - /cfs/pe/PE_HkTlm_t.GpsTimeout + /cfs/$(CPUID)/pe/PE_HkTlm_t.GpsTimeout @@ -588,7 +588,7 @@ $(pv_value) ON - /cfs/pe/PE_HkTlm_t.GpsFuse + /cfs/$(CPUID)/pe/PE_HkTlm_t.GpsFuse @@ -686,7 +686,7 @@ $(pv_value) ON - /cfs/pe/PE_HkTlm_t.ReceivedGPS + /cfs/$(CPUID)/pe/PE_HkTlm_t.ReceivedGPS @@ -753,7 +753,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/pe/EnableGPS', {});]]> true @@ -809,7 +809,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/pe/DisableGPS', {});]]> true @@ -926,7 +926,7 @@ $(pv_value) Text Update_29 0 false - /cfs/pe/PE_HkTlm_t.VehicleGpsPositionMsgCount + /cfs/$(CPUID)/pe/PE_HkTlm_t.VehicleGpsPositionMsgCount 0.0 @@ -978,7 +978,7 @@ $(pv_value) Text Update_31 0 false - /cfs/pe/PE_HkTlm_t.TimeLastGps.Subseconds + /cfs/$(CPUID)/pe/PE_HkTlm_t.TimeLastGps.Subseconds 0.0 diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/PE/Landing.opi b/core/base/tools/commander/workspace_template/Displays/Apps/PE/Landing.opi index a8c360b76..a46ec1df9 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/PE/Landing.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/PE/Landing.opi @@ -100,7 +100,7 @@ Text Update_4 0 false - /cfs/pe/PE_HkTlm_t.TimeLastLand.Seconds + /cfs/$(CPUID)/pe/PE_HkTlm_t.TimeLastLand.Seconds 0.0 @@ -192,7 +192,7 @@ $(pv_value) Text Update_14 0 false - /cfs/pe/PE_HkTlm_t.LandCount + /cfs/$(CPUID)/pe/PE_HkTlm_t.LandCount 0.0 @@ -294,7 +294,7 @@ $(pv_value) ON - /cfs/pe/PE_HkTlm_t.LandInitialized + /cfs/$(CPUID)/pe/PE_HkTlm_t.LandInitialized @@ -432,7 +432,7 @@ $(pv_value) ON - /cfs/pe/PE_HkTlm_t.LandFuse + /cfs/$(CPUID)/pe/PE_HkTlm_t.LandFuse @@ -499,7 +499,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/pe/EnableLanding', {});]]> true @@ -555,7 +555,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/pe/DisableLanding', {});]]> true @@ -672,7 +672,7 @@ $(pv_value) Text Update_28 0 false - /cfs/pe/PE_HkTlm_t.VehicleLandDetectedMsgCount + /cfs/$(CPUID)/pe/PE_HkTlm_t.VehicleLandDetectedMsgCount 0.0 @@ -724,7 +724,7 @@ $(pv_value) Text Update_33 0 false - /cfs/pe/PE_HkTlm_t.TimeLastLand.Subseconds + /cfs/$(CPUID)/pe/PE_HkTlm_t.TimeLastLand.Subseconds 0.0 diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/PE/Main.opi b/core/base/tools/commander/workspace_template/Displays/Apps/PE/Main.opi index fce840b6f..bc0e0e83c 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/PE/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/PE/Main.opi @@ -10,7 +10,7 @@ - 1.5.5.202103162101 + 1.6.2.202104092231 @@ -64,7 +64,7 @@ Text Update 0 false - /cfs/pe/PE_HkTlm_t.CmdCnt + /cfs/$(CPUID)/pe/PE_HkTlm_t.CmdCnt 0.0 @@ -196,7 +196,7 @@ $(pv_value) Text Update_1 0 false - /cfs/pe/PE_HkTlm_t.CmdErrCnt + /cfs/$(CPUID)/pe/PE_HkTlm_t.CmdErrCnt 0.0 @@ -267,7 +267,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/pe/Noop', {});]]> true @@ -323,7 +323,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/pe/Reset', {});]]> true @@ -440,7 +440,7 @@ $(pv_value) Text Update_8 3 false - /cfs/pe/PE_HkTlm_t.AltOrigin + /cfs/$(CPUID)/pe/PE_HkTlm_t.AltOrigin 0.0 @@ -532,7 +532,7 @@ $(pv_value) Text Update_9 0 false - /cfs/pe/PE_HkTlm_t.Timestamp.Seconds + /cfs/$(CPUID)/pe/PE_HkTlm_t.Timestamp.Seconds 0.0 @@ -624,7 +624,7 @@ $(pv_value) Text Update_10 0 false - /cfs/pe/PE_HkTlm_t.Timestamp_Hist.Seconds + /cfs/$(CPUID)/pe/PE_HkTlm_t.Timestamp_Hist.Seconds 0.0 @@ -716,7 +716,7 @@ $(pv_value) Text Update_22 0 false - /cfs/pe/PE_HkTlm_t.WakeupCount + /cfs/$(CPUID)/pe/PE_HkTlm_t.WakeupCount 0.0 @@ -768,7 +768,7 @@ $(pv_value) Text Update_30 0 false - /cfs/pe/PE_HkTlm_t.Timestamp.Subseconds + /cfs/$(CPUID)/pe/PE_HkTlm_t.Timestamp.Subseconds 0.0 @@ -820,7 +820,7 @@ $(pv_value) Text Update_37 0 false - /cfs/pe/PE_HkTlm_t.Timestamp_Hist.Subseconds + /cfs/$(CPUID)/pe/PE_HkTlm_t.Timestamp_Hist.Subseconds 0.0 @@ -897,7 +897,7 @@ $(pv_value) 164 -69f8bd78:177f094d5fe:-1f28 63 - 228 + 248 @@ -952,7 +952,7 @@ $(pv_value) 164 -69f8bd78:177f094d5fe:-1f20 63 - 247 + 267 @@ -1007,7 +1007,7 @@ $(pv_value) 164 -69f8bd78:177f094d5fe:-1f18 63 - 266 + 286 @@ -1062,7 +1062,7 @@ $(pv_value) 164 -69f8bd78:177f094d5fe:-1f10 63 - 285 + 305 @@ -1117,7 +1117,7 @@ $(pv_value) 164 -69f8bd78:177f094d5fe:-1f08 63 - 304 + 324 @@ -1172,7 +1172,7 @@ $(pv_value) 164 -69f8bd78:177f094d5fe:-1f00 63 - 323 + 343 @@ -1227,7 +1227,7 @@ $(pv_value) 164 -69f8bd78:177f094d5fe:-1ef8 63 - 342 + 362 @@ -1288,7 +1288,7 @@ $(pv_value) 164 -69f8bd78:177f094d5fe:-1ef0 63 - 361 + 381 @@ -1297,7 +1297,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/pe/SendHK', {});]]> true @@ -1344,7 +1344,7 @@ $(pv_value) 164 -69f8bd78:177f094d5fe:-1ebb 63 - 380 + 400 @@ -1353,7 +1353,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/pe/Wakeup', {});]]> true @@ -1400,6 +1400,67 @@ $(pv_value) 164 -69f8bd78:177f094d5fe:-1eb1 63 - 399 + 419 - + + + + + + true + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 20 + + AppControl + 0 + + + + + true + true + false + + + + App Control + false + $(pv_name) +$(pv_value) + true + Action Button + 164 + 49c9ccd0:178c6a335db:-47d0 + 63 + 229 + + \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/PE/MessagesReceived.opi b/core/base/tools/commander/workspace_template/Displays/Apps/PE/MessagesReceived.opi index c03950780..4c7a6a2c1 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/PE/MessagesReceived.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/PE/MessagesReceived.opi @@ -100,7 +100,7 @@ Text Update_15 0 false - /cfs/pe/PE_HkTlm_t.VehicleLandDetectedMsgCount + /cfs/$(CPUID)/pe/PE_HkTlm_t.VehicleLandDetectedMsgCount 0.0 @@ -192,7 +192,7 @@ $(pv_value) Text Update_16 0 false - /cfs/pe/PE_HkTlm_t.ActuatorArmedMsgCount + /cfs/$(CPUID)/pe/PE_HkTlm_t.ActuatorArmedMsgCount 0.0 @@ -284,7 +284,7 @@ $(pv_value) Text Update_17 0 false - /cfs/pe/PE_HkTlm_t.VehicleAttitudeMsgCount + /cfs/$(CPUID)/pe/PE_HkTlm_t.VehicleAttitudeMsgCount 0.0 @@ -376,7 +376,7 @@ $(pv_value) Text Update_18 0 false - /cfs/pe/PE_HkTlm_t.SensorCombinedMsgCount + /cfs/$(CPUID)/pe/PE_HkTlm_t.SensorCombinedMsgCount 0.0 @@ -468,7 +468,7 @@ $(pv_value) Text Update_19 0 false - /cfs/pe/PE_HkTlm_t.VehicleAttitudeSetpointMsgCount + /cfs/$(CPUID)/pe/PE_HkTlm_t.VehicleAttitudeSetpointMsgCount 0.0 @@ -560,7 +560,7 @@ $(pv_value) Text Update_20 0 false - /cfs/pe/PE_HkTlm_t.VehicleGpsPositionMsgCount + /cfs/$(CPUID)/pe/PE_HkTlm_t.VehicleGpsPositionMsgCount 0.0 @@ -652,7 +652,7 @@ $(pv_value) Text Update_21 0 false - /cfs/pe/PE_HkTlm_t.DistanceSensorMsgCount + /cfs/$(CPUID)/pe/PE_HkTlm_t.DistanceSensorMsgCount 0.0 @@ -744,7 +744,7 @@ $(pv_value) Text Update_23 0 false - /cfs/pe/PE_HkTlm_t.VehicleStatusMsgCount + /cfs/$(CPUID)/pe/PE_HkTlm_t.VehicleStatusMsgCount 0.0 @@ -836,7 +836,7 @@ $(pv_value) Text Update_24 0 false - /cfs/pe/PE_HkTlm_t.OpticalFlowMsgCount + /cfs/$(CPUID)/pe/PE_HkTlm_t.OpticalFlowMsgCount 0.0 diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/PE/State.opi b/core/base/tools/commander/workspace_template/Displays/Apps/PE/State.opi index 7fcef96da..0d9a7a12a 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/PE/State.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/PE/State.opi @@ -110,7 +110,7 @@ ON - /cfs/pe/PE_HkTlm_t.XyEstValid + /cfs/$(CPUID)/pe/PE_HkTlm_t.XyEstValid @@ -208,7 +208,7 @@ $(pv_value) ON - /cfs/pe/PE_HkTlm_t.ZEstValid + /cfs/$(CPUID)/pe/PE_HkTlm_t.ZEstValid @@ -306,7 +306,7 @@ $(pv_value) ON - /cfs/pe/PE_HkTlm_t.TzEstValid + /cfs/$(CPUID)/pe/PE_HkTlm_t.TzEstValid @@ -404,7 +404,7 @@ $(pv_value) ON - /cfs/pe/PE_HkTlm_t.EstimatorLocalInitialized + /cfs/$(CPUID)/pe/PE_HkTlm_t.EstimatorLocalInitialized @@ -542,7 +542,7 @@ $(pv_value) ON - /cfs/pe/PE_HkTlm_t.EstimatorGlobalInitialized + /cfs/$(CPUID)/pe/PE_HkTlm_t.EstimatorGlobalInitialized @@ -640,7 +640,7 @@ $(pv_value) ON - /cfs/pe/PE_HkTlm_t.AltOriginInitialized + /cfs/$(CPUID)/pe/PE_HkTlm_t.AltOriginInitialized @@ -738,7 +738,7 @@ $(pv_value) ON - /cfs/pe/PE_HkTlm_t.LastArmedState + /cfs/$(CPUID)/pe/PE_HkTlm_t.LastArmedState diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/PX4/PX4_SensorBaro.opi b/core/base/tools/commander/workspace_template/Displays/Apps/PX4/PX4_SensorBaro.opi index c690a15b8..8a640fafc 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/PX4/PX4_SensorBaro.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/PX4/PX4_SensorBaro.opi @@ -100,7 +100,7 @@ Text Update 2 false - /cfs/px4lib/PX4_SensorBaroMsg_t.Pressure + /cfs/$(CPUID)/px4lib/PX4_SensorBaroMsg_t.Pressure 0.0 @@ -192,7 +192,7 @@ $(pv_value) Text Update_1 1 false - /cfs/px4lib/PX4_SensorBaroMsg_t.Temperature + /cfs/$(CPUID)/px4lib/PX4_SensorBaroMsg_t.Temperature 0.0 @@ -284,7 +284,7 @@ $(pv_value) Text Update_2 3 false - /cfs/px4lib/PX4_SensorBaroMsg_t.Altitude + /cfs/$(CPUID)/px4lib/PX4_SensorBaroMsg_t.Altitude 0.0 @@ -376,7 +376,7 @@ $(pv_value) Text Update_3 3 false - /cfs/px4lib/PX4_SensorBaroMsg_t.ErrorCount + /cfs/$(CPUID)/px4lib/PX4_SensorBaroMsg_t.ErrorCount 0.0 diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SC/AppendAts.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SC/AppendAts.opi index 3001ba2bc..4ac15091b 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SC/AppendAts.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SC/AppendAts.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - SC - Append ATS + ($(CPUID)) SC - Append ATS true @@ -28,7 +28,7 @@ true true Display - 190 + 240 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,17 +60,17 @@ false - Append ATS + ($(CPUID)) SC - Append ATS true 1 true Label - 98 + 238 false -10b748b0:17773fb054b:-7a20 - 42 - 12 + 3 + 6 @@ -109,7 +109,7 @@ 61 false -10b748b0:17773fb054b:-7a0f - 0 + 24 36 @@ -122,7 +122,7 @@ importPackage(Packages.org.yamcs.studio.data); var AtsId = VTypeHelper.getString(display.getWidget('AtsId').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/sc/AppendAts', { +Yamcs.issueCommand('/cfs/$(CPUID)/sc/AppendAts', { 'AtsId': AtsId});]]> true @@ -169,7 +169,7 @@ $(pv_value) Action Button 92 -10b748b0:17773fb054b:-79c7 - 48 + 72 66 @@ -184,7 +184,7 @@ $(pv_value) - 1 + 4 1 true @@ -226,7 +226,7 @@ $(pv_value) Text Input 100 -10b748b0:17773fb054b:-78ff - 72 + 96 36 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SC/ContinueATSOnFailure.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SC/ContinueATSOnFailure.opi index f7a126e9d..dd8fa979e 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SC/ContinueATSOnFailure.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SC/ContinueATSOnFailure.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - SC - Continue ATS + ($(CPUID)) SC - Continue ATS true @@ -28,7 +28,7 @@ true true Display - 190 + 300 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,17 +60,17 @@ false - Continue ATS on Failure + ($(CPUID)) SC - Continue ATS on Failure true 1 true Label - 193 + 283 false -10b748b0:17773fb054b:-7a20 - -3 - 12 + 6 + 6 @@ -90,7 +90,7 @@ if( ContinueState == 'False' ) { pContinueState = 1; } -Yamcs.issueCommand('/cfs/sc/ContinueAtsOnFailure', { +Yamcs.issueCommand('/cfs/$(CPUID)/sc/ContinueAtsOnFailure', { 'ContinueState': pContinueState}); ]]> @@ -139,7 +139,7 @@ $(pv_value) Action Button 92 -10b748b0:17773fb054b:-79c7 - 48 + 102 66 @@ -189,7 +189,7 @@ $(pv_value) Radio Box 157 54e87698:1777e01a75d:-76b3 - 30 - 31 + 78 + 30 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SC/DisableRTS.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SC/DisableRTS.opi index 534132308..7e6645b42 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SC/DisableRTS.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SC/DisableRTS.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - SC - Disable RTS + ($(CPUID)) SC - Disable RTS true @@ -28,7 +28,7 @@ true true Display - 190 + 240 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,16 +60,16 @@ false - Disable RTS + ($(CPUID)) SC - Disable RTS true 1 true Label - 98 + 235 false -10b748b0:17773fb054b:-7a20 - 45 + 6 6 @@ -109,7 +109,7 @@ 55 false -10b748b0:17773fb054b:-7a0f - 6 + 30 36 @@ -122,7 +122,7 @@ importPackage(Packages.org.yamcs.studio.data); var RtsId = VTypeHelper.getString(display.getWidget('RtsId').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/sc/DisableRts', { +Yamcs.issueCommand('/cfs/$(CPUID)/sc/DisableRts', { 'RtsId': RtsId});]]> true @@ -169,7 +169,7 @@ $(pv_value) Action Button 92 -10b748b0:17773fb054b:-79c7 - 48 + 72 66 @@ -184,7 +184,7 @@ $(pv_value) - 1 + 4 1 true @@ -226,7 +226,7 @@ $(pv_value) Text Input 100 -10b748b0:17773fb054b:-78ff - 72 + 96 36 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SC/DisableRTSGroup.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SC/DisableRTSGroup.opi index 05a4aa2ca..a3200c8e7 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SC/DisableRTSGroup.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SC/DisableRTSGroup.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - SC - Disable RTS Group + ($(CPUID)) SC - Disable RTS Group true @@ -28,7 +28,7 @@ true true Display - 220 + 260 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,16 +60,16 @@ false - Disable RTS Group + ($(CPUID)) SC - Disable RTS Group true 1 true Label - 160 + 250 false -10b748b0:17773fb054b:-7a20 - 24 + 6 6 @@ -109,7 +109,7 @@ 91 false -10b748b0:17773fb054b:-7a0f - 6 + 18 36 @@ -123,7 +123,7 @@ importPackage(Packages.org.yamcs.studio.data); var FirstRtsId = VTypeHelper.getString(display.getWidget('FirstRtsId').getPropertyValue('pv_value')); var LastRtsId = VTypeHelper.getString(display.getWidget('LastRtsId').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/sc/DisableRtsGroup', { +Yamcs.issueCommand('/cfs/$(CPUID)/sc/DisableRtsGroup', { 'FirstRtsId': FirstRtsId, 'LastRtsId': LastRtsId}); ]]> @@ -172,7 +172,7 @@ $(pv_value) Action Button 92 -10b748b0:17773fb054b:-79c7 - 58 + 70 90 @@ -187,7 +187,7 @@ $(pv_value) - 1 + 4 1 true @@ -229,7 +229,7 @@ $(pv_value) Text Input 100 -10b748b0:17773fb054b:-78ff - 108 + 120 36 @@ -269,7 +269,7 @@ $(pv_value) 91 false 54e87698:1777e01a75d:-70ef - 6 + 18 55 @@ -284,7 +284,7 @@ $(pv_value) - 1 + 4 1 true @@ -326,7 +326,7 @@ $(pv_value) Text Input 100 54e87698:1777e01a75d:-70ee - 108 + 120 55 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SC/EnableRTS.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SC/EnableRTS.opi index 37dd7944f..4bec3d2ad 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SC/EnableRTS.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SC/EnableRTS.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - SC - Enable RTS + ($(CPUID)) SC - Enable RTS true @@ -28,7 +28,7 @@ true true Display - 190 + 230 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,16 +60,16 @@ false - Enable RTS + ($(CPUID)) SC - Enable RTS true 1 true Label - 98 + 212 false -10b748b0:17773fb054b:-7a20 - 45 + 6 6 @@ -109,7 +109,7 @@ 55 false -10b748b0:17773fb054b:-7a0f - 6 + 18 36 @@ -122,7 +122,7 @@ importPackage(Packages.org.yamcs.studio.data); var RtsId = VTypeHelper.getString(display.getWidget('RtsId').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/sc/EnableRts', { +Yamcs.issueCommand('/cfs/$(CPUID)/sc/EnableRts', { 'RtsId': RtsId});]]> true @@ -169,7 +169,7 @@ $(pv_value) Action Button 92 -10b748b0:17773fb054b:-79c7 - 48 + 60 66 @@ -184,7 +184,7 @@ $(pv_value) - 1 + 4 1 true @@ -226,7 +226,7 @@ $(pv_value) Text Input 100 -10b748b0:17773fb054b:-78ff - 72 + 84 36 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SC/EnableRTSGroup.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SC/EnableRTSGroup.opi index d66034fcf..cfa191b62 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SC/EnableRTSGroup.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SC/EnableRTSGroup.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - SC - Enable RTS Group + ($(CPUID)) SC - Enable RTS Group true @@ -28,7 +28,7 @@ true true Display - 220 + 270 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,16 +60,16 @@ false - Enable RTS Group + ($(CPUID)) SC - Enable RTS Group true 1 true Label - 160 + 259 false -10b748b0:17773fb054b:-7a20 - 24 + 6 6 @@ -123,7 +123,7 @@ importPackage(Packages.org.yamcs.studio.data); var FirstRtsId = VTypeHelper.getString(display.getWidget('FirstRtsId').getPropertyValue('pv_value')); var LastRtsId = VTypeHelper.getString(display.getWidget('LastRtsId').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/sc/EnableRtsGroup', { +Yamcs.issueCommand('/cfs/$(CPUID)/sc/EnableRtsGroup', { 'FirstRtsId': FirstRtsId, 'LastRtsId': LastRtsId}); ]]> @@ -172,7 +172,7 @@ $(pv_value) Action Button 92 -10b748b0:17773fb054b:-79c7 - 58 + 78 90 @@ -187,7 +187,7 @@ $(pv_value) - 1 + 4 1 true @@ -284,7 +284,7 @@ $(pv_value) - 1 + 4 1 true diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SC/JumpATS.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SC/JumpATS.opi index a1997b234..cf0620e9f 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SC/JumpATS.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SC/JumpATS.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - SC - Jump ATS + ($(CPUID)) SC - Jump ATS true @@ -28,7 +28,7 @@ true true Display - 190 + 220 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,17 +60,17 @@ false - Jump ATS + ($(CPUID)) SC - Jump ATS true 1 true Label - 98 + 199 false -10b748b0:17773fb054b:-7a20 - 42 - 12 + 12 + 6 @@ -109,7 +109,7 @@ 73 false -10b748b0:17773fb054b:-7a0f - 0 + 12 36 @@ -122,7 +122,7 @@ importPackage(Packages.org.yamcs.studio.data); var NewTime = VTypeHelper.getString(display.getWidget('NewTime').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/sc/JumpATS', { +Yamcs.issueCommand('/cfs/$(CPUID)/sc/JumpATS', { 'NewTime': NewTime});]]> true @@ -169,7 +169,7 @@ $(pv_value) Action Button 92 -10b748b0:17773fb054b:-79c7 - 48 + 60 66 @@ -184,7 +184,7 @@ $(pv_value) - 1 + 4 1 true @@ -226,7 +226,7 @@ $(pv_value) Text Input 100 -10b748b0:17773fb054b:-78ff - 84 + 96 36 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SC/Main.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SC/Main.opi index 7b23cfa32..475ba32bd 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SC/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SC/Main.opi @@ -10,7 +10,7 @@ - 1.5.5.202103162101 + 1.6.2.202104092231 @@ -23,7 +23,7 @@ Displays /modules/sc - SC + ($(CPUID)) SC true @@ -48,7 +48,7 @@ - 1 + 4 1 true @@ -64,7 +64,7 @@ Text Update 0 false - /cfs/sc/SC_HkTlm_t.CmdCtr + /cfs/$(CPUID)/sc/SC_HkTlm_t.CmdCtr 0.0 @@ -180,7 +180,7 @@ $(pv_value) - 1 + 4 1 true @@ -196,7 +196,7 @@ $(pv_value) Text Update_1 0 false - /cfs/sc/SC_HkTlm_t.CmdErrCtr + /cfs/$(CPUID)/sc/SC_HkTlm_t.CmdErrCtr 0.0 @@ -227,7 +227,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/sc/Noop',{});]]> true @@ -283,7 +283,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/sc/Reset', {});]]> true @@ -360,7 +360,7 @@ $(pv_value) false - Stored Command + ($(CPUID)) Stored Command true 1 @@ -384,7 +384,7 @@ $(pv_value) - 1 + 4 1 true @@ -400,7 +400,7 @@ $(pv_value) Text Update_2 0 false - /cfs/sc/SC_HkTlm_t.AtsNumber + /cfs/$(CPUID)/sc/SC_HkTlm_t.AtsNumber 0.0 @@ -436,7 +436,7 @@ $(pv_value) - 1 + 4 1 true @@ -452,7 +452,7 @@ $(pv_value) Text Update_3 0 false - /cfs/sc/SC_HkTlm_t.AtpState + /cfs/$(CPUID)/sc/SC_HkTlm_t.AtpState 0.0 @@ -502,7 +502,7 @@ $(pv_value) 20 Text Update_4 - /cfs/sc/SC_HkTlm_t.ContinueAtsOnFailureFlag + /cfs/$(CPUID)/sc/SC_HkTlm_t.ContinueAtsOnFailureFlag @@ -549,7 +549,7 @@ $(pv_value) 20 Text Update_5 - /cfs/sc/SC_HkTlm_t.SwitchPendFlag + /cfs/$(CPUID)/sc/SC_HkTlm_t.SwitchPendFlag @@ -582,7 +582,7 @@ $(pv_value) - 1 + 4 1 true @@ -598,7 +598,7 @@ $(pv_value) Text Update_6 0 false - /cfs/sc/SC_HkTlm_t.NumRtsActive + /cfs/$(CPUID)/sc/SC_HkTlm_t.NumRtsActive 0.0 @@ -634,7 +634,7 @@ $(pv_value) - 1 + 4 1 true @@ -650,7 +650,7 @@ $(pv_value) Text Update_7 0 false - /cfs/sc/SC_HkTlm_t.RtsNumber + /cfs/$(CPUID)/sc/SC_HkTlm_t.RtsNumber 0.0 @@ -686,7 +686,7 @@ $(pv_value) - 1 + 4 1 true @@ -702,7 +702,7 @@ $(pv_value) Text Update_8 0 false - /cfs/sc/SC_HkTlm_t.RtsActiveCtr + /cfs/$(CPUID)/sc/SC_HkTlm_t.RtsActiveCtr 0.0 @@ -738,7 +738,7 @@ $(pv_value) - 1 + 4 1 true @@ -754,7 +754,7 @@ $(pv_value) Text Update_9 0 false - /cfs/sc/SC_HkTlm_t.RtsActiveErrCtr + /cfs/$(CPUID)/sc/SC_HkTlm_t.RtsActiveErrCtr 0.0 @@ -790,7 +790,7 @@ $(pv_value) - 1 + 4 1 true @@ -806,7 +806,7 @@ $(pv_value) Text Update_10 0 false - /cfs/sc/SC_HkTlm_t.AtsCmdCtr + /cfs/$(CPUID)/sc/SC_HkTlm_t.AtsCmdCtr 0.0 @@ -842,7 +842,7 @@ $(pv_value) - 1 + 4 1 true @@ -858,7 +858,7 @@ $(pv_value) Text Update_11 0 false - /cfs/sc/SC_HkTlm_t.AtsCmdErrCtr + /cfs/$(CPUID)/sc/SC_HkTlm_t.AtsCmdErrCtr 0.0 @@ -894,7 +894,7 @@ $(pv_value) - 1 + 4 1 true @@ -910,7 +910,7 @@ $(pv_value) Text Update_12 0 false - /cfs/sc/SC_HkTlm_t.RtsCmdCtr + /cfs/$(CPUID)/sc/SC_HkTlm_t.RtsCmdCtr 0.0 @@ -946,7 +946,7 @@ $(pv_value) - 1 + 4 1 true @@ -962,7 +962,7 @@ $(pv_value) Text Update_13 0 false - /cfs/sc/SC_HkTlm_t.RtsCmdErrCtr + /cfs/$(CPUID)/sc/SC_HkTlm_t.RtsCmdErrCtr 0.0 @@ -998,7 +998,7 @@ $(pv_value) - 1 + 4 1 true @@ -1014,7 +1014,7 @@ $(pv_value) Text Update_14 0 false - /cfs/sc/SC_HkTlm_t.LastAtsErrSeq + /cfs/$(CPUID)/sc/SC_HkTlm_t.LastAtsErrSeq 0.0 @@ -1050,7 +1050,7 @@ $(pv_value) - 1 + 4 1 true @@ -1066,7 +1066,7 @@ $(pv_value) Text Update_15 0 false - /cfs/sc/SC_HkTlm_t.LastAtsErrCmd + /cfs/$(CPUID)/sc/SC_HkTlm_t.LastAtsErrCmd 0.0 @@ -1102,7 +1102,7 @@ $(pv_value) - 1 + 4 1 true @@ -1118,7 +1118,7 @@ $(pv_value) Text Update_16 0 false - /cfs/sc/SC_HkTlm_t.LastRtsErrSeq + /cfs/$(CPUID)/sc/SC_HkTlm_t.LastRtsErrSeq 0.0 @@ -1154,7 +1154,7 @@ $(pv_value) - 1 + 4 1 true @@ -1170,7 +1170,7 @@ $(pv_value) Text Update_17 0 false - /cfs/sc/SC_HkTlm_t.LastAtsErrCmd + /cfs/$(CPUID)/sc/SC_HkTlm_t.LastAtsErrCmd 0.0 @@ -1206,7 +1206,7 @@ $(pv_value) - 1 + 4 1 true @@ -1222,7 +1222,7 @@ $(pv_value) Text Update_18 0 false - /cfs/sc/SC_HkTlm_t.AppendCmdArg + /cfs/$(CPUID)/sc/SC_HkTlm_t.AppendCmdArg 0.0 @@ -1258,7 +1258,7 @@ $(pv_value) - 1 + 4 1 true @@ -1274,7 +1274,7 @@ $(pv_value) Text Update_19 0 false - /cfs/sc/SC_HkTlm_t.AppendEntryCount + /cfs/$(CPUID)/sc/SC_HkTlm_t.AppendEntryCount 0.0 @@ -1310,7 +1310,7 @@ $(pv_value) - 1 + 4 1 true @@ -1326,7 +1326,7 @@ $(pv_value) Text Update_20 0 false - /cfs/sc/SC_HkTlm_t.AppendByteCount + /cfs/$(CPUID)/sc/SC_HkTlm_t.AppendByteCount 0.0 @@ -1362,7 +1362,7 @@ $(pv_value) - 1 + 4 1 true @@ -1378,7 +1378,7 @@ $(pv_value) Text Update_21 0 false - /cfs/sc/SC_HkTlm_t.AppendLoadCount + /cfs/$(CPUID)/sc/SC_HkTlm_t.AppendLoadCount 0.0 @@ -1414,7 +1414,7 @@ $(pv_value) - 1 + 4 1 true @@ -1430,7 +1430,7 @@ $(pv_value) Text Update_22 0 false - /cfs/sc/SC_HkTlm_t.AtpCmdNumber + /cfs/$(CPUID)/sc/SC_HkTlm_t.AtpCmdNumber 0.0 @@ -1466,7 +1466,7 @@ $(pv_value) - 1 + 4 1 true @@ -1482,7 +1482,7 @@ $(pv_value) Text Update_23 0 false - /cfs/sc/SC_HkTlm_t.AtpFreeBytes_0_ + /cfs/$(CPUID)/sc/SC_HkTlm_t.AtpFreeBytes_0_ 0.0 @@ -1518,7 +1518,7 @@ $(pv_value) - 0 + 4 1 true @@ -1534,7 +1534,7 @@ $(pv_value) Text Update_24 0 false - /cfs/sc/SC_HkTlm_t.AtpFreeBytes_1_ + /cfs/$(CPUID)/sc/SC_HkTlm_t.AtpFreeBytes_1_ 0.0 @@ -1555,7 +1555,7 @@ $(pv_value) 100 false 7b256c5c:150b979c7e3:-7659 - 291 + 300 496 @@ -1570,7 +1570,7 @@ $(pv_value) - 1 + 4 1 true @@ -1586,7 +1586,7 @@ $(pv_value) Text Update_25 0 false - /cfs/sc/SC_HkTlm_t.NextRtsTime + /cfs/$(CPUID)/sc/SC_HkTlm_t.NextRtsTime 0.0 @@ -1622,7 +1622,7 @@ $(pv_value) - 1 + 4 1 true @@ -1638,7 +1638,7 @@ $(pv_value) Text Update_26 0 false - /cfs/sc/SC_HkTlm_t.NextAtsTime + /cfs/$(CPUID)/sc/SC_HkTlm_t.NextAtsTime 0.0 @@ -2684,7 +2684,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/sc/StopAts',{});]]> true @@ -2740,7 +2740,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/sc/SwitchAts',{});]]> true @@ -2796,7 +2796,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/sc/ManageTable',{});]]> true @@ -2843,7 +2843,7 @@ $(pv_value) 164 54e87698:1777e01a75d:-750f 317 - 420 + 431 @@ -3017,7 +3017,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/sc/SendHK',{});]]> true @@ -3064,7 +3064,7 @@ $(pv_value) 164 54e87698:1777e01a75d:-74ef 317 - 439 + 450 @@ -3073,7 +3073,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/sc/1HzWakeUp',{});]]> true @@ -3120,7 +3120,7 @@ $(pv_value) 164 54e87698:1777e01a75d:-74e7 317 - 458 + 469 @@ -3623,4 +3623,65 @@ $(pv_value) 317 382 + + + + + + true + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 20 + + AppControl + 0 + + + + + true + true + false + + + + App Control + false + $(pv_name) +$(pv_value) + true + Action Button + 164 + 49c9ccd0:178c6a335db:-3687 + 317 + 401 + \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SC/StartATS.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SC/StartATS.opi index 1d1f9601c..04b77607b 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SC/StartATS.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SC/StartATS.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - SC - Start ATS + ($(CPUID)) SC - Start ATS true @@ -28,7 +28,7 @@ true true Display - 190 + 210 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,17 +60,17 @@ false - Start ATS + ($(CPUID)) SC - Start ATS true 1 true Label - 98 + 205 false -10b748b0:17773fb054b:-7a20 - 42 - 12 + 6 + 6 @@ -109,7 +109,7 @@ 61 false -10b748b0:17773fb054b:-7a0f - 0 + 12 36 @@ -122,7 +122,7 @@ importPackage(Packages.org.yamcs.studio.data); var AtsId = VTypeHelper.getString(display.getWidget('AtsId').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/sc/StartAts', { +Yamcs.issueCommand('/cfs/$(CPUID)/sc/StartAts', { 'AtsId': AtsId});]]> true @@ -169,7 +169,7 @@ $(pv_value) Action Button 72 -10b748b0:17773fb054b:-79c7 - 55 + 67 66 @@ -184,7 +184,7 @@ $(pv_value) - 1 + 4 1 true @@ -226,7 +226,7 @@ $(pv_value) Text Input 100 -10b748b0:17773fb054b:-78ff - 72 + 84 36 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SC/StartRTS.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SC/StartRTS.opi index 5f5a56862..b29e5be24 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SC/StartRTS.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SC/StartRTS.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - SC - Start RTS + ($(CPUID)) SC - Start RTS true @@ -60,16 +60,16 @@ false - Start RTS + ($(CPUID)) SC - Start RTS true 1 true Label - 98 + 181 false -10b748b0:17773fb054b:-7a20 - 45 + 6 6 @@ -122,7 +122,7 @@ importPackage(Packages.org.yamcs.studio.data); var RtsId = VTypeHelper.getString(display.getWidget('RtsId').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/sc/StartRts', { +Yamcs.issueCommand('/cfs/$(CPUID)/sc/StartRts', { 'RtsId': RtsId});]]> true @@ -184,7 +184,7 @@ $(pv_value) - 1 + 4 1 true diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SC/StartRTSGroup.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SC/StartRTSGroup.opi index 5f957c2bc..1be3f6aa4 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SC/StartRTSGroup.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SC/StartRTSGroup.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - SC - Start RTS Group + ($(CPUID)) SC - Start RTS Group true @@ -28,7 +28,7 @@ true true Display - 220 + 250 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,16 +60,16 @@ false - Start RTS Group + ($(CPUID)) SC - Start RTS Group true 1 true Label - 160 + 235 false -10b748b0:17773fb054b:-7a20 - 24 + 12 6 @@ -109,7 +109,7 @@ 91 false -10b748b0:17773fb054b:-7a0f - 6 + 18 36 @@ -123,7 +123,7 @@ importPackage(Packages.org.yamcs.studio.data); var FirstRtsId = VTypeHelper.getString(display.getWidget('FirstRtsId').getPropertyValue('pv_value')); var LastRtsId = VTypeHelper.getString(display.getWidget('LastRtsId').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/sc/StartRtsGroup', { +Yamcs.issueCommand('/cfs/$(CPUID)/sc/StartRtsGroup', { 'FirstRtsId': FirstRtsId, 'LastRtsId': LastRtsId}); ]]> @@ -172,7 +172,7 @@ $(pv_value) Action Button 92 -10b748b0:17773fb054b:-79c7 - 58 + 70 90 @@ -187,7 +187,7 @@ $(pv_value) - 1 + 4 1 true @@ -229,7 +229,7 @@ $(pv_value) Text Input 100 -10b748b0:17773fb054b:-78ff - 108 + 120 36 @@ -269,7 +269,7 @@ $(pv_value) 91 false 54e87698:1777e01a75d:-70ef - 6 + 18 55 @@ -284,7 +284,7 @@ $(pv_value) - 1 + 4 1 true @@ -326,7 +326,7 @@ $(pv_value) Text Input 100 54e87698:1777e01a75d:-70ee - 108 + 120 55 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SC/StopRTS.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SC/StopRTS.opi index df9849552..fb3be8ccb 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SC/StopRTS.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SC/StopRTS.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - SC - Stop RTS + ($(CPUID)) SC - Stop RTS true @@ -28,7 +28,7 @@ true true Display - 190 + 210 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,16 +60,16 @@ false - Stop RTS + ($(CPUID)) SC - Stop RTS true 1 true Label - 98 + 199 false -10b748b0:17773fb054b:-7a20 - 45 + 6 6 @@ -109,7 +109,7 @@ 55 false -10b748b0:17773fb054b:-7a0f - 6 + 18 36 @@ -122,7 +122,7 @@ importPackage(Packages.org.yamcs.studio.data); var RtsId = VTypeHelper.getString(display.getWidget('RtsId').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/sc/StopRts', { +Yamcs.issueCommand('/cfs/$(CPUID)/sc/StopRts', { 'RtsId': RtsId});]]> true @@ -169,7 +169,7 @@ $(pv_value) Action Button 92 -10b748b0:17773fb054b:-79c7 - 48 + 60 66 @@ -184,7 +184,7 @@ $(pv_value) - 1 + 4 1 true @@ -226,7 +226,7 @@ $(pv_value) Text Input 100 -10b748b0:17773fb054b:-78ff - 72 + 84 36 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SC/StopRTSGroup.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SC/StopRTSGroup.opi index 8dd27ba09..ff469c9c0 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SC/StopRTSGroup.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SC/StopRTSGroup.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - SC - Stop RTS Group + ($(CPUID)) SC - Stop RTS Group true @@ -28,7 +28,7 @@ true true Display - 220 + 260 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,16 +60,16 @@ false - Stop RTS Group + ($(CPUID)) SC - Stop RTS Group true 1 true Label - 160 + 241 false -10b748b0:17773fb054b:-7a20 - 24 + 12 6 @@ -109,7 +109,7 @@ 91 false -10b748b0:17773fb054b:-7a0f - 6 + 18 36 @@ -123,7 +123,7 @@ importPackage(Packages.org.yamcs.studio.data); var FirstRtsId = VTypeHelper.getString(display.getWidget('FirstRtsId').getPropertyValue('pv_value')); var LastRtsId = VTypeHelper.getString(display.getWidget('LastRtsId').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/sc/StopRtsGroup', { +Yamcs.issueCommand('/cfs/$(CPUID)/sc/StopRtsGroup', { 'FirstRtsId': FirstRtsId, 'LastRtsId': LastRtsId}); ]]> @@ -172,7 +172,7 @@ $(pv_value) Action Button 92 -10b748b0:17773fb054b:-79c7 - 58 + 78 90 @@ -187,7 +187,7 @@ $(pv_value) - 1 + 4 1 true @@ -229,7 +229,7 @@ $(pv_value) Text Input 100 -10b748b0:17773fb054b:-78ff - 108 + 120 36 @@ -269,7 +269,7 @@ $(pv_value) 91 false 54e87698:1777e01a75d:-70ef - 6 + 18 55 @@ -284,7 +284,7 @@ $(pv_value) - 1 + 4 1 true @@ -326,7 +326,7 @@ $(pv_value) Text Input 100 54e87698:1777e01a75d:-70ee - 108 + 120 55 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SCH/Diagnostic.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SCH/Diagnostic.opi index b362dfe3a..2a08a9842 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SCH/Diagnostic.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SCH/Diagnostic.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - SCH - Diagnostic + ($(CPUID)) SCH - Diagnostic true @@ -28,7 +28,7 @@ true true Display - 180 + 400 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,13 +60,13 @@ false - SCH - Diagnostic + ($(CPUID)) SCH - Diagnostic true 1 true Label - 134 + 295 false -10b748b0:17773fb054b:-7a20 24 @@ -80,7 +80,7 @@ importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); -Yamcs.issueCommand('/cfs/sch/SendDiag', {});]]> +Yamcs.issueCommand('/cfs/$(CPUID)/sch/SendDiag', {});]]> true @@ -126,7 +126,7 @@ $(pv_value) Action Button 103 -10b748b0:17773fb054b:-79c7 - 36 + 114 84 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SCH/DisableActivity.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SCH/DisableActivity.opi index 52be95a55..7f6177538 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SCH/DisableActivity.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SCH/DisableActivity.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - SCH - Disable Activity + ($(CPUID)) SCH - Disable Activity true @@ -28,7 +28,7 @@ true true Display - 180 + 260 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,17 +60,17 @@ false - Disable Activity + ($(CPUID)) SCH - Disable Activity true 1 true Label - 134 + 241 false -10b748b0:17773fb054b:-7a20 - 24 - 12 + 5 + 6 @@ -109,7 +109,7 @@ 49 false -10b748b0:17773fb054b:-7a0f - 5 + 42 36 @@ -149,7 +149,7 @@ 49 false -10b748b0:17773fb054b:-79f1 - 5 + 42 55 @@ -163,7 +163,7 @@ importPackage(Packages.org.yamcs.studio.data); var SlotNumber = VTypeHelper.getString(display.getWidget('Slot').getPropertyValue('pv_value')); var EntryNumber = VTypeHelper.getString(display.getWidget('Entry').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/sch/Disable', { +Yamcs.issueCommand('/cfs/$(CPUID)/sch/Disable', { 'SlotNumber': SlotNumber, 'EntryNumber': EntryNumber});]]> true @@ -211,7 +211,7 @@ $(pv_value) Action Button 84 -10b748b0:17773fb054b:-79c7 - 49 + 86 84 @@ -226,7 +226,7 @@ $(pv_value) - 1 + 4 1 true @@ -268,7 +268,7 @@ $(pv_value) Text Input 100 -10b748b0:17773fb054b:-78ff - 65 + 102 36 @@ -283,7 +283,7 @@ $(pv_value) - 1 + 4 1 true @@ -325,7 +325,7 @@ $(pv_value) Text Input 100 -10b748b0:17773fb054b:-78f7 - 65 + 102 55 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SCH/DisableGroup.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SCH/DisableGroup.opi index a72a20c23..a6af3d47b 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SCH/DisableGroup.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SCH/DisableGroup.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - SCH - Disable Group + ($(CPUID)) SCH - Disable Group true @@ -28,7 +28,7 @@ true true Display - 190 + 250 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,17 +60,17 @@ false - Disable Group + ($(CPUID)) SCH - Disable Group true 1 true Label - 134 + 235 false -10b748b0:17773fb054b:-7a20 - 24 - 12 + 6 + 6 @@ -109,7 +109,7 @@ 67 false -10b748b0:17773fb054b:-7a0f - 6 + 36 36 @@ -122,7 +122,7 @@ importPackage(Packages.org.yamcs.studio.data); var GroupID = VTypeHelper.getString(display.getWidget('GroupID').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/sch/DisableGroup', { +Yamcs.issueCommand('/cfs/$(CPUID)/sch/DisableGroup', { 'GroupData': GroupID});]]> true @@ -169,7 +169,7 @@ $(pv_value) Action Button 84 -10b748b0:17773fb054b:-79c7 - 49 + 79 66 @@ -184,7 +184,7 @@ $(pv_value) - 1 + 4 1 true @@ -226,7 +226,7 @@ $(pv_value) Text Input 100 -10b748b0:17773fb054b:-78ff - 78 + 108 36 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SCH/EnableActivity.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SCH/EnableActivity.opi index f0be82098..bec8e3aa8 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SCH/EnableActivity.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SCH/EnableActivity.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - SCH - Enable Activity + ($(CPUID)) SCH - Enable Activity true @@ -28,7 +28,7 @@ true true Display - 180 + 260 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,17 +60,17 @@ false - Enable Activity + ($(CPUID)) SCH - Enable Activity true 1 true Label - 134 + 241 false -10b748b0:17773fb054b:-7a20 - 24 - 12 + 5 + 6 @@ -109,7 +109,7 @@ 49 false -10b748b0:17773fb054b:-7a0f - 5 + 24 36 @@ -149,7 +149,7 @@ 49 false -10b748b0:17773fb054b:-79f1 - 5 + 24 55 @@ -163,7 +163,7 @@ importPackage(Packages.org.yamcs.studio.data); var SlotNumber = VTypeHelper.getString(display.getWidget('Slot').getPropertyValue('pv_value')); var EntryNumber = VTypeHelper.getString(display.getWidget('Entry').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/sch/Enable', { +Yamcs.issueCommand('/cfs/$(CPUID)/sch/Enable', { 'SlotNumber': SlotNumber, 'EntryNumber': EntryNumber});]]> true @@ -209,9 +209,9 @@ Yamcs.issueCommand('/cfs/sch/Enable', { $(pv_value) true Action Button - 72 + 89 -10b748b0:17773fb054b:-79c7 - 55 + 74 84 @@ -226,7 +226,7 @@ $(pv_value) - 1 + 4 1 true @@ -268,7 +268,7 @@ $(pv_value) Text Input 100 -10b748b0:17773fb054b:-78ff - 65 + 84 36 @@ -283,7 +283,7 @@ $(pv_value) - 1 + 4 1 true @@ -325,7 +325,7 @@ $(pv_value) Text Input 100 -10b748b0:17773fb054b:-78f7 - 65 + 84 55 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SCH/EnableGroup.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SCH/EnableGroup.opi index ca434aa87..8cf837693 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SCH/EnableGroup.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SCH/EnableGroup.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - SCH - Enable Group + ($(CPUID)) SCH - Enable Group true @@ -28,7 +28,7 @@ true true Display - 190 + 240 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,17 +60,17 @@ false - Enable Group + ($(CPUID)) SCH - Enable Group true 1 true Label - 134 + 229 false -10b748b0:17773fb054b:-7a20 - 24 - 12 + 6 + 6 @@ -109,7 +109,7 @@ 67 false -10b748b0:17773fb054b:-7a0f - 6 + 30 36 @@ -122,7 +122,7 @@ importPackage(Packages.org.yamcs.studio.data); var GroupID = VTypeHelper.getString(display.getWidget('GroupID').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/sch/EnableGroup', { +Yamcs.issueCommand('/cfs/$(CPUID)/sch/EnableGroup', { 'GroupData': GroupID});]]> true @@ -169,7 +169,7 @@ $(pv_value) Action Button 84 -10b748b0:17773fb054b:-79c7 - 49 + 73 66 @@ -184,7 +184,7 @@ $(pv_value) - 1 + 4 1 true @@ -226,7 +226,7 @@ $(pv_value) Text Input 100 -10b748b0:17773fb054b:-78ff - 78 + 102 36 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SCH/Main.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SCH/Main.opi index 3f46df4af..dff73af59 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SCH/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SCH/Main.opi @@ -10,12 +10,12 @@ - 1.5.5.202103162101 + 1.6.2.202104092231 6 - 600 + 585 true sch @@ -23,7 +23,7 @@ Displays /modules/sch - SCH + ($(CPUID)) SCH true @@ -32,7 +32,7 @@ true true Display - 600 + 340 -33cb7c72:150aa4c347f:-76c2 -1 -1 @@ -48,7 +48,7 @@ - 0 + 4 1 true @@ -64,7 +64,7 @@ Text Update 0 false - /cfs/sch/SCH_HkPacket_t.CmdCounter + /cfs/$(CPUID)/sch/SCH_HkPacket_t.CmdCounter 0.0 @@ -180,7 +180,7 @@ $(pv_value) - 0 + 4 1 true @@ -196,7 +196,7 @@ $(pv_value) Text Update_1 0 false - /cfs/sch/SCH_HkPacket_t.ErrCounter + /cfs/$(CPUID)/sch/SCH_HkPacket_t.ErrCounter 0.0 @@ -227,7 +227,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/sch/Noop', {});]]> true @@ -283,7 +283,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/sch/Reset', {});]]> true @@ -360,7 +360,7 @@ $(pv_value) false - Scheduler + ($(CPUID)) Scheduler true 1 @@ -384,7 +384,7 @@ $(pv_value) - 1 + 4 1 true @@ -400,7 +400,7 @@ $(pv_value) Text Update_2 0 false - /cfs/sch/SCH_HkPacket_t.SyncToMET + /cfs/$(CPUID)/sch/SCH_HkPacket_t.SyncToMET 0.0 @@ -436,7 +436,7 @@ $(pv_value) - 1 + 4 1 true @@ -452,7 +452,7 @@ $(pv_value) Text Update_3 0 false - /cfs/sch/SCH_HkPacket_t.MajorFrameSource + /cfs/$(CPUID)/sch/SCH_HkPacket_t.MajorFrameSource 0.0 @@ -488,7 +488,7 @@ $(pv_value) - 1 + 4 1 true @@ -504,7 +504,7 @@ $(pv_value) Text Update_4 0 false - /cfs/sch/SCH_HkPacket_t.ScheduleActivitySuccessCount + /cfs/$(CPUID)/sch/SCH_HkPacket_t.ScheduleActivitySuccessCount 0.0 @@ -540,7 +540,7 @@ $(pv_value) - 1 + 4 1 true @@ -556,7 +556,7 @@ $(pv_value) Text Update_5 0 false - /cfs/sch/SCH_HkPacket_t.ScheduleActivityFailureCount + /cfs/$(CPUID)/sch/SCH_HkPacket_t.ScheduleActivityFailureCount 0.0 @@ -592,7 +592,7 @@ $(pv_value) - 1 + 4 1 true @@ -608,7 +608,7 @@ $(pv_value) Text Update_6 0 false - /cfs/sch/SCH_HkPacket_t.SlotsProcessedCount + /cfs/$(CPUID)/sch/SCH_HkPacket_t.SlotsProcessedCount 0.0 @@ -644,7 +644,7 @@ $(pv_value) - 1 + 4 1 true @@ -660,7 +660,7 @@ $(pv_value) Text Update_7 0 false - /cfs/sch/SCH_HkPacket_t.SkippedSlotsCount + /cfs/$(CPUID)/sch/SCH_HkPacket_t.SkippedSlotsCount 0.0 @@ -696,7 +696,7 @@ $(pv_value) - 1 + 4 1 true @@ -712,7 +712,7 @@ $(pv_value) Text Update_8 0 false - /cfs/sch/SCH_HkPacket_t.MultipleSlotsCount + /cfs/$(CPUID)/sch/SCH_HkPacket_t.MultipleSlotsCount 0.0 @@ -748,7 +748,7 @@ $(pv_value) - 1 + 4 1 true @@ -764,7 +764,7 @@ $(pv_value) Text Update_9 0 false - /cfs/sch/SCH_HkPacket_t.SameSlotCount + /cfs/$(CPUID)/sch/SCH_HkPacket_t.SameSlotCount 0.0 @@ -800,7 +800,7 @@ $(pv_value) - 1 + 4 1 true @@ -816,7 +816,7 @@ $(pv_value) Text Update_10 0 false - /cfs/sch/SCH_HkPacket_t.BadTableDataCount + /cfs/$(CPUID)/sch/SCH_HkPacket_t.BadTableDataCount 0.0 @@ -852,7 +852,7 @@ $(pv_value) - 1 + 4 1 true @@ -868,7 +868,7 @@ $(pv_value) Text Update_11 0 false - /cfs/sch/SCH_HkPacket_t.TableVerifySuccessCount + /cfs/$(CPUID)/sch/SCH_HkPacket_t.TableVerifySuccessCount 0.0 @@ -904,7 +904,7 @@ $(pv_value) - 1 + 4 1 true @@ -920,7 +920,7 @@ $(pv_value) Text Update_12 0 false - /cfs/sch/SCH_HkPacket_t.TableVerifyFailureCount + /cfs/$(CPUID)/sch/SCH_HkPacket_t.TableVerifyFailureCount 0.0 @@ -956,7 +956,7 @@ $(pv_value) - 1 + 4 1 true @@ -972,7 +972,7 @@ $(pv_value) Text Update_13 0 false - /cfs/sch/SCH_HkPacket_t.TablePassCount + /cfs/$(CPUID)/sch/SCH_HkPacket_t.TablePassCount 0.0 @@ -1008,7 +1008,7 @@ $(pv_value) - 1 + 4 1 true @@ -1024,7 +1024,7 @@ $(pv_value) Text Update_14 0 false - /cfs/sch/SCH_HkPacket_t.ValidMajorFrameCount + /cfs/$(CPUID)/sch/SCH_HkPacket_t.ValidMajorFrameCount 0.0 @@ -1060,7 +1060,7 @@ $(pv_value) - 1 + 4 1 true @@ -1076,7 +1076,7 @@ $(pv_value) Text Update_15 0 false - /cfs/sch/SCH_HkPacket_t.MissedMajorFrameCount + /cfs/$(CPUID)/sch/SCH_HkPacket_t.MissedMajorFrameCount 0.0 @@ -1112,7 +1112,7 @@ $(pv_value) - 1 + 4 1 true @@ -1128,7 +1128,7 @@ $(pv_value) Text Update_16 0 false - /cfs/sch/SCH_HkPacket_t.UnexpectedMajorFrameCount + /cfs/$(CPUID)/sch/SCH_HkPacket_t.UnexpectedMajorFrameCount 0.0 @@ -1164,7 +1164,7 @@ $(pv_value) - 1 + 4 1 true @@ -1180,7 +1180,7 @@ $(pv_value) Text Update_17 0 false - /cfs/sch/SCH_HkPacket_t.MinorFramesSinceTone + /cfs/$(CPUID)/sch/SCH_HkPacket_t.MinorFramesSinceTone 0.0 @@ -1216,7 +1216,7 @@ $(pv_value) - 1 + 4 1 true @@ -1232,7 +1232,7 @@ $(pv_value) Text Update_18 0 false - /cfs/sch/SCH_HkPacket_t.NextSlotNumber + /cfs/$(CPUID)/sch/SCH_HkPacket_t.NextSlotNumber 0.0 @@ -1268,7 +1268,7 @@ $(pv_value) - 1 + 4 1 true @@ -1284,7 +1284,7 @@ $(pv_value) Text Update_19 0 false - /cfs/sch/SCH_HkPacket_t.LastSyncMETSlot + /cfs/$(CPUID)/sch/SCH_HkPacket_t.LastSyncMETSlot 0.0 @@ -1320,7 +1320,7 @@ $(pv_value) - 1 + 4 1 true @@ -1336,7 +1336,7 @@ $(pv_value) Text Update_20 0 false - /cfs/sch/SCH_HkPacket_t.IgnoreMajorFrame + /cfs/$(CPUID)/sch/SCH_HkPacket_t.IgnoreMajorFrame 0.0 @@ -1372,7 +1372,7 @@ $(pv_value) - 1 + 4 1 true @@ -1388,7 +1388,7 @@ $(pv_value) Text Update_21 0 false - /cfs/sch/SCH_HkPacket_t.UnexpectedMajorFrame + /cfs/$(CPUID)/sch/SCH_HkPacket_t.UnexpectedMajorFrame 0.0 @@ -2439,7 +2439,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/sch/EnableSync', {});]]> true @@ -2495,7 +2495,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/sch/SendHK', {});]]> true @@ -2660,4 +2660,65 @@ $(pv_value) 36 543 + + + + + + true + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 20 + + AppControl + 0 + + + + + true + true + false + + + + App Control + false + $(pv_name) +$(pv_value) + true + Action Button + 127 + 49c9ccd0:178c6a335db:-3581 + 36 + 562 + \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SENS/Accel.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SENS/Accel.opi index 43a80fe44..3900f907b 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SENS/Accel.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SENS/Accel.opi @@ -110,7 +110,7 @@ ON - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.AccInvalid + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.AccInvalid @@ -198,7 +198,7 @@ $(pv_value) Text Update_49 6 false - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.AccIntegralDt + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.AccIntegralDt 0.0 @@ -290,7 +290,7 @@ $(pv_value) Text Update_50 0 false - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.AccTimestamp.Subseconds + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.AccTimestamp.Subseconds 0.0 @@ -342,7 +342,7 @@ $(pv_value) Text Update_51 0 false - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.AccTimestamp.Seconds + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.AccTimestamp.Seconds 0.0 @@ -513,7 +513,7 @@ $(trace_0_y_pv_value) 1 - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.Acc_0_ + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.Acc_0_ true 100 @@ -534,7 +534,7 @@ $(trace_0_y_pv_value) 1 - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.Acc_1_ + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.Acc_1_ true 100 @@ -555,7 +555,7 @@ $(trace_0_y_pv_value) 1 - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.Acc_2_ + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.Acc_2_ 3 false diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SENS/Baro.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SENS/Baro.opi index edc3b17bf..783e2038f 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SENS/Baro.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SENS/Baro.opi @@ -110,7 +110,7 @@ ON - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.BaroInvalid + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.BaroInvalid @@ -198,7 +198,7 @@ $(pv_value) Text Update_61 0 false - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.BaroTimestamp.Subseconds + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.BaroTimestamp.Subseconds 0.0 @@ -250,7 +250,7 @@ $(pv_value) Text Update_62 0 false - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.BaroTimestamp.Seconds + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.BaroTimestamp.Seconds 0.0 @@ -382,7 +382,7 @@ $(pv_value) Text Update_63 3 false - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.BaroAlt + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.BaroAlt 0.0 @@ -474,7 +474,7 @@ $(pv_value) Text Update_64 1 false - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.BaroTemp + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.BaroTemp 0.0 @@ -605,7 +605,7 @@ $(trace_0_y_pv_value) 1 - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.BaroAlt + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.BaroAlt 1 false diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SENS/Gyro.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SENS/Gyro.opi index 1479665d1..375bbd8d8 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SENS/Gyro.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SENS/Gyro.opi @@ -100,7 +100,7 @@ Text Update_31 6 false - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.GyroIntegralDt + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.GyroIntegralDt 0.0 @@ -203,7 +203,7 @@ $(pv_value) - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.GyroRad_0_ + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.GyroRad_0_ true @@ -367,7 +367,7 @@ $(trace_0_y_pv_value) 1 - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.GyroRad_0_ + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.GyroRad_0_ true 100 @@ -388,7 +388,7 @@ $(trace_0_y_pv_value) 1 - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.GyroRad_1_ + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.GyroRad_1_ true 100 @@ -409,7 +409,7 @@ $(trace_0_y_pv_value) 1 - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.GyroRad_2_ + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.GyroRad_2_ 3 false diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SENS/Mag.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SENS/Mag.opi index 92fa18c53..9d9f06969 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SENS/Mag.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SENS/Mag.opi @@ -110,7 +110,7 @@ ON - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.MagInvalid + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.MagInvalid @@ -198,7 +198,7 @@ $(pv_value) Text Update_56 0 false - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.MagTimestamp.Subseconds + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.MagTimestamp.Subseconds 0.0 @@ -250,7 +250,7 @@ $(pv_value) Text Update_57 0 false - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.MagTimestamp.Seconds + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.MagTimestamp.Seconds 0.0 @@ -421,7 +421,7 @@ $(trace_0_y_pv_value) 1 - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.Mag_0_ + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.Mag_0_ true 100 @@ -442,7 +442,7 @@ $(trace_0_y_pv_value) 1 - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.Mag_1_ + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.Mag_1_ true 100 @@ -463,7 +463,7 @@ $(trace_0_y_pv_value) 1 - /cfs/sens/SENS_HkTlm_t.SensorCombinedMsg.Mag_2_ + /cfs/$(CPUID)/sens/SENS_HkTlm_t.SensorCombinedMsg.Mag_2_ 3 false diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/SENS/Main.opi b/core/base/tools/commander/workspace_template/Displays/Apps/SENS/Main.opi index 678329385..263316bdb 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/SENS/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/SENS/Main.opi @@ -10,7 +10,7 @@ - 1.5.5.202103162101 + 1.6.2.202104092231 @@ -64,7 +64,7 @@ Text Update 0 false - /cfs/sens/SENS_HkTlm_t.usCmdCnt + /cfs/$(CPUID)/sens/SENS_HkTlm_t.usCmdCnt 0.0 @@ -196,7 +196,7 @@ $(pv_value) Text Update_1 0 false - /cfs/sens/SENS_HkTlm_t.usCmdErrCnt + /cfs/$(CPUID)/sens/SENS_HkTlm_t.usCmdErrCnt 0.0 @@ -267,7 +267,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/sens/Noop', {});]]> true @@ -323,7 +323,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/sens/Reset', {});]]> true @@ -431,7 +431,7 @@ $(pv_value) 124 -69f8bd78:177f094d5fe:-1634 174 - 96 + 115 @@ -440,7 +440,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/sens/SendHK', {});]]> true @@ -487,7 +487,7 @@ $(pv_value) 124 -69f8bd78:177f094d5fe:-162c 174 - 115 + 134 @@ -496,7 +496,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/sens/WakeUp', {});]]> true @@ -543,7 +543,7 @@ $(pv_value) 124 -69f8bd78:177f094d5fe:-1624 174 - 134 + 153 @@ -765,4 +765,65 @@ $(pv_value) 31 153 - + + + + + + true + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 20 + + AppControl + 0 + + + + + true + true + false + + + + App Control + false + $(pv_name) +$(pv_value) + true + Action Button + 124 + 49c9ccd0:178c6a335db:-34b1 + 174 + 96 + + \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/TO/AddMessageFlow.opi b/core/base/tools/commander/workspace_template/Displays/Apps/TO/AddMessageFlow.opi index 72423821b..f9b21f44a 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/TO/AddMessageFlow.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/TO/AddMessageFlow.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - TO - Add Message Flow + ($(CPUID)) TO - Add Msg Flow true @@ -28,7 +28,7 @@ true true Display - 240 + 270 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,17 +60,17 @@ false - Add Message Flow + ($(CPUID)) TO - Add Message Flow true 1 true Label - 182 + 259 false -10b748b0:17773fb054b:-7a20 - 36 - 12 + 6 + 6 @@ -205,7 +205,7 @@ var MsgID = VTypeHelper.getString(display.getWidget('MsgID').getPropertyValue('p var MsgLimit = VTypeHelper.getString(display.getWidget('MsgLimit').getPropertyValue('pv_value')); var PQueueIdx = VTypeHelper.getString(display.getWidget('PQueueIdx').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/to/AddMessageFlow', { +Yamcs.issueCommand('/cfs/$(CPUID)/to/AddMessageFlow', { 'ChannelIdx': ChannelIdx, 'MsgID': MsgID, 'MsgLimit': MsgLimit, @@ -270,7 +270,7 @@ $(pv_value) - 1 + 4 1 true @@ -327,7 +327,7 @@ $(pv_value) - 1 + 4 1 true @@ -384,7 +384,7 @@ $(pv_value) - 1 + 4 1 true diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/TO/Main.opi b/core/base/tools/commander/workspace_template/Displays/Apps/TO/Main.opi index aa774e317..7780290d1 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/TO/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/TO/Main.opi @@ -10,7 +10,7 @@ - 1.5.5.202103162101 + 1.6.2.202104092231 @@ -23,7 +23,7 @@ /Displays/Core/EVS/Events.opi /modules/to - TO + ($(CPUID)) TO true @@ -48,7 +48,7 @@ - 1 + 4 1 true @@ -64,7 +64,7 @@ Text Update 0 false - /cfs/to/TO_HkTlm_t.usCmdCnt + /cfs/$(CPUID)/to/TO_HkTlm_t.usCmdCnt 0.0 @@ -180,7 +180,7 @@ $(pv_value) - 1 + 4 1 true @@ -196,7 +196,7 @@ $(pv_value) Text Update_1 0 false - /cfs/to/TO_HkTlm_t.usCmdErrCnt + /cfs/$(CPUID)/to/TO_HkTlm_t.usCmdErrCnt 0.0 @@ -248,16 +248,16 @@ $(pv_value) false - Telemetry Output + ($(CPUID)) Telemetry Output true 1 true Label - 182 + 232 false -33cb7c72:150aa4c347f:-75c9 - 84 + 63 12 @@ -267,7 +267,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/to/Noop', {});]]> true @@ -323,7 +323,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/to/Reset', {});]]> true @@ -424,7 +424,7 @@ $(pv_value) - 1 + 4 1 true @@ -440,7 +440,7 @@ $(pv_value) Text Update_2 0 false - /cfs/to/TO_HkTlm_t.uiSentMsgCountChannel_0_ + /cfs/$(CPUID)/to/TO_HkTlm_t.uiSentMsgCountChannel_0_ 0.0 @@ -516,7 +516,7 @@ $(pv_value) - 1 + 4 1 true @@ -532,7 +532,7 @@ $(pv_value) Text Update_3 0 false - /cfs/to/TO_HkTlm_t.uiQueuedMsgCountChannel_0_ + /cfs/$(CPUID)/to/TO_HkTlm_t.uiQueuedMsgCountChannel_0_ 0.0 @@ -608,7 +608,7 @@ $(pv_value) - 1 + 4 1 true @@ -624,7 +624,7 @@ $(pv_value) Text Update_4 0 false - /cfs/to/TO_HkTlm_t.uiDropMsgCountChannel_0_ + /cfs/$(CPUID)/to/TO_HkTlm_t.uiDropMsgCountChannel_0_ 0.0 @@ -700,7 +700,7 @@ $(pv_value) - 1 + 4 1 true @@ -716,7 +716,7 @@ $(pv_value) Text Update_5 0 false - /cfs/to/TO_HkTlm_t.uiFailedMsgCountChannel_0_ + /cfs/$(CPUID)/to/TO_HkTlm_t.uiFailedMsgCountChannel_0_ 0.0 @@ -792,7 +792,7 @@ $(pv_value) - 1 + 4 1 true @@ -808,7 +808,7 @@ $(pv_value) Text Update_6 0 false - /cfs/to/TO_HkTlm_t.uiBytesSentChannel_0_ + /cfs/$(CPUID)/to/TO_HkTlm_t.uiBytesSentChannel_0_ 0.0 @@ -884,7 +884,7 @@ $(pv_value) - 1 + 4 1 true @@ -900,7 +900,7 @@ $(pv_value) Text Update_7 0 false - /cfs/to/TO_HkTlm_t.usTotalMsgDropped + /cfs/$(CPUID)/to/TO_HkTlm_t.usTotalMsgDropped 0.0 @@ -976,7 +976,7 @@ $(pv_value) - 1 + 4 1 true @@ -992,7 +992,7 @@ $(pv_value) Text Update_8 0 false - /cfs/to/TO_HkTlm_t.ChannelMemInfo_0_.MemInUse + /cfs/$(CPUID)/to/TO_HkTlm_t.ChannelMemInfo_0_.MemInUse 0.0 @@ -1068,7 +1068,7 @@ $(pv_value) - 1 + 4 1 true @@ -1084,7 +1084,7 @@ $(pv_value) Text Update_9 0 false - /cfs/to/TO_HkTlm_t.SentBytes + /cfs/$(CPUID)/to/TO_HkTlm_t.SentBytes 0.0 @@ -1160,7 +1160,7 @@ $(pv_value) - 1 + 4 1 true @@ -1176,7 +1176,7 @@ $(pv_value) Text Update_10 0 false - /cfs/to/TO_HkTlm_t.ChannelMaxMem + /cfs/$(CPUID)/to/TO_HkTlm_t.ChannelMaxMem 0.0 @@ -1292,7 +1292,7 @@ $(pv_value) - 1 + 4 1 true @@ -1308,7 +1308,7 @@ $(pv_value) Text Update_11 0 false - /cfs/to/TO_HkTlm_t.ChannelMemInfo_0_.PeakMemInUse + /cfs/$(CPUID)/to/TO_HkTlm_t.ChannelMemInfo_0_.PeakMemInUse 0.0 @@ -1384,7 +1384,7 @@ $(pv_value) - 1 + 4 1 true @@ -1400,7 +1400,7 @@ $(pv_value) Text Update_12 0 false - /cfs/to/TO_HkTlm_t.QueuedInOutputChannel_0_ + /cfs/$(CPUID)/to/TO_HkTlm_t.QueuedInOutputChannel_0_ 0.0 @@ -1884,7 +1884,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/to/SendHK', {});]]> true @@ -1940,7 +1940,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/to/SendTelemetry', {});]]> true @@ -1989,4 +1989,65 @@ $(pv_value) 192 436 + + + + + + true + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 20 + + AppControl + 0 + + + + + true + true + false + + + + App Control + false + $(pv_name) +$(pv_value) + true + Action Button + 175 + 49c9ccd0:178c6a335db:-342c + 6 + 455 + \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/TO/QueryMessageFlow.opi b/core/base/tools/commander/workspace_template/Displays/Apps/TO/QueryMessageFlow.opi index ad55df71b..e55e2b284 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/TO/QueryMessageFlow.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/TO/QueryMessageFlow.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - TO - Query Msg Flow + ($(CPUID)) TO - Query Msg Flow true @@ -28,7 +28,7 @@ true true Display - 220 + 280 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,17 +60,17 @@ false - Query Message Flow + ($(CPUID)) TO - Query Message Flow true 1 true Label - 182 + 259 false -10b748b0:17773fb054b:-7a20 - 18 - 12 + 6 + 6 @@ -109,7 +109,7 @@ 85 false -10b748b0:17773fb054b:-7a0f - 6 + 30 36 @@ -123,7 +123,7 @@ importPackage(Packages.org.yamcs.studio.data); var ChannelIdx = 0; var MsgID = VTypeHelper.getString(display.getWidget('MsgID').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/to/QueryMessageFlow', { +Yamcs.issueCommand('/cfs/$(CPUID)/to/QueryMessageFlow', { 'ChannelIdx': ChannelIdx, 'MsgID': MsgID});]]> true @@ -171,7 +171,7 @@ $(pv_value) Action Button 84 -10b748b0:17773fb054b:-79c7 - 67 + 91 66 @@ -186,7 +186,7 @@ $(pv_value) - 1 + 4 1 true @@ -228,7 +228,7 @@ $(pv_value) Text Input 103 -10b748b0:17773fb054b:-78ff - 102 + 126 36 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/TO/QueryOutputChannel.opi b/core/base/tools/commander/workspace_template/Displays/Apps/TO/QueryOutputChannel.opi index 879b0f814..bba4bbc59 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/TO/QueryOutputChannel.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/TO/QueryOutputChannel.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - TO - Query Output + ($(CPUID)) TO - Query Output true @@ -28,7 +28,7 @@ true true Display - 220 + 280 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,17 +60,17 @@ false - Query Output Queue + ($(CPUID)) TO - Query Output Queue true 1 true Label - 182 + 265 false -10b748b0:17773fb054b:-7a20 - 18 - 12 + 6 + 6 @@ -82,7 +82,7 @@ importPackage(Packages.org.yamcs.studio.data); var ChannelIdx = 0; -Yamcs.issueCommand('/cfs/to/QueryOutputChannel', { +Yamcs.issueCommand('/cfs/$(CPUID)/to/QueryOutputChannel', { 'ChannelIdx': ChannelIdx});]]> true @@ -129,7 +129,7 @@ $(pv_value) Action Button 84 -10b748b0:17773fb054b:-79c7 - 67 + 90 66 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/TO/QueryPriorityQueue.opi b/core/base/tools/commander/workspace_template/Displays/Apps/TO/QueryPriorityQueue.opi index 6457ba542..1ddc60206 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/TO/QueryPriorityQueue.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/TO/QueryPriorityQueue.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -28,7 +28,7 @@ true true Display - 240 + 290 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,17 +60,17 @@ false - Query Priority Queue + ($(CPUID)) TO - Query Priority Queue true 1 true Label - 182 + 271 false -10b748b0:17773fb054b:-7a20 - 36 - 12 + 12 + 6 @@ -109,7 +109,7 @@ 109 false -10b748b0:17773fb054b:-79df - 12 + 30 36 @@ -123,7 +123,7 @@ importPackage(Packages.org.yamcs.studio.data); var ChannelIdx = 0; var PQueueIdx = VTypeHelper.getString(display.getWidget('PQueueIdx').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/to/QueryPriorityQueue', { +Yamcs.issueCommand('/cfs/$(CPUID)/to/QueryPriorityQueue', { 'ChannelIdx': ChannelIdx, 'PQueueIndex': PQueueIdx});]]> true @@ -171,7 +171,7 @@ $(pv_value) Action Button 72 -10b748b0:17773fb054b:-79c7 - 84 + 102 66 @@ -186,7 +186,7 @@ $(pv_value) - 1 + 4 1 true @@ -228,7 +228,7 @@ $(pv_value) Text Input 100 -10b748b0:17773fb054b:-78ef - 132 + 150 36 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/TO/RemoveMessageFlow.opi b/core/base/tools/commander/workspace_template/Displays/Apps/TO/RemoveMessageFlow.opi index 43e8ccf3d..75f315d9c 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/TO/RemoveMessageFlow.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/TO/RemoveMessageFlow.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - TO - Remove Message Flow + ($(CPUID)) TO - Remove Msg Flow true @@ -28,7 +28,7 @@ true true Display - 220 + 300 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,17 +60,17 @@ false - Remove Message Flow + ($(CPUID)) TO - Remove Message Flow true 1 true Label - 182 + 283 false -10b748b0:17773fb054b:-7a20 - 18 - 12 + 6 + 6 @@ -109,7 +109,7 @@ 85 false -10b748b0:17773fb054b:-7a0f - 6 + 36 36 @@ -123,7 +123,7 @@ importPackage(Packages.org.yamcs.studio.data); var ChannelIdx = 0; var MsgID = VTypeHelper.getString(display.getWidget('MsgID').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/to/RemoveMessageFlow', { +Yamcs.issueCommand('/cfs/$(CPUID)/to/RemoveMessageFlow', { 'ChannelIdx': ChannelIdx, 'MsgID': MsgID});]]> true @@ -171,7 +171,7 @@ $(pv_value) Action Button 90 -10b748b0:17773fb054b:-79c7 - 64 + 94 66 @@ -186,7 +186,7 @@ $(pv_value) - 1 + 4 1 true @@ -228,7 +228,7 @@ $(pv_value) Text Input 103 -10b748b0:17773fb054b:-78ff - 102 + 132 36 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/TO/Scripts/query_diag.py b/core/base/tools/commander/workspace_template/Displays/Apps/TO/Scripts/query_diag.py index 4ccc418e6..d14b2844f 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/TO/Scripts/query_diag.py +++ b/core/base/tools/commander/workspace_template/Displays/Apps/TO/Scripts/query_diag.py @@ -23,7 +23,7 @@ # Hopefully there is a way to alias this stuff in Studio. And then perhaps all of thse python scripts could be auto-generated. # FIXME: I really wish we could just access aggregates. Might be possible through the HTTP client API. -AGGREGATE_PV = "/cfs/to/TO_ChannelDiagTlm_t.PQueue" +AGGREGATE_PV = "/cfs/"+display.getMacroValue("CPUID")+"/to/TO_ChannelDiagTlm_t.PQueue" class UI_Business(Runnable): diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/TO/SendDiag.opi b/core/base/tools/commander/workspace_template/Displays/Apps/TO/SendDiag.opi index 9c68f79e9..3b5343ece 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/TO/SendDiag.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/TO/SendDiag.opi @@ -10,16 +10,16 @@ - 1.5.3 + 1.5.5.202103012118 6 - 100 + 630 true - TO - Send Diag + ($(CPUID)) TO - Send Diag true @@ -28,7 +28,7 @@ true true Display - 220 + 1200 -10b748b0:17773fb054b:-7a2f -1 -1 @@ -60,16 +60,16 @@ false - Send Diag + ($(CPUID)) TO - Diagnostics true 1 true Label - 182 + 284 false -10b748b0:17773fb054b:-7a20 - 18 + 17 12 @@ -82,7 +82,7 @@ importPackage(Packages.org.yamcs.studio.data); var ChannelIdx = 0; -Yamcs.issueCommand('/cfs/to/SendDiag', { +Yamcs.issueCommand('/cfs/$(CPUID)/to/SendDiag', { 'ChannelIdx': ChannelIdx});]]> true @@ -144,7 +144,7 @@ $(pv_value) - 1 + 4 1 true @@ -160,7 +160,7 @@ $(pv_value) Text Update 0 false - /cfs/to/TO_ChannelDiagTlm_t.ChannelIndex + /cfs/$(CPUID)/to/TO_ChannelDiagTlm_t.ChannelIndex 0.0 @@ -236,7 +236,7 @@ $(pv_value) - 1 + 4 1 true @@ -252,7 +252,7 @@ $(pv_value) Text Update_1 0 false - /cfs/to/TO_ChannelDiagTlm_t.TableID + /cfs/$(CPUID)/to/TO_ChannelDiagTlm_t.TableID 0.0 @@ -328,7 +328,7 @@ $(pv_value) - 1 + 4 1 true @@ -344,7 +344,7 @@ $(pv_value) Text Update_2 0 false - /cfs/to/TO_ChannelDiagTlm_t.MemPoolHandle + /cfs/$(CPUID)/to/TO_ChannelDiagTlm_t.MemPoolHandle 0.0 @@ -420,7 +420,7 @@ $(pv_value) - 1 + 4 1 true @@ -436,7 +436,7 @@ $(pv_value) Text Update_3 0 false - /cfs/to/TO_ChannelDiagTlm_t.MemFullCount + /cfs/$(CPUID)/to/TO_ChannelDiagTlm_t.MemFullCount 0.0 @@ -512,7 +512,7 @@ $(pv_value) - 1 + 4 1 true @@ -528,7 +528,7 @@ $(pv_value) Text Update_5 0 false - /cfs/to/TO_ChannelDiagTlm_t.ChannelName + /cfs/$(CPUID)/to/TO_ChannelDiagTlm_t.ChannelName 0.0 @@ -604,7 +604,7 @@ $(pv_value) - 1 + 4 1 true @@ -620,7 +620,7 @@ $(pv_value) Text Update_6 0 false - /cfs/to/TO_ChannelDiagTlm_t.State + /cfs/$(CPUID)/to/TO_ChannelDiagTlm_t.State 0.0 @@ -696,7 +696,7 @@ $(pv_value) - 1 + 4 1 true @@ -712,7 +712,7 @@ $(pv_value) Text Update_7 0 false - /cfs/to/TO_ChannelDiagTlm_t.ConfigTableName + /cfs/$(CPUID)/to/TO_ChannelDiagTlm_t.ConfigTableName 0.0 @@ -788,7 +788,7 @@ $(pv_value) - 1 + 4 1 true @@ -804,7 +804,7 @@ $(pv_value) Text Update_8 0 false - /cfs/to/TO_ChannelDiagTlm_t.DumpTableName + /cfs/$(CPUID)/to/TO_ChannelDiagTlm_t.DumpTableName 0.0 @@ -880,7 +880,7 @@ $(pv_value) - 1 + 4 1 true @@ -896,7 +896,7 @@ $(pv_value) Text Update_9 0 false - /cfs/to/TO_ChannelDiagTlm_t.ConfigTableFileName + /cfs/$(CPUID)/to/TO_ChannelDiagTlm_t.ConfigTableFileName 0.0 @@ -1252,7 +1252,7 @@ $(pv_value) - 1 + 4 1 true @@ -1268,7 +1268,7 @@ $(pv_value) Text Update_10 0 false - /cfs/to/TO_ChannelDiagTlm_t.PQueue_0_.DroppedMsgCnt + /cfs/$(CPUID)/to/TO_ChannelDiagTlm_t.PQueue_0_.DroppedMsgCnt 0.0 @@ -1304,7 +1304,7 @@ $(pv_value) - 1 + 4 1 true @@ -1320,7 +1320,7 @@ $(pv_value) Text Update_11 0 false - /cfs/to/TO_ChannelDiagTlm_t.PQueue_0_.QueuedMsgCnt + /cfs/$(CPUID)/to/TO_ChannelDiagTlm_t.PQueue_0_.QueuedMsgCnt 0.0 @@ -1356,7 +1356,7 @@ $(pv_value) - 1 + 4 1 true @@ -1372,7 +1372,7 @@ $(pv_value) Text Update_12 0 false - /cfs/to/TO_ChannelDiagTlm_t.PQueue_0_.CurrentlyQueuedCnt + /cfs/$(CPUID)/to/TO_ChannelDiagTlm_t.PQueue_0_.CurrentlyQueuedCnt 0.0 @@ -1408,7 +1408,7 @@ $(pv_value) - 1 + 4 1 true @@ -1424,7 +1424,7 @@ $(pv_value) Text Update_13 0 false - /cfs/to/TO_ChannelDiagTlm_t.PQueue_0_.HighwaterMark + /cfs/$(CPUID)/to/TO_ChannelDiagTlm_t.PQueue_0_.HighwaterMark 0.0 @@ -1460,7 +1460,7 @@ $(pv_value) - 1 + 4 1 true @@ -1476,7 +1476,7 @@ $(pv_value) Text Update_14 0 false - /cfs/to/TO_ChannelDiagTlm_t.PQueue_0_.MsgLimit + /cfs/$(CPUID)/to/TO_ChannelDiagTlm_t.PQueue_0_.MsgLimit 0.0 @@ -1512,7 +1512,7 @@ $(pv_value) - 1 + 4 1 true @@ -1528,7 +1528,7 @@ $(pv_value) Text Update_15 0 false - /cfs/to/TO_ChannelDiagTlm_t.PQueue_0_.State + /cfs/$(CPUID)/to/TO_ChannelDiagTlm_t.PQueue_0_.State 0.0 @@ -1564,7 +1564,7 @@ $(pv_value) - 1 + 4 1 true @@ -1580,7 +1580,7 @@ $(pv_value) Text Update_16 0 false - /cfs/to/TO_ChannelDiagTlm_t.PQueue_0_.QType + /cfs/$(CPUID)/to/TO_ChannelDiagTlm_t.PQueue_0_.QType 0.0 @@ -1816,7 +1816,7 @@ $(pv_value) - 1 + 4 1 true @@ -1832,7 +1832,7 @@ $(pv_value) Text Update_17 0 false - /cfs/to/TO_ChannelDiagTlm_t.OQueue.SentCount + /cfs/$(CPUID)/to/TO_ChannelDiagTlm_t.OQueue.SentCount 0.0 @@ -1868,7 +1868,7 @@ $(pv_value) - 1 + 4 1 true @@ -1884,7 +1884,7 @@ $(pv_value) Text Update_18 0 false - /cfs/to/TO_ChannelDiagTlm_t.OQueue.CurrentlyQueuedCnt + /cfs/$(CPUID)/to/TO_ChannelDiagTlm_t.OQueue.CurrentlyQueuedCnt 0.0 @@ -1920,7 +1920,7 @@ $(pv_value) - 1 + 4 1 true @@ -1936,7 +1936,7 @@ $(pv_value) Text Update_19 0 false - /cfs/to/TO_ChannelDiagTlm_t.OQueue.HighwaterMark + /cfs/$(CPUID)/to/TO_ChannelDiagTlm_t.OQueue.HighwaterMark 0.0 @@ -1972,7 +1972,7 @@ $(pv_value) - 1 + 4 1 true @@ -1988,7 +1988,7 @@ $(pv_value) Text Update_20 0 false - /cfs/to/TO_ChannelDiagTlm_t.OQueue.SentBytes + /cfs/$(CPUID)/to/TO_ChannelDiagTlm_t.OQueue.SentBytes 0.0 diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/VM/Arming.opi b/core/base/tools/commander/workspace_template/Displays/Apps/VM/Arming.opi index 8518ff392..407997ea5 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/VM/Arming.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/VM/Arming.opi @@ -103,7 +103,7 @@ Text Update_40 0 false - /cfs/vm/VM_HkTlm_t.ArmingState + /cfs/$(CPUID)/vm/VM_HkTlm_t.ArmingState 0.0 @@ -134,7 +134,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/vm/Arm', {});]]> true @@ -190,7 +190,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/vm/Disarm', {});]]> true diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/VM/Main.opi b/core/base/tools/commander/workspace_template/Displays/Apps/VM/Main.opi index 60ae192c1..623300910 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/VM/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/VM/Main.opi @@ -10,7 +10,7 @@ - 1.5.5.202103162101 + 1.6.2.202104092231 @@ -64,7 +64,7 @@ Text Update 0 false - /cfs/vm/VM_HkTlm_t.CmdCnt + /cfs/$(CPUID)/vm/VM_HkTlm_t.CmdCnt 0.0 @@ -196,7 +196,7 @@ $(pv_value) Text Update_1 0 false - /cfs/vm/VM_HkTlm_t.CmdErrCnt + /cfs/$(CPUID)/vm/VM_HkTlm_t.CmdErrCnt 0.0 @@ -267,7 +267,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/vm/Noop', {});]]> true @@ -323,7 +323,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/vm/Reset', {});]]> true @@ -440,7 +440,7 @@ $(pv_value) Text Update_10 0 false - /cfs/vm/VM_HkTlm_t.WakeupCount + /cfs/$(CPUID)/vm/VM_HkTlm_t.WakeupCount 0.0 @@ -581,7 +581,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/vm/SendHK', {});]]> true @@ -637,7 +637,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/vm/WakeUp', {});]]> true @@ -754,7 +754,7 @@ $(pv_value) Text Update_26 0 false - /cfs/vm/VM_HkTlm_t.BootTimestamp.Seconds + /cfs/$(CPUID)/vm/VM_HkTlm_t.BootTimestamp.Seconds 0.0 @@ -846,7 +846,7 @@ $(pv_value) Text Update_31 0 false - /cfs/vm/VM_HkTlm_t.StickOffCounter + /cfs/$(CPUID)/vm/VM_HkTlm_t.StickOffCounter 0.0 @@ -938,7 +938,7 @@ $(pv_value) Text Update_32 0 false - /cfs/vm/VM_HkTlm_t.StickOnCounter + /cfs/$(CPUID)/vm/VM_HkTlm_t.StickOnCounter 0.0 @@ -1030,7 +1030,7 @@ $(pv_value) Text Update_33 0 false - /cfs/vm/VM_HkTlm_t.LastSpManArmSwitch + /cfs/$(CPUID)/vm/VM_HkTlm_t.LastSpManArmSwitch 0.0 @@ -1122,7 +1122,7 @@ $(pv_value) Text Update_37 0 false - /cfs/vm/VM_HkTlm_t.RCSignalLostTimestamp.Seconds + /cfs/$(CPUID)/vm/VM_HkTlm_t.RCSignalLostTimestamp.Seconds 0.0 @@ -1174,7 +1174,7 @@ $(pv_value) Text Update_42 0 false - /cfs/vm/VM_HkTlm_t.BootTimestamp.Subseconds + /cfs/$(CPUID)/vm/VM_HkTlm_t.BootTimestamp.Subseconds 0.0 @@ -1226,7 +1226,7 @@ $(pv_value) Text Update_43 0 false - /cfs/vm/VM_HkTlm_t.RCSignalLostTimestamp.Subseconds + /cfs/$(CPUID)/vm/VM_HkTlm_t.RCSignalLostTimestamp.Subseconds 0.0 @@ -1311,4 +1311,65 @@ $(pv_value) 10 297 - + + + + + + true + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 20 + + AppControl + 0 + + + + + true + true + false + + + + App Control + false + $(pv_name) +$(pv_value) + true + Action Button + 134 + 49c9ccd0:178c6a335db:-3365 + 10 + 316 + + \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/VM/MessagesReceived.opi b/core/base/tools/commander/workspace_template/Displays/Apps/VM/MessagesReceived.opi index 14902293b..13424e2a4 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/VM/MessagesReceived.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/VM/MessagesReceived.opi @@ -143,7 +143,7 @@ Text Update_2 0 false - /cfs/vm/VM_HkTlm_t.SensorMagMsgCount + /cfs/$(CPUID)/vm/VM_HkTlm_t.SensorMagMsgCount 0.0 @@ -235,7 +235,7 @@ $(pv_value) Text Update_3 0 false - /cfs/vm/VM_HkTlm_t.SensorGyroMsgCount + /cfs/$(CPUID)/vm/VM_HkTlm_t.SensorGyroMsgCount 0.0 @@ -327,7 +327,7 @@ $(pv_value) Text Update_4 0 false - /cfs/vm/VM_HkTlm_t.BatteryStatusMsgCount + /cfs/$(CPUID)/vm/VM_HkTlm_t.BatteryStatusMsgCount 0.0 @@ -419,7 +419,7 @@ $(pv_value) Text Update_5 0 false - /cfs/vm/VM_HkTlm_t.TelemetryStatusMsgCount + /cfs/$(CPUID)/vm/VM_HkTlm_t.TelemetryStatusMsgCount 0.0 @@ -511,7 +511,7 @@ $(pv_value) Text Update_6 0 false - /cfs/vm/VM_HkTlm_t.SubsystemInfoMsgCount + /cfs/$(CPUID)/vm/VM_HkTlm_t.SubsystemInfoMsgCount 0.0 @@ -603,7 +603,7 @@ $(pv_value) Text Update_8 0 false - /cfs/vm/VM_HkTlm_t.VehicleAttitudeMsgCount + /cfs/$(CPUID)/vm/VM_HkTlm_t.VehicleAttitudeMsgCount 0.0 @@ -695,7 +695,7 @@ $(pv_value) Text Update_11 0 false - /cfs/vm/VM_HkTlm_t.VehicleLocalPositionMsgCount + /cfs/$(CPUID)/vm/VM_HkTlm_t.VehicleLocalPositionMsgCount 0.0 @@ -787,7 +787,7 @@ $(pv_value) Text Update_12 0 false - /cfs/vm/VM_HkTlm_t.VehicleLandDetectedMsgCount + /cfs/$(CPUID)/vm/VM_HkTlm_t.VehicleLandDetectedMsgCount 0.0 @@ -879,7 +879,7 @@ $(pv_value) Text Update_13 0 false - /cfs/vm/VM_HkTlm_t.MissionResultMsgCount + /cfs/$(CPUID)/vm/VM_HkTlm_t.MissionResultMsgCount 0.0 @@ -971,7 +971,7 @@ $(pv_value) Text Update_14 0 false - /cfs/vm/VM_HkTlm_t.ManualControlSetpointMsgCount + /cfs/$(CPUID)/vm/VM_HkTlm_t.ManualControlSetpointMsgCount 0.0 @@ -1063,7 +1063,7 @@ $(pv_value) Text Update_15 0 false - /cfs/vm/VM_HkTlm_t.PositionSetpointTripletMsgCount + /cfs/$(CPUID)/vm/VM_HkTlm_t.PositionSetpointTripletMsgCount 0.0 @@ -1155,7 +1155,7 @@ $(pv_value) Text Update_16 0 false - /cfs/vm/VM_HkTlm_t.SensorAccelMsgCount + /cfs/$(CPUID)/vm/VM_HkTlm_t.SensorAccelMsgCount 0.0 @@ -1247,7 +1247,7 @@ $(pv_value) Text Update_17 0 false - /cfs/vm/VM_HkTlm_t.SafetyMsgCount + /cfs/$(CPUID)/vm/VM_HkTlm_t.SafetyMsgCount 0.0 @@ -1339,7 +1339,7 @@ $(pv_value) Text Update_18 0 false - /cfs/vm/VM_HkTlm_t.SensorCorrectionMsgCount + /cfs/$(CPUID)/vm/VM_HkTlm_t.SensorCorrectionMsgCount 0.0 @@ -1431,7 +1431,7 @@ $(pv_value) Text Update_19 0 false - /cfs/vm/VM_HkTlm_t.SensorCombinedMsgCount + /cfs/$(CPUID)/vm/VM_HkTlm_t.SensorCombinedMsgCount 0.0 @@ -1523,7 +1523,7 @@ $(pv_value) Text Update_20 0 false - /cfs/vm/VM_HkTlm_t.VehicleCommandMsgCount + /cfs/$(CPUID)/vm/VM_HkTlm_t.VehicleCommandMsgCount 0.0 @@ -1615,7 +1615,7 @@ $(pv_value) Text Update_21 0 false - /cfs/vm/VM_HkTlm_t.VehicleGlobalPositionMsgCount + /cfs/$(CPUID)/vm/VM_HkTlm_t.VehicleGlobalPositionMsgCount 0.0 @@ -1707,7 +1707,7 @@ $(pv_value) Text Update_22 0 false - /cfs/vm/VM_HkTlm_t.VehicleGpsPositionMsgCount + /cfs/$(CPUID)/vm/VM_HkTlm_t.VehicleGpsPositionMsgCount 0.0 @@ -1799,7 +1799,7 @@ $(pv_value) Text Update_23 0 false - /cfs/vm/VM_HkTlm_t.VehicleStatusMsgCount + /cfs/$(CPUID)/vm/VM_HkTlm_t.VehicleStatusMsgCount 0.0 @@ -1891,7 +1891,7 @@ $(pv_value) Text Update_24 0 false - /cfs/vm/VM_HkTlm_t.VehicleControlModeMsgCount + /cfs/$(CPUID)/vm/VM_HkTlm_t.VehicleControlModeMsgCount 0.0 diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/VM/Moding.opi b/core/base/tools/commander/workspace_template/Displays/Apps/VM/Moding.opi index a2e4a6acd..adc313a5c 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/VM/Moding.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/VM/Moding.opi @@ -42,7 +42,7 @@ +Yamcs.issueCommand('/cfs/$(CPUID)/vm/Manual', {});]]> true @@ -98,7 +98,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/vm/AutoLoiter', {});]]> true @@ -154,7 +154,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/vm/AutoRtl', {});]]> true @@ -210,7 +210,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/vm/AutoTakeoff', {});]]> true @@ -266,7 +266,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/vm/AutoLand', {});]]> true @@ -322,7 +322,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/vm/Acrobatic', {});]]> true @@ -378,7 +378,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/vm/Rattitude', {});]]> true @@ -434,7 +434,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/vm/Stabilized', {});]]> true @@ -551,7 +551,7 @@ $(pv_value) Text Update_41 0 false - /cfs/vm/VM_HkTlm_t.NavState + /cfs/$(CPUID)/vm/VM_HkTlm_t.NavState 0.0 @@ -693,7 +693,7 @@ $(pv_value) ON - /cfs/vm/VM_HkTlm_t.PreviousModes.inPosCtl + /cfs/$(CPUID)/vm/VM_HkTlm_t.PreviousModes.inPosCtl @@ -791,7 +791,7 @@ $(pv_value) ON - /cfs/vm/VM_HkTlm_t.PreviousModes.inRtl + /cfs/$(CPUID)/vm/VM_HkTlm_t.PreviousModes.inRtl @@ -889,7 +889,7 @@ $(pv_value) ON - /cfs/vm/VM_HkTlm_t.PreviousModes.inLoiter + /cfs/$(CPUID)/vm/VM_HkTlm_t.PreviousModes.inLoiter @@ -987,7 +987,7 @@ $(pv_value) ON - /cfs/vm/VM_HkTlm_t.PreviousModes.inManual + /cfs/$(CPUID)/vm/VM_HkTlm_t.PreviousModes.inManual @@ -1085,7 +1085,7 @@ $(pv_value) ON - /cfs/vm/VM_HkTlm_t.PreviousModes.inTakeoff + /cfs/$(CPUID)/vm/VM_HkTlm_t.PreviousModes.inTakeoff @@ -1183,7 +1183,7 @@ $(pv_value) ON - /cfs/vm/VM_HkTlm_t.PreviousModes.inAltCtl + /cfs/$(CPUID)/vm/VM_HkTlm_t.PreviousModes.inAltCtl diff --git a/core/base/tools/commander/workspace_template/Displays/Apps/VM/State.opi b/core/base/tools/commander/workspace_template/Displays/Apps/VM/State.opi index 696e8fcde..372568dee 100644 --- a/core/base/tools/commander/workspace_template/Displays/Apps/VM/State.opi +++ b/core/base/tools/commander/workspace_template/Displays/Apps/VM/State.opi @@ -433,7 +433,7 @@ ON - /cfs/vm/VM_HkTlm_t.NotInitialized + /cfs/$(CPUID)/vm/VM_HkTlm_t.NotInitialized @@ -491,7 +491,7 @@ $(pv_value) ON - /cfs/vm/VM_HkTlm_t.LocalPositionIsValid + /cfs/$(CPUID)/vm/VM_HkTlm_t.LocalPositionIsValid @@ -549,7 +549,7 @@ $(pv_value) ON - /cfs/vm/VM_HkTlm_t.PrevLanded + /cfs/$(CPUID)/vm/VM_HkTlm_t.PrevLanded @@ -607,7 +607,7 @@ $(pv_value) ON - /cfs/vm/VM_HkTlm_t.PrevInFlight + /cfs/$(CPUID)/vm/VM_HkTlm_t.PrevInFlight @@ -665,7 +665,7 @@ $(pv_value) ON - /cfs/vm/VM_HkTlm_t.LowBatteryVoltageActionsDone + /cfs/$(CPUID)/vm/VM_HkTlm_t.LowBatteryVoltageActionsDone @@ -723,7 +723,7 @@ $(pv_value) ON - /cfs/vm/VM_HkTlm_t.EmergencyBatteryVoltageActionsDone + /cfs/$(CPUID)/vm/VM_HkTlm_t.EmergencyBatteryVoltageActionsDone @@ -781,7 +781,7 @@ $(pv_value) ON - /cfs/vm/VM_HkTlm_t.CriticalBatteryVoltageActionsDone + /cfs/$(CPUID)/vm/VM_HkTlm_t.CriticalBatteryVoltageActionsDone @@ -839,7 +839,7 @@ $(pv_value) ON - /cfs/vm/VM_HkTlm_t.ArmingStateChanged + /cfs/$(CPUID)/vm/VM_HkTlm_t.ArmingStateChanged @@ -937,7 +937,7 @@ $(pv_value) ON - /cfs/vm/VM_HkTlm_t.StatusFlags.SensorsInitialized + /cfs/$(CPUID)/vm/VM_HkTlm_t.StatusFlags.SensorsInitialized @@ -1035,7 +1035,7 @@ $(pv_value) ON - /cfs/vm/VM_HkTlm_t.StatusFlags.ReturnToHomeSet + /cfs/$(CPUID)/vm/VM_HkTlm_t.StatusFlags.ReturnToHomeSet @@ -1133,7 +1133,7 @@ $(pv_value) ON - /cfs/vm/VM_HkTlm_t.StatusFlags.HomePositionValid + /cfs/$(CPUID)/vm/VM_HkTlm_t.StatusFlags.HomePositionValid @@ -1231,7 +1231,7 @@ $(pv_value) ON - /cfs/vm/VM_HkTlm_t.StatusFlags.UsbPowerConnected + /cfs/$(CPUID)/vm/VM_HkTlm_t.StatusFlags.UsbPowerConnected @@ -1329,7 +1329,7 @@ $(pv_value) ON - /cfs/vm/VM_HkTlm_t.StatusFlags.RcSignalFoundOnce + /cfs/$(CPUID)/vm/VM_HkTlm_t.StatusFlags.RcSignalFoundOnce @@ -1427,7 +1427,7 @@ $(pv_value) ON - /cfs/vm/VM_HkTlm_t.StatusFlags.RcSignalLostModeIsCmded + /cfs/$(CPUID)/vm/VM_HkTlm_t.StatusFlags.RcSignalLostModeIsCmded @@ -1525,7 +1525,7 @@ $(pv_value) ON - /cfs/vm/VM_HkTlm_t.StatusFlags.RcInputIsTemporarilyBlocked + /cfs/$(CPUID)/vm/VM_HkTlm_t.StatusFlags.RcInputIsTemporarilyBlocked diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/ApplicationControl_App.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/ApplicationControl_App.opi index ce1e73616..328c45cd4 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/ApplicationControl_App.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/ApplicationControl_App.opi @@ -10,7 +10,7 @@ - 1.5.5.202103162101 + 1.6.2.202104092231 @@ -20,7 +20,7 @@ true /modules/core/modules/cfe/modules/cfe_es - App Control + ($(CPUID)) App Control @@ -105,7 +105,7 @@ Text Update_15 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.StartAddress + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.StartAddress 0.0 @@ -197,7 +197,7 @@ $(pv_value) inExceptionAction 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.ExceptionAction + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.ExceptionAction 0.0 @@ -289,7 +289,7 @@ $(pv_value) inPriority 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.Priority + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.Priority 0.0 @@ -381,7 +381,7 @@ $(pv_value) Text Update_18 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.MainTaskId + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.MainTaskId 0.0 @@ -473,7 +473,7 @@ $(pv_value) Text Update_19 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.ExecutionCounter + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.ExecutionCounter 0.0 @@ -565,7 +565,7 @@ $(pv_value) Text Update_20 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.MainTaskName + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.MainTaskName 0.0 @@ -657,7 +657,7 @@ $(pv_value) Text Update_21 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.NumOfChildTasks + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.NumOfChildTasks 0.0 @@ -749,7 +749,7 @@ $(pv_value) Text Update_1 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.AppId + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.AppId 0.0 @@ -841,7 +841,7 @@ $(pv_value) Text Update_2 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.Type + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.Type 0.0 @@ -933,7 +933,7 @@ $(pv_value) inAppName 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.Name + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.Name 0.0 @@ -1025,7 +1025,7 @@ $(pv_value) inEntryPoint 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.EntryPoint + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.EntryPoint 0.0 @@ -1117,7 +1117,7 @@ $(pv_value) inFileName 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.FileName + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.FileName 0.0 @@ -1209,7 +1209,7 @@ $(pv_value) inStackSize 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.StackSize + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.StackSize 0.0 @@ -1301,7 +1301,7 @@ $(pv_value) Text Update_7 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.ModuleId + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.ModuleId 0.0 @@ -1393,7 +1393,7 @@ $(pv_value) Text Update_8 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.AddressesAreValid + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.AddressesAreValid 0.0 @@ -1485,7 +1485,7 @@ $(pv_value) Text Update_9 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.CodeAddress + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.CodeAddress 0.0 @@ -1577,7 +1577,7 @@ $(pv_value) Text Update_10 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.CodeSize + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.CodeSize 0.0 @@ -1669,7 +1669,7 @@ $(pv_value) Text Update_11 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.DataAddress + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.DataAddress 0.0 @@ -1761,7 +1761,7 @@ $(pv_value) Text Update_12 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.DataSize + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.DataSize 0.0 @@ -1853,7 +1853,7 @@ $(pv_value) Text Update_13 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.BSSAddress + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.BSSAddress 0.0 @@ -1945,7 +1945,7 @@ $(pv_value) Text Update_14 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.BSSSize + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.BSSSize 0.0 @@ -1997,7 +1997,7 @@ $(pv_value) false - Application Control + ($(CPUID)) Application Control true 1 @@ -2022,7 +2022,7 @@ app_name = display.getMacroValue("APP"); if app_name: app_name = app_name.upper() -Yamcs.issueCommand('/cfs/cfe_es/QueryOneApp', {"Payload.Application": app_name}); +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/QueryOneApp', {"Payload.Application": app_name}); ]]> true @@ -2074,12 +2074,19 @@ $(pv_value) - + - +#We assume that the parent has defined this macro +app_name = display.getMacroValue("APP"); + +if app_name: + app_name = app_name.upper() + +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/RestartApp', {"Payload.Application": app_name}); +]]> true @@ -2246,12 +2253,19 @@ $(pv_value) - + - +#We assume that the parent has defined this macro +app_name = display.getMacroValue("APP"); + +if app_name: + app_name = app_name.upper() + +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/StopApp', {"Payload.Application": app_name}); +]]> true diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/ApplicationControl_General.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/ApplicationControl_General.opi index ce0e56527..79f0b24ef 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/ApplicationControl_General.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/ApplicationControl_General.opi @@ -18,9 +18,9 @@ 500 true - /Displays/Resources/definitions.yaml + /Displays/Resources/config_registry.yaml - CFE-ES - App Control + ($(CPUID)) CFE-ES - App Control true @@ -101,7 +101,7 @@ Text Update_15 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.StartAddress + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.StartAddress 0.0 @@ -193,7 +193,7 @@ $(pv_value) inExceptionAction 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.ExceptionAction + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.ExceptionAction 0.0 @@ -285,7 +285,7 @@ $(pv_value) inPriority 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.Priority + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.Priority 0.0 @@ -377,7 +377,7 @@ $(pv_value) Text Update_18 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.MainTaskId + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.MainTaskId 0.0 @@ -469,7 +469,7 @@ $(pv_value) Text Update_19 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.ExecutionCounter + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.ExecutionCounter 0.0 @@ -561,7 +561,7 @@ $(pv_value) Text Update_20 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.MainTaskName + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.MainTaskName 0.0 @@ -653,7 +653,7 @@ $(pv_value) Text Update_21 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.NumOfChildTasks + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.NumOfChildTasks 0.0 @@ -745,7 +745,7 @@ $(pv_value) Text Update_1 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.AppId + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.AppId 0.0 @@ -837,7 +837,7 @@ $(pv_value) Text Update_2 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.Type + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.Type 0.0 @@ -929,7 +929,7 @@ $(pv_value) inAppName 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.Name + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.Name 0.0 @@ -1021,7 +1021,7 @@ $(pv_value) inEntryPoint 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.EntryPoint + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.EntryPoint 0.0 @@ -1113,7 +1113,7 @@ $(pv_value) inFileName 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.FileName + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.FileName 0.0 @@ -1205,7 +1205,7 @@ $(pv_value) inStackSize 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.StackSize + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.StackSize 0.0 @@ -1297,7 +1297,7 @@ $(pv_value) Text Update_7 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.ModuleId + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.ModuleId 0.0 @@ -1389,7 +1389,7 @@ $(pv_value) Text Update_8 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.AddressesAreValid + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.AddressesAreValid 0.0 @@ -1481,7 +1481,7 @@ $(pv_value) Text Update_9 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.CodeAddress + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.CodeAddress 0.0 @@ -1573,7 +1573,7 @@ $(pv_value) Text Update_10 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.CodeSize + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.CodeSize 0.0 @@ -1665,7 +1665,7 @@ $(pv_value) Text Update_11 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.DataAddress + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.DataAddress 0.0 @@ -1757,7 +1757,7 @@ $(pv_value) Text Update_12 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.DataSize + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.DataSize 0.0 @@ -1849,7 +1849,7 @@ $(pv_value) Text Update_13 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.BSSAddress + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.BSSAddress 0.0 @@ -1941,7 +1941,7 @@ $(pv_value) Text Update_14 0 false - /cfs/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.BSSSize + /cfs/$(CPUID)/cfe_es/CFE_ES_OneAppTlm_t.Payload.AppInfo.BSSSize 0.0 @@ -1993,7 +1993,7 @@ $(pv_value) false - Application Control + ($(CPUID)) Application Control true 1 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/Console.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/Console.opi index eed645523..a16033643 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/Console.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/Console.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.6.2.202104092231 @@ -19,7 +19,7 @@ true - CFE-ES - Console + ($(CPUID)) CFE-ES - Console @@ -35,7 +35,7 @@ var combined = prevOutput + newOutput; display.getWidget('ConsoleDisplay').setPropertyValue('pv_value', combined); ]]> - /cfs/cfe_es/CFE_ES_ShellPacket_t.Payload.ShellOutput + /cfs/$(CPUID)/cfe_es/CFE_ES_ShellPacket_t.Payload.ShellOutput true @@ -59,7 +59,7 @@ importPackage(Packages.org.yamcs.studio.data); var consoleInput =VTypeHelper.getString(display.getWidget('inConsoleInput').getPropertyValue('pv_value')); var fileName =VTypeHelper.getString(display.getWidget('inFileName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_es/ShellCmd', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/ShellCmd', { 'Payload.CmdString': consoleInput, 'Payload.OutputFilename': fileName}); @@ -140,7 +140,7 @@ $(pv_value) false - Console + ($(CPUID)) Console true 1 @@ -150,7 +150,7 @@ $(pv_value) false -e1e6812:1508d3700d4:-75c4 276 - 12 + 9 @@ -300,7 +300,7 @@ $(pv_value) 1 true Label - 64 + 65 false -e1e6812:1508d3700d4:-747d 11 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/DeleteCDS.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/DeleteCDS.opi index a68503df0..53e630f8d 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/DeleteCDS.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/DeleteCDS.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-ES - Delete CDS + ($(CPUID)) CFE-ES - Delete CDS true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var name =VTypeHelper.getString(display.getWidget('inName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_es/DeleteCDS', {'Payload.CdsName': name}); +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/DeleteCDS', {'Payload.CdsName': name}); ]]> true @@ -160,16 +160,16 @@ $(pv_value) false - Delete Critical Data Store + ($(CPUID)) Delete Critical Data Store true 1 true Label - 231 + 254 false 72a2bf2b:1508717c835:-76c0 - 11 + 6 12 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/DumpCDSReg.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/DumpCDSReg.opi index afa4250f1..c3e4aa092 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/DumpCDSReg.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/DumpCDSReg.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-ES - Dump CDS Reg + ($(CPUID)) CFE-ES - Dump CDS Reg true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var fileName =VTypeHelper.getString(display.getWidget('inFileName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_es/DumpCDSReg', {'Payload.DumpFilename': fileName}); +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/DumpCDSReg', {'Payload.DumpFilename': fileName}); ]]> true @@ -161,16 +161,16 @@ $(pv_value) false - Dump Critical Data Store Registry to File System + ($(CPUID)) Dump Critical Data Store Registry to File System true 1 true Label - 361 + 421 false 72a2bf2b:1508717c835:-76c0 - 24 + 6 12 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/Main.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/Main.opi index 044177bbb..91480d8ef 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/Main.opi @@ -10,7 +10,7 @@ - 1.5.5.202103162101 + 1.5.5.202103012118 @@ -23,7 +23,7 @@ Displays /modules/core/modules/cfe/modules/cfe_es - CFE-ES - Main + ($(CPUID)) CFE-ES - Main true @@ -64,7 +64,7 @@ Text Update 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.CmdCounter + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.CmdCounter 0.0 @@ -1556,7 +1556,7 @@ $(pv_value) Text Update_1 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.ErrCounter + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.ErrCounter 0.0 @@ -1608,7 +1608,7 @@ $(pv_value) Text Update_2 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.CFECoreChecksum + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.CFECoreChecksum 0.0 @@ -1660,7 +1660,7 @@ $(pv_value) Text Update_3 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.CFEMajorVersion + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.CFEMajorVersion 0.0 @@ -1712,7 +1712,7 @@ $(pv_value) Text Update_4 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.CFEMinorVersion + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.CFEMinorVersion 0.0 @@ -1764,7 +1764,7 @@ $(pv_value) Text Update_5 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.CFERevision + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.CFERevision 0.0 @@ -1816,7 +1816,7 @@ $(pv_value) Text Update_6 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.CFEMissionRevision + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.CFEMissionRevision 0.0 @@ -1868,7 +1868,7 @@ $(pv_value) Text Update_7 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.OSALMajorVersion + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.OSALMajorVersion 0.0 @@ -1920,7 +1920,7 @@ $(pv_value) Text Update_8 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.OSALMinorVersion + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.OSALMinorVersion 0.0 @@ -1972,7 +1972,7 @@ $(pv_value) Text Update_9 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.OSALRevision + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.OSALRevision 0.0 @@ -2024,7 +2024,7 @@ $(pv_value) Text Update_10 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.OSALMissionRevision + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.OSALMissionRevision 0.0 @@ -2076,7 +2076,7 @@ $(pv_value) Text Update_11 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.SysLogSize + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.SysLogSize 0.0 @@ -2128,7 +2128,7 @@ $(pv_value) Text Update_12 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.SysLogEntries + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.SysLogEntries 0.0 @@ -2180,7 +2180,7 @@ $(pv_value) Text Update_13 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.SysLogMode + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.SysLogMode 0.0 @@ -2232,7 +2232,7 @@ $(pv_value) Text Update_14 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.ERLogIndex + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.ERLogIndex 0.0 @@ -2284,7 +2284,7 @@ $(pv_value) Text Update_15 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.ERLogEntries + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.ERLogEntries 0.0 @@ -2336,7 +2336,7 @@ $(pv_value) Text Update_16 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.RegisteredExternalApps + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.RegisteredExternalApps 0.0 @@ -2388,7 +2388,7 @@ $(pv_value) Text Update_17 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.RegisteredTasks + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.RegisteredTasks 0.0 @@ -2440,7 +2440,7 @@ $(pv_value) Text Update_18 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.RegisteredLibs + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.RegisteredLibs 0.0 @@ -2492,7 +2492,7 @@ $(pv_value) Text Update_19 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.RegisteredCoreApps + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.RegisteredCoreApps 0.0 @@ -2544,7 +2544,7 @@ $(pv_value) Text Update_29 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.HeapBytesFree + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.HeapBytesFree 0.0 @@ -2596,7 +2596,7 @@ $(pv_value) Text Update_30 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.HeapBlocksFree + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.HeapBlocksFree 0.0 @@ -2648,7 +2648,7 @@ $(pv_value) Text Update_31 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.HeapMaxBlockSize + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.HeapMaxBlockSize 0.0 @@ -2700,7 +2700,7 @@ $(pv_value) Text Update_32 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.ResetType + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.ResetType 0.0 @@ -2752,7 +2752,7 @@ $(pv_value) Text Update_33 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.ResetSubtype + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.ResetSubtype 0.0 @@ -2804,7 +2804,7 @@ $(pv_value) Text Update_34 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.ProcessorResets + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.ProcessorResets 0.0 @@ -2856,7 +2856,7 @@ $(pv_value) Text Update_35 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.MaxProcessorResets + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.MaxProcessorResets 0.0 @@ -2908,7 +2908,7 @@ $(pv_value) Text Update_36 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.BootSource + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.BootSource 0.0 @@ -2939,7 +2939,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/Noop', {});]]> true @@ -2995,7 +2995,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/Reset', {});]]> true @@ -3051,7 +3051,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/Restart', {'Payload.RestartType': 'PROCESSOR_RESET'});]]> true @@ -3107,7 +3107,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/Restart', {'Payload.RestartType': 'POWERON_RESET'});]]> true @@ -3224,7 +3224,7 @@ $(pv_value) Text Update_38 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.SysLogBytesUsed + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.SysLogBytesUsed 0.0 @@ -3371,16 +3371,16 @@ $(pv_value) false - Core Flight Executive - Essential Services + ($(CPUID)) Core Flight Executive - Essential Services true 1 true Label - 295 + 475 false 763e00b7:150973f1dd8:-7cf4 - 213 + 102 12 @@ -3390,7 +3390,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/ClearSysLog', {});]]> true @@ -3611,7 +3611,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/ClearERLog', {});]]> true @@ -3667,7 +3667,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/ResetPRCount', {});]]> true @@ -3833,7 +3833,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/SendHK', {});]]> true diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/MemoryPoolViewer.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/MemoryPoolViewer.opi index e8ed2c421..d729a9836 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/MemoryPoolViewer.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/MemoryPoolViewer.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-ES - MemPool + ($(CPUID)) CFE-ES - MemPool true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var poolHandle =display.getWidget('inPoolHandle').getPropertyValue('text'); -Yamcs.issueCommand('/cfs/cfe_es/TlmPoolStats', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/TlmPoolStats', { 'Payload.Application': '', 'Payload.PoolHandle': poolHandle}); ]]> @@ -122,7 +122,7 @@ $(pv_value) Handle 0 true - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolHandle + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolHandle 0.0 @@ -174,7 +174,7 @@ $(pv_value) Text Update_23 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.PoolSize + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.PoolSize 0.0 @@ -226,7 +226,7 @@ $(pv_value) Text Update_24 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.NumBlocksRequested + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.NumBlocksRequested 0.0 @@ -278,7 +278,7 @@ $(pv_value) Text Update_25 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.CheckErrCtr + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.CheckErrCtr 0.0 @@ -330,7 +330,7 @@ $(pv_value) Text Update_26 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.NumFreeBytes + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.NumFreeBytes 0.0 @@ -1519,7 +1519,7 @@ $(pv_value) Text Update_27 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_0_.BlockSize + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_0_.BlockSize 0.0 @@ -1571,7 +1571,7 @@ $(pv_value) Text Update_28 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_0_.NumCreated + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_0_.NumCreated 0.0 @@ -1623,7 +1623,7 @@ $(pv_value) Text Update_29 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_0_.NumFree + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_0_.NumFree 0.0 @@ -1675,7 +1675,7 @@ $(pv_value) Text Update_80 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_1_.BlockSize + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_1_.BlockSize 0.0 @@ -1727,7 +1727,7 @@ $(pv_value) Text Update_81 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_1_.NumCreated + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_1_.NumCreated 0.0 @@ -1779,7 +1779,7 @@ $(pv_value) Text Update_82 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_1_.NumFree + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_1_.NumFree 0.0 @@ -1831,7 +1831,7 @@ $(pv_value) Text Update_83 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_2_.BlockSize + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_2_.BlockSize 0.0 @@ -1883,7 +1883,7 @@ $(pv_value) Text Update_84 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_2_.NumCreated + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_2_.NumCreated 0.0 @@ -1935,7 +1935,7 @@ $(pv_value) Text Update_85 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_2_.NumFree + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_2_.NumFree 0.0 @@ -1987,7 +1987,7 @@ $(pv_value) Text Update_86 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_3_.BlockSize + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_3_.BlockSize 0.0 @@ -2039,7 +2039,7 @@ $(pv_value) Text Update_87 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_3_.NumCreated + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_3_.NumCreated 0.0 @@ -2091,7 +2091,7 @@ $(pv_value) Text Update_88 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_3_.NumFree + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_3_.NumFree 0.0 @@ -2143,7 +2143,7 @@ $(pv_value) Text Update_89 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_4_.BlockSize + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_4_.BlockSize 0.0 @@ -2195,7 +2195,7 @@ $(pv_value) Text Update_90 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_4_.NumCreated + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_4_.NumCreated 0.0 @@ -2247,7 +2247,7 @@ $(pv_value) Text Update_91 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_4_.NumFree + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_4_.NumFree 0.0 @@ -2299,7 +2299,7 @@ $(pv_value) Text Update_92 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_5_.BlockSize + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_5_.BlockSize 0.0 @@ -2351,7 +2351,7 @@ $(pv_value) Text Update_93 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_5_.NumCreated + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_5_.NumCreated 0.0 @@ -2403,7 +2403,7 @@ $(pv_value) Text Update_94 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_5_.NumFree + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_5_.NumFree 0.0 @@ -2455,7 +2455,7 @@ $(pv_value) Text Update_95 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_6_.BlockSize + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_6_.BlockSize 0.0 @@ -2507,7 +2507,7 @@ $(pv_value) Text Update_96 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_6_.NumCreated + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_6_.NumCreated 0.0 @@ -2559,7 +2559,7 @@ $(pv_value) Text Update_97 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_6_.NumFree + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_6_.NumFree 0.0 @@ -2611,7 +2611,7 @@ $(pv_value) Text Update_98 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_7_.BlockSize + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_7_.BlockSize 0.0 @@ -2663,7 +2663,7 @@ $(pv_value) Text Update_99 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_7_.NumCreated + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_7_.NumCreated 0.0 @@ -2715,7 +2715,7 @@ $(pv_value) Text Update_100 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_7_.NumFree + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_7_.NumFree 0.0 @@ -2767,7 +2767,7 @@ $(pv_value) Text Update_101 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_8_.BlockSize + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_8_.BlockSize 0.0 @@ -2819,7 +2819,7 @@ $(pv_value) Text Update_102 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_8_.NumCreated + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_8_.NumCreated 0.0 @@ -2871,7 +2871,7 @@ $(pv_value) Text Update_103 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_8_.NumFree + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_8_.NumFree 0.0 @@ -2923,7 +2923,7 @@ $(pv_value) Text Update_104 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_9_.BlockSize + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_9_.BlockSize 0.0 @@ -2975,7 +2975,7 @@ $(pv_value) Text Update_105 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_9_.NumCreated + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_9_.NumCreated 0.0 @@ -3027,7 +3027,7 @@ $(pv_value) Text Update_106 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_9_.NumFree + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_9_.NumFree 0.0 @@ -3079,7 +3079,7 @@ $(pv_value) Text Update_107 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_10_.BlockSize + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_10_.BlockSize 0.0 @@ -3131,7 +3131,7 @@ $(pv_value) Text Update_108 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_10_.NumCreated + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_10_.NumCreated 0.0 @@ -3183,7 +3183,7 @@ $(pv_value) Text Update_109 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_10_.NumFree + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_10_.NumFree 0.0 @@ -3235,7 +3235,7 @@ $(pv_value) Text Update_110 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_11_.BlockSize + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_11_.BlockSize 0.0 @@ -3287,7 +3287,7 @@ $(pv_value) Text Update_111 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_11_.NumCreated + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_11_.NumCreated 0.0 @@ -3339,7 +3339,7 @@ $(pv_value) Text Update_112 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_11_.NumFree + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_11_.NumFree 0.0 @@ -3391,7 +3391,7 @@ $(pv_value) Text Update_113 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_12_.BlockSize + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_12_.BlockSize 0.0 @@ -3443,7 +3443,7 @@ $(pv_value) Text Update_114 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_12_.NumCreated + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_12_.NumCreated 0.0 @@ -3495,7 +3495,7 @@ $(pv_value) Text Update_115 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_12_.NumFree + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_12_.NumFree 0.0 @@ -3547,7 +3547,7 @@ $(pv_value) Text Update_116 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_13_.BlockSize + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_13_.BlockSize 0.0 @@ -3599,7 +3599,7 @@ $(pv_value) Text Update_117 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_13_.NumCreated + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_13_.NumCreated 0.0 @@ -3651,7 +3651,7 @@ $(pv_value) Text Update_118 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_13_.NumFree + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_13_.NumFree 0.0 @@ -3703,7 +3703,7 @@ $(pv_value) Text Update_119 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_14_.BlockSize + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_14_.BlockSize 0.0 @@ -3755,7 +3755,7 @@ $(pv_value) Text Update_120 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_14_.NumCreated + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_14_.NumCreated 0.0 @@ -3807,7 +3807,7 @@ $(pv_value) Text Update_121 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_14_.NumFree + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_14_.NumFree 0.0 @@ -3859,7 +3859,7 @@ $(pv_value) Text Update_122 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_15_.BlockSize + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_15_.BlockSize 0.0 @@ -3911,7 +3911,7 @@ $(pv_value) Text Update_123 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_15_.NumCreated + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_15_.NumCreated 0.0 @@ -3963,7 +3963,7 @@ $(pv_value) Text Update_124 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_15_.NumFree + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_15_.NumFree 0.0 @@ -4015,7 +4015,7 @@ $(pv_value) Text Update_125 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_16_.BlockSize + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_16_.BlockSize 0.0 @@ -4067,7 +4067,7 @@ $(pv_value) Text Update_126 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_16_.NumCreated + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_16_.NumCreated 0.0 @@ -4119,7 +4119,7 @@ $(pv_value) Text Update_127 0 false - /cfs/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_16_.NumFree + /cfs/$(CPUID)/cfe_es/CFE_ES_PoolStatsTlm_t.Payload.PoolStats.BlockStats_16_.NumFree 0.0 @@ -4171,16 +4171,16 @@ $(pv_value) false - Memory Pool Viewer + ($(CPUID)) Memory Pool Viewer true 1 true Label - 164 + 281 false -2dc23c5:177557ff444:-635b - 96 + 56 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/PerfCollection.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/PerfCollection.opi index 256ddc5c8..7e649912c 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/PerfCollection.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/PerfCollection.opi @@ -10,7 +10,7 @@ - 1.5.5.202103162101 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-ES - Perf + ($(CPUID)) CFE-ES - Perf @@ -38,7 +38,7 @@ for(var i = 1; i <= 32; ++i) { } display.getWidget(RequestFilterName).setPropertyValue('pv_value', newValue); }]]> - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.PerfFilterMask_0_ + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.PerfFilterMask_0_ true @@ -359,16 +359,16 @@ for(var i = 1; i <= 32; ++i) { false - Performance Collection + ($(CPUID)) Performance Collection true 1 true Label - 193 + 344 false 2b4f25d5:1502b5812fe:-7d80 - 243 + 167 12 @@ -399,7 +399,7 @@ for(var i = 1; i <= 32; ++i) { Text Update_20 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.PerfState + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.PerfState 0.0 @@ -451,7 +451,7 @@ $(pv_value) Text Update_21 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.PerfMode + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.PerfMode 0.0 @@ -503,7 +503,7 @@ $(pv_value) Text Update_22 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.PerfTriggerCount + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.PerfTriggerCount 0.0 @@ -555,7 +555,7 @@ $(pv_value) Text Update_25 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.PerfDataStart + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.PerfDataStart 0.0 @@ -607,7 +607,7 @@ $(pv_value) Text Update_26 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.PerfDataEnd + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.PerfDataEnd 0.0 @@ -659,7 +659,7 @@ $(pv_value) Text Update_27 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.PerfDataCount + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.PerfDataCount 0.0 @@ -711,7 +711,7 @@ $(pv_value) Text Update_28 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.PerfDataToWrite + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.PerfDataToWrite 0.0 @@ -8527,7 +8527,7 @@ for i in range(1,32): else: maskValue = int(maskValue) | 0x80000000 -Yamcs.issueCommand( '/cfs/cfe_es/PerfSetFilterMask', { +Yamcs.issueCommand( '/cfs/$(CPUID)/cfe_es/PerfSetFilterMask', { 'Payload.FilterMaskNum': maskNumber, 'Payload.FilterMask': maskValue});]]> true @@ -8586,7 +8586,7 @@ $(pv_value) importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); -var cmdString = '/cfs/cfe_es/PerfSetTriggerMask1('; +var cmdString = '/cfs/$(CPUID)/cfe_es/PerfSetTriggerMask1('; for(var i = 1; i <= 32; ++i) { var PerfID = 'PerfTrigger' + i; diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/QueryAllApps.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/QueryAllApps.opi index f10033a83..a51efcbe9 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/QueryAllApps.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/QueryAllApps.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-ES - Query All Apps + ($(CPUID)) CFE-ES - Query All Apps true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var fileName =VTypeHelper.getString(display.getWidget('inFileName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_es/QueryAllApps', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/QueryAllApps', { 'Payload.QueryAllFileName': fileName});]]> true @@ -120,16 +120,16 @@ $(pv_value) false - Query All Applications + ($(CPUID)) Query All Applications true 1 true Label - 175 + 253 false 14292858:17759dd02e1:-7cd3 - 72 + 36 12 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/QueryAllTasks.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/QueryAllTasks.opi index ab98aadc2..3579211ba 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/QueryAllTasks.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/QueryAllTasks.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-ES - Query All Tasks + ($(CPUID)) CFE-ES - Query All Tasks true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var fileName =VTypeHelper.getString(display.getWidget('inFileName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_es/QueryAllTasks', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/QueryAllTasks', { 'Payload.QueryAllFileName': fileName});]]> true @@ -120,16 +120,16 @@ $(pv_value) false - Query All Tasks + ($(CPUID)) Query All Tasks true 1 true Label - 175 + 241 false 14292858:17759dd02e1:-7cd3 - 80 + 42 12 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/QueryOneApp.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/QueryOneApp.opi index 455a38b69..b39d684a9 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/QueryOneApp.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/QueryOneApp.opi @@ -10,7 +10,7 @@ - 1.5.4.202102122300 + 1.6.2.202104092231 @@ -19,7 +19,7 @@ true - CFE-ES - Query App + ($(CPUID)) CFE-ES - Query App true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var appName =VTypeHelper.getString(display.getWidget('inAppName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_es/QueryOneApp', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/QueryOneApp', { 'Payload.Application': appName});]]> true @@ -132,9 +132,10 @@ $(pv_value) 2 47 - + false + false false @@ -145,6 +146,7 @@ $(pv_value) 1 1 + true Default @@ -153,33 +155,19 @@ $(pv_value) + 0 32 - - CF - CI - CS - DS - EIM - HS - FM - HK - LC - MM - SCH - TO - SBN - CFE_ES - CFE_EVS - CFE_SB - CFE_TBL - CFE_TIME - SIM - SIM_LIB - - false + 0 + false + Infinity + -Infinity + false inAppName + 0 + true loc://AppName + 0.0 true @@ -187,10 +175,15 @@ $(pv_value) false + 0 + true + + $(pv_name) $(pv_value) + false true - Combo + Text Input 115 -3fca34e1:15096a78c93:-79bc 62 @@ -224,13 +217,13 @@ $(pv_value) false - Query One Application + ($(CPUID)) Query One Application true 1 true Label - 175 + 235 false 14292858:17759dd02e1:-7cd3 18 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/ReloadApp.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/ReloadApp.opi index 209c7e418..58748ccfe 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/ReloadApp.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/ReloadApp.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.6.2.202104092231 @@ -19,7 +19,7 @@ true - CFE-ES - Reload App + ($(CPUID)) CFE-ES - Reload App true @@ -43,8 +43,8 @@ importPackage(Packages.org.yamcs.studio.data); var appName =VTypeHelper.getString(display.getWidget('inAppName').getPropertyValue('pv_value')); var fileName =VTypeHelper.getString(display.getWidget('inFileName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_es/AppReload', { - 'Payload.Application': appName, +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/AppReload', { + 'Payload.Application': appName.toUpperCase(), 'Payload.AppFileName': fileName});]]> true @@ -134,9 +134,10 @@ $(pv_value) 12 47 - + false + false false @@ -147,6 +148,7 @@ $(pv_value) 1 1 + true Default @@ -155,26 +157,19 @@ $(pv_value) - 30 - - CF - CI - CS - DS - EIM - HS - FM - HK - LC - MM - SCH - TO - SBN - - false + 0 + 32 + 0 + false + 1.7976931348623157E308 + -1.7976931348623157E308 + false inAppName + 0 + true loc://AppName + 0.0 true @@ -182,10 +177,15 @@ $(pv_value) false + 0 + true + + $(pv_name) $(pv_value) + false true - Combo + Text Input 157 72a2bf2b:1508717c835:-76fa 102 @@ -219,7 +219,7 @@ $(pv_value) false - Reload Application + ($(CPUID)) Reload Application true 1 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/ReloadApp_App.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/ReloadApp_App.opi index 49c883c25..a8506f39e 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/ReloadApp_App.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/ReloadApp_App.opi @@ -10,7 +10,7 @@ - 1.5.5.202103012118 + 1.6.2.202104092231 @@ -18,9 +18,9 @@ 150 true - /Displays/Resources/definitions.yaml + /Displays/Resources/config_registry.yaml - ReloadApp + ($(CPUID)) ReloadApp @@ -48,8 +48,8 @@ importPackage(Packages.org.yamcs.studio.data); var appName = display.getMacroValue("APP"); var fileName =VTypeHelper.getString(display.getWidget('inFileName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_es/AppReload', { - 'Payload.Application': appName, +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/AppReload', { + 'Payload.Application': appName.toUpperCase(), 'Payload.AppFileName': fileName});]]> true @@ -127,7 +127,7 @@ $(pv_value) false - Reload Application + ($(CPUID)) Reload Application true 1 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/Resources/Scripts/ReloadApplicationInit.py b/core/base/tools/commander/workspace_template/Displays/Core/ES/Resources/Scripts/ReloadApplicationInit.py index 4b3b818c5..1e868d5d8 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/Resources/Scripts/ReloadApplicationInit.py +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/Resources/Scripts/ReloadApplicationInit.py @@ -6,7 +6,7 @@ """ # import java packages from org.csstudio.opibuilder.scriptUtil import PVUtil, ScriptUtil, FileUtil, WidgetUtil, DataUtil -from org.csstudio.opibuilder.scriptUtil import YAMLUtil +from com.windhoverlabs.studio.registry import YAMLRegistry, ConfigRegistry from org.eclipse.swt.graphics import RGB # import python packages @@ -64,11 +64,12 @@ def main(): logger.warning(project_name) yaml_path_macro = display.getMacroValue("CONFIG_REGISTRY") logger.warning(yaml_path_macro) - yaml_path = FileUtil.workspacePathToSysPath(yaml_path_macro) - yaml_data = YAMLUtil.parseYAML(yaml_path) - module_data = get_module(app_name, yaml_data) + registry_path = display.getMacroValue("REGISTRY_PATH") - display.getWidget("app_name").setPropertyValue("text", module_data["short_name"].upper() + " - Reload App") + registry = YAMLRegistry() + + display.getWidget("app_name").setPropertyValue("text", + registry.get(registry_path + "/short_name").upper() + " - Reload App") main() diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/Resources/Scripts/perf_init.py b/core/base/tools/commander/workspace_template/Displays/Core/ES/Resources/Scripts/perf_init.py index e24a9c013..032a5d2c4 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/Resources/Scripts/perf_init.py +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/Resources/Scripts/perf_init.py @@ -15,6 +15,8 @@ def main(): new_perf_record.setPropertyValue("border_color", RGB(240, 240, 240)) new_perf_record.setPropertyValue("border_style", 0) new_perf_record.setPropertyValue("name", "perf_name") + # Refer to org.csstudio.opibuilder.widgets.model for resize_behaviour + new_perf_record.setPropertyValue("resize_behaviour", 1) display.getWidget("PerfRecordContainer").addChild(new_perf_record) # newMask = PVUtil.getLong(pvs[0]) diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/Resources/Scripts/set_actual_filters.py b/core/base/tools/commander/workspace_template/Displays/Core/ES/Resources/Scripts/set_actual_filters.py index 1b062850b..5daa8eb1b 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/Resources/Scripts/set_actual_filters.py +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/Resources/Scripts/set_actual_filters.py @@ -15,7 +15,7 @@ else: maskValue = int(maskValue) | 0x80000000 -Yamcs.issueCommand('/cfs/cfe_es/PerfSetFilterMask', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/PerfSetFilterMask', { 'Payload.FilterMaskNum': maskNumber, 'Payload.FilterMask': maskValue}) diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/Resources/Templates/PerfCollection.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/Resources/Templates/PerfCollection.opi index 6336f9837..9b1e9a7aa 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/Resources/Templates/PerfCollection.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/Resources/Templates/PerfCollection.opi @@ -10,7 +10,7 @@ - 1.5.5.202103162101 + 1.5.5.202103012118 @@ -20,7 +20,7 @@ true /Displays/Core/ES/Resources/Templates/PerfRecord.opi - CFE-ES - Perf + ($(CPUID)) CFE-ES - Perf @@ -345,13 +345,13 @@ false - Performance Collection + ($(CPUID)) Performance Collection true 1 true Label - 193 + 322 false 2b4f25d5:1502b5812fe:-7d80 243 @@ -385,7 +385,7 @@ Text Update_20 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.PerfState + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.PerfState 0.0 @@ -437,7 +437,7 @@ $(pv_value) Text Update_21 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.PerfMode + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.PerfMode 0.0 @@ -489,7 +489,7 @@ $(pv_value) Text Update_22 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.PerfTriggerCount + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.PerfTriggerCount 0.0 @@ -541,7 +541,7 @@ $(pv_value) Text Update_25 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.PerfDataStart + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.PerfDataStart 0.0 @@ -593,7 +593,7 @@ $(pv_value) Text Update_26 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.PerfDataEnd + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.PerfDataEnd 0.0 @@ -645,7 +645,7 @@ $(pv_value) Text Update_27 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.PerfDataCount + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.PerfDataCount 0.0 @@ -697,7 +697,7 @@ $(pv_value) Text Update_28 0 false - /cfs/cfe_es/CFE_ES_HkPacket_t.Payload.PerfDataToWrite + /cfs/$(CPUID)/cfe_es/CFE_ES_HkPacket_t.Payload.PerfDataToWrite 0.0 @@ -1217,7 +1217,7 @@ for i in range(1,32): else: maskValue = int(maskValue) | 0x80000000 -Yamcs.issueCommand( '/cfs/cfe_es/PerfSetFilterMask', { +Yamcs.issueCommand( '/cfs/$(CPUID)/cfe_es/PerfSetFilterMask', { 'Payload.FilterMaskNum': maskNumber, 'Payload.FilterMask': maskValue});]]> true @@ -1276,7 +1276,7 @@ $(pv_value) importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); -var cmdString = '/cfs/cfe_es/PerfSetTriggerMask1('; +var cmdString = '/cfs/$(CPUID)/cfe_es/PerfSetTriggerMask1('; for(var i = 1; i <= 32; ++i) { var PerfID = 'PerfTrigger' + i; diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/Resources/Templates/PerfRecord.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/Resources/Templates/PerfRecord.opi index 92f6cb325..fb7316f06 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/Resources/Templates/PerfRecord.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/Resources/Templates/PerfRecord.opi @@ -10,7 +10,7 @@ - 1.5.5.202103162101 + 1.5.5.202104022333 @@ -302,19 +302,11 @@ $(pv_value) false - 2 + 50 Grid Layout 5 Grid Layout 7a03ebb6:17840dde0b7:-6415 - - false - 2 - Grid Layout - 3 - Grid Layout - 7a03ebb6:17840dde0b7:-6185 - \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/RestartApp.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/RestartApp.opi index af53bb808..3a8e08bbb 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/RestartApp.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/RestartApp.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-ES - Restart App + ($(CPUID)) CFE-ES - Restart App true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var appName =VTypeHelper.getString(display.getWidget('inAppName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_es/RestartApp', {'Payload.Application': appName});]]> +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/RestartApp', {'Payload.Application': appName});]]> true @@ -216,7 +216,7 @@ $(pv_value) false - Restart Application + ($(CPUID)) Restart Application true 1 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/SetMaxPRCount.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/SetMaxPRCount.opi index b3ceeeb82..b4058c8c0 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/SetMaxPRCount.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/SetMaxPRCount.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-ES - Set Max Proc Reset + ($(CPUID)) CFE-ES - Set Max Proc Reset true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var maxResets =VTypeHelper.getDouble(display.getWidget('inMaxResets').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_es/SetMaxPRCount', {'Payload.MaxPRCount': maxResets});]]> +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/SetMaxPRCount', {'Payload.MaxPRCount': maxResets});]]> true @@ -214,16 +214,16 @@ $(pv_value) false - Set Maximum Processor Resets + ($(CPUID)) Set Maximum Processor Resets true 1 true Label - 231 + 271 false 72a2bf2b:1508717c835:-76c0 - 25 + 6 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/SetSysLogMode.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/SetSysLogMode.opi index 2363b0e4f..7477f5b16 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/SetSysLogMode.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/SetSysLogMode.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-ES - Set SysLog Mode + ($(CPUID)) CFE-ES - Set SysLog Mode true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var strMode =VTypeHelper.getString(display.getWidget('inMode').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_es/SetSysLogMode', {'Payload.Mode': strMode});]]> +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/SetSysLogMode', {'Payload.Mode': strMode});]]> true @@ -205,7 +205,7 @@ $(pv_value) false - Set SysLog Mode + ($(CPUID)) Set SysLog Mode true 1 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/StartApp.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/StartApp.opi index 6d2173379..12af5327f 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/StartApp.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/StartApp.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.6.2.202104092231 @@ -19,7 +19,7 @@ true - CFE-ES - Start App + ($(CPUID)) CFE-ES - Start App true @@ -47,7 +47,7 @@ var stackSize = VTypeHelper.getNumber(display.getWidget("inStackSize").getProper var exceptionAction =VTypeHelper.getString(display.getWidget('inExceptionAction').getPropertyValue('pv_value')); var priority = VTypeHelper.getNumber(display.getWidget("inPriority").getPropertyValue("pv_value")); -Yamcs.issueCommand('/cfs/cfe_es/StartApp', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/StartApp', { 'Payload.Application': appName, 'Payload.AppEntryPoint': entryPoint, 'Payload.AppFileName': fileName, @@ -142,9 +142,10 @@ $(pv_value) 29 41 - + false + false false @@ -155,6 +156,7 @@ $(pv_value) 14 1 + true Default @@ -163,26 +165,19 @@ $(pv_value) - 32 - - CF - CI - CS - DS - EIM - HS - FM - HK - LC - MM - SCH - TO - SBN - - false + 0 + 34 + 0 + false + Infinity + -Infinity + false inAppName + 0 + true loc://AppName<VString>("") + 0.0 true @@ -190,10 +185,15 @@ $(pv_value) false + 0 + true + + $(pv_name) $(pv_value) + false true - Combo + Text Input 226 72a2bf2b:1508717c835:-76fa 119 @@ -227,7 +227,7 @@ $(pv_value) false - Start Application + ($(CPUID)) Start Application true 1 @@ -688,7 +688,7 @@ $(pv_value) - 32 + 34 RESTART_APP PROC_RESTART diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/StartPerfCollection.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/StartPerfCollection.opi index 73c1b4783..f469a0e02 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/StartPerfCollection.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/StartPerfCollection.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -129,7 +129,7 @@ importPackage(Packages.org.yamcs.studio.data); triggerOn = VTypeHelper.getString(display.getWidget('TriggerOn').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_es/PerfStart', {'Payload.TriggerMode': triggerOn});]]> +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/PerfStart', {'Payload.TriggerMode': triggerOn});]]> true @@ -206,13 +206,13 @@ $(pv_value) false - Start Performance Collection + ($(CPUID)) Start Performance Collection true 1 true Label - 235 + 300 false -2dc23c5:177557ff444:-5f3b 13 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/StopApp.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/StopApp.opi index ede8e1235..95aa4e974 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/StopApp.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/StopApp.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-ES - Stop App + ($(CPUID)) CFE-ES - Stop App true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var appName =VTypeHelper.getString(display.getWidget('inAppName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_es/StopApp', {'Payload.Application': appName});]]> +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/StopApp', {'Payload.Application': appName});]]> true @@ -216,7 +216,7 @@ $(pv_value) false - Stop Application + ($(CPUID)) Stop Application true 1 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/StopPerfCollection.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/StopPerfCollection.opi index 4f75e97e6..057beb761 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/StopPerfCollection.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/StopPerfCollection.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-ES - Stop Perf + ($(CPUID)) CFE-ES - Stop Perf true @@ -82,7 +82,7 @@ importPackage(Packages.org.yamcs.studio.data); fileName = VTypeHelper.getString(display.getWidget('FileName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_es/PerfStop', {'Payload.DataFileName': fileName});]]> +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/PerfStop', {'Payload.DataFileName': fileName});]]> true @@ -216,7 +216,7 @@ $(pv_value) false - Stop Performance Collection + ($(CPUID)) Stop Performance Collection true 1 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/WriteErrLog.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/WriteErrLog.opi index 0d3a65b6c..30b569691 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/WriteErrLog.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/WriteErrLog.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-ES - Write Err Log + ($(CPUID)) CFE-ES - Write Err Log true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var fileName =VTypeHelper.getString(display.getWidget('inFileName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_es/WriteErLog', {'Payload.ERLogFileName': fileName}); +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/WriteErLog', {'Payload.ERLogFileName': fileName}); ]]> true @@ -160,16 +160,16 @@ $(pv_value) false - Dump Error Log to File System + ($(CPUID)) Dump Error Log to File System true 1 true Label - 231 + 307 false 72a2bf2b:1508717c835:-76c0 - 80 + 54 12 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/ES/WriteSysLog.opi b/core/base/tools/commander/workspace_template/Displays/Core/ES/WriteSysLog.opi index 3a10482ed..8aee338c0 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/ES/WriteSysLog.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/ES/WriteSysLog.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-ES - Write Sys Log + ($(CPUID)) CFE-ES - Write Sys Log true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var fileName =VTypeHelper.getString(display.getWidget('inFileName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_es/WriteSysLog', {'Payload.SysLogFileName': fileName}); +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_es/WriteSysLog', {'Payload.SysLogFileName': fileName}); ]]> true @@ -160,7 +160,7 @@ $(pv_value) false - Dump System Log to File System + ($(CPUID)) Dump System Log to File System true 1 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/EVS/AddFilter.opi b/core/base/tools/commander/workspace_template/Displays/Core/EVS/AddFilter.opi index dd2b30170..a59d78457 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/EVS/AddFilter.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/EVS/AddFilter.opi @@ -10,7 +10,7 @@ - 1.5.4.202102122300 + 1.5.5.202103012118 @@ -20,7 +20,7 @@ true Displays - CFE-EVS - Add Filter + ($(CPUID)) CFE-EVS - Add Filter true @@ -47,7 +47,7 @@ appName = VTypeHelper.getString(display.getWidget('AppName').getPropertyValue('p eventID = VTypeHelper.getDouble(display.getWidget('EventID').getPropertyValue('pv_value')); mask = VTypeHelper.getString(display.getWidget('Mask').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_evs/AddAppEventFilter', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/AddAppEventFilter', { 'Payload.AppName': appName, 'Payload.EventID': eventID, 'Payload.Mask': mask});]]> @@ -160,7 +160,7 @@ $(pv_value) - 34 + 32 CF CI @@ -420,16 +420,16 @@ $(pv_value) false - Add Filter + ($(CPUID)) Add Filter true 1 true Label - 109 + 206 false 6b3345f4:17760d4a2f0:-7b26 - 72 + 24 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/EVS/DeleteFilter.opi b/core/base/tools/commander/workspace_template/Displays/Core/EVS/DeleteFilter.opi index 453803790..4016991bd 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/EVS/DeleteFilter.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/EVS/DeleteFilter.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-EVS - Delete Filter + ($(CPUID)) CFE-EVS - Delete Filter true @@ -43,7 +43,7 @@ importPackage(Packages.org.yamcs.studio.data); appName = VTypeHelper.getString(display.getWidget('AppName').getPropertyValue('pv_value')); eventID = VTypeHelper.getDouble(display.getWidget('EventID').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_evs/DeleteAppEventFilter', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/DeleteAppEventFilter', { 'Payload.AppName': appName, 'Payload.EventID': eventID});]]> true @@ -318,16 +318,16 @@ $(pv_value) false - Delete Filter + ($(CPUID)) Delete Filter true 1 true Label - 120 + 212 false 6b3345f4:17760d4a2f0:-7b35 - 67 + 24 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/EVS/DumpAppData.opi b/core/base/tools/commander/workspace_template/Displays/Core/EVS/DumpAppData.opi index 3d8de7bff..cb5f38a75 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/EVS/DumpAppData.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/EVS/DumpAppData.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-EVS - Dump App Data + ($(CPUID)) CFE-EVS - Dump App Data true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var fileName =VTypeHelper.getString(display.getWidget('inFileName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_evs/WriteAppData', {'Payload.AppDataFilename': fileName}); +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/WriteAppData', {'Payload.AppDataFilename': fileName}); ]]> true @@ -160,16 +160,16 @@ $(pv_value) false - Write App Data to File System + ($(CPUID)) Write App Data to File System true 1 true Label - 231 + 319 false 72a2bf2b:1508717c835:-76c0 - 90 + 48 12 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/EVS/DumpEventLog.opi b/core/base/tools/commander/workspace_template/Displays/Core/EVS/DumpEventLog.opi index 00f22df7c..6cfcade9b 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/EVS/DumpEventLog.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/EVS/DumpEventLog.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-EVS - Dump Log + ($(CPUID)) CFE-EVS - Dump Log true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var fileName =VTypeHelper.getString(display.getWidget('inFileName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_evs/WriteLogData', {'Payload.LogFilename': fileName}); +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/WriteLogData', {'Payload.LogFilename': fileName}); ]]> true @@ -160,16 +160,16 @@ $(pv_value) false - Write Event Log to File System + ($(CPUID)) Write Event Log to File System true 1 true Label - 231 + 295 false 72a2bf2b:1508717c835:-76c0 - 96 + 60 12 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/EVS/EnaDisAppEventType.opi b/core/base/tools/commander/workspace_template/Displays/Core/EVS/EnaDisAppEventType.opi index f7e410c79..445c54284 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/EVS/EnaDisAppEventType.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/EVS/EnaDisAppEventType.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -28,7 +28,7 @@ true true Display - 270 + 330 763e00b7:150973f1dd8:-7ba3 -1 -1 @@ -236,7 +236,7 @@ debugFlag = VTypeHelper.getDouble(display.getWidget('Debug').getPropertyValue('p var mask = (critFlag * 8) + (errorFlag * 4) + (infoFlag * 2) + (debugFlag); -Yamcs.issueCommand('/cfs/cfe_evs/EnableAppEventType', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/EnableAppEventType', { 'Payload.AppName': appName, 'Payload.BitMask': mask, 'Payload.Spare': 0 @@ -305,7 +305,7 @@ debugFlag = VTypeHelper.getDouble(display.getWidget('Debug').getPropertyValue('p var mask = (critFlag * 8) + (errorFlag * 4) + (infoFlag * 2) + (debugFlag); -Yamcs.issueCommand('/cfs/cfe_evs/DisableAppEventType', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/DisableAppEventType', { 'Payload.AppName': appName, 'Payload.BitMask': mask, 'Payload.Spare': 0 @@ -485,16 +485,16 @@ $(pv_value) false - Enable / Disable App Event Type + ($(CPUID)) Enable / Disable App Event Type true 1 true Label - 265 + 319 false 6b3345f4:17760d4a2f0:-7b68 - 12 + 6 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/EVS/EnaDisAppEvents.opi b/core/base/tools/commander/workspace_template/Displays/Core/EVS/EnaDisAppEvents.opi index c1843addc..f484aacc6 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/EVS/EnaDisAppEvents.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/EVS/EnaDisAppEvents.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-EVS - Ena/dis App Event + ($(CPUID)) CFE-EVS - Ena/dis App Event true @@ -28,7 +28,7 @@ true true Display - 250 + 280 763e00b7:150973f1dd8:-7ba3 -1 130 @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); appName = VTypeHelper.getString(display.getWidget('AppName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_evs/EnableAppEvents', {'Payload.AppName': appName});]]> +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/EnableAppEvents', {'Payload.AppName': appName});]]> true @@ -101,7 +101,7 @@ importPackage(Packages.org.yamcs.studio.data); appName = VTypeHelper.getString(display.getWidget('AppName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_evs/DisableAppEvents', {'Payload.AppName': appName});]]> +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/DisableAppEvents', {'Payload.AppName': appName});]]> true @@ -277,16 +277,16 @@ $(pv_value) false - Enable / Disable App Events + ($(CPUID)) Enable / Disable App Events true 1 true Label - 205 + 271 false 6b3345f4:17760d4a2f0:-7b58 - 27 + 6 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/EVS/EnaDisEventType.opi b/core/base/tools/commander/workspace_template/Displays/Core/EVS/EnaDisEventType.opi index bd88392de..75cf56ff3 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/EVS/EnaDisEventType.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/EVS/EnaDisEventType.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-EVS - Ena/Dis Event + ($(CPUID)) CFE-EVS - Ena/Dis Event true @@ -28,7 +28,7 @@ true true Display - 250 + 260 763e00b7:150973f1dd8:-7ba3 -1 -1 @@ -228,7 +228,7 @@ $(pv_value) importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); -var cmdString = '/cfs/cfe_evs/EnableEventType('; +var cmdString = '/cfs/$(CPUID)/cfe_evs/EnableEventType('; critFlag = VTypeHelper.getDouble(display.getWidget('Critical').getPropertyValue('pv_value')); errorFlag = VTypeHelper.getDouble(display.getWidget('Error').getPropertyValue('pv_value')); infoFlag = VTypeHelper.getDouble(display.getWidget('Information').getPropertyValue('pv_value')); @@ -236,7 +236,7 @@ debugFlag = VTypeHelper.getDouble(display.getWidget('Debug').getPropertyValue('p var mask = (critFlag * 8) + (errorFlag * 4) + (infoFlag * 2) + (debugFlag); -Yamcs.issueCommand('/cfs/cfe_evs/EnableEventType', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/EnableEventType', { 'Payload.BitMask': mask, 'Payload.Spare': 0 });]]> @@ -296,7 +296,7 @@ $(pv_value) importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); -var cmdString = '/cfs/cfe_evs/EnableEventType('; +var cmdString = '/cfs/$(CPUID)/cfe_evs/EnableEventType('; critFlag = VTypeHelper.getDouble(display.getWidget('Critical').getPropertyValue('pv_value')); errorFlag = VTypeHelper.getDouble(display.getWidget('Error').getPropertyValue('pv_value')); infoFlag = VTypeHelper.getDouble(display.getWidget('Information').getPropertyValue('pv_value')); @@ -304,7 +304,7 @@ debugFlag = VTypeHelper.getDouble(display.getWidget('Debug').getPropertyValue('p var mask = (critFlag * 8) + (errorFlag * 4) + (infoFlag * 2) + (debugFlag); -Yamcs.issueCommand('/cfs/cfe_evs/DisableEventType', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/DisableEventType', { 'Payload.BitMask': mask, 'Payload.Spare': 0 });]]> @@ -384,16 +384,16 @@ $(pv_value) false - Enable / Disable Event + ($(CPUID)) Enable / Disable Event true 1 true Label - 187 + 247 false 6b3345f4:17760d4a2f0:-7b90 - 30 + 6 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/EVS/EnaDisPorts.opi b/core/base/tools/commander/workspace_template/Displays/Core/EVS/EnaDisPorts.opi index bfe0af2c8..05640389c 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/EVS/EnaDisPorts.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/EVS/EnaDisPorts.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-EVS - Ena/Dis Ports + ($(CPUID)) CFE-EVS - Ena/Dis Ports true @@ -28,7 +28,7 @@ true true Display - 230 + 250 763e00b7:150973f1dd8:-7ba3 -1 -1 @@ -235,7 +235,7 @@ port1 = VTypeHelper.getDouble(display.getWidget('Port1').getPropertyValue('pv_va var mask = (port4 * 8) + (port3 * 4) + (port2 * 2) + (port1); -Yamcs.issueCommand('/cfs/cfe_evs/EnablePorts', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/EnablePorts', { 'Payload.BitMask': mask, 'Payload.Spare': 0 });]]> @@ -302,7 +302,7 @@ port1 = VTypeHelper.getDouble(display.getWidget('Port1').getPropertyValue('pv_va var mask = (port4 * 8) + (port3 * 4) + (port2 * 2) + (port1); -Yamcs.issueCommand('/cfs/cfe_evs/DisablePorts', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/DisablePorts', { 'Payload.BitMask': mask, 'Payload.Spare': 0 });]]> @@ -382,16 +382,16 @@ $(pv_value) false - Enable / Disable Ports + ($(CPUID)) Enable / Disable Ports true 1 true Label - 170 + 241 false 6b3345f4:17760d4a2f0:-7ba3 - 24 + 6 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/EVS/Events.opi b/core/base/tools/commander/workspace_template/Displays/Core/EVS/Events.opi index 852e20c75..6a2e15260 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/EVS/Events.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/EVS/Events.opi @@ -18,7 +18,7 @@ 800 true - /Displays/Resources/definitions.yaml + /Displays/Resources/config_registry.yaml EventRecord.opi diff --git a/core/base/tools/commander/workspace_template/Displays/Core/EVS/Main.opi b/core/base/tools/commander/workspace_template/Displays/Core/EVS/Main.opi index e8aa9e25c..8bf7c6720 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/EVS/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/EVS/Main.opi @@ -10,12 +10,12 @@ - 1.5.5.202103162101 + 1.6.2.202104092231 6 - 470 + 500 true cfe_evs @@ -23,7 +23,7 @@ Displays /modules/core/modules/cfe/modules/cfe_evs - CFE-EVS + ($(CPUID)) CFE-EVS true @@ -64,7 +64,7 @@ Text Update 0 false - /cfs/cfe_evs/CFE_EVS_TlmPkt_t.Payload.CommandCounter + /cfs/$(CPUID)/cfe_evs/CFE_EVS_TlmPkt_t.Payload.CommandCounter 0.0 @@ -636,7 +636,7 @@ $(pv_value) Text Update_1 0 false - /cfs/cfe_evs/CFE_EVS_TlmPkt_t.Payload.CommandErrCounter + /cfs/$(CPUID)/cfe_evs/CFE_EVS_TlmPkt_t.Payload.CommandErrCounter 0.0 @@ -688,7 +688,7 @@ $(pv_value) Text Update_2 0 false - /cfs/cfe_evs/CFE_EVS_TlmPkt_t.Payload.MessageFormatMode + /cfs/$(CPUID)/cfe_evs/CFE_EVS_TlmPkt_t.Payload.MessageFormatMode 0.0 @@ -740,7 +740,7 @@ $(pv_value) Text Update_3 0 false - /cfs/cfe_evs/CFE_EVS_TlmPkt_t.Payload.MessageTruncCounter + /cfs/$(CPUID)/cfe_evs/CFE_EVS_TlmPkt_t.Payload.MessageTruncCounter 0.0 @@ -792,7 +792,7 @@ $(pv_value) Text Update_4 0 false - /cfs/cfe_evs/CFE_EVS_TlmPkt_t.Payload.UnregisteredAppCounter + /cfs/$(CPUID)/cfe_evs/CFE_EVS_TlmPkt_t.Payload.UnregisteredAppCounter 0.0 @@ -844,7 +844,7 @@ $(pv_value) Text Update_5 0 false - /cfs/cfe_evs/CFE_EVS_TlmPkt_t.Payload.OutputPort + /cfs/$(CPUID)/cfe_evs/CFE_EVS_TlmPkt_t.Payload.OutputPort 0.0 @@ -896,7 +896,7 @@ $(pv_value) Text Update_6 0 false - /cfs/cfe_evs/CFE_EVS_TlmPkt_t.Payload.LogFullFlag + /cfs/$(CPUID)/cfe_evs/CFE_EVS_TlmPkt_t.Payload.LogFullFlag 0.0 @@ -948,7 +948,7 @@ $(pv_value) Text Update_7 0 false - /cfs/cfe_evs/CFE_EVS_TlmPkt_t.Payload.LogMode + /cfs/$(CPUID)/cfe_evs/CFE_EVS_TlmPkt_t.Payload.LogMode 0.0 @@ -1000,7 +1000,7 @@ $(pv_value) Text Update_8 0 false - /cfs/cfe_evs/CFE_EVS_TlmPkt_t.Payload.MessageSendCounter + /cfs/$(CPUID)/cfe_evs/CFE_EVS_TlmPkt_t.Payload.MessageSendCounter 0.0 @@ -1052,7 +1052,7 @@ $(pv_value) Text Update_9 0 false - /cfs/cfe_evs/CFE_EVS_TlmPkt_t.Payload.LogOverflowCounter + /cfs/$(CPUID)/cfe_evs/CFE_EVS_TlmPkt_t.Payload.LogOverflowCounter 0.0 @@ -1104,7 +1104,7 @@ $(pv_value) Text Update_10 0 false - /cfs/cfe_evs/CFE_EVS_TlmPkt_t.Payload.LogEnabled + /cfs/$(CPUID)/cfe_evs/CFE_EVS_TlmPkt_t.Payload.LogEnabled 0.0 @@ -1135,7 +1135,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/NoOp', {});]]> true @@ -1190,7 +1190,7 @@ Yamcs.issueCommand('/cfs/cfe_evs/NoOp', {});]]> +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/Reset', {});]]> true @@ -1267,13 +1267,13 @@ $(pv_value) false - Core Flight Executive - Event Services + ($(CPUID)) Core Flight Executive - Event Services true 1 true Label - 295 + 367 false 763e00b7:150973f1dd8:-7cf4 18 @@ -1946,7 +1946,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/ClearLog', {});]]> true @@ -2057,7 +2057,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/SendHK', {});]]> true @@ -2103,7 +2103,7 @@ $(pv_value) Action Button 86 2285957:177658292c4:-6b26 - 333 + 406 12 @@ -2176,7 +2176,7 @@ importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); importPackage(org.csstudio.opibuilder.runmode) -var opi_to_open_path = FileUtil.workspacePathToSysPath("/Displays/Core/ES/ApplicationControl.opi"); +var opi_to_open_path = FileUtil.workspacePathToSysPath("/Displays/Core/ES/ApplicationControl_App.opi"); var macroInput = DataUtil.createMacrosInput(true); ScriptUtil.openOPI(display.getWidget("AppControl"), opi_to_open_path, RunModeService.DisplayMode.REPLACE, macroInput );]]> @@ -2225,7 +2225,7 @@ $(pv_value) Action Button 187 -69f8bd78:177f094d5fe:-248 - 18 - 462 + 220 + 437 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/EVS/ResetAppCounter.opi b/core/base/tools/commander/workspace_template/Displays/Core/EVS/ResetAppCounter.opi index 9ff7518f6..a818b0345 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/EVS/ResetAppCounter.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/EVS/ResetAppCounter.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - + ($(CPUID)) CFE-EVS - Reset App Cntr true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); appName = VTypeHelper.getString(display.getWidget('AppName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_evs/ResetAppEventCounters', {'Payload.AppName': appName});]]> +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/ResetAppEventCounters', {'Payload.AppName': appName});]]> true @@ -218,16 +218,16 @@ $(pv_value) false - Reset App Counter + ($(CPUID)) Reset App Counter true 1 true Label - 146 + 224 false 6b3345f4:17760d4a2f0:-7bb3 - 54 + 12 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/EVS/ResetFilter.opi b/core/base/tools/commander/workspace_template/Displays/Core/EVS/ResetFilter.opi index 6e3a59335..aa79a87cb 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/EVS/ResetFilter.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/EVS/ResetFilter.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-EVS - Reset Filter + ($(CPUID)) CFE-EVS - Reset Filter true @@ -43,7 +43,7 @@ importPackage(Packages.org.yamcs.studio.data); appName = VTypeHelper.getString(display.getWidget('AppName').getPropertyValue('pv_value')); eventID = VTypeHelper.getDouble(display.getWidget('EventID').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_evs/ResetAppEventFilter', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/ResetAppEventFilter', { 'Payload.AppName': appName, 'Payload.EventID': eventID});]]> true @@ -300,7 +300,7 @@ importPackage(Packages.org.yamcs.studio.data); appName = VTypeHelper.getString(display.getWidget('AppName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_evs/ResetAppFilters', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/ResetAppFilters', { 'Payload.AppName': appName});]]> true @@ -378,16 +378,16 @@ $(pv_value) false - Reset App Event Filter + ($(CPUID)) Reset App Event Filter true 1 true Label - 193 + 254 false 6b3345f4:17760d4a2f0:-7bc4 - 43 + 18 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/EVS/Scripts/Python/DeleteEventFilter.py b/core/base/tools/commander/workspace_template/Displays/Core/EVS/Scripts/Python/DeleteEventFilter.py index b1079146f..c577ed5e3 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/EVS/Scripts/Python/DeleteEventFilter.py +++ b/core/base/tools/commander/workspace_template/Displays/Core/EVS/Scripts/Python/DeleteEventFilter.py @@ -7,7 +7,7 @@ # it looks like and not the OPI instance. app_name = display.getMacroValue("APP").upper() -Yamcs.issueCommand('/cfs/cfe_evs/DeleteAppEventFilter', +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/DeleteAppEventFilter', { 'Payload.AppName': app_name, 'Payload.EventID': event_id diff --git a/core/base/tools/commander/workspace_template/Displays/Core/EVS/Scripts/Python/ResetEventFilter.py b/core/base/tools/commander/workspace_template/Displays/Core/EVS/Scripts/Python/ResetEventFilter.py index 940006b0e..968f30f10 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/EVS/Scripts/Python/ResetEventFilter.py +++ b/core/base/tools/commander/workspace_template/Displays/Core/EVS/Scripts/Python/ResetEventFilter.py @@ -7,7 +7,7 @@ # it looks like and not the OPI instance. app_name = display.getMacroValue("APP").upper() -Yamcs.issueCommand('/cfs/cfe_evs/ResetAppEventFilter', +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/ResetAppEventFilter', { 'Payload.AppName': app_name, 'Payload.EventID': event_id diff --git a/core/base/tools/commander/workspace_template/Displays/Core/EVS/Scripts/XML/ResetEvent.xml b/core/base/tools/commander/workspace_template/Displays/Core/EVS/Scripts/XML/ResetEvent.xml index cb2382906..bcc884077 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/EVS/Scripts/XML/ResetEvent.xml +++ b/core/base/tools/commander/workspace_template/Displays/Core/EVS/Scripts/XML/ResetEvent.xml @@ -8,7 +8,7 @@ importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); -Yamcs.issueCommand('/cfs/cfe_evs/ResetAppEventFilter', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/ResetAppEventFilter', { 'Payload.AppName': display.getMacroValue("APP"), 'Payload.EventID': VTypeHelper.getDouble(widget.getPropertyValue("pv_value"))});]]> true diff --git a/core/base/tools/commander/workspace_template/Displays/Core/EVS/SetFilter.opi b/core/base/tools/commander/workspace_template/Displays/Core/EVS/SetFilter.opi index 45b20d25c..f0bf19406 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/EVS/SetFilter.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/EVS/SetFilter.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-EVS - Set Filter + ($(CPUID)) CFE-EVS - Set Filter true @@ -44,7 +44,7 @@ appName = VTypeHelper.getString(display.getWidget('AppName').getPropertyValue('p eventID = VTypeHelper.getDouble(display.getWidget('EventID').getPropertyValue('pv_value')); mask = VTypeHelper.getDouble(display.getWidget('Mask').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_evs/SetAppEventFilter', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/SetAppEventFilter', { 'Payload.AppName': appName, 'Payload.EventID': eventID, 'Payload.Mask': mask});]]> @@ -124,7 +124,7 @@ $(pv_value) false - Set Filter + ($(CPUID)) Set Filter true 1 @@ -197,7 +197,7 @@ $(pv_value) - 34 + 32 CF CI diff --git a/core/base/tools/commander/workspace_template/Displays/Core/EVS/SetLogMode.opi b/core/base/tools/commander/workspace_template/Displays/Core/EVS/SetLogMode.opi index 11e2289d2..ee38cc7ca 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/EVS/SetLogMode.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/EVS/SetLogMode.opi @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var strMode =VTypeHelper.getString(display.getWidget('inMode').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_evs/SetLogMode', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/SetLogMode', { 'Payload.Mode': strMode, 'Payload.Spare': 0 });]]> diff --git a/core/base/tools/commander/workspace_template/Displays/Core/EVS/SetMessageFormat.opi b/core/base/tools/commander/workspace_template/Displays/Core/EVS/SetMessageFormat.opi index fe6f60244..7b8bdbcef 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/EVS/SetMessageFormat.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/EVS/SetMessageFormat.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-EVS - Set Msg Format + ($(CPUID)) CFE-EVS - Set Msg Format true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var strFormat =VTypeHelper.getString(display.getWidget('inFormat').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_evs/SetEventFormatMode', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_evs/SetEventFormatMode', { 'Payload.Mode': strFormat, 'Payload.Spare': 0}); ]]> @@ -208,16 +208,16 @@ $(pv_value) false - Set Message Format + ($(CPUID)) Set Message Format true 1 true Label - 205 + 235 false 72a2bf2b:1508717c835:-76c0 - 24 + 12 14 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/SB/DumpMapInfo.opi b/core/base/tools/commander/workspace_template/Displays/Core/SB/DumpMapInfo.opi index 16698c2d3..87d7006c8 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/SB/DumpMapInfo.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/SB/DumpMapInfo.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-SB - Write Map Info + ($(CPUID)) CFE-SB - Write Map Info true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var fileName =VTypeHelper.getString(display.getWidget('inFileName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_sb/WriteMapInfo', {'Payload.Filename': fileName}); +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_sb/WriteMapInfo', {'Payload.Filename': fileName}); ]]> true @@ -161,16 +161,16 @@ $(pv_value) false - Write Map Info to File System + ($(CPUID)) Write Map Info to File System true 1 true Label - 231 + 325 false 72a2bf2b:1508717c835:-76c0 - 54 + 6 12 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/SB/DumpPipeInfo.opi b/core/base/tools/commander/workspace_template/Displays/Core/SB/DumpPipeInfo.opi index 79e28af4a..6450abda6 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/SB/DumpPipeInfo.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/SB/DumpPipeInfo.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-SB - Write Pipe Info + ($(CPUID)) CFE-SB - Write Pipe Info true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var fileName =VTypeHelper.getString(display.getWidget('inFileName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_sb/WritePipeInfo', {'Payload.Filename': fileName}); +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_sb/WritePipeInfo', {'Payload.Filename': fileName}); ]]> true @@ -161,16 +161,16 @@ $(pv_value) false - Write Pipe Info to File System + ($(CPUID)) Write Pipe Info to File System true 1 true Label - 231 + 307 false 72a2bf2b:1508717c835:-76c0 - 42 + 6 12 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/SB/DumpRoutingInfo.opi b/core/base/tools/commander/workspace_template/Displays/Core/SB/DumpRoutingInfo.opi index 6fcdac7ec..edc07780e 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/SB/DumpRoutingInfo.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/SB/DumpRoutingInfo.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-SB - Write Routes + ($(CPUID)) CFE-SB - Write Routes true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var fileName =VTypeHelper.getString(display.getWidget('inFileName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_sb/WriteRouteInfo', {'Payload.Filename': fileName}); +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_sb/WriteRouteInfo', {'Payload.Filename': fileName}); ]]> true @@ -161,16 +161,16 @@ $(pv_value) false - Write Routing Data to File System + ($(CPUID)) Write Routing Data to File System true 1 true Label - 253 + 343 false 763e00b7:150973f1dd8:-468d - 61 + 18 12 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/SB/EnaDisRoutes.opi b/core/base/tools/commander/workspace_template/Displays/Core/SB/EnaDisRoutes.opi index 67435104f..4e5cb6fd0 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/SB/EnaDisRoutes.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/SB/EnaDisRoutes.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-SB - Ena/Dis Routes + ($(CPUID)) CFE-SB - Ena/Dis Routes true @@ -28,7 +28,7 @@ true true Display - 210 + 260 72a2bf2b:1508717c835:-7d33 -1 -1 @@ -43,7 +43,7 @@ importPackage(Packages.org.yamcs.studio.data); var MsgID =VTypeHelper.getString(display.getWidget('MsgID').getPropertyValue('pv_value')); var PipeID =VTypeHelper.getDouble(display.getWidget('PipeID').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_sb/EnableRoute', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_sb/EnableRoute', { 'Payload.MsgId': MsgID, 'Payload.Pipe': PipeID, 'Payload.Spare': 0}); @@ -93,8 +93,8 @@ $(pv_value) Action Button 85 72a2bf2b:1508717c835:-7cf7 - 12 - 114 + 30 + 116 @@ -133,8 +133,8 @@ $(pv_value) 50 false 72a2bf2b:1508717c835:-7c63 - 24 - 43 + 42 + 45 @@ -190,8 +190,8 @@ $(pv_value) Text Input 100 35ebaa52:1509cf6a868:-7c52 - 84 - 40 + 102 + 42 @@ -230,8 +230,8 @@ $(pv_value) 50 false 35ebaa52:1509cf6a868:-7c4a - 24 - 75 + 42 + 77 @@ -287,8 +287,8 @@ $(pv_value) Text Input 100 35ebaa52:1509cf6a868:-7c40 - 84 - 72 + 102 + 74 @@ -318,13 +318,13 @@ $(pv_value) false - Enable / Disable Routes + ($(CPUID)) Enable / Disable Routes true 1 true Label - 196 + 253 false 6b3345f4:17760d4a2f0:-75ae 6 @@ -341,7 +341,7 @@ importPackage(Packages.org.yamcs.studio.data); var MsgID =VTypeHelper.getString(display.getWidget('MsgID').getPropertyValue('pv_value')); var PipeID =VTypeHelper.getString(display.getWidget('PipeID').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_sb/DisableRoute', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_sb/DisableRoute', { 'Payload.MsgId': MsgID, 'Payload.Pipe': PipeID, 'Payload.Spare': 0}); @@ -391,7 +391,7 @@ $(pv_value) Action Button 85 6b3345f4:17760d4a2f0:-75a0 - 108 - 114 + 126 + 116 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/SB/Main.opi b/core/base/tools/commander/workspace_template/Displays/Core/SB/Main.opi index cc537ede6..faf387423 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/SB/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/SB/Main.opi @@ -10,7 +10,7 @@ - 1.5.5.202103162101 + 1.6.2.202104092231 @@ -23,7 +23,7 @@ Displays /modules/core/modules/cfe/modules/cfe_sb - CFE-SB + ($(CPUID)) CFE-SB true @@ -32,7 +32,7 @@ true true Display - 600 + 500 45ea5983:1502a6e6386:-7f06 -1 -1 @@ -64,7 +64,7 @@ Text Update 0 false - /cfs/cfe_sb/CFE_SB_HKMsg_t.Payload.CommandCnt + /cfs/$(CPUID)/cfe_sb/CFE_SB_HKMsg_t.Payload.CommandCnt 0.0 @@ -636,7 +636,7 @@ $(pv_value) Text Update_1 0 false - /cfs/cfe_sb/CFE_SB_HKMsg_t.Payload.CmdErrCnt + /cfs/$(CPUID)/cfe_sb/CFE_SB_HKMsg_t.Payload.CmdErrCnt 0.0 @@ -688,7 +688,7 @@ $(pv_value) Text Update_2 0 false - /cfs/cfe_sb/CFE_SB_HKMsg_t.Payload.NoSubscribersCnt + /cfs/$(CPUID)/cfe_sb/CFE_SB_HKMsg_t.Payload.NoSubscribersCnt 0.0 @@ -740,7 +740,7 @@ $(pv_value) Text Update_3 0 false - /cfs/cfe_sb/CFE_SB_HKMsg_t.Payload.MsgSendErrCnt + /cfs/$(CPUID)/cfe_sb/CFE_SB_HKMsg_t.Payload.MsgSendErrCnt 0.0 @@ -792,7 +792,7 @@ $(pv_value) Text Update_4 0 false - /cfs/cfe_sb/CFE_SB_HKMsg_t.Payload.MsgReceiveErrCnt + /cfs/$(CPUID)/cfe_sb/CFE_SB_HKMsg_t.Payload.MsgReceiveErrCnt 0.0 @@ -844,7 +844,7 @@ $(pv_value) Text Update_5 0 false - /cfs/cfe_sb/CFE_SB_HKMsg_t.Payload.InternalErrCnt + /cfs/$(CPUID)/cfe_sb/CFE_SB_HKMsg_t.Payload.InternalErrCnt 0.0 @@ -896,7 +896,7 @@ $(pv_value) Text Update_6 0 false - /cfs/cfe_sb/CFE_SB_HKMsg_t.Payload.CreatePipeErrCnt + /cfs/$(CPUID)/cfe_sb/CFE_SB_HKMsg_t.Payload.CreatePipeErrCnt 0.0 @@ -948,7 +948,7 @@ $(pv_value) Text Update_7 0 false - /cfs/cfe_sb/CFE_SB_HKMsg_t.Payload.SubscribeErrCnt + /cfs/$(CPUID)/cfe_sb/CFE_SB_HKMsg_t.Payload.SubscribeErrCnt 0.0 @@ -1000,7 +1000,7 @@ $(pv_value) Text Update_8 0 false - /cfs/cfe_sb/CFE_SB_HKMsg_t.Payload.DupSubscriptionsCnt + /cfs/$(CPUID)/cfe_sb/CFE_SB_HKMsg_t.Payload.DupSubscriptionsCnt 0.0 @@ -1052,7 +1052,7 @@ $(pv_value) Text Update_9 0 false - /cfs/cfe_sb/CFE_SB_HKMsg_t.Payload.PipeOverflowErrCnt + /cfs/$(CPUID)/cfe_sb/CFE_SB_HKMsg_t.Payload.PipeOverflowErrCnt 0.0 @@ -1104,7 +1104,7 @@ $(pv_value) Text Update_10 0 false - /cfs/cfe_sb/CFE_SB_HKMsg_t.Payload.MsgLimErrCnt + /cfs/$(CPUID)/cfe_sb/CFE_SB_HKMsg_t.Payload.MsgLimErrCnt 0.0 @@ -1135,7 +1135,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_sb/NoOp', {});]]> true @@ -1190,7 +1190,7 @@ Yamcs.issueCommand('/cfs/cfe_sb/NoOp', {});]]> +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_sb/Reset', {});]]> true @@ -1267,35 +1267,24 @@ $(pv_value) false - Core Flight Executive - Software Bus + ($(CPUID)) Core Flight Executive - Software Bus true 1 true Label - 295 + 349 false 763e00b7:150973f1dd8:-7cf4 6 6 - - - - ViewStatistics.opi - - true - - 1 - - - - false - false + + + false - + - false @@ -1305,16 +1294,12 @@ $(pv_value) Default - false - 26 - - Action Button - 0 - - + 20 + 2 + Label_50 true @@ -1322,39 +1307,31 @@ $(pv_value) false - - View Statistics - false - $(pv_name) -$(pv_value) + Memory In Use + + true + 1 true - Action Button - 142 - 763e00b7:150973f1dd8:-7bb2 - 294 - 168 + Label + 146 + false + 763e00b7:150973f1dd8:-7381 + 6 + 311 - - - - DumpRoutingInfo.opi - - true - - 1 - - - + + false + false false - + - false + true - + - 0 + 1 1 true @@ -1364,12 +1341,15 @@ $(pv_value) - 26 - - Action Button_1 - 0 - + 0 + 20 + 0 + Text Update_11 + 0 + false + /cfs/$(CPUID)/cfe_sb/CFE_SB_HKMsg_t.Payload.MemInUse + 0.0 true @@ -1377,35 +1357,26 @@ $(pv_value) false - - Dump Routing Info - false + true + ###### $(pv_name) $(pv_value) + false + 1 true - Action Button - 142 - 763e00b7:150973f1dd8:-7ba6 - 294 - 193 + Text Update + 100 + false + 763e00b7:150973f1dd8:-7380 + 169 + 311 - - - - DumpPipeInfo.opi - - true - - 1 - - - - false - false + + + false - + - false @@ -1415,16 +1386,62 @@ $(pv_value) Default + + + + 20 + 2 + Label_51 + + + true + true + false + + + Unmarked Memory + + true + 1 + true + Label + 146 + false + 763e00b7:150973f1dd8:-7379 + 6 + 330 + + + + false + false + false + + + + true + + + + 1 + 1 + true + + Default + false - 26 - - Action Button_2 - 0 - + 0 + 20 + 0 + Text Update_12 + 0 + false + /cfs/$(CPUID)/cfe_sb/CFE_SB_HKMsg_t.Payload.UnmarkedMem + 0.0 true @@ -1432,22 +1449,24 @@ $(pv_value) false - - Dump Pipe Info - false + true + ###### $(pv_name) $(pv_value) + false + 1 true - Action Button - 142 - 763e00b7:150973f1dd8:-769d - 294 - 218 + Text Update + 100 + false + 763e00b7:150973f1dd8:-7378 + 169 + 330 - /Displays/Core/SB/DumpMapInfo.opi + EnaDisRoutes.opi true @@ -1476,7 +1495,7 @@ $(pv_value) 26 - Action Button_3 + Action Button_4 0 @@ -1488,16 +1507,16 @@ $(pv_value) - Dump Map Info + Ena/Dis Routes false $(pv_name) $(pv_value) true Action Button 142 - 763e00b7:150973f1dd8:-75e2 + 35ebaa52:1509cf6a868:-7ca7 294 - 243 + 118 @@ -1519,7 +1538,7 @@ $(pv_value) 20 2 - Label_50 + Label_52 true @@ -1527,7 +1546,7 @@ $(pv_value) false - Memory In Use + Mem Pool Handle true 1 @@ -1535,9 +1554,9 @@ $(pv_value) Label 146 false - 763e00b7:150973f1dd8:-7381 + 2285957:177658292c4:-7be3 6 - 311 + 292 @@ -1561,13 +1580,13 @@ $(pv_value) - 0 + 3 20 0 - Text Update_11 + Text Update_13 0 false - /cfs/cfe_sb/CFE_SB_HKMsg_t.Payload.MemInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_HKMsg_t.Payload.MemPoolHandle 0.0 @@ -1587,16 +1606,27 @@ $(pv_value) Text Update 100 false - 763e00b7:150973f1dd8:-7380 + 2285957:177658292c4:-7be2 169 - 311 + 292 - - - false + + + + ViewStatistics.opi + + true + + 1 + + + + false + false - + + false @@ -1606,12 +1636,16 @@ $(pv_value) Default + false - 20 - 2 - Label_51 + 26 + + Action Button + 0 + + true @@ -1619,31 +1653,39 @@ $(pv_value) false - Unmarked Memory - - true - 1 + + View Statistics + false + $(pv_name) +$(pv_value) true - Label - 146 - false - 763e00b7:150973f1dd8:-7379 - 6 - 330 + Action Button + 142 + -c05c465:1785c72c4a1:-6bf4 + 294 + 159 - - + + + + DumpRoutingInfo.opi + + true + + 1 + + + false - false false - + - true + false - + - 1 + 0 1 true @@ -1653,15 +1695,12 @@ $(pv_value) - 0 - 20 - 0 - Text Update_12 - 0 - false - /cfs/cfe_sb/CFE_SB_HKMsg_t.Payload.UnmarkedMem + 26 + + Action Button_1 + 0 + - 0.0 true @@ -1669,24 +1708,22 @@ $(pv_value) false - true - ###### + + Dump Routing Info + false $(pv_name) $(pv_value) - false - 1 true - Text Update - 100 - false - 763e00b7:150973f1dd8:-7378 - 169 - 330 + Action Button + 142 + -c05c465:1785c72c4a1:-6bec + 294 + 184 - EnaDisRoutes.opi + DumpPipeInfo.opi true @@ -1715,7 +1752,7 @@ $(pv_value) 26 - Action Button_4 + Action Button_2 0 @@ -1727,23 +1764,34 @@ $(pv_value) - Ena/Dis Routes + Dump Pipe Info false $(pv_name) $(pv_value) true Action Button 142 - 35ebaa52:1509cf6a868:-7ca7 + -c05c465:1785c72c4a1:-6be4 294 - 118 + 209 - - - false + + + + /Displays/Core/SB/DumpMapInfo.opi + + true + + 1 + + + + false + false - + + false @@ -1753,12 +1801,16 @@ $(pv_value) Default + false - 20 - 2 - Label_52 + 26 + + Action Button_3 + 0 + + true @@ -1766,31 +1818,45 @@ $(pv_value) false - Mem Pool Handle - - true - 1 + + Dump Map Info + false + $(pv_name) +$(pv_value) true - Label - 146 - false - 2285957:177658292c4:-7be3 - 6 - 292 + Action Button + 142 + -c05c465:1785c72c4a1:-6bdc + 294 + 232 - - + + + + + + true + + + false - false false - + - true + false - + - 1 + 0 1 true @@ -1800,15 +1866,12 @@ $(pv_value) - 3 - 20 - 0 - Text Update_13 - 0 - false - /cfs/cfe_sb/CFE_SB_HKMsg_t.Payload.MemPoolHandle + 26 + + Events + 0 + - 0.0 true @@ -1816,19 +1879,17 @@ $(pv_value) false - true - ###### + + Event Filters + false $(pv_name) $(pv_value) - false - 1 true - Text Update - 100 - false - 2285957:177658292c4:-7be2 - 169 - 292 + Action Button + 142 + -c05c465:1785c72c4a1:-6bcc + 294 + 257 @@ -1837,7 +1898,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_sb/SendHK', {});]]> true @@ -1861,7 +1922,7 @@ Yamcs.issueCommand('/cfs/cfe_sb/SendHK', {});]]> - 20 + 26 ../../Resources/send.png NoOp_34 0 @@ -1881,10 +1942,10 @@ Yamcs.issueCommand('/cfs/cfe_sb/SendHK', {});]]> $(pv_value) true Action Button - 86 - 1075cf36:17766873921:-7abf - 342 - 6 + 142 + -c05c465:1785c72c4a1:-6bbc + 294 + 306 @@ -1895,10 +1956,10 @@ importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); importPackage(org.csstudio.opibuilder.runmode) -var opi_to_open_path = FileUtil.workspacePathToSysPath(display.getMacroValue("EVENTS_OPI")); +var opi_to_open_path = FileUtil.workspacePathToSysPath("Displays/Core/ES/ApplicationControl_App.opi"); var macroInput = DataUtil.createMacrosInput(true); -ScriptUtil.openOPI(display.getWidget("Events"), opi_to_open_path, RunModeService.DisplayMode.REPLACE, macroInput );]]> +ScriptUtil.openOPI(display.getWidget("AppControl"), opi_to_open_path, RunModeService.DisplayMode.REPLACE, macroInput );]]> true @@ -1924,7 +1985,7 @@ ScriptUtil.openOPI(display.getWidget("Events"), opi_to_open_path, RunModeService 26 - Events + AppControl 0 @@ -1936,15 +1997,15 @@ ScriptUtil.openOPI(display.getWidget("Events"), opi_to_open_path, RunModeService - Event Filters + App Control false $(pv_name) $(pv_value) true Action Button 142 - -19107c2b:177da1db5df:2196 + 49c9ccd0:178c6a335db:-5561 294 - 268 + 282 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/SB/ViewAllSubReports.opi b/core/base/tools/commander/workspace_template/Displays/Core/SB/ViewAllSubReports.opi index fd26c50ca..d36487cc2 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/SB/ViewAllSubReports.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/SB/ViewAllSubReports.opi @@ -19,7 +19,7 @@ true - CFE-SB - Subs + ($(CPUID)) CFE-SB - Subs true @@ -60,7 +60,7 @@ Text Update 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.PktSegment + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.PktSegment 0.0 @@ -152,7 +152,7 @@ $(pv_value) Text Update_1 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.TotalSegments + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.TotalSegments 0.0 @@ -244,7 +244,7 @@ $(pv_value) Text Update_2 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entries + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entries 0.0 @@ -336,7 +336,7 @@ $(pv_value) false - Previous SubReport Message + ($(CPUID)) Previous SubReport Message true 1 @@ -376,7 +376,7 @@ $(pv_value) Text Update_5 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_0_.MsgId + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_0_.MsgId 0.0 @@ -468,7 +468,7 @@ $(pv_value) Text Update_6 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_0_.Qos.Priority + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_0_.Qos.Priority 0.0 @@ -560,7 +560,7 @@ $(pv_value) Text Update_7 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_0_.Qos.Reliability + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_0_.Qos.Reliability 0.0 @@ -692,7 +692,7 @@ $(pv_value) Text Update_8 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_1_.MsgId + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_1_.MsgId 0.0 @@ -744,7 +744,7 @@ $(pv_value) Text Update_9 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_1_.Qos.Priority + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_1_.Qos.Priority 0.0 @@ -796,7 +796,7 @@ $(pv_value) Text Update_10 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_1_.Qos.Reliability + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_1_.Qos.Reliability 0.0 @@ -888,7 +888,7 @@ $(pv_value) Text Update_11 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_2_.MsgId + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_2_.MsgId 0.0 @@ -940,7 +940,7 @@ $(pv_value) Text Update_12 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_2_.Qos.Priority + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_2_.Qos.Priority 0.0 @@ -992,7 +992,7 @@ $(pv_value) Text Update_13 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_2_.Qos.Reliability + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_2_.Qos.Reliability 0.0 @@ -1084,7 +1084,7 @@ $(pv_value) Text Update_14 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_4_.MsgId + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_4_.MsgId 0.0 @@ -1136,7 +1136,7 @@ $(pv_value) Text Update_15 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_4_.Qos.Priority + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_4_.Qos.Priority 0.0 @@ -1188,7 +1188,7 @@ $(pv_value) Text Update_16 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_4_.Qos.Reliability + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_4_.Qos.Reliability 0.0 @@ -1280,7 +1280,7 @@ $(pv_value) Text Update_17 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_6_.MsgId + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_6_.MsgId 0.0 @@ -1332,7 +1332,7 @@ $(pv_value) Text Update_18 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_6_.Qos.Priority + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_6_.Qos.Priority 0.0 @@ -1384,7 +1384,7 @@ $(pv_value) Text Update_19 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_6_.Qos.Reliability + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_6_.Qos.Reliability 0.0 @@ -1476,7 +1476,7 @@ $(pv_value) Text Update_23 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_9_.MsgId + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_9_.MsgId 0.0 @@ -1528,7 +1528,7 @@ $(pv_value) Text Update_24 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_9_.Qos.Priority + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_9_.Qos.Priority 0.0 @@ -1580,7 +1580,7 @@ $(pv_value) Text Update_25 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_9_.Qos.Reliability + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_9_.Qos.Reliability 0.0 @@ -1672,7 +1672,7 @@ $(pv_value) Text Update_26 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_8_.MsgId + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_8_.MsgId 0.0 @@ -1724,7 +1724,7 @@ $(pv_value) Text Update_27 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_8_.Qos.Priority + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_8_.Qos.Priority 0.0 @@ -1776,7 +1776,7 @@ $(pv_value) Text Update_28 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_8_.Qos.Reliability + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_8_.Qos.Reliability 0.0 @@ -1868,7 +1868,7 @@ $(pv_value) Text Update_29 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_5_.MsgId + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_5_.MsgId 0.0 @@ -1920,7 +1920,7 @@ $(pv_value) Text Update_30 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_5_.Qos.Priority + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_5_.Qos.Priority 0.0 @@ -1972,7 +1972,7 @@ $(pv_value) Text Update_31 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_5_.Qos.Reliability + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_5_.Qos.Reliability 0.0 @@ -2064,7 +2064,7 @@ $(pv_value) Text Update_32 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_14_.MsgId + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_14_.MsgId 0.0 @@ -2116,7 +2116,7 @@ $(pv_value) Text Update_33 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_14_.Qos.Priority + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_14_.Qos.Priority 0.0 @@ -2168,7 +2168,7 @@ $(pv_value) Text Update_34 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_14_.Qos.Reliability + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_14_.Qos.Reliability 0.0 @@ -2260,7 +2260,7 @@ $(pv_value) Text Update_35 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_7_.MsgId + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_7_.MsgId 0.0 @@ -2312,7 +2312,7 @@ $(pv_value) Text Update_36 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_7_.Qos.Priority + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_7_.Qos.Priority 0.0 @@ -2364,7 +2364,7 @@ $(pv_value) Text Update_37 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_7_.Qos.Reliability + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_7_.Qos.Reliability 0.0 @@ -2456,7 +2456,7 @@ $(pv_value) Text Update_38 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_3_.MsgId + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_3_.MsgId 0.0 @@ -2508,7 +2508,7 @@ $(pv_value) Text Update_39 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_3_.Qos.Priority + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_3_.Qos.Priority 0.0 @@ -2560,7 +2560,7 @@ $(pv_value) Text Update_40 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_3_.Qos.Reliability + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_3_.Qos.Reliability 0.0 @@ -2652,7 +2652,7 @@ $(pv_value) Text Update_41 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_11_.MsgId + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_11_.MsgId 0.0 @@ -2704,7 +2704,7 @@ $(pv_value) Text Update_42 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_11_.Qos.Priority + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_11_.Qos.Priority 0.0 @@ -2756,7 +2756,7 @@ $(pv_value) Text Update_43 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_11_.Qos.Reliability + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_11_.Qos.Reliability 0.0 @@ -2848,7 +2848,7 @@ $(pv_value) Text Update_44 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_10_.MsgId + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_10_.MsgId 0.0 @@ -2900,7 +2900,7 @@ $(pv_value) Text Update_45 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_10_.Qos.Priority + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_10_.Qos.Priority 0.0 @@ -2952,7 +2952,7 @@ $(pv_value) Text Update_46 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_10_.Qos.Reliability + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_10_.Qos.Reliability 0.0 @@ -3044,7 +3044,7 @@ $(pv_value) Text Update_47 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_16_.MsgId + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_16_.MsgId 0.0 @@ -3096,7 +3096,7 @@ $(pv_value) Text Update_48 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_16_.Qos.Priority + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_16_.Qos.Priority 0.0 @@ -3148,7 +3148,7 @@ $(pv_value) Text Update_49 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_16_.Qos.Reliability + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_16_.Qos.Reliability 0.0 @@ -3240,7 +3240,7 @@ $(pv_value) Text Update_50 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_18_.MsgId + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_18_.MsgId 0.0 @@ -3292,7 +3292,7 @@ $(pv_value) Text Update_51 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_18_.Qos.Priority + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_18_.Qos.Priority 0.0 @@ -3344,7 +3344,7 @@ $(pv_value) Text Update_52 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_18_.Qos.Reliability + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_18_.Qos.Reliability 0.0 @@ -3436,7 +3436,7 @@ $(pv_value) Text Update_53 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_17_.MsgId + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_17_.MsgId 0.0 @@ -3488,7 +3488,7 @@ $(pv_value) Text Update_54 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_17_.Qos.Priority + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_17_.Qos.Priority 0.0 @@ -3540,7 +3540,7 @@ $(pv_value) Text Update_55 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_17_.Qos.Reliability + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_17_.Qos.Reliability 0.0 @@ -3632,7 +3632,7 @@ $(pv_value) Text Update_56 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_13_.MsgId + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_13_.MsgId 0.0 @@ -3684,7 +3684,7 @@ $(pv_value) Text Update_57 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_13_.Qos.Priority + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_13_.Qos.Priority 0.0 @@ -3736,7 +3736,7 @@ $(pv_value) Text Update_58 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_13_.Qos.Reliability + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_13_.Qos.Reliability 0.0 @@ -3828,7 +3828,7 @@ $(pv_value) Text Update_59 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_12_.MsgId + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_12_.MsgId 0.0 @@ -3880,7 +3880,7 @@ $(pv_value) Text Update_60 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_12_.Qos.Priority + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_12_.Qos.Priority 0.0 @@ -3932,7 +3932,7 @@ $(pv_value) Text Update_61 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_12_.Qos.Reliability + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_12_.Qos.Reliability 0.0 @@ -4024,7 +4024,7 @@ $(pv_value) Text Update_62 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_15_.MsgId + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_15_.MsgId 0.0 @@ -4076,7 +4076,7 @@ $(pv_value) Text Update_63 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_15_.Qos.Priority + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_15_.Qos.Priority 0.0 @@ -4128,7 +4128,7 @@ $(pv_value) Text Update_64 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_15_.Qos.Reliability + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_15_.Qos.Reliability 0.0 @@ -4220,7 +4220,7 @@ $(pv_value) Text Update_65 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_19_.MsgId + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_19_.MsgId 0.0 @@ -4272,7 +4272,7 @@ $(pv_value) Text Update_66 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_19_.Qos.Priority + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_19_.Qos.Priority 0.0 @@ -4324,7 +4324,7 @@ $(pv_value) Text Update_67 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_19_.Qos.Reliability + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_19_.Qos.Reliability 0.0 @@ -4416,7 +4416,7 @@ $(pv_value) Text Update_68 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_0_.Pipe + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_0_.Pipe 0.0 @@ -4508,7 +4508,7 @@ $(pv_value) Text Update_69 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_1_.Pipe + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_1_.Pipe 0.0 @@ -4560,7 +4560,7 @@ $(pv_value) Text Update_70 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_2_.Pipe + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_2_.Pipe 0.0 @@ -4612,7 +4612,7 @@ $(pv_value) Text Update_71 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_4_.Pipe + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_4_.Pipe 0.0 @@ -4664,7 +4664,7 @@ $(pv_value) Text Update_72 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_6_.Pipe + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_6_.Pipe 0.0 @@ -4716,7 +4716,7 @@ $(pv_value) Text Update_73 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_9_.Pipe + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_9_.Pipe 0.0 @@ -4768,7 +4768,7 @@ $(pv_value) Text Update_74 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_8_.Pipe + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_8_.Pipe 0.0 @@ -4820,7 +4820,7 @@ $(pv_value) Text Update_75 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_5_.Pipe + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_5_.Pipe 0.0 @@ -4872,7 +4872,7 @@ $(pv_value) Text Update_76 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_14_.Pipe + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_14_.Pipe 0.0 @@ -4924,7 +4924,7 @@ $(pv_value) Text Update_77 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_7_.Pipe + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_7_.Pipe 0.0 @@ -4976,7 +4976,7 @@ $(pv_value) Text Update_78 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_3_.Pipe + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_3_.Pipe 0.0 @@ -5028,7 +5028,7 @@ $(pv_value) Text Update_79 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_11_.Pipe + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_11_.Pipe 0.0 @@ -5080,7 +5080,7 @@ $(pv_value) Text Update_80 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_10_.Pipe + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_10_.Pipe 0.0 @@ -5132,7 +5132,7 @@ $(pv_value) Text Update_81 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_16_.Pipe + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_16_.Pipe 0.0 @@ -5184,7 +5184,7 @@ $(pv_value) Text Update_82 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_18_.Pipe + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_18_.Pipe 0.0 @@ -5236,7 +5236,7 @@ $(pv_value) Text Update_83 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_17_.Pipe + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_17_.Pipe 0.0 @@ -5288,7 +5288,7 @@ $(pv_value) Text Update_84 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_13_.Pipe + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_13_.Pipe 0.0 @@ -5340,7 +5340,7 @@ $(pv_value) Text Update_85 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_12_.Pipe + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_12_.Pipe 0.0 @@ -5392,7 +5392,7 @@ $(pv_value) Text Update_86 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_15_.Pipe + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_15_.Pipe 0.0 @@ -5444,7 +5444,7 @@ $(pv_value) Text Update_87 0 true - /cfs/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_19_.Pipe + /cfs/$(CPUID)/cfe_sb/CFE_SB_PrevSubMsg_t.Payload.Entry_19_.Pipe 0.0 @@ -5475,7 +5475,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_sb/SendPrevSubs', {});]]> true diff --git a/core/base/tools/commander/workspace_template/Displays/Core/SB/ViewStatistics.opi b/core/base/tools/commander/workspace_template/Displays/Core/SB/ViewStatistics.opi index 6f676b5e9..f59bb0292 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/SB/ViewStatistics.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/SB/ViewStatistics.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-SB - Statistics + ($(CPUID)) CFE-SB - Statistics true @@ -39,7 +39,7 @@ +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_sb/SendStats', {});]]> true @@ -116,7 +116,7 @@ $(pv_value) Text Update 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.MsgIdsInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.MsgIdsInUse 0.0 @@ -168,7 +168,7 @@ $(pv_value) Text Update_1 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PeakMsgIdsInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PeakMsgIdsInUse 0.0 @@ -220,7 +220,7 @@ $(pv_value) Text Update_2 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.MaxMsgIdsAllowed + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.MaxMsgIdsAllowed 0.0 @@ -272,7 +272,7 @@ $(pv_value) Text Update_3 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipesInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipesInUse 0.0 @@ -324,7 +324,7 @@ $(pv_value) Text Update_4 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PeakPipesInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PeakPipesInUse 0.0 @@ -376,7 +376,7 @@ $(pv_value) Text Update_5 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.MaxPipesAllowed + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.MaxPipesAllowed 0.0 @@ -428,7 +428,7 @@ $(pv_value) Text Update_6 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.MemInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.MemInUse 0.0 @@ -480,7 +480,7 @@ $(pv_value) Text Update_7 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PeakMemInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PeakMemInUse 0.0 @@ -532,7 +532,7 @@ $(pv_value) Text Update_8 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.MaxMemAllowed + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.MaxMemAllowed 0.0 @@ -584,7 +584,7 @@ $(pv_value) Text Update_9 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.SubscriptionsInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.SubscriptionsInUse 0.0 @@ -636,7 +636,7 @@ $(pv_value) Text Update_10 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PeakSubscriptionsInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PeakSubscriptionsInUse 0.0 @@ -688,7 +688,7 @@ $(pv_value) Text Update_11 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload..MaxSubscriptionsAllowed + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload..MaxSubscriptionsAllowed 0.0 @@ -740,7 +740,7 @@ $(pv_value) Text Update_12 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload..SBBuffersInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload..SBBuffersInUse 0.0 @@ -792,7 +792,7 @@ $(pv_value) Text Update_13 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload..PeakSBBuffersInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload..PeakSBBuffersInUse 0.0 @@ -844,7 +844,7 @@ $(pv_value) Text Update_14 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload..MaxPipeDepthAllowed + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload..MaxPipeDepthAllowed 0.0 @@ -1496,7 +1496,7 @@ $(pv_value) Text Update_15 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_0_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_0_.PipeId 0.0 @@ -1628,7 +1628,7 @@ $(pv_value) Text Update_16 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_0_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_0_.Depth 0.0 @@ -1758,7 +1758,7 @@ $(pv_value) 20 Check Box - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_0_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_0_.InUse @@ -1807,7 +1807,7 @@ $(pv_value) Text Update_17 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_0_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_0_.PeakInUse 0.0 @@ -1899,7 +1899,7 @@ $(pv_value) Text Update_19 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_1_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_1_.PipeId 0.0 @@ -1991,7 +1991,7 @@ $(pv_value) Text Update_20 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_1_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_1_.Depth 0.0 @@ -2041,7 +2041,7 @@ $(pv_value) 20 Check Box_1 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_1_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_1_.InUse @@ -2090,7 +2090,7 @@ $(pv_value) Text Update_21 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_1_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_1_.InUse 0.0 @@ -2142,7 +2142,7 @@ $(pv_value) Text Update_23 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_2_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_2_.PipeId 0.0 @@ -2234,7 +2234,7 @@ $(pv_value) Text Update_24 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_1_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_1_.Depth 0.0 @@ -2284,7 +2284,7 @@ $(pv_value) 20 Check Box_2 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_2_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_2_.InUse @@ -2333,7 +2333,7 @@ $(pv_value) Text Update_25 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_1_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_1_.PeakInUse 0.0 @@ -2385,7 +2385,7 @@ $(pv_value) Text Update_27 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_3_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_3_.PipeId 0.0 @@ -2477,7 +2477,7 @@ $(pv_value) Text Update_28 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_3_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_3_.Depth 0.0 @@ -2527,7 +2527,7 @@ $(pv_value) 20 Check Box_3 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_3_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_3_.PipeId @@ -2576,7 +2576,7 @@ $(pv_value) Text Update_29 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_1_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_1_.PeakInUse 0.0 @@ -2628,7 +2628,7 @@ $(pv_value) Text Update_31 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_4_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_4_.PipeId 0.0 @@ -2720,7 +2720,7 @@ $(pv_value) Text Update_32 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_4_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_4_.Depth 0.0 @@ -2770,7 +2770,7 @@ $(pv_value) 20 Check Box_4 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_4_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_4_.InUse @@ -2819,7 +2819,7 @@ $(pv_value) Text Update_33 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_4_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_4_.PeakInUse 0.0 @@ -2871,7 +2871,7 @@ $(pv_value) Text Update_35 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_5_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_5_.PipeId 0.0 @@ -2963,7 +2963,7 @@ $(pv_value) Text Update_36 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_5_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_5_.Depth 0.0 @@ -3013,7 +3013,7 @@ $(pv_value) 20 Check Box_5 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_5_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_5_.InUse @@ -3062,7 +3062,7 @@ $(pv_value) Text Update_37 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_5_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_5_.PeakInUse 0.0 @@ -3114,7 +3114,7 @@ $(pv_value) Text Update_39 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_5_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_5_.PipeId 0.0 @@ -3206,7 +3206,7 @@ $(pv_value) Text Update_40 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_5_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_5_.Depth 0.0 @@ -3256,7 +3256,7 @@ $(pv_value) 20 Check Box_6 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_6_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_6_.InUse @@ -3305,7 +3305,7 @@ $(pv_value) Text Update_41 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_5_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_5_.PeakInUse 0.0 @@ -3357,7 +3357,7 @@ $(pv_value) Text Update_43 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_6_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_6_.PipeId 0.0 @@ -3449,7 +3449,7 @@ $(pv_value) Text Update_44 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_7_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_7_.Depth 0.0 @@ -3499,7 +3499,7 @@ $(pv_value) 20 Check Box_7 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_7_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_7_.InUse @@ -3548,7 +3548,7 @@ $(pv_value) Text Update_45 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_7_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_7_.PeakInUse 0.0 @@ -3600,7 +3600,7 @@ $(pv_value) Text Update_47 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_8_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_8_.PipeId 0.0 @@ -3692,7 +3692,7 @@ $(pv_value) Text Update_48 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_8_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_8_.Depth 0.0 @@ -3742,7 +3742,7 @@ $(pv_value) 20 Check Box_8 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_8_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_8_.InUse @@ -3791,7 +3791,7 @@ $(pv_value) Text Update_49 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_8_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_8_.PeakInUse 0.0 @@ -3843,7 +3843,7 @@ $(pv_value) Text Update_51 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_9_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_9_.PipeId 0.0 @@ -3935,7 +3935,7 @@ $(pv_value) Text Update_52 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_9_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_9_.Depth 0.0 @@ -3985,7 +3985,7 @@ $(pv_value) 20 Check Box_9 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_9_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_9_.InUse @@ -4034,7 +4034,7 @@ $(pv_value) Text Update_53 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_9_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_9_.PeakInUse 0.0 @@ -4086,7 +4086,7 @@ $(pv_value) Text Update_54 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_10_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_10_.PipeId 0.0 @@ -4178,7 +4178,7 @@ $(pv_value) Text Update_55 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_10_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_10_.Depth 0.0 @@ -4228,7 +4228,7 @@ $(pv_value) 20 Check Box_10 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_10_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_10_.InUse @@ -4277,7 +4277,7 @@ $(pv_value) Text Update_56 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_10_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_10_.PeakInUse 0.0 @@ -4329,7 +4329,7 @@ $(pv_value) Text Update_57 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_11_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_11_.PipeId 0.0 @@ -4421,7 +4421,7 @@ $(pv_value) Text Update_58 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_11_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_11_.Depth 0.0 @@ -4471,7 +4471,7 @@ $(pv_value) 20 Check Box_11 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_11_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_11_.InUse @@ -4520,7 +4520,7 @@ $(pv_value) Text Update_59 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_11_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_11_.PeakInUse 0.0 @@ -4572,7 +4572,7 @@ $(pv_value) Text Update_60 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_12_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_12_.PipeId 0.0 @@ -4664,7 +4664,7 @@ $(pv_value) Text Update_61 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_12_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_12_.Depth 0.0 @@ -4714,7 +4714,7 @@ $(pv_value) 20 Check Box_12 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_12_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_12_.PipeId @@ -4763,7 +4763,7 @@ $(pv_value) Text Update_62 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_12_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_12_.PeakInUse 0.0 @@ -4815,7 +4815,7 @@ $(pv_value) Text Update_63 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_13_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_13_.PipeId 0.0 @@ -4907,7 +4907,7 @@ $(pv_value) Text Update_64 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_11_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_11_.Depth 0.0 @@ -4957,7 +4957,7 @@ $(pv_value) 20 Check Box_13 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_13_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_13_.InUse @@ -5006,7 +5006,7 @@ $(pv_value) Text Update_65 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_13_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_13_.PeakInUse 0.0 @@ -5058,7 +5058,7 @@ $(pv_value) Text Update_66 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_14_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_14_.PipeId 0.0 @@ -5150,7 +5150,7 @@ $(pv_value) Text Update_67 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_14_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_14_.Depth 0.0 @@ -5200,7 +5200,7 @@ $(pv_value) 20 Check Box_14 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_14_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_14_.InUse @@ -5249,7 +5249,7 @@ $(pv_value) Text Update_68 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_14_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_14_.PeakInUse 0.0 @@ -5301,7 +5301,7 @@ $(pv_value) Text Update_69 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_15_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_15_.PipeId 0.0 @@ -5393,7 +5393,7 @@ $(pv_value) Text Update_70 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_15_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_15_.Depth 0.0 @@ -5443,7 +5443,7 @@ $(pv_value) 20 Check Box_15 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_15_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_15_.InUse @@ -5492,7 +5492,7 @@ $(pv_value) Text Update_71 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_15_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_15_.PeakInUse 0.0 @@ -5544,7 +5544,7 @@ $(pv_value) Text Update_72 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_16_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_16_.PipeId 0.0 @@ -5636,7 +5636,7 @@ $(pv_value) Text Update_73 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_16_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_16_.Depth 0.0 @@ -5686,7 +5686,7 @@ $(pv_value) 20 Check Box_16 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_16_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_16_.InUse @@ -5735,7 +5735,7 @@ $(pv_value) Text Update_74 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_16_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_16_.PeakInUse 0.0 @@ -5787,7 +5787,7 @@ $(pv_value) Text Update_75 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_17_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_17_.PipeId 0.0 @@ -5879,7 +5879,7 @@ $(pv_value) Text Update_76 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_17_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_17_.Depth 0.0 @@ -5929,7 +5929,7 @@ $(pv_value) 20 Check Box_17 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_17_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_17_.InUse @@ -5978,7 +5978,7 @@ $(pv_value) Text Update_77 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_17_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_17_.PeakInUse 0.0 @@ -6030,7 +6030,7 @@ $(pv_value) Text Update_78 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_18_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_18_.PipeId 0.0 @@ -6122,7 +6122,7 @@ $(pv_value) Text Update_79 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_18_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_18_.Depth 0.0 @@ -6172,7 +6172,7 @@ $(pv_value) 20 Check Box_18 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_18_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_18_.InUse @@ -6221,7 +6221,7 @@ $(pv_value) Text Update_80 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_18_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_18_.PeakInUse 0.0 @@ -6273,7 +6273,7 @@ $(pv_value) Text Update_81 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_19_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_19_.PipeId 0.0 @@ -6365,7 +6365,7 @@ $(pv_value) Text Update_82 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_19_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_19_.Depth 0.0 @@ -6415,7 +6415,7 @@ $(pv_value) 20 Check Box_19 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_19_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_19_.InUse @@ -6464,7 +6464,7 @@ $(pv_value) Text Update_83 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_19_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_19_.PeakInUse 0.0 @@ -6516,7 +6516,7 @@ $(pv_value) Text Update_84 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_20_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_20_.PipeId 0.0 @@ -6608,7 +6608,7 @@ $(pv_value) Text Update_85 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_20_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_20_.Depth 0.0 @@ -6658,7 +6658,7 @@ $(pv_value) 20 Check Box_20 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_20_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_20_.InUse @@ -6707,7 +6707,7 @@ $(pv_value) Text Update_86 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_11_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_11_.PeakInUse 0.0 @@ -6759,7 +6759,7 @@ $(pv_value) Text Update_87 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_21_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_21_.PipeId 0.0 @@ -6851,7 +6851,7 @@ $(pv_value) Text Update_88 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_11_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_11_.Depth 0.0 @@ -6901,7 +6901,7 @@ $(pv_value) 20 Check Box_21 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_11_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_11_.PipeId @@ -6950,7 +6950,7 @@ $(pv_value) Text Update_89 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_11_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_11_.PeakInUse 0.0 @@ -7002,7 +7002,7 @@ $(pv_value) Text Update_90 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_22_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_22_.PipeId 0.0 @@ -7094,7 +7094,7 @@ $(pv_value) Text Update_91 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_22_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_22_.Depth 0.0 @@ -7144,7 +7144,7 @@ $(pv_value) 20 Check Box_22 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_22_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_22_.InUse @@ -7193,7 +7193,7 @@ $(pv_value) Text Update_92 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_22_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_22_.PeakInUse 0.0 @@ -7245,7 +7245,7 @@ $(pv_value) Text Update_93 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_23_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_23_.PipeId 0.0 @@ -7337,7 +7337,7 @@ $(pv_value) Text Update_94 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_23_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_23_.Depth 0.0 @@ -7387,7 +7387,7 @@ $(pv_value) 20 Check Box_23 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_23_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_23_.InUse @@ -7436,7 +7436,7 @@ $(pv_value) Text Update_95 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_23_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_23_.PeakInUse 0.0 @@ -7488,7 +7488,7 @@ $(pv_value) Text Update_96 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_24_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_24_.PipeId 0.0 @@ -7580,7 +7580,7 @@ $(pv_value) Text Update_97 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_24_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_24_.Depth 0.0 @@ -7630,7 +7630,7 @@ $(pv_value) 20 Check Box_24 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_24_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_24_.InUse @@ -7679,7 +7679,7 @@ $(pv_value) Text Update_98 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_24_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_24_.PeakInUse 0.0 @@ -7731,7 +7731,7 @@ $(pv_value) Text Update_99 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_25_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_25_.PipeId 0.0 @@ -7823,7 +7823,7 @@ $(pv_value) Text Update_100 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_25_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_25_.Depth 0.0 @@ -7873,7 +7873,7 @@ $(pv_value) 20 Check Box_25 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_25_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_25_.InUse @@ -7922,7 +7922,7 @@ $(pv_value) Text Update_101 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_25_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_25_.PeakInUse 0.0 @@ -7974,7 +7974,7 @@ $(pv_value) Text Update_102 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_26_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_26_.PipeId 0.0 @@ -8066,7 +8066,7 @@ $(pv_value) Text Update_103 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_26_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_26_.Depth 0.0 @@ -8116,7 +8116,7 @@ $(pv_value) 20 Check Box_26 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_26_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_26_.InUse @@ -8165,7 +8165,7 @@ $(pv_value) Text Update_104 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_26_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_26_.PeakInUse 0.0 @@ -8217,7 +8217,7 @@ $(pv_value) Text Update_105 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_27_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_27_.PipeId 0.0 @@ -8309,7 +8309,7 @@ $(pv_value) Text Update_106 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_27_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_27_.Depth 0.0 @@ -8359,7 +8359,7 @@ $(pv_value) 20 Check Box_27 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_27_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_27_.InUse @@ -8408,7 +8408,7 @@ $(pv_value) Text Update_107 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_27_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_27_.PeakInUse 0.0 @@ -8460,7 +8460,7 @@ $(pv_value) Text Update_108 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_28_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_28_.PipeId 0.0 @@ -8552,7 +8552,7 @@ $(pv_value) Text Update_109 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_28_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_28_.Depth 0.0 @@ -8602,7 +8602,7 @@ $(pv_value) 20 Check Box_28 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_28_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_28_.InUse @@ -8651,7 +8651,7 @@ $(pv_value) Text Update_110 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_28_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_28_.InUse 0.0 @@ -8703,7 +8703,7 @@ $(pv_value) Text Update_111 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_29_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_29_.PipeId 0.0 @@ -8795,7 +8795,7 @@ $(pv_value) Text Update_112 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_29_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_29_.Depth 0.0 @@ -8845,7 +8845,7 @@ $(pv_value) 20 Check Box_29 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_29_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_29_.InUse @@ -8894,7 +8894,7 @@ $(pv_value) Text Update_113 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_29_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_29_.Depth 0.0 @@ -8946,7 +8946,7 @@ $(pv_value) Text Update_114 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_30_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_30_.PipeId 0.0 @@ -9038,7 +9038,7 @@ $(pv_value) Text Update_115 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_30_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_30_.Depth 0.0 @@ -9088,7 +9088,7 @@ $(pv_value) 20 Check Box_30 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_30_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_30_.InUse @@ -9137,7 +9137,7 @@ $(pv_value) Text Update_116 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_30_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_30_.PeakInUse 0.0 @@ -9189,7 +9189,7 @@ $(pv_value) Text Update_117 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_31_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_31_.PipeId 0.0 @@ -9281,7 +9281,7 @@ $(pv_value) Text Update_118 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_31_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_31_.Depth 0.0 @@ -9331,7 +9331,7 @@ $(pv_value) 20 Check Box_31 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_31_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_31_.InUse @@ -9380,7 +9380,7 @@ $(pv_value) Text Update_119 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_31_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_31_.PeakInUse 0.0 @@ -9432,7 +9432,7 @@ $(pv_value) Text Update_120 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_32_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_32_.PipeId 0.0 @@ -9524,7 +9524,7 @@ $(pv_value) Text Update_121 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_32_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_32_.Depth 0.0 @@ -9574,7 +9574,7 @@ $(pv_value) 20 Check Box_32 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_32_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_32_.InUse @@ -9623,7 +9623,7 @@ $(pv_value) Text Update_122 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_32_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_32_.PeakInUse 0.0 @@ -9675,7 +9675,7 @@ $(pv_value) Text Update_123 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_33_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_33_.PipeId 0.0 @@ -9767,7 +9767,7 @@ $(pv_value) Text Update_124 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_33_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_33_.Depth 0.0 @@ -9817,7 +9817,7 @@ $(pv_value) 20 Check Box_33 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_33_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_33_.InUse @@ -9866,7 +9866,7 @@ $(pv_value) Text Update_125 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_33_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_33_.PeakInUse 0.0 @@ -9918,7 +9918,7 @@ $(pv_value) Text Update_126 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_34_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_34_.PipeId 0.0 @@ -10010,7 +10010,7 @@ $(pv_value) Text Update_127 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_34_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_34_.Depth 0.0 @@ -10060,7 +10060,7 @@ $(pv_value) 20 Check Box_34 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_34_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_34_.InUse @@ -10109,7 +10109,7 @@ $(pv_value) Text Update_128 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_34_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_34_.PeakInUse 0.0 @@ -10161,7 +10161,7 @@ $(pv_value) Text Update_129 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_35_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_35_.PipeId 0.0 @@ -10253,7 +10253,7 @@ $(pv_value) Text Update_130 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_35_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_35_.Depth 0.0 @@ -10303,7 +10303,7 @@ $(pv_value) 20 Check Box_35 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_35_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_35_.InUse @@ -10352,7 +10352,7 @@ $(pv_value) Text Update_131 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_35_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_35_.PeakInUse 0.0 @@ -10404,7 +10404,7 @@ $(pv_value) Text Update_132 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_36_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_36_.PipeId 0.0 @@ -10496,7 +10496,7 @@ $(pv_value) Text Update_133 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_36_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_36_.Depth 0.0 @@ -10546,7 +10546,7 @@ $(pv_value) 20 Check Box_36 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_36_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_36_.InUse @@ -10595,7 +10595,7 @@ $(pv_value) Text Update_134 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_36_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_36_.PeakInUse 0.0 @@ -10647,7 +10647,7 @@ $(pv_value) Text Update_135 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_37_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_37_.PipeId 0.0 @@ -10739,7 +10739,7 @@ $(pv_value) Text Update_136 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_37_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_37_.Depth 0.0 @@ -10789,7 +10789,7 @@ $(pv_value) 20 Check Box_37 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_37_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_37_.InUse @@ -10838,7 +10838,7 @@ $(pv_value) Text Update_137 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_37_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_37_.Depth 0.0 @@ -10890,7 +10890,7 @@ $(pv_value) Text Update_138 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_38_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_38_.PipeId 0.0 @@ -10982,7 +10982,7 @@ $(pv_value) Text Update_139 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_38_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_38_.Depth 0.0 @@ -11032,7 +11032,7 @@ $(pv_value) 20 Check Box_38 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_38_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_38_.InUse @@ -11081,7 +11081,7 @@ $(pv_value) Text Update_140 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_38_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_38_.PeakInUse 0.0 @@ -11133,7 +11133,7 @@ $(pv_value) Text Update_141 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_39_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_39_.PipeId 0.0 @@ -11225,7 +11225,7 @@ $(pv_value) Text Update_142 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_39_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_39_.Depth 0.0 @@ -11275,7 +11275,7 @@ $(pv_value) 20 Check Box_39 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_39_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_39_.InUse @@ -11324,7 +11324,7 @@ $(pv_value) Text Update_143 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_39_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_39_.PeakInUse 0.0 @@ -11376,7 +11376,7 @@ $(pv_value) Text Update_144 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_40_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_40_.PipeId 0.0 @@ -11468,7 +11468,7 @@ $(pv_value) Text Update_145 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_40_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_40_.Depth 0.0 @@ -11518,7 +11518,7 @@ $(pv_value) 20 Check Box_40 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_40_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_40_.InUse @@ -11567,7 +11567,7 @@ $(pv_value) Text Update_146 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_40_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_40_.PeakInUse 0.0 @@ -11619,7 +11619,7 @@ $(pv_value) Text Update_147 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_41_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_41_.PipeId 0.0 @@ -11711,7 +11711,7 @@ $(pv_value) Text Update_148 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_41_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_41_.Depth 0.0 @@ -11761,7 +11761,7 @@ $(pv_value) 20 Check Box_41 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_41_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_41_.InUse @@ -11810,7 +11810,7 @@ $(pv_value) Text Update_149 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_41_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_41_.PeakInUse 0.0 @@ -11862,7 +11862,7 @@ $(pv_value) Text Update_150 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_42_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_42_.PipeId 0.0 @@ -11954,7 +11954,7 @@ $(pv_value) Text Update_151 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_42_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_42_.Depth 0.0 @@ -12004,7 +12004,7 @@ $(pv_value) 20 Check Box_42 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_42_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_42_.InUse @@ -12053,7 +12053,7 @@ $(pv_value) Text Update_152 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_42_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_42_.PeakInUse 0.0 @@ -12105,7 +12105,7 @@ $(pv_value) Text Update_153 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_43_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_43_.PipeId 0.0 @@ -12197,7 +12197,7 @@ $(pv_value) Text Update_154 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_43_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_43_.Depth 0.0 @@ -12247,7 +12247,7 @@ $(pv_value) 20 Check Box_43 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_43_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_43_.InUse @@ -12296,7 +12296,7 @@ $(pv_value) Text Update_155 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_43_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_43_.PeakInUse 0.0 @@ -12348,7 +12348,7 @@ $(pv_value) Text Update_156 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_44_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_44_.PipeId 0.0 @@ -12440,7 +12440,7 @@ $(pv_value) Text Update_157 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_44_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_44_.Depth 0.0 @@ -12490,7 +12490,7 @@ $(pv_value) 20 Check Box_44 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_44_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_44_.InUse @@ -12539,7 +12539,7 @@ $(pv_value) Text Update_158 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_44_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_44_.PeakInUse 0.0 @@ -12591,7 +12591,7 @@ $(pv_value) Text Update_159 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_45_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_45_.PipeId 0.0 @@ -12683,7 +12683,7 @@ $(pv_value) Text Update_160 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_45_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_45_.Depth 0.0 @@ -12733,7 +12733,7 @@ $(pv_value) 20 Check Box_45 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_45_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_45_.InUse @@ -12782,7 +12782,7 @@ $(pv_value) Text Update_161 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_45_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_45_.PeakInUse 0.0 @@ -12834,7 +12834,7 @@ $(pv_value) Text Update_162 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_46_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_46_.PipeId 0.0 @@ -12926,7 +12926,7 @@ $(pv_value) Text Update_163 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_46_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_46_.Depth 0.0 @@ -12976,7 +12976,7 @@ $(pv_value) 20 Check Box_46 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_46_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_46_.InUse @@ -13025,7 +13025,7 @@ $(pv_value) Text Update_164 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_46_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_46_.PeakInUse 0.0 @@ -13077,7 +13077,7 @@ $(pv_value) Text Update_165 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_47_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_47_.PipeId 0.0 @@ -13169,7 +13169,7 @@ $(pv_value) Text Update_166 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_47_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_47_.Depth 0.0 @@ -13219,7 +13219,7 @@ $(pv_value) 20 Check Box_47 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_47_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_47_.InUse @@ -13268,7 +13268,7 @@ $(pv_value) Text Update_167 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_47_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_47_.PeakInUse 0.0 @@ -13320,7 +13320,7 @@ $(pv_value) Text Update_168 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_48_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_48_.InUse 0.0 @@ -13412,7 +13412,7 @@ $(pv_value) Text Update_169 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_48_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_48_.Depth 0.0 @@ -13462,7 +13462,7 @@ $(pv_value) 20 Check Box_48 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_48_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_48_.InUse @@ -13511,7 +13511,7 @@ $(pv_value) Text Update_170 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_48_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_48_.PeakInUse 0.0 @@ -13563,7 +13563,7 @@ $(pv_value) Text Update_171 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_49_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_49_.PipeId 0.0 @@ -13655,7 +13655,7 @@ $(pv_value) Text Update_172 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_49_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_49_.Depth 0.0 @@ -13705,7 +13705,7 @@ $(pv_value) 20 Check Box_49 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_49_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_49_.InUse @@ -13754,7 +13754,7 @@ $(pv_value) Text Update_173 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_49_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_49_.PeakInUse 0.0 @@ -13806,7 +13806,7 @@ $(pv_value) Text Update_174 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_50_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_50_.PipeId 0.0 @@ -13898,7 +13898,7 @@ $(pv_value) Text Update_175 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_50_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_50_.Depth 0.0 @@ -13948,7 +13948,7 @@ $(pv_value) 20 Check Box_50 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_50_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_50_.InUse @@ -13997,7 +13997,7 @@ $(pv_value) Text Update_176 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_50_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_50_.PeakInUse 0.0 @@ -14049,7 +14049,7 @@ $(pv_value) Text Update_177 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_50_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_50_.PipeId 0.0 @@ -14141,7 +14141,7 @@ $(pv_value) Text Update_178 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_51_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_51_.Depth 0.0 @@ -14191,7 +14191,7 @@ $(pv_value) 20 Check Box_51 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_51_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_51_.InUse @@ -14240,7 +14240,7 @@ $(pv_value) Text Update_179 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_51_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_51_.PeakInUse 0.0 @@ -14292,7 +14292,7 @@ $(pv_value) Text Update_180 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_52_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_52_.PipeId 0.0 @@ -14384,7 +14384,7 @@ $(pv_value) Text Update_181 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_52_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_52_.Depth 0.0 @@ -14434,7 +14434,7 @@ $(pv_value) 20 Check Box_52 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_52_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_52_.InUse @@ -14483,7 +14483,7 @@ $(pv_value) Text Update_182 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_52_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_52_.PeakInUse 0.0 @@ -14535,7 +14535,7 @@ $(pv_value) Text Update_183 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_53_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_53_.PipeId 0.0 @@ -14627,7 +14627,7 @@ $(pv_value) Text Update_184 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_53_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_53_.Depth 0.0 @@ -14677,7 +14677,7 @@ $(pv_value) 20 Check Box_53 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_53_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_53_.InUse @@ -14726,7 +14726,7 @@ $(pv_value) Text Update_185 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_54_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_54_.PeakInUse 0.0 @@ -14778,7 +14778,7 @@ $(pv_value) Text Update_186 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_54_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_54_.PipeId 0.0 @@ -14870,7 +14870,7 @@ $(pv_value) Text Update_187 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_54_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_54_.Depth 0.0 @@ -14920,7 +14920,7 @@ $(pv_value) 20 Check Box_54 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_54_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_54_.InUse @@ -14969,7 +14969,7 @@ $(pv_value) Text Update_188 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_54_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_54_.PeakInUse 0.0 @@ -15021,7 +15021,7 @@ $(pv_value) Text Update_189 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_55_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_55_.PipeId 0.0 @@ -15113,7 +15113,7 @@ $(pv_value) Text Update_190 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_55_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_55_.Depth 0.0 @@ -15163,7 +15163,7 @@ $(pv_value) 20 Check Box_55 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_54_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_54_.InUse @@ -15212,7 +15212,7 @@ $(pv_value) Text Update_191 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_55_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_55_.PeakInUse 0.0 @@ -15264,7 +15264,7 @@ $(pv_value) Text Update_192 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_56_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_56_.PipeId 0.0 @@ -15356,7 +15356,7 @@ $(pv_value) Text Update_193 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_56_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_56_.Depth 0.0 @@ -15406,7 +15406,7 @@ $(pv_value) 20 Check Box_56 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_56_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_56_.InUse @@ -15455,7 +15455,7 @@ $(pv_value) Text Update_194 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_56_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_56_.PeakInUse 0.0 @@ -15507,7 +15507,7 @@ $(pv_value) Text Update_195 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_57_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_57_.PipeId 0.0 @@ -15599,7 +15599,7 @@ $(pv_value) Text Update_196 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_57_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_57_.Depth 0.0 @@ -15649,7 +15649,7 @@ $(pv_value) 20 Check Box_57 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_57_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_57_.InUse @@ -15698,7 +15698,7 @@ $(pv_value) Text Update_197 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_57_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_57_.PeakInUse 0.0 @@ -15750,7 +15750,7 @@ $(pv_value) Text Update_198 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_58_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_58_.PipeId 0.0 @@ -15842,7 +15842,7 @@ $(pv_value) Text Update_199 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_58_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_58_.Depth 0.0 @@ -15892,7 +15892,7 @@ $(pv_value) 20 Check Box_58 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_58_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_58_.InUse @@ -15941,7 +15941,7 @@ $(pv_value) Text Update_200 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_58_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_58_.PeakInUse 0.0 @@ -15993,7 +15993,7 @@ $(pv_value) Text Update_201 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_59_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_59_.PipeId 0.0 @@ -16085,7 +16085,7 @@ $(pv_value) Text Update_202 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_59_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_59_.Depth 0.0 @@ -16135,7 +16135,7 @@ $(pv_value) 20 Check Box_59 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_59_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_59_.InUse @@ -16184,7 +16184,7 @@ $(pv_value) Text Update_203 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_59_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_59_.PeakInUse 0.0 @@ -16236,7 +16236,7 @@ $(pv_value) Text Update_204 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_60_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_60_.PipeId 0.0 @@ -16328,7 +16328,7 @@ $(pv_value) Text Update_205 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_60_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_60_.Depth 0.0 @@ -16378,7 +16378,7 @@ $(pv_value) 20 Check Box_60 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_60_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_60_.InUse @@ -16427,7 +16427,7 @@ $(pv_value) Text Update_206 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_60_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_60_.PeakInUse 0.0 @@ -16479,7 +16479,7 @@ $(pv_value) Text Update_207 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_61_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_61_.PipeId 0.0 @@ -16571,7 +16571,7 @@ $(pv_value) Text Update_208 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_61_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_61_.Depth 0.0 @@ -16621,7 +16621,7 @@ $(pv_value) 20 Check Box_61 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_61_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_61_.InUse @@ -16670,7 +16670,7 @@ $(pv_value) Text Update_209 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_61_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_61_.PeakInUse 0.0 @@ -16722,7 +16722,7 @@ $(pv_value) Text Update_210 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_62_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_62_.PipeId 0.0 @@ -16814,7 +16814,7 @@ $(pv_value) Text Update_211 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_62_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_62_.Depth 0.0 @@ -16864,7 +16864,7 @@ $(pv_value) 20 Check Box_62 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_62_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_62_.InUse @@ -16913,7 +16913,7 @@ $(pv_value) Text Update_212 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_62_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_62_.PeakInUse 0.0 @@ -16965,7 +16965,7 @@ $(pv_value) Text Update_213 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_63_.PipeId + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_63_.PipeId 0.0 @@ -17057,7 +17057,7 @@ $(pv_value) Text Update_214 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_63_.Depth + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_63_.Depth 0.0 @@ -17107,7 +17107,7 @@ $(pv_value) 20 Check Box_63 - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_63_.InUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_63_.InUse @@ -17156,7 +17156,7 @@ $(pv_value) Text Update_215 0 false - /cfs/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_63_.PeakInUse + /cfs/$(CPUID)/cfe_sb/CFE_SB_StatMsg_t.Payload.PipeDepthStats_63_.PeakInUse 0.0 @@ -17208,16 +17208,16 @@ $(pv_value) false - Statistics + ($(CPUID)) Statistics true 1 true Label - 120 + 229 false 6b3345f4:17760d4a2f0:-789d - 97 + 42 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/SB/ViewSubReport.opi b/core/base/tools/commander/workspace_template/Displays/Core/SB/ViewSubReport.opi index 3fe730a04..5e386441c 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/SB/ViewSubReport.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/SB/ViewSubReport.opi @@ -19,7 +19,7 @@ true - CFE-SB - Sub + ($(CPUID)) CFE-SB - Sub true @@ -60,7 +60,7 @@ Text Update 0 true - /cfs/cfe_sb/CFE_SB_SubRprtMsg_t.Payload.SubType + /cfs/$(CPUID)/cfe_sb/CFE_SB_SubRprtMsg_t.Payload.SubType 0.0 @@ -152,7 +152,7 @@ $(pv_value) Text Update_1 0 true - /cfs/cfe_sb/CFE_SB_SubRprtMsg_t.Payload._spare0 + /cfs/$(CPUID)/cfe_sb/CFE_SB_SubRprtMsg_t.Payload._spare0 0.0 @@ -244,7 +244,7 @@ $(pv_value) Text Update_2 0 true - /cfs/cfe_sb/CFE_SB_SubRprtMsg_t.Payload.MsgId + /cfs/$(CPUID)/cfe_sb/CFE_SB_SubRprtMsg_t.Payload.MsgId 0.0 @@ -336,7 +336,7 @@ $(pv_value) Text Update_3 0 true - /cfs/cfe_sb/CFE_SB_SubRprtMsg_t.Payload.Qos.Priority + /cfs/$(CPUID)/cfe_sb/CFE_SB_SubRprtMsg_t.Payload.Qos.Priority 0.0 @@ -428,7 +428,7 @@ $(pv_value) Text Update_4 0 true - /cfs/cfe_sb/CFE_SB_SubRprtMsg_t.Payload.Qos.Reliability + /cfs/$(CPUID)/cfe_sb/CFE_SB_SubRprtMsg_t.Payload.Qos.Reliability 0.0 @@ -520,7 +520,7 @@ $(pv_value) Text Update_5 0 true - /cfs/cfe_sb/CFE_SB_SubRprtMsg_t.Payload.Pipe + /cfs/$(CPUID)/cfe_sb/CFE_SB_SubRprtMsg_t.Payload.Pipe 0.0 @@ -612,7 +612,7 @@ $(pv_value) Text Update_6 0 true - /cfs/cfe_sb/CFE_SB_SubRprtMsg_t.Payload._spare_end + /cfs/$(CPUID)/cfe_sb/CFE_SB_SubRprtMsg_t.Payload._spare_end 0.0 @@ -704,7 +704,7 @@ $(pv_value) false - SubReport Message + ($(CPUID)) SubReport Message true 1 @@ -723,7 +723,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_sb/DisableSubReport', {});]]> true @@ -779,7 +779,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_sb/EnableSubReport', {});]]> true diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TBL/AbortTableLoad.opi b/core/base/tools/commander/workspace_template/Displays/Core/TBL/AbortTableLoad.opi index 6d11e90ce..eab30bef8 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TBL/AbortTableLoad.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TBL/AbortTableLoad.opi @@ -19,7 +19,7 @@ true - CFE-TBL - Abort + ($(CPUID)) CFE-TBL - Abort true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var tableName =VTypeHelper.getString(display.getWidget('TableName').getPropertyValue('pv_value')); -var cmd = '/cfs/cfe_tbl/AbortLoad(Payload.TableName: ' + tableName + ')'; +var cmd = '/cfs/$(CPUID)/cfe_tbl/AbortLoad(Payload.TableName: ' + tableName + ')'; Yamcs.issueCommand(cmd); @@ -220,16 +220,16 @@ $(pv_value) false - Abort Table Load + ($(CPUID)) Abort Table Load true 1 true Label - 151 + 249 false 6b3345f4:17760d4a2f0:-7325 - 66 + 12 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TBL/ActivateTable.opi b/core/base/tools/commander/workspace_template/Displays/Core/TBL/ActivateTable.opi index 0357c9132..91db04124 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TBL/ActivateTable.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TBL/ActivateTable.opi @@ -19,7 +19,7 @@ true - CFE-TBL - Activate + ($(CPUID)) CFE-TBL - Activate true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var tableName =VTypeHelper.getString(display.getWidget('TableName').getPropertyValue('pv_value')); -var cmd = '/cfs/cfe_tbl/Activate(Payload.TableName: ' + tableName + ')'; +var cmd = '/cfs/$(CPUID)/cfe_tbl/Activate(Payload.TableName: ' + tableName + ')'; Yamcs.issueCommand(cmd); @@ -220,16 +220,16 @@ $(pv_value) false - Activate Table + ($(CPUID)) Activate Table true 1 true Label - 112 + 249 false 6b3345f4:17760d4a2f0:-7334 - 78 + 12 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TBL/DeleteCDS.opi b/core/base/tools/commander/workspace_template/Displays/Core/TBL/DeleteCDS.opi index 504fd3097..2a3df3904 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TBL/DeleteCDS.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TBL/DeleteCDS.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-TBL - Delete CDS + ($(CPUID)) CFE-TBL - Delete CDS true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var tableName =VTypeHelper.getString(display.getWidget('TableName').getPropertyValue('pv_value')); -var cmd = '/cfs/cfe_tbl/DelCDS(Payload.TableName: ' + tableName + ')'; +var cmd = '/cfs/$(CPUID)/cfe_tbl/DelCDS(Payload.TableName: ' + tableName + ')'; Yamcs.issueCommand(cmd); @@ -220,16 +220,16 @@ $(pv_value) false - Delete CDS + ($(CPUID)) Delete CDS true 1 true Label - 112 + 243 false 6b3345f4:17760d4a2f0:-7346 - 78 + 18 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TBL/DumpRegistry.opi b/core/base/tools/commander/workspace_template/Displays/Core/TBL/DumpRegistry.opi index 056c81ecc..25f6b4f06 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TBL/DumpRegistry.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TBL/DumpRegistry.opi @@ -19,7 +19,7 @@ true - CFE-TBL - Dump Reg + ($(CPUID)) CFE-TBL - Dump Reg true @@ -28,7 +28,7 @@ true true Display - 275 + 310 35ebaa52:1509cf6a868:-791f -1 -1 @@ -45,9 +45,9 @@ var fileName =VTypeHelper.getString(display.getWidget('FileName').getPropertyVal var cmd; if( fileName != 'no value' ) { - cmd = '/cfs/cfe_tbl/DumpReg(Payload.DumpFilename: ' + fileName + ')'; + cmd = '/cfs/$(CPUID)/cfe_tbl/DumpReg(Payload.DumpFilename: ' + fileName + ')'; } else { - cmd = '/cfs/cfe_tbl/DumpReg(Payload.DumpFilename: "")'; + cmd = '/cfs/$(CPUID)/cfe_tbl/DumpReg(Payload.DumpFilename: "")'; } Yamcs.issueCommand(cmd); @@ -169,16 +169,16 @@ $(pv_value) false - Write Registry to File System + ($(CPUID)) Write Registry to File System true 1 true Label - 231 + 307 false 35ebaa52:1509cf6a868:-78e8 - 24 + 6 12 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TBL/DumpTable.opi b/core/base/tools/commander/workspace_template/Displays/Core/TBL/DumpTable.opi index 95d95a1c5..c731fe32c 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TBL/DumpTable.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TBL/DumpTable.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-TBL - Dump Table + ($(CPUID)) CFE-TBL - Dump Table true @@ -45,7 +45,7 @@ var tableName =VTypeHelper.getString(display.getWidget('TableName').getPropertyV var fileName =VTypeHelper.getString(display.getWidget('FileName').getPropertyValue('pv_value')); var cmd; -cmd = '/cfs/cfe_tbl/Dump'; +cmd = '/cfs/$(CPUID)/cfe_tbl/Dump'; var args; @@ -177,13 +177,13 @@ $(pv_value) false - Dump Table to File System + ($(CPUID)) Dump Table to File System true 1 true Label - 231 + 313 false 35ebaa52:1509cf6a868:-78e8 24 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TBL/LoadTable.opi b/core/base/tools/commander/workspace_template/Displays/Core/TBL/LoadTable.opi index 2a30e29e5..51a3f1ce8 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TBL/LoadTable.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TBL/LoadTable.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -19,7 +19,7 @@ true - CFE-TBL - Load Table + ($(CPUID)) CFE-TBL - Load Table true @@ -28,7 +28,7 @@ true true Display - 275 + 310 35ebaa52:1509cf6a868:-791f -1 -1 @@ -45,9 +45,9 @@ var fileName =VTypeHelper.getString(display.getWidget('FileName').getPropertyVal var cmd; if( fileName != 'no value' ) { - cmd = '/cfs/cfe_tbl/Load(Payload.LoadFilename: ' + fileName + ')'; + cmd = '/cfs/$(CPUID)/cfe_tbl/Load(Payload.LoadFilename: ' + fileName + ')'; } else { - cmd = '/cfs/cfe_tbl/Load(Payload.LoadFilename: "")'; + cmd = '/cfs/$(CPUID)/cfe_tbl/Load(Payload.LoadFilename: "")'; } Yamcs.issueCommand(cmd); @@ -169,16 +169,16 @@ $(pv_value) false - Load Table from File System. + ($(CPUID)) Load Table from File System true 1 true Label - 231 + 295 false 35ebaa52:1509cf6a868:-78e8 - 24 + 12 12 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TBL/Main.opi b/core/base/tools/commander/workspace_template/Displays/Core/TBL/Main.opi index a5019cc4c..5dbe72241 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TBL/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TBL/Main.opi @@ -10,7 +10,7 @@ - 1.5.5.202103162101 + 1.6.2.202104092231 @@ -23,7 +23,7 @@ Displays /modules/core/modules/cfe/modules/cfe_tbl - CFE-TBL + ($(CPUID)) CFE-TBL true @@ -32,7 +32,7 @@ true true Display - 600 + 510 45ea5983:1502a6e6386:-7f06 -1 -1 @@ -64,7 +64,7 @@ Text Update 0 false - /cfs/cfe_tbl/CFE_TBL_HkPacket_t.Payload.CmdCounter + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_HkPacket_t.Payload.CmdCounter 0.0 @@ -556,7 +556,7 @@ $(pv_value) Text Update_1 0 false - /cfs/cfe_tbl/CFE_TBL_HkPacket_t.Payload.ErrCounter + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_HkPacket_t.Payload.ErrCounter 0.0 @@ -608,7 +608,7 @@ $(pv_value) Text Update_4 0 false - /cfs/cfe_tbl/CFE_TBL_HkPacket_t.Payload.NumTables + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_HkPacket_t.Payload.NumTables 0.0 @@ -660,7 +660,7 @@ $(pv_value) Text Update_5 0 false - /cfs/cfe_tbl/CFE_TBL_HkPacket_t.Payload.NumLoadPending + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_HkPacket_t.Payload.NumLoadPending 0.0 @@ -712,7 +712,7 @@ $(pv_value) Text Update_6 0 false - /cfs/cfe_tbl/CFE_TBL_HkPacket_t.Payload.ValidationCtr + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_HkPacket_t.Payload.ValidationCtr 0.0 @@ -764,7 +764,7 @@ $(pv_value) Text Update_7 0 false - /cfs/cfe_tbl/CFE_TBL_HkPacket_t.Payload.LastValCrc + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_HkPacket_t.Payload.LastValCrc 0.0 @@ -816,7 +816,7 @@ $(pv_value) Text Update_8 0 false - /cfs/cfe_tbl/CFE_TBL_HkPacket_t.Payload.LastValStatus + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_HkPacket_t.Payload.LastValStatus 0.0 @@ -868,7 +868,7 @@ $(pv_value) Text Update_9 0 false - /cfs/cfe_tbl/CFE_TBL_HkPacket_t.Payload.ActiveBuffer + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_HkPacket_t.Payload.ActiveBuffer 0.0 @@ -920,7 +920,7 @@ $(pv_value) Text Update_10 0 false - /cfs/cfe_tbl/CFE_TBL_HkPacket_t.Payload.LastValTableName + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_HkPacket_t.Payload.LastValTableName 0.0 @@ -951,7 +951,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_tbl/NoOp', {});]]> true @@ -1006,7 +1006,7 @@ Yamcs.issueCommand('/cfs/cfe_tbl/NoOp', {});]]> +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_tbl/Reset', {});]]> true @@ -1083,16 +1083,16 @@ $(pv_value) false - Core Flight Executive - Table Services + ($(CPUID)) Core Flight Executive - Table Services true 1 true Label - 295 + 343 false 763e00b7:150973f1dd8:-7cf4 - 66 + 18 6 @@ -1218,7 +1218,7 @@ $(pv_value) Text Update_11 0 false - /cfs/cfe_tbl/CFE_TBL_HkPacket_t.Payload.SuccessValCtr + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_HkPacket_t.Payload.SuccessValCtr 0.0 @@ -1310,7 +1310,7 @@ $(pv_value) Text Update_12 0 false - /cfs/cfe_tbl/CFE_TBL_HkPacket_t.Payload.FailedValCtr + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_HkPacket_t.Payload.FailedValCtr 0.0 @@ -1402,7 +1402,7 @@ $(pv_value) Text Update_13 0 false - /cfs/cfe_tbl/CFE_TBL_HkPacket_t.Payload.NumValRequests + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_HkPacket_t.Payload.NumValRequests 0.0 @@ -1494,7 +1494,7 @@ $(pv_value) Text Update_14 0 false - /cfs/cfe_tbl/CFE_TBL_HkPacket_t.Payload.NumFreeSharedBufs + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_HkPacket_t.Payload.NumFreeSharedBufs 0.0 @@ -1586,7 +1586,7 @@ $(pv_value) Text Update_15 0 false - /cfs/cfe_tbl/CFE_TBL_HkPacket_t.Payload.MemPoolHandle + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_HkPacket_t.Payload.MemPoolHandle 0.0 @@ -1678,7 +1678,7 @@ $(pv_value) Text Update_16 0 false - /cfs/cfe_tbl/CFE_TBL_HkPacket_t.Payload.LastUpdateTime.Seconds + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_HkPacket_t.Payload.LastUpdateTime.Seconds 0.0 @@ -1730,7 +1730,7 @@ $(pv_value) Text Update_17 0 false - /cfs/cfe_tbl/CFE_TBL_HkPacket_t.Payload.LastUpdateTime.Subseconds + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_HkPacket_t.Payload.LastUpdateTime.Subseconds 0.0 @@ -1822,7 +1822,7 @@ $(pv_value) Text Update_18 0 false - /cfs/cfe_tbl/CFE_TBL_HkPacket_t.Payload.LastUpdatedTbl + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_HkPacket_t.Payload.LastUpdatedTbl 0.0 @@ -1914,7 +1914,7 @@ $(pv_value) Text Update_19 0 false - /cfs/cfe_tbl/CFE_TBL_HkPacket_t.Payload.LastFileLoaded + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_HkPacket_t.Payload.LastFileLoaded 0.0 @@ -2006,7 +2006,7 @@ $(pv_value) Text Update_20 0 false - /cfs/cfe_tbl/CFE_TBL_HkPacket_t.Payload.LastFileDumped + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_HkPacket_t.Payload.LastFileDumped 0.0 @@ -2098,7 +2098,7 @@ $(pv_value) Text Update_21 0 false - /cfs/cfe_tbl/CFE_TBL_HkPacket_t.Payload.LastTableLoaded + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_HkPacket_t.Payload.LastTableLoaded 0.0 @@ -2513,8 +2513,69 @@ $(pv_value) + true + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 26 + + Events + 0 + + + + + true + true + false + + + + Events + false + $(pv_name) +$(pv_value) + true + Action Button + 129 + -19107c2b:177da1db5df:2519 + 361 + 344 + + + + + + +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_tbl/SendHK', {});]]> true @@ -2538,7 +2599,7 @@ Yamcs.issueCommand('/cfs/cfe_tbl/SendHK', {});]]> - 20 + 26 ../../Resources/send.png NoOp_34 0 @@ -2558,10 +2619,10 @@ Yamcs.issueCommand('/cfs/cfe_tbl/SendHK', {});]]> $(pv_value) true Action Button - 86 - 1075cf36:17766873921:-79f9 - 396 - 6 + 129 + -c05c465:1785c72c4a1:-698f + 361 + 368 @@ -2572,10 +2633,10 @@ importPackage(Packages.org.yamcs.studio.script); importPackage(Packages.org.yamcs.studio.data); importPackage(org.csstudio.opibuilder.runmode) -var opi_to_open_path = FileUtil.workspacePathToSysPath(display.getMacroValue("EVENTS_OPI")); +var opi_to_open_path = FileUtil.workspacePathToSysPath("Displays/Core/ES/ApplicationControl_App.opi"); var macroInput = DataUtil.createMacrosInput(true); -ScriptUtil.openOPI(display.getWidget("Events"), opi_to_open_path, RunModeService.DisplayMode.REPLACE, macroInput );]]> +ScriptUtil.openOPI(display.getWidget("AppControl"), opi_to_open_path, RunModeService.DisplayMode.REPLACE, macroInput );]]> true @@ -2601,7 +2662,7 @@ ScriptUtil.openOPI(display.getWidget("Events"), opi_to_open_path, RunModeService 26 - Events + AppControl 0 @@ -2613,15 +2674,15 @@ ScriptUtil.openOPI(display.getWidget("Events"), opi_to_open_path, RunModeService - Events + App Control false $(pv_name) $(pv_value) true Action Button 129 - -19107c2b:177da1db5df:2519 + 6f9e12ff:178b8c76299:-7057 361 - 344 + 119 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TBL/ValidateTable.opi b/core/base/tools/commander/workspace_template/Displays/Core/TBL/ValidateTable.opi index 232be8d9b..2743f6f9a 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TBL/ValidateTable.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TBL/ValidateTable.opi @@ -19,7 +19,7 @@ true - CFE-TBL - Validate + ($(CPUID)) CFE-TBL - Validate true @@ -53,7 +53,7 @@ if( tableBuffer != 'Active' ) { pBuffer = 'ACTIVE_BUFFER'; } -Yamcs.issueCommand('/cfs/cfe_tbl/Validate', { +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_tbl/Validate', { 'Payload.TableName': tableName, 'Payload.ActiveTblFlag': pBuffer }); @@ -175,7 +175,7 @@ $(pv_value) false - Validate Table + ($(CPUID)) Validate Table true 1 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TBL/ViewRegistry.opi b/core/base/tools/commander/workspace_template/Displays/Core/TBL/ViewRegistry.opi index 5f998d7a3..fa2ea20f9 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TBL/ViewRegistry.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TBL/ViewRegistry.opi @@ -19,7 +19,7 @@ true - CFE-TBL - Registry + ($(CPUID)) CFE-TBL - Registry true @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var tableName =VTypeHelper.getString(display.getWidget('TableName').getPropertyValue('pv_value')); -Yamcs.issueCommand('/cfs/cfe_tbl/TlmReg', {'Payload.TableName': tableName}); +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_tbl/TlmReg', {'Payload.TableName': tableName}); ]]> true @@ -218,7 +218,7 @@ $(pv_value) Text Update 0 false - /cfs/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.Size + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.Size 0.0 @@ -270,7 +270,7 @@ $(pv_value) Text Update_1 0 false - /cfs/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.Crc + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.Crc 0.0 @@ -322,7 +322,7 @@ $(pv_value) Text Update_3 0 false - /cfs/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.InactiveBufferAddr + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.InactiveBufferAddr 0.0 @@ -374,7 +374,7 @@ $(pv_value) Text Update_4 0 false - /cfs/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.ValidationFuncPtr + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.ValidationFuncPtr 0.0 @@ -426,7 +426,7 @@ $(pv_value) Text Update_6 0 false - /cfs/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.TimeOfLastUpdate.Seconds + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.TimeOfLastUpdate.Seconds 0.0 @@ -478,7 +478,7 @@ $(pv_value) Text Update_7 0 false - /cfs/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.TimeOfLastUpdate.Subseconds + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.TimeOfLastUpdate.Subseconds 0.0 @@ -530,7 +530,7 @@ $(pv_value) Text Update_8 0 false - /cfs/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.FileCreateTimeSecs + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.FileCreateTimeSecs 0.0 @@ -582,7 +582,7 @@ $(pv_value) Text Update_9 0 false - /cfs/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.FileCreateTimeSubSecs + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.FileCreateTimeSubSecs 0.0 @@ -634,7 +634,7 @@ $(pv_value) Text Update_14 0 true - /cfs/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.Name + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.Name 0.0 @@ -686,7 +686,7 @@ $(pv_value) Text Update_15 0 true - /cfs/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.LastFileLoaded + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.LastFileLoaded 0.0 @@ -738,7 +738,7 @@ $(pv_value) Text Update_16 0 true - /cfs/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.OwnerAppName + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.OwnerAppName 0.0 @@ -1070,7 +1070,7 @@ $(pv_value) Text Update_18 0 false - /cfs/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.ActiveBufferAddr + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.ActiveBufferAddr 0.0 @@ -1160,7 +1160,7 @@ $(pv_value) 20 Check Box - /cfs/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.TableLoadedOnce + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.TableLoadedOnce @@ -1207,7 +1207,7 @@ $(pv_value) 20 Check Box_1 - /cfs/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.LoadPending + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.LoadPending @@ -1334,7 +1334,7 @@ $(pv_value) 20 Check Box_4 - /cfs/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.DumpOnly + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.DumpOnly @@ -1381,7 +1381,7 @@ $(pv_value) 20 Check Box_5 - /cfs/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.DblBuffered + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.DblBuffered @@ -1588,7 +1588,7 @@ $(pv_value) 20 Check Box_6 - /cfs/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.Critical + /cfs/$(CPUID)/cfe_tbl/CFE_TBL_TblRegPacket_t.Payload.Critical @@ -1677,16 +1677,16 @@ $(pv_value) false - Write Map Info to File System + ($(CPUID)) Write Map Info to File System true 1 true Label - 231 + 357 false 6b3345f4:17760d4a2f0:-736d - 80 + 16 12 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TIME/AbortTableLoad.opi b/core/base/tools/commander/workspace_template/Displays/Core/TIME/AbortTableLoad.opi index 561422882..0553bdbfd 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TIME/AbortTableLoad.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TIME/AbortTableLoad.opi @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var tableName =VTypeHelper.getString(display.getWidget('TableName').getPropertyValue('pv_value')); -var cmd = '/cfs/cfe_tbl/AbortLoad'; +var cmd = '/cfs/$(CPUID)/cfe_tbl/AbortLoad'; Yamcs.issueCommand(cmd, {'Payload.TableName': tableName}); diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TIME/ActivateTable.opi b/core/base/tools/commander/workspace_template/Displays/Core/TIME/ActivateTable.opi index 58b2c75bd..5e5062506 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TIME/ActivateTable.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TIME/ActivateTable.opi @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var tableName =VTypeHelper.getString(display.getWidget('TableName').getPropertyValue('pv_value')); -var cmd = '/cfs/cfe_tbl/Activate(Payload.TableName: ' + tableName + ')'; +var cmd = '/cfs/$(CPUID)/cfe_tbl/Activate(Payload.TableName: ' + tableName + ')'; Yamcs.issueCommand(cmd); diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TIME/DeleteCDS.opi b/core/base/tools/commander/workspace_template/Displays/Core/TIME/DeleteCDS.opi index 067f7538f..c246cc732 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TIME/DeleteCDS.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TIME/DeleteCDS.opi @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var tableName =VTypeHelper.getString(display.getWidget('TableName').getPropertyValue('pv_value')); -var cmd = '/cfs/cfe_tbl/DelCDS(Payload.TableName: ' + tableName + ')'; +var cmd = '/cfs/$(CPUID)/cfe_tbl/DelCDS(Payload.TableName: ' + tableName + ')'; Yamcs.issueCommand(cmd); diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TIME/DumpRegistry.opi b/core/base/tools/commander/workspace_template/Displays/Core/TIME/DumpRegistry.opi index 3273207d3..2baf4830b 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TIME/DumpRegistry.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TIME/DumpRegistry.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.5.5.202103012118 @@ -28,7 +28,7 @@ true true Display - 275 + 310 35ebaa52:1509cf6a868:-791f -1 -1 @@ -45,9 +45,9 @@ var fileName =VTypeHelper.getString(display.getWidget('FileName').getPropertyVal var cmd; if( fileName != 'no value' ) { - cmd = '/cfs/cfe_tbl/DumpReg(Payload.DumpFilename: ' + fileName + ')'; + cmd = '/cfs/$(CPUID)/cfe_tbl/DumpReg(Payload.DumpFilename: ' + fileName + ')'; } else { - cmd = '/cfs/cfe_tbl/DumpReg(Payload.DumpFilename: "")'; + cmd = '/cfs/$(CPUID)/cfe_tbl/DumpReg(Payload.DumpFilename: "")'; } Yamcs.issueCommand(cmd); @@ -154,7 +154,7 @@ $(pv_value) 1 true - Default + Default Bold @@ -169,16 +169,16 @@ $(pv_value) false - Write Registry to file system. + ($(CPUID)) Write Registry to File System true 1 true Label - 231 + 289 false 35ebaa52:1509cf6a868:-78e8 - 24 + 4 12 diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TIME/DumpTable.opi b/core/base/tools/commander/workspace_template/Displays/Core/TIME/DumpTable.opi index ed7a2d962..80982e2ff 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TIME/DumpTable.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TIME/DumpTable.opi @@ -47,9 +47,9 @@ var fileName =VTypeHelper.getString(display.getWidget('FileName').getPropertyVal var cmd; if( fileName != 'no value' ) { - cmd = '/cfs/cfe_tbl/Dump('FileName: ' + fileName)'; + cmd = '/cfs/$(CPUID)/cfe_tbl/Dump('FileName: ' + fileName)'; } else { - cmd = '/cfs/cfe_tbl/Dump('FileName:' "")'; + cmd = '/cfs/$(CPUID)/cfe_tbl/Dump('FileName:' "")'; } cmd = cmd + ', TableName: ' + tableName; diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TIME/Main.opi b/core/base/tools/commander/workspace_template/Displays/Core/TIME/Main.opi index 1c309aa30..3f83c302a 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TIME/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TIME/Main.opi @@ -10,7 +10,7 @@ - 1.5.5.202103162101 + 1.6.2.202104092231 @@ -21,7 +21,7 @@ cfe_time /Displays/Core/EVS/Events.opi Displays - /modules/core/modules/cfe/modules/cfe_es + /modules/core/modules/cfe/modules/cfe_time @@ -64,7 +64,7 @@ Text Update 0 false - /cfs/cfe_time/CFE_TIME_HkPacket_t.Payload.CmdCounter + /cfs/$(CPUID)/cfe_time/CFE_TIME_HkPacket_t.Payload.CmdCounter 0.0 @@ -556,7 +556,7 @@ $(pv_value) Text Update_1 0 false - /cfs/cfe_time/CFE_TIME_HkPacket_t.Payload.ErrCounter + /cfs/$(CPUID)/cfe_time/CFE_TIME_HkPacket_t.Payload.ErrCounter 0.0 @@ -587,7 +587,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_time/Noop', {});]]> true @@ -642,7 +642,7 @@ Yamcs.issueCommand('/cfs/cfe_time/Noop', {});]]> +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_time/Reset', {});]]> true @@ -784,7 +784,7 @@ $(pv_value) 130 763e00b7:150973f1dd8:-7ba6 294 - 118 + 142 @@ -959,7 +959,7 @@ $(pv_value) 130 35ebaa52:1509cf6a868:-7980 294 - 143 + 167 @@ -1014,7 +1014,7 @@ $(pv_value) 130 35ebaa52:1509cf6a868:-7976 294 - 168 + 192 @@ -1069,7 +1069,7 @@ $(pv_value) 130 35ebaa52:1509cf6a868:-796c 294 - 193 + 217 @@ -1124,7 +1124,7 @@ $(pv_value) 130 35ebaa52:1509cf6a868:-7965 294 - 218 + 242 @@ -1179,7 +1179,7 @@ $(pv_value) 130 35ebaa52:1509cf6a868:-794e 294 - 243 + 267 @@ -1234,7 +1234,7 @@ $(pv_value) 130 35ebaa52:1509cf6a868:-7940 294 - 268 + 292 @@ -1289,7 +1289,7 @@ $(pv_value) 130 35ebaa52:1509cf6a868:-7936 294 - 293 + 317 @@ -1317,7 +1317,7 @@ $(pv_value) 20 Check Box - /cfs/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags + /cfs/$(CPUID)/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags @@ -1364,7 +1364,7 @@ $(pv_value) 20 Check Box_1 - /cfs/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags + /cfs/$(CPUID)/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags @@ -1411,7 +1411,7 @@ $(pv_value) 20 Check Box_2 - /cfs/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags + /cfs/$(CPUID)/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags @@ -1458,7 +1458,7 @@ $(pv_value) 20 Check Box_3 - /cfs/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags + /cfs/$(CPUID)/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags @@ -1505,7 +1505,7 @@ $(pv_value) 20 Check Box_4 - /cfs/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags + /cfs/$(CPUID)/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags @@ -1552,7 +1552,7 @@ $(pv_value) 20 Check Box_5 - /cfs/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags + /cfs/$(CPUID)/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags @@ -1599,7 +1599,7 @@ $(pv_value) 20 Check Box_6 - /cfs/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags + /cfs/$(CPUID)/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags @@ -1646,7 +1646,7 @@ $(pv_value) 20 Check Box_7 - /cfs/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags + /cfs/$(CPUID)/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags @@ -1693,7 +1693,7 @@ $(pv_value) 20 Check Box_8 - /cfs/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags + /cfs/$(CPUID)/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags @@ -1740,7 +1740,7 @@ $(pv_value) 20 Check Box_9 - /cfs/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags + /cfs/$(CPUID)/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags @@ -1787,7 +1787,7 @@ $(pv_value) 20 Check Box_10 - /cfs/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags + /cfs/$(CPUID)/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags @@ -2116,7 +2116,7 @@ $(pv_value) Text Update_3 0 false - /cfs/cfe_time/CFE_TIME_HkPacket_t.Payload.LeapSeconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_HkPacket_t.Payload.LeapSeconds 0.0 @@ -2168,7 +2168,7 @@ $(pv_value) Text Update_4 0 false - /cfs/cfe_time/CFE_TIME_HkPacket_t.Payload.SecondsMET + /cfs/$(CPUID)/cfe_time/CFE_TIME_HkPacket_t.Payload.SecondsMET 0.0 @@ -2220,7 +2220,7 @@ $(pv_value) Text Update_5 0 false - /cfs/cfe_time/CFE_TIME_HkPacket_t.Payload.SubsecsMET + /cfs/$(CPUID)/cfe_time/CFE_TIME_HkPacket_t.Payload.SubsecsMET 0.0 @@ -2272,7 +2272,7 @@ $(pv_value) Text Update_6 0 false - /cfs/cfe_time/CFE_TIME_HkPacket_t.Payload.SecondsSTCF + /cfs/$(CPUID)/cfe_time/CFE_TIME_HkPacket_t.Payload.SecondsSTCF 0.0 @@ -2324,7 +2324,7 @@ $(pv_value) Text Update_7 0 false - /cfs/cfe_time/CFE_TIME_HkPacket_t.Payload.SubsecsSTCF + /cfs/$(CPUID)/cfe_time/CFE_TIME_HkPacket_t.Payload.SubsecsSTCF 0.0 @@ -2376,7 +2376,7 @@ $(pv_value) Text Update_8 0 false - /cfs/cfe_time/CFE_TIME_HkPacket_t.Payload.Seconds1HzAdj + /cfs/$(CPUID)/cfe_time/CFE_TIME_HkPacket_t.Payload.Seconds1HzAdj 0.0 @@ -2428,7 +2428,7 @@ $(pv_value) Text Update_9 0 false - /cfs/cfe_time/CFE_TIME_HkPacket_t.Payload.Subsecs1HzAdj + /cfs/$(CPUID)/cfe_time/CFE_TIME_HkPacket_t.Payload.Subsecs1HzAdj 0.0 @@ -2480,7 +2480,7 @@ $(pv_value) Text Update_10 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ClockStateAPI + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ClockStateAPI 0.0 @@ -2557,7 +2557,7 @@ $(pv_value) 130 59d9b0dc:177f3efc307:-7cdc 294 - 318 + 342 @@ -2566,7 +2566,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_time/ToneSignal',{});]]> true @@ -2622,7 +2622,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_time/FakeTone',{});]]> true @@ -2669,7 +2669,7 @@ $(pv_value) 130 59d9b0dc:177f3efc307:-759b 294 - 368 + 392 @@ -2678,7 +2678,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_time/1HZCmd',{});]]> true @@ -2725,7 +2725,7 @@ $(pv_value) 130 59d9b0dc:177f3efc307:-7554 294 - 393 + 417 @@ -2734,7 +2734,7 @@ $(pv_value) +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_time/SendCmd',{});]]> true @@ -2781,7 +2781,7 @@ $(pv_value) 130 59d9b0dc:177f3efc307:-74ff 294 - 418 + 442 @@ -2809,7 +2809,7 @@ $(pv_value) 20 Check Box_11 - /cfs/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags + /cfs/$(CPUID)/cfe_time/CFE_TIME_HkPacket_t.Payload.ClockStateFlags @@ -2889,6 +2889,67 @@ $(pv_value) 129 -19107c2b:177da1db5df:2767 295 - 344 + 368 + + + + + + + true + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 26 + + AppControl + 0 + + + + + true + true + false + + + + App Control + false + $(pv_name) +$(pv_value) + true + Action Button + 129 + 49c9ccd0:178c6a335db:-4377 + 295 + 117 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetAdjust.opi b/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetAdjust.opi index 548805935..34f0bbd3c 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetAdjust.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetAdjust.opi @@ -47,13 +47,13 @@ var Microseconds =VTypeHelper.getDouble(display.getWidget('Microseconds').getPro var cmd; if( (Direction == "Add" ) && (Frequency == "One Shot")) { - cmd = '/cfs/cfe_time/AddAdjust(Payload.Seconds:' + Seconds + ', Payload.MicroSeconds:' + Microseconds +')'; + cmd = '/cfs/$(CPUID)/cfe_time/AddAdjust(Payload.Seconds:' + Seconds + ', Payload.MicroSeconds:' + Microseconds +')'; } else if( (Direction == "Subtract" ) && (Frequency == "One Shot")) { - cmd = '/cfs/cfe_time/SubAdjust(Payload.Seconds:' + Seconds + ', Payload.MicroSeconds:' + Microseconds +')'; + cmd = '/cfs/$(CPUID)/cfe_time/SubAdjust(Payload.Seconds:' + Seconds + ', Payload.MicroSeconds:' + Microseconds +')'; } else if( (Direction == "Add" ) && (Frequency == "1 Hz")) { - cmd = '/cfs/cfe_time/Add1HzAdjust(Payload.Seconds:' + Seconds + ', Payload.Subseconds:' + Microseconds +')'; + cmd = '/cfs/$(CPUID)/cfe_time/Add1HzAdjust(Payload.Seconds:' + Seconds + ', Payload.Subseconds:' + Microseconds +')'; } else if( (Direction == "Subtract" ) && (Frequency == "1 Hz")) { - cmd = '/cfs/cfe_time/Sub1HzAdjust(Payload.Seconds:' + Seconds + ', Payload.Subseconds:' + Microseconds +')'; + cmd = '/cfs/$(CPUID)/cfe_time/Sub1HzAdjust(Payload.Seconds:' + Seconds + ', Payload.Subseconds:' + Microseconds +')'; } Yamcs.issueCommand(cmd); diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetDelay.opi b/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetDelay.opi index ad78fd09b..c69f250f9 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetDelay.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetDelay.opi @@ -47,9 +47,9 @@ var Microseconds =VTypeHelper.getDouble(display.getWidget('Microseconds').getPro var cmd; if( Direction == 'Add' ) { - cmd = '/cfs/cfe_time/AddDelay'; + cmd = '/cfs/$(CPUID)/cfe_time/AddDelay'; } else if( Direction == 'Subtract' ) { - cmd = '/cfs/cfe_time/SubDelay'; + cmd = '/cfs/$(CPUID)/cfe_time/SubDelay'; } Yamcs.issueCommand(cmd, { diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetLeaps.opi b/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetLeaps.opi index 431af54f5..4a270ab5a 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetLeaps.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetLeaps.opi @@ -10,12 +10,12 @@ - 1.5.3 + 1.5.5.202103012118 6 - 175 + 160 true @@ -28,7 +28,7 @@ true true Display - 300 + 290 35ebaa52:1509cf6a868:-791f -1 -1 @@ -42,7 +42,7 @@ importPackage(Packages.org.yamcs.studio.data); var Seconds =VTypeHelper.getDouble(display.getWidget('Seconds').getPropertyValue('pv_value')); var Microseconds=VTypeHelper.getDouble(display.getWidget('Microseconds').getPropertyValue('pv_value')); -var cmd = '/cfs/cfe_time/SetLeapSeconds'; +var cmd = '/cfs/$(CPUID)/cfe_time/SetLeapSeconds'; Yamcs.issueCommand(cmd, { 'Payload.Seconds': Seconds, @@ -291,4 +291,44 @@ $(pv_value) 114 78 + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_69 + + + true + true + false + + + ($(CPUID)) CFE-TIME - Set Leaps + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-673c + 15 + 12 + \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetSignal.opi b/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetSignal.opi index afdca18f9..33ed484b5 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetSignal.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetSignal.opi @@ -10,12 +10,12 @@ - 1.5.3 + 1.5.5.202103012118 6 - 100 + 110 true @@ -28,7 +28,7 @@ true true Display - 275 + 300 35ebaa52:1509cf6a868:-791f -1 -1 @@ -45,9 +45,9 @@ var toneSource =VTypeHelper.getString(display.getWidget('ToneSource').getPropert var cmd; if( toneSource == 'Primary' ) { - cmd = '/cfs/cfe_time/SetSignal(Payload.ToneSource: "PRIMARY")'; + cmd = '/cfs/$(CPUID)/cfe_time/SetSignal(Payload.ToneSource: "PRIMARY")'; } else if (toneSource == 'Redundant' ) { - cmd = '/cfs/cfe_time/SetSignal(Payload.ToneSource: "REDUNDANT")'; + cmd = '/cfs/$(CPUID)/cfe_time/SetSignal(Payload.ToneSource: "REDUNDANT")'; } Yamcs.issueCommand(cmd); @@ -99,7 +99,7 @@ $(pv_value) 163 35ebaa52:1509cf6a868:-78ea 54 - 60 + 78 @@ -139,7 +139,7 @@ $(pv_value) false 35ebaa52:1509cf6a868:-78e9 18 - 23 + 41 @@ -185,6 +185,46 @@ $(pv_value) 135 35ebaa52:1509cf6a868:-78e7 108 - 18 + 36 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_69 + + + true + true + false + + + ($(CPUID)) CFE-TIME - Set Tone Signal + + true + 1 + true + Label + 298 + false + -c05c465:1785c72c4a1:-6749 + 3 + 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetSource.opi b/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetSource.opi index 2aac8e9b1..fbefa426c 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetSource.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetSource.opi @@ -10,12 +10,12 @@ - 1.5.3 + 1.5.5.202103012118 6 - 100 + 110 true @@ -45,9 +45,9 @@ var clockSource =VTypeHelper.getString(display.getWidget('ClockSource').getPrope var cmd; if(clockSource == 'Internal' ) { - cmd = '/cfs/cfe_time/SetSource(Payload.TimeSource: "INTERN")'; + cmd = '/cfs/$(CPUID)/cfe_time/SetSource(Payload.TimeSource: "INTERN")'; } else if (clockSource == 'External' ) { - cmd = '/cfs/cfe_time/SetSource(Payload.TimeSource: "EXTERN")'; + cmd = '/cfs/$(CPUID)/cfe_time/SetSource(Payload.TimeSource: "EXTERN")'; } Yamcs.issueCommand(cmd); @@ -99,7 +99,7 @@ $(pv_value) 163 35ebaa52:1509cf6a868:-78ea 54 - 60 + 78 @@ -139,7 +139,7 @@ $(pv_value) false 35ebaa52:1509cf6a868:-78e9 12 - 23 + 41 @@ -185,6 +185,46 @@ $(pv_value) 135 35ebaa52:1509cf6a868:-78e7 108 - 18 + 36 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_69 + + + true + true + false + + + ($(CPUID)) CFE-TIME - Set Source + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-6754 + 3 + 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetState.opi b/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetState.opi index 81eef6099..e0049c52b 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetState.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetState.opi @@ -10,12 +10,12 @@ - 1.5.3 + 1.5.5.202103012118 6 - 100 + 110 true @@ -45,11 +45,11 @@ var clockState =VTypeHelper.getString(display.getWidget('ClockState').getPropert var cmd; if( clockState == 'Invalid' ) { - cmd = '/cfs/cfe_time/SetState(Payload.ClockState: "INVALID")'; + cmd = '/cfs/$(CPUID)/cfe_time/SetState(Payload.ClockState: "INVALID")'; } else if (clockState == 'Valid' ) { - cmd = '/cfs/cfe_time/SetState(Payload.ClockState: "VALID")'; + cmd = '/cfs/$(CPUID)/cfe_time/SetState(Payload.ClockState: "VALID")'; } else if (clockState == 'Flywheel' ) { - cmd = '/cfs/cfe_time/SetState(Payload.ClockState: "FLYWHEEL")'; + cmd = '/cfs/$(CPUID)/cfe_time/SetState(Payload.ClockState: "FLYWHEEL")'; } Yamcs.issueCommand(cmd); @@ -100,7 +100,7 @@ $(pv_value) 163 35ebaa52:1509cf6a868:-78ea 54 - 60 + 78 @@ -140,7 +140,7 @@ $(pv_value) false 35ebaa52:1509cf6a868:-78e9 18 - 23 + 41 @@ -187,6 +187,46 @@ $(pv_value) 135 35ebaa52:1509cf6a868:-78e7 108 - 18 + 36 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_69 + + + true + true + false + + + ($(CPUID)) CFE-TIME - Set State + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-6764 + 6 + 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetTime.opi b/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetTime.opi index 11b9a7b7f..b632b007a 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetTime.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TIME/SetTime.opi @@ -10,12 +10,12 @@ - 1.5.3 + 1.5.5.202103012118 6 - 150 + 170 true @@ -47,11 +47,11 @@ var Microseconds =VTypeHelper.getDouble(display.getWidget('Microseconds').getPro var cmd; if( Type == "Time" ) { - cmd = '/cfs/cfe_time/SetTime'; + cmd = '/cfs/$(CPUID)/cfe_time/SetTime'; } else if( Type == "MET" ) { - cmd = '/cfs/cfe_time/SetMET'; + cmd = '/cfs/$(CPUID)/cfe_time/SetMET'; } else if( Type == "STCF" ) { - cmd = '/cfs/cfe_time/SetSTCF'; + cmd = '/cfs/$(CPUID)/cfe_time/SetSTCF'; } Yamcs.issueCommand(cmd, { @@ -104,8 +104,8 @@ $(pv_value) Action Button 163 35ebaa52:1509cf6a868:-78ea - 54 - 114 + 56 + 133 @@ -144,8 +144,8 @@ $(pv_value) 87 false 35ebaa52:1509cf6a868:-78e9 - 16 - 54 + 18 + 73 @@ -201,8 +201,8 @@ $(pv_value) Text Input 137 35ebaa52:1509cf6a868:-78e7 - 114 - 54 + 116 + 73 @@ -241,8 +241,8 @@ $(pv_value) 87 false 35ebaa52:1509cf6a868:-657f - 16 - 79 + 18 + 98 @@ -298,8 +298,8 @@ $(pv_value) Text Input 137 35ebaa52:1509cf6a868:-657e - 114 - 79 + 116 + 98 @@ -349,7 +349,47 @@ $(pv_value) Radio Box 216 35ebaa52:1509cf6a868:-62cf - 28 + 30 + 31 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_69 + + + true + true + false + + + ($(CPUID)) CFE-TIME - Set Time + + true + 1 + true + Label + 265 + false + -c05c465:1785c72c4a1:-6559 + 6 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TIME/ToneData.opi b/core/base/tools/commander/workspace_template/Displays/Core/TIME/ToneData.opi index f1331a773..15c295ecc 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TIME/ToneData.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TIME/ToneData.opi @@ -10,12 +10,12 @@ - 1.5.3 + 1.5.5.202103012118 6 - 250 + 270 true @@ -46,7 +46,7 @@ var STCFSeconds =VTypeHelper.getDouble(display.getWidget('STCFSeconds').getPrope var STCFSubseconds =VTypeHelper.getDouble(display.getWidget('STCFSubseconds').getPropertyValue('pv_value')); var Leaps =VTypeHelper.getDouble(display.getWidget('Leaps').getPropertyValue('pv_value')); var State =VTypeHelper.getDouble(display.getWidget('State').getPropertyValue('pv_value')); -var cmd = '/cfs/cfe_time/ToneData'; +var cmd = '/cfs/$(CPUID)/cfe_time/ToneData'; Yamcs.issueCommand(cmd, { 'Payload.AtToneMET.Seconds': METSeconds, @@ -101,8 +101,8 @@ $(pv_value) Action Button 163 35ebaa52:1509cf6a868:-78ea - 84 - 210 + 82 + 228 @@ -141,8 +141,8 @@ $(pv_value) 153 false 35ebaa52:1509cf6a868:-78e9 - 30 - 12 + 28 + 42 @@ -181,8 +181,8 @@ $(pv_value) 177 false 35ebaa52:1509cf6a868:-657f - 6 - 38 + 4 + 68 @@ -221,8 +221,8 @@ $(pv_value) 165 false -51d98179:177d07182b4:-787a - 18 - 66 + 16 + 96 @@ -261,8 +261,8 @@ $(pv_value) 177 false -51d98179:177d07182b4:-786a - 6 - 96 + 4 + 126 @@ -301,8 +301,8 @@ $(pv_value) 147 false -51d98179:177d07182b4:-785c - 36 - 126 + 34 + 156 @@ -341,8 +341,8 @@ $(pv_value) 147 false -51d98179:177d07182b4:-7852 - 36 - 156 + 34 + 186 @@ -396,8 +396,8 @@ $(pv_value) Spinner 137 -51d98179:177d07182b4:e15 - 192 - 12 + 190 + 42 @@ -451,8 +451,8 @@ $(pv_value) Spinner 137 -51d98179:177d07182b4:e21 - 192 - 38 + 190 + 68 @@ -506,8 +506,8 @@ $(pv_value) Spinner 137 -51d98179:177d07182b4:e37 - 192 - 66 + 190 + 96 @@ -561,8 +561,8 @@ $(pv_value) Spinner 137 -51d98179:177d07182b4:e47 - 192 - 96 + 190 + 126 @@ -616,8 +616,8 @@ $(pv_value) Spinner 137 -51d98179:177d07182b4:e4e - 192 - 126 + 190 + 156 @@ -671,7 +671,47 @@ $(pv_value) Spinner 137 -51d98179:177d07182b4:e55 - 192 - 156 + 190 + 186 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_69 + + + true + true + false + + + ($(CPUID)) CFE-TIME - Tone Data + + true + 1 + true + Label + 279 + false + -c05c465:1785c72c4a1:-6568 + 24 + 12 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TIME/ViewDiagnostic.opi b/core/base/tools/commander/workspace_template/Displays/Core/TIME/ViewDiagnostic.opi index 3dec16d5a..8ec91ff0f 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TIME/ViewDiagnostic.opi +++ b/core/base/tools/commander/workspace_template/Displays/Core/TIME/ViewDiagnostic.opi @@ -10,25 +10,31 @@ - 1.5.3 + 1.6.1.qualifier 6 - 1350 + 700 true - + ($(CPUID)) CFE-TIME - Diag - + + + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.CurrentMET + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.CurrentMET.Seconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.CurrentMET.Subseconds + + true true true true true Display - 300 + 630 35ebaa52:1509cf6a868:-791f -1 -1 @@ -58,7 +64,7 @@ 20 Text Update_25 - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.Forced2Fly + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.Forced2Fly @@ -76,8 +82,8 @@ $(pv_value) Check Box 151 35ebaa52:1509cf6a868:-72bc - 138 - 490 + 133 + 508 @@ -107,7 +113,7 @@ $(pv_value) Text Update_54 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.DataStoreStatus + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.DataStoreStatus 0.0 @@ -125,11 +131,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-7052 - 138 - 1186 + 444 + 604 @@ -168,8 +174,8 @@ $(pv_value) 121 false 35ebaa52:1509cf6a868:-6f93 - 7 - 1186 + 313 + 604 @@ -178,7 +184,7 @@ $(pv_value) @@ -227,8 +233,8 @@ $(pv_value) Action Button 163 35ebaa52:1509cf6a868:-78ea - 53 - 12 + 217 + 30 @@ -258,7 +264,7 @@ $(pv_value) Text Update 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.AtToneMET.Seconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.AtToneMET.Seconds 0.0 @@ -279,8 +285,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72d5 - 138 - 54 + 133 + 72 @@ -310,7 +316,7 @@ $(pv_value) Text Update_1 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.AtToneMET.Subseconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.AtToneMET.Subseconds 0.0 @@ -331,8 +337,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72d4 - 138 - 73 + 133 + 91 @@ -362,7 +368,7 @@ $(pv_value) Text Update_2 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.AtToneSTCF.Seconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.AtToneSTCF.Seconds 0.0 @@ -383,8 +389,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72d3 - 138 - 92 + 133 + 110 @@ -414,7 +420,7 @@ $(pv_value) Text Update_3 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.AtToneSTCF.Subseconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.AtToneSTCF.Subseconds 0.0 @@ -435,8 +441,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72d2 - 138 - 111 + 133 + 129 @@ -466,7 +472,7 @@ $(pv_value) Text Update_4 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.AtToneDelay.Seconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.AtToneDelay.Seconds 0.0 @@ -487,8 +493,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72d1 - 138 - 130 + 133 + 148 @@ -518,7 +524,7 @@ $(pv_value) Text Update_5 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.AtToneDelay.Subseconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.AtToneDelay.Subseconds 0.0 @@ -539,8 +545,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72d0 - 138 - 149 + 133 + 167 @@ -570,7 +576,7 @@ $(pv_value) Text Update_6 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.AtToneLatch.Seconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.AtToneLatch.Seconds 0.0 @@ -591,8 +597,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72cf - 138 - 168 + 133 + 186 @@ -622,7 +628,7 @@ $(pv_value) Text Update_7 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.AtToneLatch.Subseconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.AtToneLatch.Subseconds 0.0 @@ -643,8 +649,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72ce - 138 - 187 + 133 + 205 @@ -674,7 +680,7 @@ $(pv_value) Text Update_8 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.AtToneLeaps + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.AtToneLeaps 0.0 @@ -695,8 +701,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72cd - 138 - 206 + 133 + 224 @@ -726,7 +732,7 @@ $(pv_value) Text Update_9 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ClockStateAPI + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ClockStateAPI 0.0 @@ -747,8 +753,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72cc - 138 - 225 + 133 + 243 @@ -778,7 +784,7 @@ $(pv_value) Text Update_10 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.TimeSinceTone.Seconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.TimeSinceTone.Seconds 0.0 @@ -799,8 +805,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72cb - 138 - 244 + 133 + 262 @@ -830,7 +836,7 @@ $(pv_value) Text Update_11 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.TimeSinceTone.Subseconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.TimeSinceTone.Subseconds 0.0 @@ -851,8 +857,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72ca - 138 - 263 + 133 + 281 @@ -882,7 +888,7 @@ $(pv_value) Text Update_12 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.CurrentLatch.Seconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.CurrentLatch.Seconds 0.0 @@ -903,8 +909,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72c9 - 138 - 282 + 133 + 300 @@ -934,7 +940,7 @@ $(pv_value) Text Update_13 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.CurrentLatch.Subseconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.CurrentLatch.Subseconds 0.0 @@ -955,8 +961,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72c8 - 138 - 301 + 133 + 319 @@ -986,7 +992,7 @@ $(pv_value) Text Update_14 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.CurrentMET.Seconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.CurrentMET.Seconds 0.0 @@ -1007,8 +1013,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72c7 - 138 - 320 + 133 + 338 @@ -1038,7 +1044,7 @@ $(pv_value) Text Update_15 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.CurrentMET.Subseconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.CurrentMET.Subseconds 0.0 @@ -1059,8 +1065,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72c6 - 138 - 339 + 133 + 357 @@ -1090,7 +1096,7 @@ $(pv_value) Text Update_16 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.CurrentTAI.Seconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.CurrentTAI.Seconds 0.0 @@ -1111,8 +1117,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72c5 - 138 - 358 + 133 + 376 @@ -1142,7 +1148,7 @@ $(pv_value) Text Update_17 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.CurrentTAI.Subseconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.CurrentTAI.Subseconds 0.0 @@ -1163,8 +1169,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72c4 - 138 - 377 + 133 + 395 @@ -1194,7 +1200,7 @@ $(pv_value) Text Update_18 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.CurrentUTC.Seconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.CurrentUTC.Seconds 0.0 @@ -1215,8 +1221,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72c3 - 138 - 396 + 133 + 414 @@ -1246,7 +1252,7 @@ $(pv_value) Text Update_19 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.CurrentUTC.Subseconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.CurrentUTC.Subseconds 0.0 @@ -1267,8 +1273,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72c2 - 138 - 415 + 133 + 433 @@ -1298,7 +1304,7 @@ $(pv_value) Text Update_20 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ClockSetState + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ClockSetState 0.0 @@ -1319,8 +1325,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72c1 - 138 - 434 + 133 + 452 @@ -1350,7 +1356,7 @@ $(pv_value) Text Update_21 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ClockFlyState + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ClockFlyState 0.0 @@ -1371,8 +1377,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72c0 - 138 - 453 + 133 + 471 @@ -1402,7 +1408,7 @@ $(pv_value) Text Update_22 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ClockSource + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ClockSource 0.0 @@ -1423,8 +1429,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72bf - 138 - 472 + 133 + 490 @@ -1454,7 +1460,7 @@ $(pv_value) Text Update_23 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ClockSignal + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ClockSignal 0.0 @@ -1475,8 +1481,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72be - 138 - 491 + 133 + 509 @@ -1506,7 +1512,7 @@ $(pv_value) Text Update_24 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ServerFlyState + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ServerFlyState 0.0 @@ -1527,8 +1533,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-72bd - 138 - 510 + 133 + 528 @@ -1567,8 +1573,8 @@ $(pv_value) 92 false 35ebaa52:1509cf6a868:-721b - 36 - 54 + 31 + 72 @@ -1607,8 +1613,8 @@ $(pv_value) 92 false 35ebaa52:1509cf6a868:-7213 - 36 - 168 + 31 + 186 @@ -1647,8 +1653,8 @@ $(pv_value) 92 false 35ebaa52:1509cf6a868:-720c - 36 - 92 + 31 + 110 @@ -1687,8 +1693,8 @@ $(pv_value) 92 false 35ebaa52:1509cf6a868:-71f6 - 36 - 130 + 31 + 148 @@ -1727,8 +1733,8 @@ $(pv_value) 110 false 35ebaa52:1509cf6a868:-71f1 - 18 - 225 + 13 + 243 @@ -1767,8 +1773,8 @@ $(pv_value) 98 false 35ebaa52:1509cf6a868:-71db - 30 - 206 + 25 + 224 @@ -1807,8 +1813,8 @@ $(pv_value) 116 false 35ebaa52:1509cf6a868:-71cd - 12 - 244 + 7 + 262 @@ -1847,8 +1853,8 @@ $(pv_value) 104 false 35ebaa52:1509cf6a868:-71bd - 24 - 396 + 19 + 414 @@ -1887,8 +1893,8 @@ $(pv_value) 104 false 35ebaa52:1509cf6a868:-71b6 - 24 - 282 + 19 + 300 @@ -1927,8 +1933,8 @@ $(pv_value) 110 false 35ebaa52:1509cf6a868:-71af - 18 - 472 + 13 + 490 @@ -1967,8 +1973,8 @@ $(pv_value) 92 false 35ebaa52:1509cf6a868:-71a8 - 36 - 320 + 31 + 338 @@ -2007,8 +2013,8 @@ $(pv_value) 104 false 35ebaa52:1509cf6a868:-71a1 - 24 - 434 + 19 + 452 @@ -2047,8 +2053,8 @@ $(pv_value) 92 false 35ebaa52:1509cf6a868:-719a - 36 - 358 + 31 + 376 @@ -2087,8 +2093,8 @@ $(pv_value) 121 false 35ebaa52:1509cf6a868:-7193 - 7 - 453 + 2 + 471 @@ -2127,8 +2133,8 @@ $(pv_value) 92 false 35ebaa52:1509cf6a868:-7175 - 36 - 491 + 31 + 509 @@ -2167,8 +2173,8 @@ $(pv_value) 110 false 35ebaa52:1509cf6a868:-716e - 18 - 510 + 13 + 528 @@ -2207,8 +2213,8 @@ $(pv_value) 98 false 35ebaa52:1509cf6a868:-7167 - 27 - 590 + 22 + 604 @@ -2236,7 +2242,7 @@ $(pv_value) 20 Check Box - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ClockSetState + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ClockSetState @@ -2254,8 +2260,8 @@ $(pv_value) Check Box 100 35ebaa52:1509cf6a868:-712d - 138 - 571 + 133 + 585 @@ -2285,7 +2291,7 @@ $(pv_value) Check Box_3 0 true - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ClockSource + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ClockSource 0.0 @@ -2306,8 +2312,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-712a - 138 - 529 + 133 + 547 @@ -2337,7 +2343,7 @@ $(pv_value) Check Box_4 0 true - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ClockSignal + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ClockSignal 0.0 @@ -2358,8 +2364,8 @@ $(pv_value) 151 false 35ebaa52:1509cf6a868:-7129 - 138 - 548 + 133 + 566 @@ -2387,7 +2393,7 @@ $(pv_value) 20 Check Box_6 - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.OneTimeAdjust + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.OneTimeAdjust @@ -2405,8 +2411,8 @@ $(pv_value) Check Box 100 35ebaa52:1509cf6a868:-7127 - 138 - 609 + 133 + 623 @@ -2434,7 +2440,7 @@ $(pv_value) 20 Check Box_7 - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.OneHzAdjust + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.OneHzAdjust @@ -2452,8 +2458,8 @@ $(pv_value) Check Box 100 35ebaa52:1509cf6a868:-7126 - 138 - 628 + 133 + 642 @@ -2492,8 +2498,8 @@ $(pv_value) 80 false 35ebaa52:1509cf6a868:-711b - 48 - 571 + 43 + 585 @@ -2532,8 +2538,8 @@ $(pv_value) 110 false 35ebaa52:1509cf6a868:-7105 - 18 - 548 + 13 + 566 @@ -2572,8 +2578,8 @@ $(pv_value) 104 false 35ebaa52:1509cf6a868:-7100 - 24 - 529 + 19 + 547 @@ -2612,8 +2618,8 @@ $(pv_value) 80 false 35ebaa52:1509cf6a868:-70f6 - 48 - 628 + 43 + 642 @@ -2652,8 +2658,8 @@ $(pv_value) 80 false 35ebaa52:1509cf6a868:-70e7 - 48 - 609 + 43 + 623 @@ -2683,7 +2689,7 @@ $(pv_value) Text Update_26 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.OneTimeDirection + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.OneTimeDirection 0.0 @@ -2701,11 +2707,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-706e - 138 - 654 + 444 + 72 @@ -2735,7 +2741,7 @@ $(pv_value) Text Update_27 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.OneHzDirection + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.OneHzDirection 0.0 @@ -2753,11 +2759,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-706d - 138 - 673 + 444 + 91 @@ -2787,7 +2793,7 @@ $(pv_value) Text Update_28 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.DelayDirection + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.DelayDirection 0.0 @@ -2805,11 +2811,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-706c - 138 - 692 + 444 + 110 @@ -2839,7 +2845,7 @@ $(pv_value) Text Update_29 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.OneTimeAdjust.Seconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.OneTimeAdjust.Seconds 0.0 @@ -2857,11 +2863,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-706b - 138 - 711 + 444 + 129 @@ -2891,7 +2897,7 @@ $(pv_value) Text Update_30 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.OneTimeAdjust.Subseconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.OneTimeAdjust.Subseconds 0.0 @@ -2909,11 +2915,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-706a - 138 - 730 + 444 + 148 @@ -2943,7 +2949,7 @@ $(pv_value) Text Update_31 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.OneHzAdjust.Seconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.OneHzAdjust.Seconds 0.0 @@ -2961,11 +2967,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-7069 - 138 - 749 + 444 + 167 @@ -2995,7 +3001,7 @@ $(pv_value) Text Update_32 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.OneHzAdjust.Subseconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.OneHzAdjust.Subseconds 0.0 @@ -3013,11 +3019,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-7068 - 138 - 768 + 444 + 186 @@ -3047,7 +3053,7 @@ $(pv_value) Text Update_33 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneSignalLatch.Seconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneSignalLatch.Seconds 0.0 @@ -3065,11 +3071,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-7067 - 138 - 787 + 444 + 205 @@ -3099,7 +3105,7 @@ $(pv_value) Text Update_34 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneSignalLatch.Subseconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneSignalLatch.Subseconds 0.0 @@ -3117,11 +3123,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-7066 - 138 - 806 + 444 + 224 @@ -3151,7 +3157,7 @@ $(pv_value) Text Update_35 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneDataLatch.Seconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneDataLatch.Seconds 0.0 @@ -3169,11 +3175,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-7065 - 138 - 825 + 444 + 243 @@ -3203,7 +3209,7 @@ $(pv_value) Text Update_36 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneDataLatch.Subseconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneDataLatch.Subseconds 0.0 @@ -3221,11 +3227,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-7064 - 138 - 844 + 444 + 262 @@ -3255,7 +3261,7 @@ $(pv_value) Text Update_37 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneMatchCount + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneMatchCount 0.0 @@ -3273,11 +3279,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-7063 - 138 - 863 + 444 + 281 @@ -3307,7 +3313,7 @@ $(pv_value) Text Update_38 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneMatchErrors + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneMatchErrors 0.0 @@ -3325,11 +3331,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-7062 - 138 - 882 + 444 + 300 @@ -3359,7 +3365,7 @@ $(pv_value) Text Update_39 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneSignalCount + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneSignalCount 0.0 @@ -3377,11 +3383,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-7061 - 138 - 901 + 444 + 319 @@ -3411,7 +3417,7 @@ $(pv_value) Text Update_40 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneDataCount + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneDataCount 0.0 @@ -3429,11 +3435,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-7060 - 138 - 920 + 444 + 338 @@ -3463,7 +3469,7 @@ $(pv_value) Text Update_41 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneIntCount + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneIntCount 0.0 @@ -3481,11 +3487,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-705f - 138 - 939 + 444 + 357 @@ -3515,7 +3521,7 @@ $(pv_value) Text Update_42 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneIntErrors + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneIntErrors 0.0 @@ -3533,11 +3539,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-705e - 138 - 958 + 444 + 376 @@ -3567,7 +3573,7 @@ $(pv_value) Text Update_43 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneTaskCount + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneTaskCount 0.0 @@ -3585,11 +3591,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-705d - 138 - 977 + 444 + 395 @@ -3619,7 +3625,7 @@ $(pv_value) Text Update_44 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.VersionCount + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.VersionCount 0.0 @@ -3637,11 +3643,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-705c - 138 - 996 + 444 + 414 @@ -3671,7 +3677,7 @@ $(pv_value) Text Update_45 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.LocalIntCount + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.LocalIntCount 0.0 @@ -3689,11 +3695,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-705b - 138 - 1015 + 444 + 433 @@ -3723,7 +3729,7 @@ $(pv_value) Text Update_46 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.LocalTaskCount + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.LocalTaskCount 0.0 @@ -3741,11 +3747,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-705a - 138 - 1034 + 444 + 452 @@ -3775,7 +3781,7 @@ $(pv_value) Text Update_47 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.VirtualMET + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.VirtualMET 0.0 @@ -3793,11 +3799,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-7059 - 138 - 1053 + 444 + 471 @@ -3827,7 +3833,7 @@ $(pv_value) Text Update_48 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.MinElapsed + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.MinElapsed 0.0 @@ -3845,11 +3851,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-7058 - 138 - 1072 + 444 + 490 @@ -3879,7 +3885,7 @@ $(pv_value) Text Update_49 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.MaxElapsed + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.MaxElapsed 0.0 @@ -3897,11 +3903,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-7057 - 138 - 1091 + 444 + 509 @@ -3931,7 +3937,7 @@ $(pv_value) Text Update_50 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.MaxLocalClock.Seconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.MaxLocalClock.Seconds 0.0 @@ -3949,11 +3955,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-7056 - 138 - 1110 + 444 + 528 @@ -3983,7 +3989,7 @@ $(pv_value) Text Update_51 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.MaxLocalClock.Subseconds + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.MaxLocalClock.Subseconds 0.0 @@ -4001,11 +4007,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-7055 - 138 - 1129 + 444 + 547 @@ -4035,7 +4041,7 @@ $(pv_value) Text Update_52 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneOverLimit + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneOverLimit 0.0 @@ -4053,11 +4059,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-7054 - 138 - 1148 + 444 + 566 @@ -4087,7 +4093,7 @@ $(pv_value) Text Update_53 0 false - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneUnderLimit + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.ToneUnderLimit 0.0 @@ -4105,11 +4111,11 @@ $(pv_value) 1 true Text Update - 151 + 180 false 35ebaa52:1509cf6a868:-7053 - 138 - 1167 + 444 + 585 @@ -4148,8 +4154,8 @@ $(pv_value) 128 false 35ebaa52:1509cf6a868:-7048 - 0 - 654 + 306 + 72 @@ -4188,8 +4194,8 @@ $(pv_value) 110 false 35ebaa52:1509cf6a868:-7043 - 18 - 673 + 324 + 91 @@ -4228,8 +4234,8 @@ $(pv_value) 117 false 35ebaa52:1509cf6a868:-703e - 11 - 692 + 317 + 110 @@ -4268,8 +4274,8 @@ $(pv_value) 110 false 35ebaa52:1509cf6a868:-7034 - 18 - 711 + 324 + 129 @@ -4308,8 +4314,8 @@ $(pv_value) 119 false 35ebaa52:1509cf6a868:-702f - 7 - 787 + 313 + 205 @@ -4348,8 +4354,8 @@ $(pv_value) 80 false 35ebaa52:1509cf6a868:-702a - 48 - 749 + 354 + 167 @@ -4388,8 +4394,8 @@ $(pv_value) 116 false 35ebaa52:1509cf6a868:-7020 - 12 - 825 + 318 + 243 @@ -4428,8 +4434,8 @@ $(pv_value) 117 false 35ebaa52:1509cf6a868:-7011 - 11 - 882 + 317 + 300 @@ -4468,8 +4474,8 @@ $(pv_value) 116 false 35ebaa52:1509cf6a868:-700c - 12 - 863 + 318 + 281 @@ -4508,8 +4514,8 @@ $(pv_value) 117 false 35ebaa52:1509cf6a868:-7007 - 11 - 901 + 317 + 319 @@ -4548,8 +4554,8 @@ $(pv_value) 110 false 35ebaa52:1509cf6a868:-7002 - 18 - 920 + 324 + 338 @@ -4588,8 +4594,8 @@ $(pv_value) 104 false 35ebaa52:1509cf6a868:-6ffd - 24 - 939 + 330 + 357 @@ -4628,8 +4634,8 @@ $(pv_value) 110 false 35ebaa52:1509cf6a868:-6ff8 - 18 - 958 + 324 + 376 @@ -4668,8 +4674,8 @@ $(pv_value) 104 false 35ebaa52:1509cf6a868:-6ff3 - 24 - 996 + 330 + 414 @@ -4708,8 +4714,8 @@ $(pv_value) 110 false 35ebaa52:1509cf6a868:-6fee - 18 - 977 + 324 + 395 @@ -4748,8 +4754,8 @@ $(pv_value) 104 false 35ebaa52:1509cf6a868:-6fe9 - 24 - 1015 + 330 + 433 @@ -4788,8 +4794,8 @@ $(pv_value) 116 false 35ebaa52:1509cf6a868:-6fa7 - 12 - 1110 + 318 + 528 @@ -4828,8 +4834,8 @@ $(pv_value) 112 false 35ebaa52:1509cf6a868:-6fa2 - 16 - 1033 + 322 + 451 @@ -4868,8 +4874,8 @@ $(pv_value) 110 false 35ebaa52:1509cf6a868:-6f9d - 18 - 1148 + 324 + 566 @@ -4908,8 +4914,8 @@ $(pv_value) 116 false 35ebaa52:1509cf6a868:-6f8e - 12 - 1167 + 318 + 585 @@ -4948,8 +4954,8 @@ $(pv_value) 98 false 35ebaa52:1509cf6a868:-6f89 - 30 - 1091 + 336 + 509 @@ -4988,8 +4994,8 @@ $(pv_value) 80 false 35ebaa52:1509cf6a868:-6f84 - 48 - 1073 + 354 + 491 @@ -5028,8 +5034,8 @@ $(pv_value) 80 false 35ebaa52:1509cf6a868:-6f7f - 48 - 1053 + 354 + 471 @@ -5057,7 +5063,7 @@ $(pv_value) 20 Check Box_12 - /cfs/cfe_time/CFE_TIME_DiagPacket_t.Payload.Forced2Fly + /cfs/$(CPUID)/cfe_time/CFE_TIME_DiagPacket_t.Payload.Forced2Fly @@ -5075,7 +5081,323 @@ $(pv_value) Check Box 100 59d9b0dc:177f3efc307:-78bd - 138 - 590 + 133 + 604 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 1 + Label_69 + + + true + true + false + + + ($(CPUID)) CFE-TIME - Diagnostics + + true + 1 + true + Label + 279 + false + -c05c465:1785c72c4a1:-6779 + 159 + 6 + + + + false + false + false + + + + true + + + + 1 + 1 + true + + Default + + false + + + + 0 + 20 + 0 + Met_Time_Field + 0 + false + + + 0.0 + + + true + true + false + + + true + ###### + $(pv_name) +$(pv_value) + false + 1 + true + Text Update + 180 + false + -7d13f8de:17894c334a5:-7e2e + 444 + 623 + + + + false + + + + + + + 0 + 1 + true + + Default + + + + + 20 + 2 + Label_70 + + + true + true + false + + + MET Time + + true + 1 + true + Label + 121 + false + -7d13f8de:17894c334a5:-7e2d + 313 + 623 + + + + false + false + false + + + + true + + + + 1 + 1 + true + + Default + + false + + + + 0 + 20 + 0 + GPS_Time_Field + 0 + false + + + 0.0 + + + true + true + false + + + true + ###### + $(pv_name) +$(pv_value) + false + 1 + true + Text Update + 180 + false + 69dd6e7:178b7272533:-7f16 + 444 + 642 + + + + false + + + + + + + 0 + 1 + true + + Default + + + + + 20 + 2 + Label_71 + + + true + true + false + + + GPS Time + + true + 1 + true + Label + 121 + false + 69dd6e7:178b7272533:-7f15 + 313 + 642 + + + + false + false + false + + + + true + + + + 1 + 1 + true + + Default + + false + + + + 0 + 20 + 0 + CFS_Time_Field + 0 + false + + + 0.0 + + + true + true + false + + + true + ###### + $(pv_name) +$(pv_value) + false + 1 + true + Text Update + 180 + false + -48fae9e6:178b87439dc:-7e03 + 443 + 661 + + + + false + + + + + + + 0 + 1 + true + + Default + + + + + 20 + 2 + Label_72 + + + true + true + false + + + CFS Time + + true + 1 + true + Label + 121 + false + -48fae9e6:178b87439dc:-7e02 + 312 + 661 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TIME/scripts/NoOp.js b/core/base/tools/commander/workspace_template/Displays/Core/TIME/scripts/NoOp.js index 47f92d8b9..147fd6495 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TIME/scripts/NoOp.js +++ b/core/base/tools/commander/workspace_template/Displays/Core/TIME/scripts/NoOp.js @@ -1,4 +1,4 @@ importPackage(Packages.org.csstudio.opibuilder.scriptUtil); importPackage(Packages.org.yamcs.studio.script); -Yamcs.issueCommand('/cfs/cfe_time/Noop', {}); \ No newline at end of file +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_time/Noop', {}); \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TIME/scripts/ResetCounters.js b/core/base/tools/commander/workspace_template/Displays/Core/TIME/scripts/ResetCounters.js index 5112544ae..9024db63c 100644 --- a/core/base/tools/commander/workspace_template/Displays/Core/TIME/scripts/ResetCounters.js +++ b/core/base/tools/commander/workspace_template/Displays/Core/TIME/scripts/ResetCounters.js @@ -1,4 +1,4 @@ importPackage(Packages.org.csstudio.opibuilder.scriptUtil); importPackage(Packages.org.yamcs.studio.script); -Yamcs.issueCommand('/cfs/cfe_time/Reset', {}); \ No newline at end of file +Yamcs.issueCommand('/cfs/$(CPUID)/cfe_time/Reset', {}); \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Core/TIME/scripts/format_cfe_time.py b/core/base/tools/commander/workspace_template/Displays/Core/TIME/scripts/format_cfe_time.py new file mode 100644 index 000000000..8709c913e --- /dev/null +++ b/core/base/tools/commander/workspace_template/Displays/Core/TIME/scripts/format_cfe_time.py @@ -0,0 +1,42 @@ +""" + Please reference airliner/core/base/cfe/docs/cFE UsersGuide/Doxygen/cfetimeugformat.html for details. + + International Atomic Time (TAI) + Coordinated Universal Time (UTC) + + TAI = MET + STCF + UTC = TAI - Leap Seconds + UTC = MET + STCF - Leap Seconds +""" + +from com.windhoverlabs.studio.time import CFETime +from com.windhoverlabs.studio.registry import YAMLRegistry + +import logging + +def main(): + logging.basicConfig() + logger = logging.getLogger('TIME') + + registry = YAMLRegistry() + + # Don't specify an exception type on the except clause. If you do, Jython will not catch Java exceptions. + try: + display.getWidget("Met_Time_Field").setPropertyValue('text', str(CFETime.getRelativeTime(pvs[1].getValue().getValue(), pvs[2].getValue().getValue()))) + except: + logger.error("Failed to fetch pvs for Met_Time_Field") + try: + display.getWidget("GPS_Time_Field").setPropertyValue('text', str(CFETime.getTimeSinceEpoch(pvs[1].getValue().getValue(), pvs[2].getValue().getValue(), + registry.get(display.getMacroValue("REGISTRY_PATH") + "/config/CFE_TIME_EPOCH_YEAR/value"), + registry.get(display.getMacroValue("REGISTRY_PATH") + "/config/CFE_TIME_EPOCH_DAY/value"), + registry.get(display.getMacroValue("REGISTRY_PATH") + "/config/CFE_TIME_EPOCH_HOUR/value"), + registry.get(display.getMacroValue("REGISTRY_PATH") + "/config/CFE_TIME_EPOCH_MINUTE/value"), + registry.get(display.getMacroValue("REGISTRY_PATH") + "/config/CFE_TIME_EPOCH_SECOND/value")))) + except: + logger.error("Failed to fetch pvs for GPS_Time_Field") + try: + display.getWidget("CFS_Time_Field").setPropertyValue('text', str(CFETime.getTimeSinceCFSEpoch(pvs[1].getValue().getValue(), pvs[2].getValue().getValue()))) + except: + logger.error("Failed to fetch pvs for CFS_Time_Field") + +main() diff --git a/core/base/tools/commander/workspace_template/Displays/Main.opi b/core/base/tools/commander/workspace_template/Displays/Main.opi index d5eebaf86..acb1c9fd1 100644 --- a/core/base/tools/commander/workspace_template/Displays/Main.opi +++ b/core/base/tools/commander/workspace_template/Displays/Main.opi @@ -10,7 +10,7 @@ - 1.5.3 + 1.6.2.202104092231 @@ -28,7 +28,7 @@ true true Display - 600 + 640 45ea5983:1502a6e6386:-7f06 -1 -1 @@ -66,11 +66,11 @@ 1 true Label - 193 + 161 false -9ddfcbe:1507831914f:-7a6f - 12 - 6 + 8 + 1 @@ -78,6 +78,7 @@ Core/ES/Main.opi true + PPD 1 @@ -213,6 +214,7 @@ $(pv_value) Core/EVS/Main.opi true + PPD 1 @@ -308,6 +310,7 @@ $(pv_value) Core/SB/Main.opi true + PPD 1 @@ -403,6 +406,7 @@ $(pv_value) Core/TBL/Main.opi true + PPD 1 @@ -498,6 +502,7 @@ $(pv_value) Core/TIME/Main.opi true + PPD 1 @@ -593,6 +598,7 @@ $(pv_value) Apps/CF/Main.opi true + PPD 1 @@ -728,6 +734,7 @@ $(pv_value) Apps/CS/Main.opi true + PPD 1 @@ -823,6 +830,7 @@ $(pv_value) Apps/DS/Main.opi true + PPD 1 @@ -918,6 +926,7 @@ $(pv_value) Apps/FM/Main.opi true + PPD 1 @@ -1013,6 +1022,7 @@ $(pv_value) Apps/HK/Main.opi true + PPD 1 @@ -1108,6 +1118,7 @@ $(pv_value) Apps/CI/Main.opi true + PPD 1 @@ -1203,6 +1214,7 @@ $(pv_value) Apps/HS/Main.opi true + PPD 1 @@ -1298,6 +1310,7 @@ $(pv_value) Apps/LC/Main.opi true + PPD 1 @@ -1393,6 +1406,7 @@ $(pv_value) Apps/MD/Main.opi true + PPD 1 @@ -1488,6 +1502,7 @@ $(pv_value) Apps/MM/Main.opi true + PPD 1 @@ -1583,6 +1598,7 @@ $(pv_value) Apps/SC/Main.opi true + PPD 1 @@ -1678,6 +1694,7 @@ $(pv_value) Apps/SCH/Main.opi true + PPD 1 @@ -1773,6 +1790,7 @@ $(pv_value) Apps/TO/Main.opi true + PPD 1 @@ -1877,8 +1895,8 @@ $(pv_value) Rectangle 247 -2dc23c5:177557ff444:-7811 - 282 - 30 + 420 + 6 @@ -1917,8 +1935,8 @@ $(pv_value) 247 false 572e24cf:17746304069:-718b - 282 - 30 + 420 + 6 @@ -1963,8 +1981,8 @@ $(pv_value) Action Button 223 296ade75:177554ff103:-7dc3 - 294 - 75 + 432 + 51 @@ -2009,8 +2027,8 @@ $(pv_value) Action Button 223 296ade75:177554ff103:-7dcf - 294 - 133 + 432 + 109 @@ -2055,8 +2073,8 @@ $(pv_value) Action Button 223 296ade75:177554ff103:-7dad - 294 - 163 + 432 + 139 @@ -2117,7 +2135,1295 @@ $(pv_value) Action Button 223 14292858:17759dd02e1:-7c9d - 294 - 102 + 432 + 78 + + + + false + + + + + + + 0 + 1 + true + + + + + + + 25 + 1 + Label_70 + + + true + true + false + + + PPD + + true + 1 + true + Label + 73 + false + -c05c465:1785c72c4a1:-7c2c + 186 + 6 + + + + + Core/ES/Main.opi + + true + CPD + + 1 + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 23 + + NoOp_46 + 0 + + + + + true + true + false + + + + Display + false + $(pv_name) +$(pv_value) + true + Action Button + 73 + -c05c465:1785c72c4a1:-7bea + 276 + 36 + + + + + Core/EVS/Main.opi + + true + CPD + + 1 + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 23 + + NoOp_47 + 0 + + + + + true + true + false + + + + Display + false + $(pv_name) +$(pv_value) + true + Action Button + 73 + -c05c465:1785c72c4a1:-7be9 + 276 + 66 + + + + + Core/SB/Main.opi + + true + CPD + + 1 + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 23 + + NoOp_48 + 0 + + + + + true + true + false + + + + Display + false + $(pv_name) +$(pv_value) + true + Action Button + 73 + -c05c465:1785c72c4a1:-7be8 + 276 + 96 + + + + + Core/TBL/Main.opi + + true + CPD + + 1 + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 23 + + NoOp_49 + 0 + + + + + true + true + false + + + + Display + false + $(pv_name) +$(pv_value) + true + Action Button + 73 + -c05c465:1785c72c4a1:-7be7 + 276 + 126 + + + + + Core/TIME/Main.opi + + true + CPD + + 1 + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 23 + + NoOp_50 + 0 + + + + + true + true + false + + + + Display + false + $(pv_name) +$(pv_value) + true + Action Button + 73 + -c05c465:1785c72c4a1:-7be6 + 276 + 156 + + + + + Apps/CF/Main.opi + + true + PPD + + 1 + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 23 + + NoOp_51 + 0 + + + + + true + true + false + + + + Display + false + $(pv_name) +$(pv_value) + true + Action Button + 73 + -c05c465:1785c72c4a1:-7be5 + 276 + 232 + + + + + Apps/CS/Main.opi + + true + CPD + + 1 + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 23 + + NoOp_52 + 0 + + + + + true + true + false + + + + Display + false + $(pv_name) +$(pv_value) + true + Action Button + 73 + -c05c465:1785c72c4a1:-7be4 + 276 + 292 + + + + + Apps/FM/Main.opi + + true + CPD + + 1 + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 23 + + NoOp_54 + 0 + + + + + true + true + false + + + + Display + false + $(pv_name) +$(pv_value) + true + Action Button + 73 + -c05c465:1785c72c4a1:-7be2 + 276 + 352 + + + + + Apps/HS/Main.opi + + true + CPD + + 1 + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 23 + + NoOp_57 + 0 + + + + + true + true + false + + + + Display + false + $(pv_name) +$(pv_value) + true + Action Button + 73 + -c05c465:1785c72c4a1:-7bdf + 276 + 410 + + + + + Apps/LC/Main.opi + + true + CPD + + 1 + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 23 + + NoOp_58 + 0 + + + + + true + true + false + + + + Display + false + $(pv_name) +$(pv_value) + true + Action Button + 73 + -c05c465:1785c72c4a1:-7bde + 276 + 440 + + + + + Apps/MD/Main.opi + + true + CPD + + 1 + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 23 + + NoOp_59 + 0 + + + + + true + true + false + + + + Display + false + $(pv_name) +$(pv_value) + true + Action Button + 73 + -c05c465:1785c72c4a1:-7bdd + 276 + 470 + + + + + Apps/MM/Main.opi + + true + CPD + + 1 + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 23 + + NoOp_60 + 0 + + + + + true + true + false + + + + Display + false + $(pv_name) +$(pv_value) + true + Action Button + 73 + -c05c465:1785c72c4a1:-7bdc + 276 + 502 + + + + + Apps/SC/Main.opi + + true + CPD + + 1 + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 23 + + NoOp_61 + 0 + + + + + true + true + false + + + + Display + false + $(pv_name) +$(pv_value) + true + Action Button + 73 + -c05c465:1785c72c4a1:-7bdb + 276 + 532 + + + + + Apps/SCH/Main.opi + + true + CPD + + 1 + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 23 + + NoOp_62 + 0 + + + + + true + true + false + + + + Display + false + $(pv_name) +$(pv_value) + true + Action Button + 73 + -c05c465:1785c72c4a1:-7bda + 276 + 562 + + + + + Apps/TO/Main.opi + + true + CPD + + 1 + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 23 + + NoOp_63 + 0 + + + + + true + true + false + + + + Display + false + $(pv_name) +$(pv_value) + true + Action Button + 73 + -c05c465:1785c72c4a1:-7bd9 + 276 + 592 + + + + false + + + + + + + 0 + 1 + true + + + + + + + 25 + 1 + Label_71 + + + true + true + false + + + CPD + + true + 1 + true + Label + 73 + false + -c05c465:1785c72c4a1:-7bd8 + 276 + 6 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 0 + Label_72 + + + true + true + false + + + Position Estimator + + true + 1 + true + Label + 137 + false + -c05c465:1785c72c4a1:-5532 + 402 + 234 + + + + + Apps/PE/Main.opi + + true + CPD + + 1 + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 23 + + NoOp_65 + 0 + + + + + true + true + false + + + + Display + false + $(pv_name) +$(pv_value) + true + Action Button + 73 + -c05c465:1785c72c4a1:-5530 + 642 + 232 + + + + false + + + + + + + 0 + 1 + true + + + + + + + 25 + 1 + Label_73 + + + true + true + false + + + PPD + + true + 1 + true + Label + 73 + false + -c05c465:1785c72c4a1:-5521 + 552 + 195 + + + + false + + + + + + + 0 + 1 + true + + + + + + + 25 + 1 + Label_74 + + + true + true + false + + + CPD + + true + 1 + true + Label + 73 + false + -c05c465:1785c72c4a1:-5520 + 642 + 195 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 0 + Label_75 + + + true + true + false + + + Sensor + + true + 1 + true + Label + 137 + false + -c05c465:1785c72c4a1:-550e + 402 + 262 + + + + + Apps/SENS/Main.opi + + true + CPD + + 1 + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 23 + + NoOp_67 + 0 + + + + + true + true + false + + + + Display + false + $(pv_name) +$(pv_value) + true + Action Button + 73 + -c05c465:1785c72c4a1:-550c + 642 + 260 + + + + false + + + + + + + 0 + 1 + true + + Default Bold + + + + + 20 + 0 + Label_76 + + + true + true + false + + + Vehicle Manager + + true + 1 + true + Label + 137 + false + -c05c465:1785c72c4a1:-54ff + 402 + 292 + + + + + Apps/VM/Main.opi + + true + CPD + + 1 + + + + false + false + + + + false + + + + 0 + 1 + true + + Default + + false + + + + 23 + + NoOp_69 + 0 + + + + + true + true + false + + + + Display + false + $(pv_name) +$(pv_value) + true + Action Button + 73 + -c05c465:1785c72c4a1:-54fd + 642 + 290 \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/Displays/Resources/definitions.yaml b/core/base/tools/commander/workspace_template/Displays/Resources/definitions.yaml index 00e391e1a..771883390 100644 --- a/core/base/tools/commander/workspace_template/Displays/Resources/definitions.yaml +++ b/core/base/tools/commander/workspace_template/Displays/Resources/definitions.yaml @@ -4,11 +4,11 @@ xtce_config: global: TelemetryMetaData: BaseContainer: - container_ref: 'cfs-ccsds' + container_ref: 'cfs' size: 96 CommandMetaData: BaseContainer: - container_ref: 'cfs-ccsds/cfs-cmd' + container_ref: 'cfs/cfs-cmd' size: 64 modules: core: diff --git a/core/base/tools/commander/workspace_template/Displays/Resources/opi_util/time_util.py b/core/base/tools/commander/workspace_template/Displays/Resources/opi_util/time_util.py new file mode 100644 index 000000000..e5e6416bf --- /dev/null +++ b/core/base/tools/commander/workspace_template/Displays/Resources/opi_util/time_util.py @@ -0,0 +1,78 @@ +""" +CFE Time Utilities +""" +from com.windhoverlabs.studio.registry import ConfigRegistry + +# FIXME: This module might get messy if we keep adding functions to it...perhaps we should re-structure it differently. + +def get_cfe_time_fs_factor(registry, registry_path): + """ + This function assumes that registry has been loaded by the caller. + """ + fs_factor = registry.get(ConfigRegistry.appendPath(registry_path, "config/CFE_TIME_FS_FACTOR/")) + + return fs_factor['value'] + + +def micro_2_seconds(microseconds): + seconds = microseconds / 1000000 + + return seconds + + +def CFE_TIME_Sub2MicroSecs(SubSeconds): + """ + Refer to airliner/core/base/cfe/fsw/src/time/cfe_time_api.c + """ + MicroSeconds = None + if SubSeconds > 0xffffdf00: + MicroSeconds = 999999 + else: + MicroSeconds = (((((SubSeconds >> 7) * 125) >> 7) * 125) >> 12) + + if (SubSeconds & 0x3ffffff) != 0: + MicroSeconds += 1 + + if MicroSeconds > 500000: + MicroSeconds -= 1 + + return MicroSeconds + + +def CFE_TIME_Micro2SubSecs(MicroSeconds): + """ + Refer to airliner/core/base/cfe/fsw/src/time/cfe_time_api.c + """ + SubSeconds = None + + if MicroSeconds > 999999: + SubSeconds = 0xFFFFFFFF + + else: + SubSeconds = ((((MicroSeconds << 11) / 5) << 3) / 3125) << 12 + + if SubSeconds > 0x80001000: + SubSeconds += 0x1000 + + return SubSeconds + + +def CFE_TIME_CFE2FSSeconds(SecondsCFE): + """ + Refer to airliner/core/base/cfe/fsw/src/time/cfe_time_api.c + """ + + # Using a signed integer allows the factor to be negative... + registry = YAMLRegistry() + # hardcoding the path for now + ConvertFactor = get_cfe_time_fs_factor(registry, "/modules/core/modules/cfe/modules/cfe_time") + + # File system time = cFE time + conversion factor... + SecondsFS = SecondsCFE + ConvertFactor + + # Prevent file system time from going below zero... + if ConvertFactor < 0: + if -ConvertFactor > SecondsCFE: + SecondsFS = 0 + + return SecondsFS diff --git a/core/base/tools/commander/workspace_template/bin/wh_defs.yaml b/core/base/tools/commander/workspace_template/bin/wh_defs.yaml index a8733b213..a0aab5d98 100644 --- a/core/base/tools/commander/workspace_template/bin/wh_defs.yaml +++ b/core/base/tools/commander/workspace_template/bin/wh_defs.yaml @@ -4,11 +4,11 @@ xtce_config: global: TelemetryMetaData: BaseContainer: - container_ref: 'cfs-ccsds' + container_ref: 'cfs' size: 96 CommandMetaData: BaseContainer: - container_ref: 'cfs-ccsds/cfs-cmd' + container_ref: 'cfs/cfs-cmd' size: 64 modules: core: diff --git a/core/base/tools/commander/workspace_template/etc/roles.yaml b/core/base/tools/commander/workspace_template/etc/roles.yaml new file mode 100644 index 000000000..10bd2bebf --- /dev/null +++ b/core/base/tools/commander/workspace_template/etc/roles.yaml @@ -0,0 +1,22 @@ +Operator: + ReadParameter: [".*"] + WriteParameter: [] + ReadPacket: [".*"] + Command: [".*"] + CommandHistory: [".*"] + System: + - ControlProcessor + - ModifyCommandHistory + - ControlCommandQueue + - Command + - GetMissionDatabase + - ControlAlarms + - ControlArchiving + +guest: + ReadParameter: [".*"] + WriteParameter: [] + ReadPacket: [".*"] + Command: [".*"] + CommandHistory: [".*"] + System: [] \ No newline at end of file diff --git a/core/base/tools/commander/workspace_template/etc/security.yaml b/core/base/tools/commander/workspace_template/etc/security.yaml new file mode 100644 index 000000000..6b15e071e --- /dev/null +++ b/core/base/tools/commander/workspace_template/etc/security.yaml @@ -0,0 +1,9 @@ +authModules: + - class: org.yamcs.security.YamlAuthModule + args: + required: true + #Comment out the hasher to use plain-text passwords. + hasher: org.yamcs.security.PBKDF2PasswordHasher + + + diff --git a/core/base/tools/commander/workspace_template/etc/users.yaml b/core/base/tools/commander/workspace_template/etc/users.yaml new file mode 100644 index 000000000..cf8874f2c --- /dev/null +++ b/core/base/tools/commander/workspace_template/etc/users.yaml @@ -0,0 +1,9 @@ +admin: + superuser: true + password: root + +lorenzo_gomez: + displayName: lorenzo_gomez + password: guest2 + roles: ["guest"] + diff --git a/core/base/tools/commander/workspace_template/etc/yamcs.yamcs-cfs.yaml b/core/base/tools/commander/workspace_template/etc/yamcs.yamcs-cfs.yaml index 8aa1d016e..932680bbc 100644 --- a/core/base/tools/commander/workspace_template/etc/yamcs.yamcs-cfs.yaml +++ b/core/base/tools/commander/workspace_template/etc/yamcs.yamcs-cfs.yaml @@ -65,8 +65,9 @@ mdb: # Valid loaders are: sheet, xtce or fully qualified name of the class - type: "xtce" spec: "mdb/cfs-ccsds.xml" - - type: "xtce" - spec: "mdb/cfs.xml" + subLoaders: + - type: "xtce" + spec: "mdb/cfs.xml" # Configuration for streams created at server startup streamConfig: diff --git a/core/base/tools/commander/workspace_template/mdb/cfs-ccsds.xml b/core/base/tools/commander/workspace_template/mdb/cfs-ccsds.xml index 22fc13fad..48e9c7f30 100644 --- a/core/base/tools/commander/workspace_template/mdb/cfs-ccsds.xml +++ b/core/base/tools/commander/workspace_template/mdb/cfs-ccsds.xml @@ -1,5 +1,5 @@ - + diff --git a/core/base/tools/commander/workspace_template/mdb/cfs.xml b/core/base/tools/commander/workspace_template/mdb/cfs.xml new file mode 100644 index 000000000..4f6dc223e --- /dev/null +++ b/core/base/tools/commander/workspace_template/mdb/cfs.xml @@ -0,0 +1,8 @@ + + + + + + + + \ No newline at end of file diff --git a/core/base/tools/commander/xtce_config.yaml b/core/base/tools/commander/xtce_config.yaml index 7f0aa2611..eca23c074 100644 --- a/core/base/tools/commander/xtce_config.yaml +++ b/core/base/tools/commander/xtce_config.yaml @@ -1,8 +1,6 @@ #Not sure if this is the best config file for xtce configuration # Configuration for xtce_generator xtce_config: - root_spacesystem: cfs - # The global settings affect every namespace except for the root namespace/spacesystem since the root spacesystem is # merely used as an abstraction that may represent anything such as a vehicle, particular mission or even a hardware # architecture. This is particularly useful when users want to decouple the protocol(an example is ccsds) from the payload @@ -10,14 +8,14 @@ xtce_config: global: TelemetryMetaData: BaseContainer: - container_ref: 'cfs-ccsds' + container_ref: 'cfs' #size is in bits size: 96 CommandMetaData: # This is equivalent to a BaseCommand BaseContainer: - container_ref: 'cfs-ccsds/cfs-cmd' + container_ref: 'cfs/cfs-cmd' # size is in bits size: 64 diff --git a/core/base/tools/config/requirements.txt b/core/base/tools/config/requirements.txt index 420dc7a0b..0eef6649e 100644 --- a/core/base/tools/config/requirements.txt +++ b/core/base/tools/config/requirements.txt @@ -1,3 +1,3 @@ PyYAML==5.3.1 cerberus==1.3.2 -yamlpath==0.0.0 +yamlpath==3.4.0 diff --git a/core/base/tools/config/wh_defgen.py b/core/base/tools/config/wh_defgen.py index 031f948fb..22f99f174 100644 --- a/core/base/tools/config/wh_defgen.py +++ b/core/base/tools/config/wh_defgen.py @@ -140,6 +140,8 @@ def main(): merge_parent_config(merged_config, abs_config_base, abs_local_dir) + yaml_merger.merge(local_config, merged_config) + # We don't want to write the configuration to the file system if there is a file # already there that contains an identical configuration. See if there's a file # there already. diff --git a/core/base/tools/config/yaml_path_merger.py b/core/base/tools/config/yaml_path_merger.py new file mode 100644 index 000000000..1fbf3796c --- /dev/null +++ b/core/base/tools/config/yaml_path_merger.py @@ -0,0 +1,121 @@ +""" +Usage: +For obc-like builds: +python3 yaml_path_merger.py --yaml_output final_yaml_ppd.yaml --yaml_input merged_yaml.yaml --yaml_path /modules/cpd +python3 yaml_path_merger.py --yaml_output final_yaml_ppd.yaml --yaml_input merged_yaml.yaml --yaml_path /modules/ppd + +For bebop-like builds: +Notice how the path is omitted. These configurations tend to be a lot simpler. + +python3 yaml_path_merger.py --yaml_output final_yaml_ppd.yaml --yaml_input merged_yaml.yaml +""" +import argparse +import yaml +import yaml_merger +import os + +ROOT_PATH = "/" + + +def parse_cli() -> argparse.Namespace: + """ + Parses cli argyments. + :return: The namespace that has all of the arguments that have been parsed. + """ + parser = argparse.ArgumentParser(description='Takes in paths to yaml file and sqlite database.') + parser.add_argument('--yaml_output', type=str, + help='The output yaml file that has everything merged in.', + required=True) + parser.add_argument('--yaml_input', type=str, + help='The input file that will be merged into the output file at yaml_path.', required=True) + + parser.add_argument('--yaml_path', type=str, + help='The path to the node in the output file which to merge the contents into', + default=ROOT_PATH) + + return parser.parse_args() + + +def add_value_to_dict(yaml_dict: dict, value: object): + for key in yaml_dict: + if type(yaml_dict[key]) == dict and len(yaml_dict[key]) > 0: + add_value_to_dict(yaml_dict[key], value) + else: + yaml_dict[key] = value + + +def add_dict(path_node: str, root_dict: dict): + root_dict[path_node] = dict() + + +def make_dict_from_path(paths): + """ + Adds an empty nested dictionary from the path. + """ + root_dict = dict() + dict_partition = root_dict + for path in paths: + add_dict(path, dict_partition) + dict_partition = dict_partition[path] + + return root_dict + + +# NOTE: Could actually be useful. +def get_dict_at_path(paths, root_dict): + dict_partition = root_dict + for path in paths: + dict_partition = dict_partition[path] + + return dict_partition + + +def add_new_module(yaml_path, yaml_input): + new_node = make_dict_from_path(yaml_path.split(ROOT_PATH)[1:]) + with open(yaml_input, 'r+') as outFile: + yaml_dict = yaml.load(outFile, Loader=yaml.FullLoader) + add_value_to_dict(new_node, yaml_dict) + + return new_node + + +def main(): + # FIXME: Could definitely use some cleanup + args = parse_cli() + # Create the file in case it does not exist + if os.path.exists(args.yaml_output) is False: + f = open(args.yaml_output, '+w') + f.close() + + if args.yaml_path != ROOT_PATH: + new_module_dict = add_new_module(args.yaml_path, args.yaml_input) + + with open(args.yaml_output, 'r+') as output_file: + yaml_dict = yaml.load(output_file, Loader=yaml.FullLoader) + + # If our output YAML has content, merge th new one onto it + if yaml_dict is not None: + yaml_merger.merge(new_module_dict, yaml_dict) + + # I don't like doing this, but yaml.dump does not overwrite the contents of the file. + output_file.seek(0) + output_file.truncate() + + yaml_merger.merge(new_module_dict, yaml_dict) + yaml.dump(yaml_dict, output_file) + + else: + with open(args.yaml_output, 'r+') as outFile: + yaml.dump(new_module_dict, outFile) + + # If all we want is to add it to the root, then it is really simple. + else: + with open(args.yaml_input, 'r+') as input_file: + yaml_dict_input = yaml.load(input_file, Loader=yaml.FullLoader) + + with open(args.yaml_output, 'r+') as output_file: + yaml.dump(yaml_dict_input, output_file) + + +if __name__ == '__main__': + main() diff --git a/core/tools/auto-yamcs b/core/tools/auto-yamcs index 6b8f24d67..38e7cb9ae 160000 --- a/core/tools/auto-yamcs +++ b/core/tools/auto-yamcs @@ -1 +1 @@ -Subproject commit 6b8f24d676dac4a55648cb34872762caed8c82e8 +Subproject commit 38e7cb9ae0d14304eed056e5f26f1670c8ba1714