diff --git a/.gitmodules b/.gitmodules index d309e0f5..ac6824b8 100644 --- a/.gitmodules +++ b/.gitmodules @@ -11,7 +11,7 @@ path = thirdparty/lwgps url = https://github.com/rmspacefish/lwgps.git [submodule "generators/fsfwgen"] - path = generators/fsfwgen + path = generators/deps/fsfwgen url = https://egit.irs.uni-stuttgart.de/fsfw/fsfw-gen.git [submodule "thirdparty/arcsec_star_tracker"] path = thirdparty/arcsec_star_tracker @@ -19,3 +19,6 @@ [submodule "thirdparty/json"] path = thirdparty/json url = https://github.com/nlohmann/json.git +[submodule "thirdparty/rapidcsv"] + path = thirdparty/rapidcsv + url = https://github.com/d99kris/rapidcsv.git diff --git a/CHANGELOG.md b/CHANGELOG.md index 2baa3275..6256ceec 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -10,6 +10,62 @@ list yields a list of all related PRs for each release. # [unreleased] +# [v1.12.0] 04.07.2022 + +## Added + +- Dummy components to run OBSW without relying on external hardware + PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/266 +- Basic Thermal Controller + PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/266 +- PUS11 TC scheduler + PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/259 +- Regular reboot command + PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/242 +- Commands for individual RTD devices + PR: https://egit.irs.uni-stuttgart.de/eive/eive-tmtc/pulls/84 +- `RwAssembly` added to system components. Assembly works in principle, + issues making 4 consecutives RWs communicate at once.. + PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/224 +- Adds a yocto helper script which is able to install the release build binaries + (OBSW and Watchdog) into the `q7s-yocto` repository as long as the `q7s-package` + or `q7s-yocto` repo was cloned in the same directory the EIVE OBSW repo. + This makes updating the root filesystem a lot easier. It also creates and installs a + version file. + PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/248 +- Create the generic image by default for the Q7S build. The unique binary with the + username appended at the end is created as a side-product now + PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/248 + +## Fixed + +- `q7s-cp.py` bugfix + PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/256 +- Generator scripts output now produce platform-independent artifacts + PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/267 + +### Heater + +- Adds `HealthIF` to heaters. Heaters are own system object with queues now which allows to set them faulty. +- SW will attempt to shut down heaters which are on but marked faulty +- Some simplifications for `HeaterHandler`, use `std::vector` instead of `std::unordered_map` for primary container. Using the heater indexes 0 to 7 allows to use natural array indexing +- Some additional input sanity checks in `executeAction` + PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/236 + +## Changed + +- CCSDS handler improvements + PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/268 +- Build unittest as default side product of hosted builds + PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/244 +- Let CI/CD build host build and run unittest side product in same step +- Catch2 pre-installed in CI/CD docker container, Xiphos SDK installed in CI/CD docker + PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/247 +- Sun Sensors have names denoting their location and poiting in the satellite now + PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/245 +- Better RTD names denoting their purpose (and location consequently) + PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/246 + # [v1.11.0] ## Fixed diff --git a/CMakeLists.txt b/CMakeLists.txt index 54049b34..18b14092 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,12 +1,12 @@ -################################################################################ +# ############################################################################## # CMake support for the EIVE OBSW -# +# # Author: R. Mueller -################################################################################ +# ############################################################################## -################################################################################ +# ############################################################################## # Pre-Project preparation -################################################################################ +# ############################################################################## cmake_minimum_required(VERSION 3.13) set(OBSW_VERSION_MAJOR_IF_GIT_FAILS 0) @@ -15,28 +15,36 @@ set(OBSW_VERSION_REVISION_IF_GIT_FAILS 0) # set(CMAKE_VERBOSE TRUE) -option(EIVE_HARDCODED_TOOLCHAIN_FILE "\ +option( + EIVE_HARDCODED_TOOLCHAIN_FILE + "\ For Linux Board Target BSPs, a default toolchain file will be set. Should be set to OFF \ -if a different toolchain file is set externally" ON -) +if a different toolchain file is set externally" + ON) if(NOT FSFW_OSAL) - set(FSFW_OSAL linux CACHE STRING "OS for the FSFW.") + set(FSFW_OSAL + linux + CACHE STRING "OS for the FSFW.") endif() if(TGT_BSP) - if(TGT_BSP MATCHES "arm/q7s" OR TGT_BSP MATCHES "arm/raspberrypi" OR TGT_BSP MATCHES "arm/beagleboneblack") - option(LINUX_CROSS_COMPILE ON) - endif() - if(TGT_BSP MATCHES "arm/raspberrypi" OR TGT_BSP MATCHES "arm/beagleboneblack") - option(EIVE_BUILD_GPSD_GPS_HANDLER "Build GPSD dependent GPS Handler" OFF) - elseif(TGT_BSP MATCHES "arm/q7s") - option(EIVE_Q7S_EM "Build configuration for the EM" OFF) - option(EIVE_BUILD_GPSD_GPS_HANDLER "Build GPSD dependent GPS Handler" ON) - endif() - option(EIVE_CREATE_UNIQUE_OBSW_BIN "Append username to generated binary name" ON) + if(TGT_BSP MATCHES "arm/q7s" + OR TGT_BSP MATCHES "arm/raspberrypi" + OR TGT_BSP MATCHES "arm/beagleboneblack") + option(LINUX_CROSS_COMPILE ON) + endif() + if(TGT_BSP MATCHES "arm/raspberrypi" OR TGT_BSP MATCHES "arm/beagleboneblack") + option(EIVE_BUILD_GPSD_GPS_HANDLER "Build GPSD dependent GPS Handler" OFF) + elseif(TGT_BSP MATCHES "arm/q7s") + option(EIVE_Q7S_EM "Build configuration for the EM" OFF) + option(EIVE_BUILD_GPSD_GPS_HANDLER "Build GPSD dependent GPS Handler" ON) + endif() + option(EIVE_CREATE_UNIQUE_OBSW_BIN "Append username to generated binary name" + ON) else() - option(EIVE_CREATE_UNIQUE_OBSW_BIN "Append username to generated binary name" OFF) + option(EIVE_CREATE_UNIQUE_OBSW_BIN "Append username to generated binary name" + OFF) endif() list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake") @@ -56,61 +64,99 @@ include(EiveHelpers) option(EIVE_ADD_ETL_LIB "Add ETL library" ON) option(EIVE_ADD_JSON_LIB "Add JSON library" ON) -if(EIVE_Q7S_EM) - set(OBSW_Q7S_EM 1 CACHE STRING "Q7S EM configuration") - set(INIT_VAL 0) -else() - set(OBSW_Q7S_EM 0 CACHE STRING "Q7S EM configuration") - set(INIT_VAL 1) -endif() -set(OBSW_ADD_MGT ${INIT_VAL} CACHE STRING "Add MGT module" ) -set(OBSW_ADD_BPX_BATTERY_HANDLER ${INIT_VAL} CACHE STRING "Add MGT module") -set(OBSW_ADD_STAR_TRACKER ${INIT_VAL} CACHE STRING "Add Startracker module") -set(OBSW_ADD_SUN_SENSORS ${INIT_VAL} CACHE STRING "Add sun sensor module") -set(OBSW_ADD_SUS_BOARD_ASS ${INIT_VAL} CACHE STRING "Add sun sensor board assembly") -set(OBSW_ADD_ACS_BOARD ${INIT_VAL} CACHE STRING "Add ACS board module") -set(OBSW_ADD_ACS_HANDLERS ${INIT_VAL} CACHE STRING "Add ACS handlers") -set(OBSW_ADD_RTD_DEVICES ${INIT_VAL} CACHE STRING "Add RTD devices") -set(OBSW_ADD_RAD_SENSORS ${INIT_VAL} CACHE STRING "Add Rad Sensor module") -set(OBSW_ADD_PL_PCDU ${INIT_VAL} CACHE STRING "Add Payload PCDU modukle") -set(OBSW_ADD_SYRLINKS ${INIT_VAL} CACHE STRING "Add Syrlinks module") -set(OBSW_ADD_TMP_DEVICES ${INIT_VAL} CACHE STRING "Add TMP devices") -set(OBSW_ADD_GOMSPACE_PCDU ${INIT_VAL} CACHE STRING "Add GomSpace PCDU modules") -set(OBSW_ADD_RW ${INIT_VAL} CACHE STRING "Add RW modules") +set(OBSW_MAX_SCHEDULED_TCS 500) -################################################################################ +if(EIVE_Q7S_EM) + set(OBSW_Q7S_EM + 1 + CACHE STRING "Q7S EM configuration") + set(INIT_VAL 0) +else() + set(OBSW_Q7S_EM + 0 + CACHE STRING "Q7S EM configuration") + set(INIT_VAL 1) +endif() +set(OBSW_ADD_MGT + ${INIT_VAL} + CACHE STRING "Add MGT module") +set(OBSW_ADD_BPX_BATTERY_HANDLER + ${INIT_VAL} + CACHE STRING "Add MGT module") +set(OBSW_ADD_STAR_TRACKER + ${INIT_VAL} + CACHE STRING "Add Startracker module") +set(OBSW_ADD_SUN_SENSORS + ${INIT_VAL} + CACHE STRING "Add sun sensor module") +set(OBSW_ADD_SUS_BOARD_ASS + ${INIT_VAL} + CACHE STRING "Add sun sensor board assembly") +set(OBSW_ADD_ACS_BOARD + ${INIT_VAL} + CACHE STRING "Add ACS board module") +set(OBSW_ADD_ACS_HANDLERS + ${INIT_VAL} + CACHE STRING "Add ACS handlers") +set(OBSW_ADD_RTD_DEVICES + ${INIT_VAL} + CACHE STRING "Add RTD devices") +set(OBSW_ADD_RAD_SENSORS + ${INIT_VAL} + CACHE STRING "Add Rad Sensor module") +set(OBSW_ADD_PL_PCDU + ${INIT_VAL} + CACHE STRING "Add Payload PCDU modukle") +set(OBSW_ADD_SYRLINKS + ${INIT_VAL} + CACHE STRING "Add Syrlinks module") +set(OBSW_ADD_TMP_DEVICES + ${INIT_VAL} + CACHE STRING "Add TMP devices") +set(OBSW_ADD_GOMSPACE_PCDU + ${INIT_VAL} + CACHE STRING "Add GomSpace PCDU modules") +set(OBSW_ADD_RW + ${INIT_VAL} + CACHE STRING "Add RW modules") + +# ############################################################################## # Pre-Sources preparation -################################################################################ +# ############################################################################## # Version handling set(GIT_VER_HANDLING_OK FALSE) if(EXISTS ${CMAKE_CURRENT_SOURCE_DIR}/.git) - determine_version_with_git("--exclude" "docker_*") - set(GIT_INFO ${GIT_INFO} CACHE STRING "Version information retrieved with git describe") - if(GIT_INFO) - set(GIT_INFO ${GIT_INFO} CACHE STRING "Version information retrieved with git describe") - list(GET GIT_INFO 1 OBSW_VERSION_MAJOR) - list(GET GIT_INFO 2 OBSW_VERSION_MINOR) - list(GET GIT_INFO 3 OBSW_VERSION_REVISION) - list(GET GIT_INFO 4 OBSW_VERSION_CST_GIT_SHA1) - if(NOT OBSW_VERSION_MAJOR) - set(OBSW_VERSION_MAJOR ${OBSW_VERSION_MAJOR_IF_GIT_FAILS}) - endif() - if(NOT OBSW_VERSION_MINOR) - set(FSFW_SUBVERSION ${OBSW_VERSION_MINOR_IF_GIT_FAILS}) - endif() - if(NOT OBSW_VERSION_REVISION) - set(FSFW_REVISION ${OBSW_VERSION_REVISION_IF_GIT_FAILS}) - endif() - set(GIT_VER_HANDLING_OK TRUE) - else() - set(GIT_VER_HANDLING_OK FALSE) - endif() + determine_version_with_git("--exclude" "docker_*") + set(GIT_INFO + ${GIT_INFO} + CACHE STRING "Version information retrieved with git describe") + if(GIT_INFO) + set(GIT_INFO + ${GIT_INFO} + CACHE STRING "Version information retrieved with git describe") + list(GET GIT_INFO 1 OBSW_VERSION_MAJOR) + list(GET GIT_INFO 2 OBSW_VERSION_MINOR) + list(GET GIT_INFO 3 OBSW_VERSION_REVISION) + list(GET GIT_INFO 4 OBSW_VERSION_CST_GIT_SHA1) + if(NOT OBSW_VERSION_MAJOR) + set(OBSW_VERSION_MAJOR ${OBSW_VERSION_MAJOR_IF_GIT_FAILS}) + endif() + if(NOT OBSW_VERSION_MINOR) + set(FSFW_SUBVERSION ${OBSW_VERSION_MINOR_IF_GIT_FAILS}) + endif() + if(NOT OBSW_VERSION_REVISION) + set(FSFW_REVISION ${OBSW_VERSION_REVISION_IF_GIT_FAILS}) + endif() + set(GIT_VER_HANDLING_OK TRUE) + else() + set(GIT_VER_HANDLING_OK FALSE) + endif() endif() if(NOT GIT_VER_HANDLING_OK) - set(OBSW_VERSION_MAJOR ${OBSW_VERSION_MAJOR_IF_GIT_FAILS}) - set(OBSW_VERSION_MINOR ${OBSW_VERSION_MINOR_IF_GIT_FAILS}) - set(OBSW_VERSION_REVISION ${OBSW_VERSION_REVISION_IF_GIT_FAILS}) + set(OBSW_VERSION_MAJOR ${OBSW_VERSION_MAJOR_IF_GIT_FAILS}) + set(OBSW_VERSION_MINOR ${OBSW_VERSION_MINOR_IF_GIT_FAILS}) + set(OBSW_VERSION_REVISION ${OBSW_VERSION_REVISION_IF_GIT_FAILS}) endif() # Set names and variables @@ -129,6 +175,7 @@ set(LIB_CXX_FS -lstdc++fs) set(LIB_CATCH2 Catch2) set(LIB_GPS gps) set(LIB_JSON_NAME nlohmann_json::nlohmann_json) +set(LIB_DUMMIES dummies) # Set path names set(FSFW_PATH fsfw) @@ -136,6 +183,7 @@ set(TEST_PATH test) set(UNITTEST_PATH unittest) set(LINUX_PATH linux) set(COMMON_PATH common) +set(DUMMY_PATH dummies) set(WATCHDOG_PATH watchdog) set(COMMON_CONFIG_PATH ${COMMON_PATH}/config) set(UNITTEST_CFG_PATH ${UNITTEST_PATH}/testcfg) @@ -156,167 +204,163 @@ set(EIVE_ADD_LINUX_FILES False) pre_source_hw_os_config() if(TGT_BSP) + set(LIBGPS_VERSION_MAJOR 3) + # I assume a newer version than 3.17 will be installed on other Linux board + # than the Q7S + set(LIBGPS_VERSION_MINOR 20) + if(TGT_BSP MATCHES "arm/q7s" + OR TGT_BSP MATCHES "arm/raspberrypi" + OR TGT_BSP MATCHES "arm/beagleboneblack" + OR TGT_BSP MATCHES "arm/egse" + OR TGT_BSP MATCHES "arm/te0720-1cfa") + find_library(${LIB_GPS} gps) + set(FSFW_CONFIG_PATH "linux/fsfwconfig") + if(NOT BUILD_Q7S_SIMPLE_MODE) + set(EIVE_ADD_LINUX_FILES TRUE) + set(ADD_CSP_LIB TRUE) + set(FSFW_HAL_ADD_LINUX ON) + endif() + endif() + + if(TGT_BSP MATCHES "arm/raspberrypi") + # Used by configure file + set(RASPBERRY_PI ON) + set(FSFW_HAL_ADD_RASPBERRY_PI ON) + endif() + + if(TGT_BSP MATCHES "arm/egse") + # Used by configure file + set(EGSE ON) + set(FSFW_HAL_LINUX_ADD_LIBGPIOD OFF) + set(OBSW_ADD_STAR_TRACKER 1) + set(OBSW_DEBUG_STARTRACKER 1) + endif() + + if(TGT_BSP MATCHES "arm/beagleboneblack") + # Used by configure file + set(BEAGLEBONEBLACK ON) + endif() + + if(TGT_BSP MATCHES "arm/q7s") + # Used by configure file + set(XIPHOS_Q7S ON) set(LIBGPS_VERSION_MAJOR 3) - # I assume a newer version than 3.17 will be installed on other Linux board than the Q7S - set(LIBGPS_VERSION_MINOR 20) - if(TGT_BSP MATCHES "arm/q7s" OR TGT_BSP MATCHES "arm/raspberrypi" - OR TGT_BSP MATCHES "arm/beagleboneblack" OR TGT_BSP MATCHES "arm/egse" - OR TGT_BSP MATCHES "arm/te0720-1cfa" - ) - find_library(${LIB_GPS} gps) - set(FSFW_CONFIG_PATH "linux/fsfwconfig") - if(NOT BUILD_Q7S_SIMPLE_MODE) - set(EIVE_ADD_LINUX_FILES TRUE) - set(ADD_CSP_LIB TRUE) - set(FSFW_HAL_ADD_LINUX ON) - endif() - endif() - - if(TGT_BSP MATCHES "arm/raspberrypi" ) - # Used by configure file - set(RASPBERRY_PI ON) - set(FSFW_HAL_ADD_RASPBERRY_PI ON) - endif() + set(LIBGPS_VERSION_MINOR 17) + endif() - if(TGT_BSP MATCHES "arm/egse") - # Used by configure file - set(EGSE ON) - set(FSFW_HAL_LINUX_ADD_LIBGPIOD OFF) - set(OBSW_ADD_STAR_TRACKER 1) - set(OBSW_DEBUG_STARTRACKER 1) - endif() - - if(TGT_BSP MATCHES "arm/beagleboneblack") - # Used by configure file - set(BEAGLEBONEBLACK ON) - endif() - - if(TGT_BSP MATCHES "arm/q7s") - # Used by configure file - set(XIPHOS_Q7S ON) - set(LIBGPS_VERSION_MAJOR 3) - set(LIBGPS_VERSION_MINOR 17) - endif() - - if(TGT_BSP MATCHES "arm/te0720-1cfa") - set(TE0720_1CFA ON) - endif() + if(TGT_BSP MATCHES "arm/te0720-1cfa") + set(TE0720_1CFA ON) + endif() else() - # Required by FSFW library - set(FSFW_CONFIG_PATH "${BSP_PATH}/fsfwconfig") + # Required by FSFW library + set(FSFW_CONFIG_PATH "${BSP_PATH}/fsfwconfig") endif() - # Configuration files configure_file(${COMMON_CONFIG_PATH}/commonConfig.h.in commonConfig.h) configure_file(${FSFW_CONFIG_PATH}/FSFWConfig.h.in FSFWConfig.h) configure_file(${BSP_PATH}/OBSWConfig.h.in OBSWConfig.h) if(TGT_BSP MATCHES "arm/q7s") - configure_file(${BSP_PATH}/boardconfig/q7sConfig.h.in q7sConfig.h) + configure_file(${BSP_PATH}/boardconfig/q7sConfig.h.in q7sConfig.h) elseif(TGT_BSP MATCHES "arm/raspberrypi" OR TGT_BSP MATCHES "arm/egse") - configure_file(${BSP_PATH}/boardconfig/rpiConfig.h.in rpiConfig.h) + configure_file(${BSP_PATH}/boardconfig/rpiConfig.h.in rpiConfig.h) endif() configure_file(${WATCHDOG_PATH}/watchdogConf.h.in watchdogConf.h) # Set common config path for FSFW -set(FSFW_ADDITIONAL_INC_PATHS - "${COMMON_PATH}/config" - ${CMAKE_CURRENT_BINARY_DIR} -) +set(FSFW_ADDITIONAL_INC_PATHS "${COMMON_PATH}/config" + ${CMAKE_CURRENT_BINARY_DIR}) -################################################################################ +# ############################################################################## # Executable and Sources -################################################################################ +# ############################################################################## -#global compiler options need to be set before adding executables +# global compiler options need to be set before adding executables if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU") - add_compile_options( - "-Wall" - "-Wextra" - "-Wimplicit-fallthrough=1" - "-Wno-unused-parameter" - "-Wno-psabi" - "-Wduplicated-cond" # check for duplicate conditions - "-Wduplicated-branches" # check for duplicate branches - "-Wlogical-op" # Search for bitwise operations instead of logical - "-Wnull-dereference" # Search for NULL dereference - "-Wundef" # Warn if undefind marcos are used - "-Wformat=2" # Format string problem detection - "-Wformat-overflow=2" # Formatting issues in printf - "-Wformat-truncation=2" # Formatting issues in printf - "-Wformat-security" # Search for dangerous printf operations - "-Wstrict-overflow=3" # Warn if integer overflows might happen - "-Warray-bounds=2" # Some array bounds violations will be found - "-Wshift-overflow=2" # Search for bit left shift overflows ( Installing Vivado the the Xilinx development tools +## Installing Vivado and the Xilinx development tools It's also possible to perform debugging with a normal Eclipse installation by installing the TCF plugin and downloading the cross-compiler as specified in the section below. However, @@ -342,9 +390,9 @@ installed Vivado with the SDK core tools.
-
+
-
+
* For supported OS refer to https://www.xilinx.com/support/documentation/sw_manuals/xilinx2018_2/ug973-vivado-release-notes-install-license.pdf . Installation was tested on Windows and Ubuntu 21.04. @@ -661,35 +709,7 @@ Thus the replies are received with a larger delay compared to a direct TCP conne 3. Make sure the netmask of the ehternet interface of the workstation matches the netmask of the Q7S * When IP address is set to 192.168.133.10 and the netmask is 255.255.255.0, an example IP address for the workstation is 192.168.133.2 - -4. Run tcf-agent on Q7S - - * Tcf-agent is not yet integrated in the rootfs of the Q7S. Therefore build tcf-agent manually - - ```sh - git clone git://git.eclipse.org/gitroot/tcf/org.eclipse.tcf.agent.git - cd org.eclipse.tcf.agent/agent - make CC=arm-linux-gnueabihf-gcc LD=arm-linux-gnueabihf-ld MACHINE=arm NO_SSL=1 NO_UUID=1 - ``` - - * Transfer executable agent from org.eclipse.tcf.agent/agent/obj/GNU/Linux/arm/Debug to /tmp of Q7S - - ```sh - cd obj/GNU/Linux/arm/Debug - scp agent root@192.168.133.10:/tmp - ``` - - * On Q7S - ```sh - cd /tmp - chmod +x agent - ``` - - * Run agent - ```sh - ./agent - ``` - +4. Make sure th `tcf-agent` is running by checking `systemctl status tcf-agent` 5. In Xilinx SDK 2018.2 right click on project → Debug As → Debug Configurations 6. Right click Xilinx C/C++ applicaton (System Debugger) → New → 7. Set Debug Type to Linux Application Debug and Connectin to Linux Agent @@ -699,8 +719,8 @@ Thus the replies are received with a larger delay compared to a direct TCP conne 11. Test connection (This ensures the TCF Agent is running on the Q7S) 12. Select Application tab * Project Name: eive_obsw - * Local File Path: Path to eiveobsw-linux.elf (in `_bin\linux\devel`) - * Remote File Path: `/tmp/eive_obsw.elf` + * Local File Path: Path to OBSW application image with debug symbols (non-stripped) + * Remote File Path: `/tmp/` # Transfering Files to the Q7S @@ -726,7 +746,8 @@ From a windows machine files can be copied with putty tools (note: use IPv4 addr pscp -scp -P 22 eive@192.168.199.227:/example-file ```` -More detailed information about the used q7s commands can be found in the Q7S user manual. +A helper script named `q7s-cp.py` can be used together with the `q7s-port.sh` +script to make this process easier. # Q7S OBC @@ -1106,16 +1127,28 @@ Eclipse indexer. The [TCF agent](https://wiki.eclipse.org/TCF) can be used to perform remote debugging on the Q7S. -1. Install the TCF agent plugin in Eclipse from +1. Copy the `.cproject` file and the `.project` file inside the `misc/eclipse` folder into the + repo root + + ```sh + cd eive-obsw + cp misc/eclipse/.cproject . + cp misc/eclipse/.project . + ``` + +2. Open the repo in Eclipse as a folder. + +3. Install the TCF agent plugin in Eclipse from the [releases](https://www.eclipse.org/tcf/downloads.php). Go to Help → Install New Software and use the download page, for - example https://download.eclipse.org/tools/tcf/releases/1.7/1.7.0/ to search for the plugin and install it. You can find the newest version [here](https://www.eclipse.org/tcf/downloads.php) + example https://download.eclipse.org/tools/tcf/releases/1.7/1.7.0/ to search for the plugin and + install it. You can find the newest version [here](https://www.eclipse.org/tcf/downloads.php) -2. Go to Window → Perspective → Open Perspective and open the **Target Explorer Perspective**. +4. Go to Window → Perspective → Open Perspective and open the **Target Explorer Perspective**. Here, the Q7S should show up if the local port forwarding was set up as explained previously. Please note that you have to connect to `localhost` and port `1534` with port forwaring set up. -3. A launch configuration was provided, but it might be necessary to adapt it for your own needs. +5. A launch configuration was provided, but it might be necessary to adapt it for your own needs. Alternatively: - Create a new **TCF Remote Application** by pressing the cogs button at the top or going to @@ -1204,7 +1237,7 @@ in the same way. * the formatting is based on the clang-format tools -## Setting up eclipse auto-fromatter with clang-format +## Setting up auto-formatter with clang-format in Xilinx SDK 1. Help → Install New Software → Add 2. In location insert the link http://www.cppstyle.com/luna @@ -1214,3 +1247,11 @@ in the same way. 6. Insert the path to the clang-format executable 7. Under C/C++ → Code Style → Formatter, change the formatter to CppStyle (clang-format) 8. Code can now be formatted with the clang tool by using the key combination Ctrl + Shift + f + +## Setting up auto-fromatter with clang-format in eclipse +1. Help → Eclipse market place → Search for "Cppstyle" and install +2. On windows download the clang-formatting tools from https://llvm.org/builds/. On linux clang-format can be installed with the package manager. +3. Navigate to Preferences → C/C++ → CppStyle +4. Insert the path to the clang-format executable +5. Under C/C++ → Code Style → Formatter, change the formatter to CppStyle (clang-format) +6. Code can now be formatted with the clang tool by using the key combination Ctrl + Shift + f diff --git a/automation/Dockerfile b/automation/Dockerfile index 32d7240f..73275ffb 100644 --- a/automation/Dockerfile +++ b/automation/Dockerfile @@ -4,17 +4,24 @@ RUN apt-get update RUN apt-get --yes upgrade #tzdata is a dependency, won't install otherwise ARG DEBIAN_FRONTEND=noninteractive -RUN apt-get --yes install cmake libgpiod-dev xz-utils nano curl git gcc g++ lcov valgrind libgps-dev +RUN apt-get --yes install cmake libgpiod-dev xz-utils nano curl git gcc g++ lcov valgrind libgps-dev python3 -# Q7S root filesystem, required for cross-compilation. -RUN mkdir -p /usr/rootfs; \ -curl https://buggy.irs.uni-stuttgart.de/eive/tools/eive-compile-rootfs-v0.1.0-7-gae69838.tar.xz \ - | tar -xJ -C /usr/rootfs +ARG XIPHOS_SDK_NAME=sdk-xiphos-eive-v0.2.0 +# Install Xiphos ARK SDK, which also installs Q7S root filesystem, required for cross-compilation. +RUN curl https://buggy.irs.uni-stuttgart.de/eive/tools/${XIPHOS_SDK_NAME}.tar | tar -x && \ + cd ${XIPHOS_SDK_NAME} && \ + ./ark-glibc-x86_64-eive-image-cortexa9hf-neon-toolchain-nodistro.0.sh -y # Cross compiler RUN mkdir -p /usr/tools; \ curl https://buggy.irs.uni-stuttgart.de/eive/tools/gcc-arm-8.3-2019.03-x86_64-arm-linux-gnueabihf.tar.gz \ | tar -xz -C /usr/tools -ENV ZYNQ_7020_SYSROOT="/usr/rootfs/eive-compile-rootfs" +RUN git clone https://github.com/catchorg/Catch2.git && \ + cd Catch2 && \ + git checkout v3.0.0-preview5 && \ + cmake -Bbuild -H. -DBUILD_TESTING=OFF && \ + cmake --build build/ --target install + +ENV ZYNQ_7020_SYSROOT="/opt/xiphos/sdk/ark/sysroots/cortexa9hf-neon-xiphos-linux-gnueabi" ENV PATH=$PATH:"/usr/tools/gcc-arm-8.3-2019.03-x86_64-arm-linux-gnueabihf/bin" diff --git a/automation/Jenkinsfile b/automation/Jenkinsfile index f8b180a1..6504bd1d 100644 --- a/automation/Jenkinsfile +++ b/automation/Jenkinsfile @@ -5,7 +5,7 @@ pipeline { } agent { docker { - image 'eive-obsw-ci:d4' + image 'eive-obsw-ci:d5' args '--sysctl fs.mqueue.msg_max=100' } } @@ -24,11 +24,11 @@ pipeline { } } } - stage('Unittests') { + stage('Build Host and Tests') { steps { dir(BUILDDIR_LINUX) { sh 'cmake ..' - sh 'cmake --build . -t eive-unittest -j4' + sh 'cmake --build . -j4' sh './eive-unittest' } } diff --git a/bsp_egse/CMakeLists.txt b/bsp_egse/CMakeLists.txt index cb02f937..d104354f 100644 --- a/bsp_egse/CMakeLists.txt +++ b/bsp_egse/CMakeLists.txt @@ -1,7 +1,3 @@ -target_sources(${OBSW_NAME} PUBLIC - InitMission.cpp - main.cpp - ObjectFactory.cpp -) +target_sources(${OBSW_NAME} PUBLIC InitMission.cpp main.cpp ObjectFactory.cpp) add_subdirectory(boardconfig) diff --git a/bsp_egse/boardconfig/CMakeLists.txt b/bsp_egse/boardconfig/CMakeLists.txt index f9136e3e..f08670d6 100644 --- a/bsp_egse/boardconfig/CMakeLists.txt +++ b/bsp_egse/boardconfig/CMakeLists.txt @@ -1,7 +1,3 @@ -target_sources(${OBSW_NAME} PRIVATE - print.c -) +target_sources(${OBSW_NAME} PRIVATE print.c) -target_include_directories(${OBSW_NAME} PUBLIC - ${CMAKE_CURRENT_SOURCE_DIR} -) +target_include_directories(${OBSW_NAME} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/bsp_hosted/CMakeLists.txt b/bsp_hosted/CMakeLists.txt index 7787cf7e..2804977d 100644 --- a/bsp_hosted/CMakeLists.txt +++ b/bsp_hosted/CMakeLists.txt @@ -1,8 +1,4 @@ -target_sources(${OBSW_NAME} PUBLIC - InitMission.cpp - main.cpp - ObjectFactory.cpp -) +target_sources(${OBSW_NAME} PUBLIC InitMission.cpp main.cpp ObjectFactory.cpp) add_subdirectory(fsfwconfig) add_subdirectory(boardconfig) diff --git a/bsp_hosted/InitMission.cpp b/bsp_hosted/InitMission.cpp index 0ca59db5..6ec0ed35 100644 --- a/bsp_hosted/InitMission.cpp +++ b/bsp_hosted/InitMission.cpp @@ -1,6 +1,7 @@ #include "InitMission.h" #include +#include #include #include #include @@ -89,9 +90,13 @@ void initmission::initTasks() { sif::error << "Object add component failed" << std::endl; } - PeriodicTaskIF* pusEvents = factory->createPeriodicTask( - "PUS_EVENTS", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); - result = pusVerification->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING); + PeriodicTaskIF* eventHandling = factory->createPeriodicTask( + "EVENTS", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); + result = eventHandling->addComponent(objects::EVENT_MANAGER); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("EVENT_MNGR", objects::EVENT_MANAGER); + } + result = eventHandling->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING); if (result != HasReturnvaluesIF::RETURN_OK) { initmission::printAddObjectError("PUS5", objects::PUS_SERVICE_5_EVENT_REPORTING); } @@ -106,6 +111,10 @@ void initmission::initTasks() { if (result != HasReturnvaluesIF::RETURN_OK) { initmission::printAddObjectError("PUS9", objects::PUS_SERVICE_9_TIME_MGMT); } + result = pusHighPrio->addComponent(objects::PUS_SERVICE_3_HOUSEKEEPING); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS3", objects::PUS_SERVICE_3_HOUSEKEEPING); + } PeriodicTaskIF* pusMedPrio = factory->createPeriodicTask( "PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc); @@ -129,8 +138,34 @@ void initmission::initTasks() { initmission::printAddObjectError("PUS17", objects::PUS_SERVICE_17_TEST); } - PeriodicTaskIF* testTask = factory->createPeriodicTask( - "TEST_TASK", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); + PeriodicTaskIF* thermalTask = factory->createPeriodicTask( + "THERMAL_CTL_TASK", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, missedDeadlineFunc); + result = thermalTask->addComponent(objects::RTD_0_IC3_PLOC_HEATSPREADER); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("RTD_0_dummy", objects::RTD_0_IC3_PLOC_HEATSPREADER); + } + result = thermalTask->addComponent(objects::SUS_0_N_LOC_XFYFZM_PT_XF); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("SUS_0_dummy", objects::SUS_0_N_LOC_XFYFZM_PT_XF); + } + + result = thermalTask->addComponent(objects::CORE_CONTROLLER); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("Core controller dummy", objects::CORE_CONTROLLER); + } + + result = thermalTask->addComponent(objects::THERMAL_CONTROLLER); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("THERMAL_CONTROLLER", objects::THERMAL_CONTROLLER); + } + + FixedTimeslotTaskIF* pstTask = factory->createFixedTimeslotTask( + "DUMMY_PST", 75, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.5, missedDeadlineFunc); + result = dummy_pst::pst(pstTask); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Failed to add dummy pst to fixed timeslot task" << std::endl; + } + #if OBSW_ADD_TEST_CODE == 1 result = testTask->addComponent(objects::TEST_TASK); if (result != HasReturnvaluesIF::RETURN_OK) { @@ -144,11 +179,14 @@ void initmission::initTasks() { tmtcPollingTask->startTask(); pusVerification->startTask(); - pusEvents->startTask(); + eventHandling->startTask(); pusHighPrio->startTask(); pusMedPrio->startTask(); pusLowPrio->startTask(); + pstTask->startTask(); + thermalTask->startTask(); + #if OBSW_ADD_TEST_CODE == 1 testTask->startTask(); #endif /* OBSW_ADD_TEST_CODE == 1 */ diff --git a/bsp_hosted/ObjectFactory.cpp b/bsp_hosted/ObjectFactory.cpp index 7ad599ea..8129790c 100644 --- a/bsp_hosted/ObjectFactory.cpp +++ b/bsp_hosted/ObjectFactory.cpp @@ -2,14 +2,15 @@ #include #include +#include #include -#include +#include #include #include #include -#include "fsfw_tests/integration/task/TestTask.h" #include "OBSWConfig.h" +#include "fsfw_tests/integration/task/TestTask.h" #if OBSW_USE_TMTC_TCP_BRIDGE == 0 #include "fsfw/osal/common/UdpTcPollingTask.h" @@ -25,6 +26,24 @@ #include #endif +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + void Factory::setStaticFrameworkObjectIds() { PusServiceBase::packetSource = objects::PUS_PACKET_DISTRIBUTOR; PusServiceBase::packetDestination = objects::TM_FUNNEL; @@ -44,5 +63,31 @@ void ObjectFactory::produce(void* args) { Factory::setStaticFrameworkObjectIds(); ObjectFactory::produceGenericObjects(); - new TestTask(objects::TEST_TASK); + new ComIFDummy(objects::DUMMY_COM_IF); + ComCookieDummy* comCookieDummy = new ComCookieDummy(); + new BpxDummy(objects::BPX_BATT_HANDLER, objects::DUMMY_COM_IF, comCookieDummy); + new CoreControllerDummy(objects::CORE_CONTROLLER); + new RwDummy(objects::RW1, objects::DUMMY_COM_IF, comCookieDummy); + new RwDummy(objects::RW2, objects::DUMMY_COM_IF, comCookieDummy); + new RwDummy(objects::RW3, objects::DUMMY_COM_IF, comCookieDummy); + new RwDummy(objects::RW4, objects::DUMMY_COM_IF, comCookieDummy); + new StarTrackerDummy(objects::STAR_TRACKER, objects::DUMMY_COM_IF, comCookieDummy); + new SyrlinksDummy(objects::SYRLINKS_HK_HANDLER, objects::DUMMY_COM_IF, comCookieDummy); + new ImtqDummy(objects::IMTQ_HANDLER, objects::DUMMY_COM_IF, comCookieDummy); + new AcuDummy(objects::ACU_HANDLER, objects::DUMMY_COM_IF, comCookieDummy); + new PduDummy(objects::PDU1_HANDLER, objects::DUMMY_COM_IF, comCookieDummy); + new PduDummy(objects::PDU2_HANDLER, objects::DUMMY_COM_IF, comCookieDummy); + new P60DockDummy(objects::P60DOCK_HANDLER, objects::DUMMY_COM_IF, comCookieDummy); + new GyroAdisDummy(objects::GYRO_0_ADIS_HANDLER, objects::DUMMY_COM_IF, comCookieDummy); + new GyroL3GD20Dummy(objects::GYRO_1_L3G_HANDLER, objects::DUMMY_COM_IF, comCookieDummy); + new GyroAdisDummy(objects::GYRO_2_ADIS_HANDLER, objects::DUMMY_COM_IF, comCookieDummy); + new GyroL3GD20Dummy(objects::GYRO_3_L3G_HANDLER, objects::DUMMY_COM_IF, comCookieDummy); + new MgmLIS3MDLDummy(objects::MGM_0_LIS3_HANDLER, objects::DUMMY_COM_IF, comCookieDummy); + new MgmLIS3MDLDummy(objects::MGM_2_LIS3_HANDLER, objects::DUMMY_COM_IF, comCookieDummy); + new PlPcduDummy(objects::PLPCDU_HANDLER, objects::DUMMY_COM_IF, comCookieDummy); + new TemperatureSensorsDummy(); + new SusDummy(); + new ThermalController(objects::THERMAL_CONTROLLER, objects::NO_OBJECT); + + // new TestTask(objects::TEST_TASK); } diff --git a/bsp_hosted/boardconfig/CMakeLists.txt b/bsp_hosted/boardconfig/CMakeLists.txt index 81c8c93d..f08670d6 100644 --- a/bsp_hosted/boardconfig/CMakeLists.txt +++ b/bsp_hosted/boardconfig/CMakeLists.txt @@ -1,10 +1,3 @@ -target_sources(${OBSW_NAME} PRIVATE - print.c -) - -target_include_directories(${OBSW_NAME} PUBLIC - ${CMAKE_CURRENT_SOURCE_DIR} -) - - +target_sources(${OBSW_NAME} PRIVATE print.c) +target_include_directories(${OBSW_NAME} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/bsp_hosted/comIF/CMakeLists.txt b/bsp_hosted/comIF/CMakeLists.txt index eb416f75..568cf560 100644 --- a/bsp_hosted/comIF/CMakeLists.txt +++ b/bsp_hosted/comIF/CMakeLists.txt @@ -1,8 +1 @@ -target_sources(${TARGET_NAME} PUBLIC - ArduinoComIF.cpp - ArduinoCookie.cpp -) - - - - +target_sources(${OBSW_NAME} PUBLIC ArduinoComIF.cpp ArduinoCookie.cpp) diff --git a/bsp_hosted/fsfwconfig/CMakeLists.txt b/bsp_hosted/fsfwconfig/CMakeLists.txt index 4a483eb7..95e43c2e 100644 --- a/bsp_hosted/fsfwconfig/CMakeLists.txt +++ b/bsp_hosted/fsfwconfig/CMakeLists.txt @@ -1,27 +1,17 @@ -target_sources(${OBSW_NAME} PRIVATE - ipc/MissionMessageTypes.cpp -) +target_sources(${OBSW_NAME} PRIVATE ipc/MissionMessageTypes.cpp) -target_include_directories(${OBSW_NAME} PUBLIC - ${CMAKE_CURRENT_SOURCE_DIR} -) +target_include_directories(${OBSW_NAME} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) # If a special translation file for object IDs exists, compile it. if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/objects/translateObjects.cpp") - target_sources(${OBSW_NAME} PRIVATE - objects/translateObjects.cpp - ) - target_sources(${UNITTEST_NAME} PRIVATE - objects/translateObjects.cpp - ) + target_sources(${OBSW_NAME} PRIVATE objects/translateObjects.cpp) + target_sources(${UNITTEST_NAME} PRIVATE objects/translateObjects.cpp) endif() # If a special translation file for events exists, compile it. if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/objects/translateObjects.cpp") - target_sources(${OBSW_NAME} PRIVATE - events/translateEvents.cpp - ) - target_sources(${UNITTEST_NAME} PRIVATE - events/translateEvents.cpp - ) + target_sources(${OBSW_NAME} PRIVATE events/translateEvents.cpp) + target_sources(${UNITTEST_NAME} PRIVATE events/translateEvents.cpp) endif() + +add_subdirectory(pollingsequence) diff --git a/bsp_hosted/fsfwconfig/FSFWConfig.h.in b/bsp_hosted/fsfwconfig/FSFWConfig.h.in index 1eedac67..db5a9ad8 100644 --- a/bsp_hosted/fsfwconfig/FSFWConfig.h.in +++ b/bsp_hosted/fsfwconfig/FSFWConfig.h.in @@ -7,41 +7,41 @@ //! Used to determine whether C++ ostreams are used which can increase //! the binary size significantly. If this is disabled, //! the C stdio functions can be used alternatively -#define FSFW_CPP_OSTREAM_ENABLED 1 +#define FSFW_CPP_OSTREAM_ENABLED 1 //! More FSFW related printouts depending on level. Useful for development. -#define FSFW_VERBOSE_LEVEL 1 +#define FSFW_VERBOSE_LEVEL 1 //! Can be used to completely disable printouts, even the C stdio ones. #if FSFW_CPP_OSTREAM_ENABLED == 0 && FSFW_VERBOSE_LEVEL == 0 - #define FSFW_DISABLE_PRINTOUT 0 +#define FSFW_DISABLE_PRINTOUT 0 #endif -#define FSFW_USE_PUS_C_TELEMETRY 1 +#define FSFW_USE_PUS_C_TELEMETRY 1 #define FSFW_USE_PUS_C_TELECOMMANDS 1 //! Can be used to disable the ANSI color sequences for C stdio. -#define FSFW_COLORED_OUTPUT 1 +#define FSFW_COLORED_OUTPUT 1 //! If FSFW_OBJ_EVENT_TRANSLATION is set to one, //! additional output which requires the translation files translateObjects //! and translateEvents (and their compiled source files) -#define FSFW_OBJ_EVENT_TRANSLATION 1 +#define FSFW_OBJ_EVENT_TRANSLATION 1 #if FSFW_OBJ_EVENT_TRANSLATION == 1 //! Specify whether info events are printed too. -#define FSFW_DEBUG_INFO 1 -#include "objects/translateObjects.h" +#define FSFW_DEBUG_INFO 1 #include "events/translateEvents.h" +#include "objects/translateObjects.h" #else #endif //! When using the newlib nano library, C99 support for stdio facilities //! will not be provided. This define should be set to 1 if this is the case. -#define FSFW_NO_C99_IO 1 +#define FSFW_NO_C99_IO 1 //! Specify whether a special mode store is used for Subsystem components. -#define FSFW_USE_MODESTORE 0 +#define FSFW_USE_MODESTORE 0 //! Defines if the real time scheduler for linux should be used. //! If set to 0, this will also disable priority settings for linux @@ -58,7 +58,7 @@ static constexpr uint8_t FSFW_MISSION_TIMESTAMP_SIZE = 7; //! Configure the allocated pool sizes for the event manager. static constexpr size_t FSFW_EVENTMGMR_MATCHTREE_NODES = 240; static constexpr size_t FSFW_EVENTMGMT_EVENTIDMATCHERS = 120; -static constexpr size_t FSFW_EVENTMGMR_RANGEMATCHERS = 120; +static constexpr size_t FSFW_EVENTMGMR_RANGEMATCHERS = 120; //! Defines the FIFO depth of each commanding service base which //! also determines how many commands a CSB service can handle in one cycle @@ -70,6 +70,6 @@ static constexpr size_t FSFW_PRINT_BUFFER_SIZE = 124; static constexpr size_t FSFW_MAX_TM_PACKET_SIZE = 2048; -} +} // namespace fsfwconfig #endif /* CONFIG_FSFWCONFIG_H_ */ diff --git a/bsp_hosted/fsfwconfig/objects/systemObjectList.h b/bsp_hosted/fsfwconfig/objects/systemObjectList.h index 91bd2bed..4326c108 100644 --- a/bsp_hosted/fsfwconfig/objects/systemObjectList.h +++ b/bsp_hosted/fsfwconfig/objects/systemObjectList.h @@ -22,10 +22,11 @@ enum sourceObjects : uint32_t { TEST_TASK = 0x42694269, DUMMY_INTERFACE = 0xCAFECAFE, - DUMMY_HANDLER = 0x4400AFFE, - + DUMMY_HANDLER = 0x44000001, /* 0x49 ('I') for Communication Interfaces **/ - ARDUINO_COM_IF = 0x49000001 + ARDUINO_COM_IF = 0x49000001, + + DUMMY_COM_IF = 0x49000002 }; } diff --git a/bsp_hosted/fsfwconfig/objects/translateObjects.cpp b/bsp_hosted/fsfwconfig/objects/translateObjects.cpp index f29e4d65..ee9cb057 100644 --- a/bsp_hosted/fsfwconfig/objects/translateObjects.cpp +++ b/bsp_hosted/fsfwconfig/objects/translateObjects.cpp @@ -6,6 +6,8 @@ */ #include "translateObjects.h" +#include "systemObjectList.h" + const char *TEST_TASK_STRING = "TEST_TASK"; const char *DUMMY_HANDLER_STRING = "DUMMY_HANDLER"; const char *ARDUINO_COM_IF_STRING = "ARDUINO_COM_IF"; @@ -36,6 +38,7 @@ const char *IPC_STORE_STRING = "IPC_STORE"; const char *TIME_STAMPER_STRING = "TIME_STAMPER"; const char *FSFW_OBJECTS_END_STRING = "FSFW_OBJECTS_END"; const char *DUMMY_INTERFACE_STRING = "DUMMY_INTERFACE"; +const char *THERMAL_CONTROLLER_STRING = "THERMAL_CONTROLLER"; const char *NO_OBJECT_STRING = "NO_OBJECT"; const char *translateObject(object_id_t object) { @@ -100,6 +103,8 @@ const char *translateObject(object_id_t object) { return FSFW_OBJECTS_END_STRING; case 0xCAFECAFE: return DUMMY_INTERFACE_STRING; + case objects::THERMAL_CONTROLLER: + return THERMAL_CONTROLLER_STRING; case 0xFFFFFFFF: return NO_OBJECT_STRING; default: diff --git a/bsp_hosted/fsfwconfig/pollingsequence/CMakeLists.txt b/bsp_hosted/fsfwconfig/pollingsequence/CMakeLists.txt new file mode 100644 index 00000000..f92d0c32 --- /dev/null +++ b/bsp_hosted/fsfwconfig/pollingsequence/CMakeLists.txt @@ -0,0 +1 @@ +target_sources(${OBSW_NAME} PRIVATE DummyPst.cpp) diff --git a/bsp_hosted/fsfwconfig/pollingsequence/DummyPst.cpp b/bsp_hosted/fsfwconfig/pollingsequence/DummyPst.cpp new file mode 100644 index 00000000..18fca7c6 --- /dev/null +++ b/bsp_hosted/fsfwconfig/pollingsequence/DummyPst.cpp @@ -0,0 +1,140 @@ +#include "DummyPst.h" + +#include +#include +#include +#include + +ReturnValue_t dummy_pst::pst(FixedTimeslotTaskIF *thisSequence) { + uint32_t length = thisSequence->getPeriodMs(); + + thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0, DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::STAR_TRACKER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::STAR_TRACKER, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::STAR_TRACKER, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::STAR_TRACKER, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::STAR_TRACKER, length * 0, DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0, DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::ACU_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::ACU_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::ACU_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::ACU_HANDLER, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::ACU_HANDLER, length * 0, DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::PDU1_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::PDU1_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::PDU1_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::PDU1_HANDLER, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::PDU1_HANDLER, length * 0, DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::PDU2_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::PDU2_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::PDU2_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::PDU2_HANDLER, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::PDU2_HANDLER, length * 0, DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::P60DOCK_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::P60DOCK_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::P60DOCK_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::P60DOCK_HANDLER, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::P60DOCK_HANDLER, length * 0, DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0, DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0, DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0, DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0, DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0, DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0, DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0, DeviceHandlerIF::GET_READ); + + if (thisSequence->checkSequence() == HasReturnvaluesIF::RETURN_OK) { + return HasReturnvaluesIF::RETURN_OK; + } else { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::error << "pst::pollingSequenceInitDefault: Sequence invalid!" << std::endl; +#endif + return HasReturnvaluesIF::RETURN_FAILED; + } +} diff --git a/bsp_hosted/fsfwconfig/pollingsequence/DummyPst.h b/bsp_hosted/fsfwconfig/pollingsequence/DummyPst.h new file mode 100644 index 00000000..711e39ba --- /dev/null +++ b/bsp_hosted/fsfwconfig/pollingsequence/DummyPst.h @@ -0,0 +1,14 @@ +#ifndef POLLINGSEQUENCEFACTORY_H_ +#define POLLINGSEQUENCEFACTORY_H_ + +#include + +class FixedTimeslotTaskIF; + +namespace dummy_pst { + +ReturnValue_t pst(FixedTimeslotTaskIF *thisSequence); + +} + +#endif /* POLLINGSEQUENCEINIT_H_ */ diff --git a/bsp_hosted/fsfwconfig/tmtc/apid.h b/bsp_hosted/fsfwconfig/tmtc/apid.h deleted file mode 100644 index 9d5c9ed5..00000000 --- a/bsp_hosted/fsfwconfig/tmtc/apid.h +++ /dev/null @@ -1,18 +0,0 @@ -#ifndef FSFWCONFIG_TMTC_APID_H_ -#define FSFWCONFIG_TMTC_APID_H_ - -#include - -/** - * Application Process Definition: entity, uniquely identified by an - * application process ID (APID), capable of generating telemetry source - * packets and receiving telecommand packets - * - * SOURCE APID: 0x73 / 115 / s - * APID is a 11 bit number - */ -namespace apid { -static const uint16_t EIVE_OBSW = 0x65; -} - -#endif /* FSFWCONFIG_TMTC_APID_H_ */ diff --git a/bsp_hosted/main.cpp b/bsp_hosted/main.cpp index a652aebc..24800919 100644 --- a/bsp_hosted/main.cpp +++ b/bsp_hosted/main.cpp @@ -1,9 +1,17 @@ +#include + #include #include "InitMission.h" #include "commonConfig.h" #include "fsfw/FSFWVersion.h" +#include "fsfw/controller/ControllerBase.h" +#include "fsfw/ipc/QueueFactory.h" +#include "fsfw/modes/HasModesIF.h" +#include "fsfw/modes/ModeMessage.h" +#include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/tasks/TaskFactory.h" + #ifdef WIN32 static const char* COMPILE_PRINTOUT = "Windows"; #elif LINUX diff --git a/bsp_linux_board/CMakeLists.txt b/bsp_linux_board/CMakeLists.txt index 9884b983..24e81b42 100644 --- a/bsp_linux_board/CMakeLists.txt +++ b/bsp_linux_board/CMakeLists.txt @@ -1,9 +1,5 @@ -target_sources(${OBSW_NAME} PUBLIC - InitMission.cpp - main.cpp - gpioInit.cpp - ObjectFactory.cpp -) +target_sources(${OBSW_NAME} PUBLIC InitMission.cpp main.cpp gpioInit.cpp + ObjectFactory.cpp) add_subdirectory(boardconfig) add_subdirectory(boardtest) diff --git a/bsp_linux_board/InitMission.h b/bsp_linux_board/InitMission.h index f14135dd..6e38fc94 100644 --- a/bsp_linux_board/InitMission.h +++ b/bsp_linux_board/InitMission.h @@ -3,7 +3,7 @@ #include -#include "fsfw/tasks/Typedef.h" +#include "fsfw/tasks/definitions.h" class PeriodicTaskIF; class TaskFactory; diff --git a/bsp_linux_board/ObjectFactory.cpp b/bsp_linux_board/ObjectFactory.cpp index 93a7e96a..47f80936 100644 --- a/bsp_linux_board/ObjectFactory.cpp +++ b/bsp_linux_board/ObjectFactory.cpp @@ -67,7 +67,7 @@ void ObjectFactory::produce(void* args) { GpioCookie* gpioCookie = nullptr; static_cast(gpioCookie); - SpiComIF* spiComIF = new SpiComIF(objects::SPI_COM_IF, gpioIF); + SpiComIF* spiComIF = new SpiComIF(objects::SPI_MAIN_COM_IF, spi::DEV, gpioIF); static_cast(spiComIF); auto pwrSwitcher = new DummyPowerSwitcher(objects::PCDU_HANDLER, 18, 0); static_cast(pwrSwitcher); @@ -116,73 +116,72 @@ void ObjectFactory::createRpiAcsBoard(GpioIF* gpioIF, std::string spiDev) { gpio::Direction::OUT, gpio::Levels::HIGH); gpioIF->addGpios(gpioCookie); SpiCookie* spiCookie = - new SpiCookie(addresses::MGM_0_LIS3, gpioIds::MGM_0_LIS3_CS, spiDev, - MGMLIS3MDL::MAX_BUFFER_SIZE, spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED); + new SpiCookie(addresses::MGM_0_LIS3, gpioIds::MGM_0_LIS3_CS, MGMLIS3MDL::MAX_BUFFER_SIZE, + spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED); auto mgmLis3Handler = - new MgmLIS3MDLHandler(objects::MGM_0_LIS3_HANDLER, objects::SPI_COM_IF, spiCookie, 0); + new MgmLIS3MDLHandler(objects::MGM_0_LIS3_HANDLER, objects::SPI_MAIN_COM_IF, spiCookie, 0); mgmLis3Handler->setStartUpImmediately(); #if OBSW_TEST_ACS == 1 mgmLis3Handler->setToGoToNormalMode(true); #endif spiCookie = - new SpiCookie(addresses::MGM_1_RM3100, gpioIds::MGM_1_RM3100_CS, spiDev, - RM3100::MAX_BUFFER_SIZE, spi::DEFAULT_RM3100_MODE, spi::DEFAULT_RM3100_SPEED); + new SpiCookie(addresses::MGM_1_RM3100, gpioIds::MGM_1_RM3100_CS, RM3100::MAX_BUFFER_SIZE, + spi::DEFAULT_RM3100_MODE, spi::DEFAULT_RM3100_SPEED); auto mgmRm3100Handler = - new MgmRM3100Handler(objects::MGM_1_RM3100_HANDLER, objects::SPI_COM_IF, spiCookie, 0); + new MgmRM3100Handler(objects::MGM_1_RM3100_HANDLER, objects::SPI_MAIN_COM_IF, spiCookie, 0); mgmRm3100Handler->setStartUpImmediately(); #if OBSW_TEST_ACS == 1 mgmRm3100Handler->setToGoToNormalMode(true); #endif spiCookie = - new SpiCookie(addresses::MGM_2_LIS3, gpioIds::MGM_2_LIS3_CS, spiDev, - MGMLIS3MDL::MAX_BUFFER_SIZE, spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED); + new SpiCookie(addresses::MGM_2_LIS3, gpioIds::MGM_2_LIS3_CS, MGMLIS3MDL::MAX_BUFFER_SIZE, + spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED); mgmLis3Handler = - new MgmLIS3MDLHandler(objects::MGM_2_LIS3_HANDLER, objects::SPI_COM_IF, spiCookie, 0); + new MgmLIS3MDLHandler(objects::MGM_2_LIS3_HANDLER, objects::SPI_MAIN_COM_IF, spiCookie, 0); mgmLis3Handler->setStartUpImmediately(); #if OBSW_TEST_ACS == 1 mgmLis3Handler->setToGoToNormalMode(true); #endif spiCookie = - new SpiCookie(addresses::MGM_3_RM3100, gpioIds::MGM_3_RM3100_CS, spiDev, - RM3100::MAX_BUFFER_SIZE, spi::DEFAULT_RM3100_MODE, spi::DEFAULT_RM3100_SPEED); + new SpiCookie(addresses::MGM_3_RM3100, gpioIds::MGM_3_RM3100_CS, RM3100::MAX_BUFFER_SIZE, + spi::DEFAULT_RM3100_MODE, spi::DEFAULT_RM3100_SPEED); mgmRm3100Handler = - new MgmRM3100Handler(objects::MGM_3_RM3100_HANDLER, objects::SPI_COM_IF, spiCookie, 0); + new MgmRM3100Handler(objects::MGM_3_RM3100_HANDLER, objects::SPI_MAIN_COM_IF, spiCookie, 0); mgmRm3100Handler->setStartUpImmediately(); #if OBSW_TEST_ACS == 1 mgmRm3100Handler->setToGoToNormalMode(true); #endif spiCookie = - new SpiCookie(addresses::GYRO_0_ADIS, gpioIds::GYRO_0_ADIS_CS, spiDev, - ADIS1650X::MAXIMUM_REPLY_SIZE, spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED); - auto adisHandler = new GyroADIS1650XHandler(objects::GYRO_0_ADIS_HANDLER, objects::SPI_COM_IF, - spiCookie, ADIS1650X::Type::ADIS16505); - adisHandler->setStartUpImmediately(); - spiCookie = - new SpiCookie(addresses::GYRO_1_L3G, gpioIds::GYRO_1_L3G_CS, spiDev, L3GD20H::MAX_BUFFER_SIZE, + new SpiCookie(addresses::GYRO_0_ADIS, gpioIds::GYRO_0_ADIS_CS, ADIS1650X::MAXIMUM_REPLY_SIZE, spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED); + auto adisHandler = + new GyroADIS1650XHandler(objects::GYRO_0_ADIS_HANDLER, objects::SPI_MAIN_COM_IF, spiCookie, + ADIS1650X::Type::ADIS16505); + adisHandler->setStartUpImmediately(); + spiCookie = new SpiCookie(addresses::GYRO_1_L3G, gpioIds::GYRO_1_L3G_CS, L3GD20H::MAX_BUFFER_SIZE, + spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED); auto gyroL3gHandler = - new GyroHandlerL3GD20H(objects::GYRO_1_L3G_HANDLER, objects::SPI_COM_IF, spiCookie, 0); + new GyroHandlerL3GD20H(objects::GYRO_1_L3G_HANDLER, objects::SPI_MAIN_COM_IF, spiCookie, 0); gyroL3gHandler->setStartUpImmediately(); #if OBSW_TEST_ACS == 1 gyroL3gHandler->setToGoToNormalMode(true); #endif spiCookie = - new SpiCookie(addresses::GYRO_2_ADIS, gpioIds::GYRO_2_ADIS_CS, spiDev, - ADIS1650X::MAXIMUM_REPLY_SIZE, spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED); - adisHandler = new GyroADIS1650XHandler(objects::GYRO_2_ADIS_HANDLER, objects::SPI_COM_IF, + new SpiCookie(addresses::GYRO_2_ADIS, gpioIds::GYRO_2_ADIS_CS, ADIS1650X::MAXIMUM_REPLY_SIZE, + spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED); + adisHandler = new GyroADIS1650XHandler(objects::GYRO_2_ADIS_HANDLER, objects::SPI_MAIN_COM_IF, spiCookie, ADIS1650X::Type::ADIS16505); adisHandler->setStartUpImmediately(); - spiCookie = - new SpiCookie(addresses::GYRO_3_L3G, gpioIds::GYRO_3_L3G_CS, spiDev, L3GD20H::MAX_BUFFER_SIZE, - spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED); + spiCookie = new SpiCookie(addresses::GYRO_3_L3G, gpioIds::GYRO_3_L3G_CS, L3GD20H::MAX_BUFFER_SIZE, + spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED); gyroL3gHandler = - new GyroHandlerL3GD20H(objects::GYRO_3_L3G_HANDLER, objects::SPI_COM_IF, spiCookie, 0); + new GyroHandlerL3GD20H(objects::GYRO_3_L3G_HANDLER, objects::SPI_MAIN_COM_IF, spiCookie, 0); gyroL3gHandler->setStartUpImmediately(); #if OBSW_TEST_ACS == 1 gyroL3gHandler->setToGoToNormalMode(true); diff --git a/bsp_linux_board/boardconfig/CMakeLists.txt b/bsp_linux_board/boardconfig/CMakeLists.txt index f9136e3e..f08670d6 100644 --- a/bsp_linux_board/boardconfig/CMakeLists.txt +++ b/bsp_linux_board/boardconfig/CMakeLists.txt @@ -1,7 +1,3 @@ -target_sources(${OBSW_NAME} PRIVATE - print.c -) +target_sources(${OBSW_NAME} PRIVATE print.c) -target_include_directories(${OBSW_NAME} PUBLIC - ${CMAKE_CURRENT_SOURCE_DIR} -) +target_include_directories(${OBSW_NAME} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/bsp_linux_board/boardtest/CMakeLists.txt b/bsp_linux_board/boardtest/CMakeLists.txt index fe4910f2..431972e8 100644 --- a/bsp_linux_board/boardtest/CMakeLists.txt +++ b/bsp_linux_board/boardtest/CMakeLists.txt @@ -1,6 +1 @@ -target_sources(${OBSW_NAME} PRIVATE -) - - - - +target_sources(${OBSW_NAME} PRIVATE) diff --git a/bsp_q7s/CMakeLists.txt b/bsp_q7s/CMakeLists.txt index 34ee8e2a..f6dbf590 100644 --- a/bsp_q7s/CMakeLists.txt +++ b/bsp_q7s/CMakeLists.txt @@ -1,20 +1,13 @@ -#simple mode +# simple mode add_executable(${SIMPLE_OBSW_NAME} EXCLUDE_FROM_ALL) target_compile_definitions(${SIMPLE_OBSW_NAME} PRIVATE "Q7S_SIMPLE_MODE") -target_sources(${SIMPLE_OBSW_NAME} PUBLIC - main.cpp -) -#I think this is unintentional? (produces linker errors for stuff in /linux) -target_link_libraries(${SIMPLE_OBSW_NAME} PUBLIC - ${LIB_FSFW_NAME} -) +target_sources(${SIMPLE_OBSW_NAME} PUBLIC main.cpp) +# I think this is unintentional? (produces linker errors for stuff in /linux) +target_link_libraries(${SIMPLE_OBSW_NAME} PUBLIC ${LIB_FSFW_NAME}) target_compile_definitions(${SIMPLE_OBSW_NAME} PRIVATE "Q7S_SIMPLE_MODE") add_subdirectory(simple) -target_sources(${OBSW_NAME} PUBLIC - main.cpp - obsw.cpp -) +target_sources(${OBSW_NAME} PUBLIC main.cpp obsw.cpp) add_subdirectory(boardtest) @@ -23,9 +16,9 @@ add_subdirectory(comIF) add_subdirectory(core) if(EIVE_Q7S_EM) - add_subdirectory(em) + add_subdirectory(em) else() - add_subdirectory(fm) + target_sources(${OBSW_NAME} PUBLIC fmObjectFactory.cpp) endif() add_subdirectory(memory) diff --git a/bsp_q7s/OBSWConfig.h.in b/bsp_q7s/OBSWConfig.h.in index 36fa046f..ed321f8c 100644 --- a/bsp_q7s/OBSWConfig.h.in +++ b/bsp_q7s/OBSWConfig.h.in @@ -25,8 +25,8 @@ #define OBSW_ADD_MGT @OBSW_ADD_MGT@ #define OBSW_ADD_BPX_BATTERY_HANDLER @OBSW_ADD_BPX_BATTERY_HANDLER@ #define OBSW_ADD_STAR_TRACKER @OBSW_ADD_STAR_TRACKER@ -#define OBSW_ADD_PLOC_SUPERVISOR 0 -#define OBSW_ADD_PLOC_MPSOC 0 +#define OBSW_ADD_PLOC_SUPERVISOR 1 +#define OBSW_ADD_PLOC_MPSOC 1 #define OBSW_ADD_SUN_SENSORS @OBSW_ADD_SUN_SENSORS@ #define OBSW_ADD_SUS_BOARD_ASS @OBSW_ADD_SUS_BOARD_ASS@ #define OBSW_ADD_ACS_BOARD @OBSW_ADD_ACS_BOARD@ @@ -38,6 +38,7 @@ #define OBSW_ADD_PL_PCDU @OBSW_ADD_PL_PCDU@ #define OBSW_ADD_SYRLINKS @OBSW_ADD_SYRLINKS@ #define OBSW_ENABLE_SYRLINKS_TRANSMIT_TIMEOUT 0 +#define OBSW_MPSOC_JTAG_BOOT 0 // This is a really tricky switch.. It initializes the PCDU switches to their default states // at powerup. I think it would be better diff --git a/bsp_q7s/boardconfig/CMakeLists.txt b/bsp_q7s/boardconfig/CMakeLists.txt index feefbe5a..3224d759 100644 --- a/bsp_q7s/boardconfig/CMakeLists.txt +++ b/bsp_q7s/boardconfig/CMakeLists.txt @@ -1,12 +1,5 @@ -target_sources(${OBSW_NAME} PRIVATE - print.c -) +target_sources(${OBSW_NAME} PRIVATE print.c) -target_sources(${SIMPLE_OBSW_NAME} PRIVATE - print.c -) +target_sources(${SIMPLE_OBSW_NAME} PRIVATE print.c) - -target_include_directories(${OBSW_NAME} PUBLIC - ${CMAKE_CURRENT_SOURCE_DIR} -) +target_include_directories(${OBSW_NAME} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/bsp_q7s/boardconfig/busConf.h b/bsp_q7s/boardconfig/busConf.h index e8cc5bd2..2402938f 100644 --- a/bsp_q7s/boardconfig/busConf.h +++ b/bsp_q7s/boardconfig/busConf.h @@ -4,6 +4,8 @@ namespace q7s { static constexpr char SPI_DEFAULT_DEV[] = "/dev/spi-main"; +static constexpr uint32_t SPI_MAIN_BUS_LOCK_TIMEOUT = 50; + static constexpr char SPI_RW_DEV[] = "/dev/spi-rw"; static constexpr char I2C_DEFAULT_DEV[] = "/dev/i2c-eive"; @@ -15,9 +17,9 @@ static constexpr char UART_SYRLINKS_DEV[] = "/dev/ul-syrlinks"; static constexpr char UART_STAR_TRACKER_DEV[] = "/dev/ul-str"; static constexpr char UIO_PDEC_REGISTERS[] = "/dev/uio0"; +static constexpr char UIO_PTME[] = "/dev/uio1"; static constexpr char UIO_PDEC_CONFIG_MEMORY[] = "/dev/uio2"; static constexpr char UIO_PDEC_RAM[] = "/dev/uio3"; -static constexpr char UIO_PTME[] = "/dev/uio1"; static constexpr int MAP_ID_PTME_CONFIG = 3; namespace uiomapids { diff --git a/bsp_q7s/boardconfig/etl_profile.h b/bsp_q7s/boardconfig/etl_profile.h index 54aca344..86534d14 100644 --- a/bsp_q7s/boardconfig/etl_profile.h +++ b/bsp_q7s/boardconfig/etl_profile.h @@ -34,5 +34,6 @@ SOFTWARE. #define ETL_CPP11_SUPPORTED 1 #define ETL_NO_NULLPTR_SUPPORT 0 +#define ETL_HAS_ERROR_ON_STRING_TRUNCATION 1 #endif diff --git a/bsp_q7s/boardtest/CMakeLists.txt b/bsp_q7s/boardtest/CMakeLists.txt index 29c9f1e1..9520a629 100644 --- a/bsp_q7s/boardtest/CMakeLists.txt +++ b/bsp_q7s/boardtest/CMakeLists.txt @@ -1,10 +1,5 @@ -target_sources(${OBSW_NAME} PRIVATE - FileSystemTest.cpp - Q7STestTask.cpp -) +target_sources(${OBSW_NAME} PRIVATE FileSystemTest.cpp Q7STestTask.cpp) if(EIVE_BUILD_Q7S_SIMPLE_MODE) - target_sources(${SIMPLE_OBSW_NAME} PRIVATE - FileSystemTest.cpp - ) -endif() \ No newline at end of file + target_sources(${SIMPLE_OBSW_NAME} PRIVATE FileSystemTest.cpp) +endif() diff --git a/bsp_q7s/boardtest/Q7STestTask.cpp b/bsp_q7s/boardtest/Q7STestTask.cpp index 0f6734b6..6cf4e734 100644 --- a/bsp_q7s/boardtest/Q7STestTask.cpp +++ b/bsp_q7s/boardtest/Q7STestTask.cpp @@ -156,13 +156,13 @@ void Q7STestTask::testDummyParams() { result = param.getValue(DummyParameter::DUMMY_KEY_PARAM_1, test); if (result != HasReturnvaluesIF::RETURN_OK) { sif::warning << "Q7STestTask::testDummyParams: Key " << DummyParameter::DUMMY_KEY_PARAM_1 - << " does not exist" << std::endl; + << " does not exist" << std::endl; } std::string test2; result = param.getValue(DummyParameter::DUMMY_KEY_PARAM_2, test2); if (result != HasReturnvaluesIF::RETURN_OK) { sif::warning << "Q7STestTask::testDummyParams: Key " << DummyParameter::DUMMY_KEY_PARAM_1 - << " does not exist" << std::endl; + << " does not exist" << std::endl; } sif::info << "Test value (3 expected): " << test << std::endl; sif::info << "Test value 2 (\"blirb\" expected): " << test2 << std::endl; @@ -172,7 +172,7 @@ ReturnValue_t Q7STestTask::initialize() { coreController = ObjectManager::instance()->get(objects::CORE_CONTROLLER); if (coreController == nullptr) { sif::warning << "Q7STestTask::initialize: Could not retrieve CORE_CONTROLLER object" - << std::endl; + << std::endl; } return TestTask::initialize(); } @@ -182,14 +182,14 @@ void Q7STestTask::testProtHandler() { ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; // If any chips are unlocked, lock them here result = coreController->setBootCopyProtection(xsc::Chip::ALL_CHIP, xsc::Copy::ALL_COPY, true, - opPerformed, true); + opPerformed, true); if (result != HasReturnvaluesIF::RETURN_OK) { sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl; } // unlock own copy result = coreController->setBootCopyProtection(xsc::Chip::SELF_CHIP, xsc::Copy::SELF_COPY, false, - opPerformed, true); + opPerformed, true); if (result != HasReturnvaluesIF::RETURN_OK) { sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl; } @@ -203,7 +203,7 @@ void Q7STestTask::testProtHandler() { // lock own copy result = coreController->setBootCopyProtection(xsc::Chip::SELF_CHIP, xsc::Copy::SELF_COPY, true, - opPerformed, true); + opPerformed, true); if (result != HasReturnvaluesIF::RETURN_OK) { sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl; } @@ -217,7 +217,7 @@ void Q7STestTask::testProtHandler() { // unlock specific copy result = coreController->setBootCopyProtection(xsc::Chip::CHIP_1, xsc::Copy::COPY_1, false, - opPerformed, true); + opPerformed, true); if (result != HasReturnvaluesIF::RETURN_OK) { sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl; } @@ -231,7 +231,7 @@ void Q7STestTask::testProtHandler() { // lock specific copy result = coreController->setBootCopyProtection(xsc::Chip::CHIP_1, xsc::Copy::COPY_1, true, - opPerformed, true); + opPerformed, true); if (result != HasReturnvaluesIF::RETURN_OK) { sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl; } @@ -273,7 +273,7 @@ void Q7STestTask::testGpsDaemonShm() { } void Q7STestTask::testGpsDaemonSocket() { - if(gpsmmShmPtr == nullptr) { + if (gpsmmShmPtr == nullptr) { gpsmmShmPtr = new gpsmm("localhost", DEFAULT_GPSD_PORT); } // The data from the device will generally be read all at once. Therefore, we @@ -283,7 +283,7 @@ void Q7STestTask::testGpsDaemonSocket() { // Opening failed #if FSFW_VERBOSE_LEVEL >= 1 sif::warning << "Q7STestTask::testGpsDaemonSocket: Opening GPSMM failed | " - << "Error " << errno << " | " << gps_errstr(errno) << std::endl; + << "Error " << errno << " | " << gps_errstr(errno) << std::endl; #endif gpsNotOpenSwitch = false; @@ -291,17 +291,16 @@ void Q7STestTask::testGpsDaemonSocket() { return; } // Stopwatch watch; - gps_data_t *gps = nullptr; + gps_data_t* gps = nullptr; gpsmmShmPtr->stream(WATCH_ENABLE | WATCH_JSON); - if(not gpsmmShmPtr->waiting(50000000)) { + if (not gpsmmShmPtr->waiting(50000000)) { return; } gps = gpsmmShmPtr->read(); if (gps == nullptr) { if (gpsReadFailedSwitch) { gpsReadFailedSwitch = false; - sif::warning << "Q7STestTask::testGpsDaemonSocket: Reading GPS data failed" - << std::endl; + sif::warning << "Q7STestTask::testGpsDaemonSocket: Reading GPS data failed" << std::endl; } return; } @@ -312,8 +311,8 @@ void Q7STestTask::testGpsDaemonSocket() { if (noModeSetCntr == 10) { // TODO: Trigger event here sif::warning << "Q7STestTask::testGpsDaemonSocket: No mode could be " - "read for 10 consecutive reads" - << std::endl; + "read for 10 consecutive reads" + << std::endl; noModeSetCntr = -1; } return; @@ -339,7 +338,7 @@ void Q7STestTask::testFileSystemHandlerDirect(FsOpCodes opCode) { auto fsHandler = ObjectManager::instance()->get(objects::FILE_SYSTEM_HANDLER); if (fsHandler == nullptr) { sif::warning << "Q7STestTask::testFileSystemHandlerDirect: No FS handler running.." - << std::endl; + << std::endl; } FileSystemHandler::FsCommandCfg cfg = {}; ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; @@ -366,115 +365,115 @@ void Q7STestTask::testFileSystemHandlerDirect(FsOpCodes opCode) { }; switch (opCode) { - case (FsOpCodes::CREATE_EMPTY_FILE_IN_TMP): { - // No mount prefix, cause file is created in tmp - cfg.useMountPrefix = false; - sif::info << "Creating empty file in /tmp folder" << std::endl; - // Do not delete file, user can check existence in shell - fsHandler->createFile("/tmp/", "test.txt", nullptr, 0, &cfg); - break; - } - case (FsOpCodes::REMOVE_TMP_FILE): { - sif::info << "Deleting /tmp/test.txt sample file" << std::endl; - // No mount prefix, cause file is created in tmp - cfg.useMountPrefix = false; - if (not std::filesystem::exists("/tmp/test.txt")) { - // Creating sample file - sif::info << "Creating sample file /tmp/test.txt to delete" << std::endl; + case (FsOpCodes::CREATE_EMPTY_FILE_IN_TMP): { + // No mount prefix, cause file is created in tmp + cfg.useMountPrefix = false; + sif::info << "Creating empty file in /tmp folder" << std::endl; + // Do not delete file, user can check existence in shell fsHandler->createFile("/tmp/", "test.txt", nullptr, 0, &cfg); + break; } - result = fsHandler->removeFile("/tmp", "test.txt", &cfg); - if (result == HasReturnvaluesIF::RETURN_OK) { - sif::info << "File removed successfully" << std::endl; - } else { - sif::warning << "File removal failed!" << std::endl; + case (FsOpCodes::REMOVE_TMP_FILE): { + sif::info << "Deleting /tmp/test.txt sample file" << std::endl; + // No mount prefix, cause file is created in tmp + cfg.useMountPrefix = false; + if (not std::filesystem::exists("/tmp/test.txt")) { + // Creating sample file + sif::info << "Creating sample file /tmp/test.txt to delete" << std::endl; + fsHandler->createFile("/tmp/", "test.txt", nullptr, 0, &cfg); + } + result = fsHandler->removeFile("/tmp", "test.txt", &cfg); + if (result == HasReturnvaluesIF::RETURN_OK) { + sif::info << "File removed successfully" << std::endl; + } else { + sif::warning << "File removal failed!" << std::endl; + } + break; } - break; - } - case (FsOpCodes::CREATE_DIR_IN_TMP): { - // No mount prefix, cause file is created in tmp - cfg.useMountPrefix = false; - sif::info << "Creating empty file in /tmp folder" << std::endl; - // Do not delete file, user can check existence in shell - ReturnValue_t result = fsHandler->createDirectory("/tmp/", "test", false, &cfg); - if (result == HasReturnvaluesIF::RETURN_OK) { - sif::info << "Directory created successfully" << std::endl; - } else { - sif::warning << "Directory creation failed!" << std::endl; + case (FsOpCodes::CREATE_DIR_IN_TMP): { + // No mount prefix, cause file is created in tmp + cfg.useMountPrefix = false; + sif::info << "Creating empty file in /tmp folder" << std::endl; + // Do not delete file, user can check existence in shell + ReturnValue_t result = fsHandler->createDirectory("/tmp/", "test", false, &cfg); + if (result == HasReturnvaluesIF::RETURN_OK) { + sif::info << "Directory created successfully" << std::endl; + } else { + sif::warning << "Directory creation failed!" << std::endl; + } + break; } - break; - } - case (FsOpCodes::REMOVE_EMPTY_DIR_IN_TMP): { - // No mount prefix, cause file is created in tmp - cfg.useMountPrefix = false; - if (not std::filesystem::exists("/tmp/test")) { - result = fsHandler->createDirectory("/tmp", "test", false, &cfg); - } else { - // Delete any leftover files to regular dir removal works - std::remove("/tmp/test/*"); + case (FsOpCodes::REMOVE_EMPTY_DIR_IN_TMP): { + // No mount prefix, cause file is created in tmp + cfg.useMountPrefix = false; + if (not std::filesystem::exists("/tmp/test")) { + result = fsHandler->createDirectory("/tmp", "test", false, &cfg); + } else { + // Delete any leftover files to regular dir removal works + std::remove("/tmp/test/*"); + } + result = fsHandler->removeDirectory("/tmp/", "test", false, &cfg); + if (result == HasReturnvaluesIF::RETURN_OK) { + sif::info << "Directory removed successfully" << std::endl; + } else { + sif::warning << "Directory removal failed!" << std::endl; + } + break; } - result = fsHandler->removeDirectory("/tmp/", "test", false, &cfg); - if (result == HasReturnvaluesIF::RETURN_OK) { - sif::info << "Directory removed successfully" << std::endl; - } else { - sif::warning << "Directory removal failed!" << std::endl; + case (FsOpCodes::REMOVE_FILLED_DIR_IN_TMP): { + result = createNonEmptyTmpDir(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return; + } + result = fsHandler->removeDirectory("/tmp/", "test", true, &cfg); + if (result == HasReturnvaluesIF::RETURN_OK) { + sif::info << "Directory removed recursively successfully" << std::endl; + } else { + sif::warning << "Recursive directory removal failed!" << std::endl; + } + break; } - break; - } - case (FsOpCodes::REMOVE_FILLED_DIR_IN_TMP): { - result = createNonEmptyTmpDir(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return; + case (FsOpCodes::ATTEMPT_DIR_REMOVAL_NON_EMPTY): { + result = createNonEmptyTmpDir(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return; + } + result = fsHandler->removeDirectory("/tmp/", "test", false, &cfg); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::info << "Directory removal attempt failed as expected" << std::endl; + } else { + sif::warning << "Directory removal worked when it should not have!" << std::endl; + } + break; } - result = fsHandler->removeDirectory("/tmp/", "test", true, &cfg); - if (result == HasReturnvaluesIF::RETURN_OK) { - sif::info << "Directory removed recursively successfully" << std::endl; - } else { - sif::warning << "Recursive directory removal failed!" << std::endl; + case (FsOpCodes::RENAME_FILE): { + // No mount prefix, cause file is created in tmp + cfg.useMountPrefix = false; + if (std::filesystem::exists("/tmp/test.txt")) { + fsHandler->removeDirectory("/tmp/", "test", false, &cfg); + } + sif::info << "Creating empty file /tmp/test.txt and rename to /tmp/test2.txt" << std::endl; + // Do not delete file, user can check existence in shell + fsHandler->createFile("/tmp/", "test.txt", nullptr, 0, &cfg); + fsHandler->renameFile("/tmp/", "test.txt", "test2.txt", &cfg); + break; } - break; - } - case (FsOpCodes::ATTEMPT_DIR_REMOVAL_NON_EMPTY): { - result = createNonEmptyTmpDir(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return; + case (FsOpCodes::APPEND_TO_FILE): { + // No mount prefix, cause file is created in tmp + cfg.useMountPrefix = false; + if (std::filesystem::exists("/tmp/test.txt")) { + fsHandler->removeDirectory("/tmp/", "test", false, &cfg); + } + if (std::filesystem::exists("/tmp/test.txt")) { + fsHandler->removeDirectory("/tmp/", "test", false, &cfg); + } + sif::info << "Creating empty file /tmp/test.txt and adding content" << std::endl; + std::string content = "Hello World\n"; + // Do not delete file, user can check existence in shell + fsHandler->createFile("/tmp/", "test.txt", nullptr, 0, &cfg); + fsHandler->appendToFile("/tmp/", "test.txt", reinterpret_cast(content.data()), + content.size(), 0, &cfg); } - result = fsHandler->removeDirectory("/tmp/", "test", false, &cfg); - if (result != HasReturnvaluesIF::RETURN_OK) { - sif::info << "Directory removal attempt failed as expected" << std::endl; - } else { - sif::warning << "Directory removal worked when it should not have!" << std::endl; - } - break; - } - case (FsOpCodes::RENAME_FILE): { - // No mount prefix, cause file is created in tmp - cfg.useMountPrefix = false; - if (std::filesystem::exists("/tmp/test.txt")) { - fsHandler->removeDirectory("/tmp/", "test", false, &cfg); - } - sif::info << "Creating empty file /tmp/test.txt and rename to /tmp/test2.txt" << std::endl; - // Do not delete file, user can check existence in shell - fsHandler->createFile("/tmp/", "test.txt", nullptr, 0, &cfg); - fsHandler->renameFile("/tmp/", "test.txt", "test2.txt", &cfg); - break; - } - case (FsOpCodes::APPEND_TO_FILE): { - // No mount prefix, cause file is created in tmp - cfg.useMountPrefix = false; - if (std::filesystem::exists("/tmp/test.txt")) { - fsHandler->removeDirectory("/tmp/", "test", false, &cfg); - } - if (std::filesystem::exists("/tmp/test.txt")) { - fsHandler->removeDirectory("/tmp/", "test", false, &cfg); - } - sif::info << "Creating empty file /tmp/test.txt and adding content" << std::endl; - std::string content = "Hello World\n"; - // Do not delete file, user can check existence in shell - fsHandler->createFile("/tmp/", "test.txt", nullptr, 0, &cfg); - fsHandler->appendToFile("/tmp/", "test.txt", reinterpret_cast(content.data()), - content.size(), 0, &cfg); - } } } diff --git a/bsp_q7s/boardtest/Q7STestTask.h b/bsp_q7s/boardtest/Q7STestTask.h index ad58889f..7fadbe6b 100644 --- a/bsp_q7s/boardtest/Q7STestTask.h +++ b/bsp_q7s/boardtest/Q7STestTask.h @@ -2,6 +2,7 @@ #define BSP_Q7S_BOARDTEST_Q7STESTTASK_H_ #include + #include "test/testtasks/TestTask.h" class CoreController; diff --git a/bsp_q7s/callbacks/CMakeLists.txt b/bsp_q7s/callbacks/CMakeLists.txt index 584e6026..ed2e16f1 100644 --- a/bsp_q7s/callbacks/CMakeLists.txt +++ b/bsp_q7s/callbacks/CMakeLists.txt @@ -1,6 +1,2 @@ -target_sources(${OBSW_NAME} PRIVATE - rwSpiCallback.cpp - gnssCallback.cpp - pcduSwitchCb.cpp - q7sGpioCallbacks.cpp -) +target_sources(${OBSW_NAME} PRIVATE rwSpiCallback.cpp gnssCallback.cpp + pcduSwitchCb.cpp q7sGpioCallbacks.cpp) diff --git a/bsp_q7s/callbacks/gnssCallback.cpp b/bsp_q7s/callbacks/gnssCallback.cpp index d5dbc3b0..7e854b6d 100644 --- a/bsp_q7s/callbacks/gnssCallback.cpp +++ b/bsp_q7s/callbacks/gnssCallback.cpp @@ -1,9 +1,14 @@ #include "gnssCallback.h" #include "devices/gpioIds.h" +#include "fsfw/action/HasActionsIF.h" #include "fsfw/tasks/TaskFactory.h" -ReturnValue_t gps::triggerGpioResetPin(void* args) { +ReturnValue_t gps::triggerGpioResetPin(const uint8_t* actionData, size_t len, void* args) { + // At least one byte which denotes which GPS to reset is required + if (len < 1 or actionData == nullptr) { + return HasActionsIF::INVALID_PARAMETERS; + } ResetArgs* resetArgs = reinterpret_cast(args); if (args == nullptr) { return HasReturnvaluesIF::RETURN_FAILED; @@ -12,11 +17,10 @@ ReturnValue_t gps::triggerGpioResetPin(void* args) { return HasReturnvaluesIF::RETURN_FAILED; } gpioId_t gpioId; - if (resetArgs->gnss1) { - gpioId = gpioIds::GNSS_1_NRESET; - - } else { + if (actionData[0] == 0) { gpioId = gpioIds::GNSS_0_NRESET; + } else { + gpioId = gpioIds::GNSS_1_NRESET; } resetArgs->gpioComIF->pullLow(gpioId); TaskFactory::delayTask(resetArgs->waitPeriodMs); diff --git a/bsp_q7s/callbacks/gnssCallback.h b/bsp_q7s/callbacks/gnssCallback.h index 3e769899..cd69f5a6 100644 --- a/bsp_q7s/callbacks/gnssCallback.h +++ b/bsp_q7s/callbacks/gnssCallback.h @@ -5,14 +5,13 @@ #include "fsfw_hal/linux/gpio/LinuxLibgpioIF.h" struct ResetArgs { - bool gnss1 = false; LinuxLibgpioIF* gpioComIF = nullptr; uint32_t waitPeriodMs = 100; }; namespace gps { -ReturnValue_t triggerGpioResetPin(void* args); +ReturnValue_t triggerGpioResetPin(const uint8_t* actionData, size_t len, void* args); } diff --git a/bsp_q7s/callbacks/q7sGpioCallbacks.cpp b/bsp_q7s/callbacks/q7sGpioCallbacks.cpp index 6db5aed4..cf222b03 100644 --- a/bsp_q7s/callbacks/q7sGpioCallbacks.cpp +++ b/bsp_q7s/callbacks/q7sGpioCallbacks.cpp @@ -48,7 +48,7 @@ void q7s::gpioCallbacks::initSpiCsDecoder(GpioIF* gpioComIF) { result = gpioComIF->addGpios(spiMuxGpios); if (result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "initSpiCsDecoder: Failed to add mux bit gpios to gpioComIF" << std::endl; + sif::error << "initSpiCsDecoder: Failed to add SPI MUX bit GPIOs" << std::endl; return; } } diff --git a/bsp_q7s/callbacks/rwSpiCallback.cpp b/bsp_q7s/callbacks/rwSpiCallback.cpp index 3ca3c181..0fd2c512 100644 --- a/bsp_q7s/callbacks/rwSpiCallback.cpp +++ b/bsp_q7s/callbacks/rwSpiCallback.cpp @@ -1,5 +1,7 @@ #include "rwSpiCallback.h" +#include + #include "devices/gpioIds.h" #include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw_hal/linux/UnixFileGuard.h" @@ -8,8 +10,25 @@ namespace rwSpiCallback { +namespace { +static bool MODE_SET = false; + +ReturnValue_t openSpi(const std::string& devname, int flags, GpioIF* gpioIF, gpioId_t gpioId, + MutexIF* mutex, MutexIF::TimeoutType timeoutType, uint32_t timeoutMs, + int& fd); +/** + * @brief This function closes a spi session. Pulls the chip select to high an releases the + * mutex. + * @param gpioId Gpio ID of chip select + * @param gpioIF Pointer to gpio interface to drive the chip select + * @param mutex The spi mutex + */ +void closeSpi(int fd, gpioId_t gpioId, GpioIF* gpioIF, MutexIF* mutex); +} // namespace + ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sendData, size_t sendLen, void* args) { + // Stopwatch watch; ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; RwHandler* handler = reinterpret_cast(args); @@ -18,51 +37,45 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sen return HasReturnvaluesIF::RETURN_FAILED; } - uint8_t writeBuffer[2]; + uint8_t writeBuffer[2] = {}; uint8_t writeSize = 0; gpioId_t gpioId = cookie->getChipSelectPin(); GpioIF* gpioIF = comIf->getGpioInterface(); MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING; uint32_t timeoutMs = 0; - MutexIF* mutex = comIf->getMutex(&timeoutType, &timeoutMs); + MutexIF* mutex = comIf->getCsMutex(); + cookie->getMutexParams(timeoutType, timeoutMs); if (mutex == nullptr or gpioIF == nullptr) { sif::debug << "rwSpiCallback::spiCallback: Mutex or GPIO interface invalid" << std::endl; return HasReturnvaluesIF::RETURN_FAILED; } int fileDescriptor = 0; - std::string device = cookie->getSpiDevice(); - UnixFileGuard fileHelper(device, &fileDescriptor, O_RDWR, "rwSpiCallback::spiCallback"); - if (fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { - sif::error << "rwSpiCallback::spiCallback: Failed to open device file" << std::endl; - return SpiComIF::OPENING_FILE_FAILED; - } - spi::SpiModes spiMode = spi::SpiModes::MODE_0; - uint32_t spiSpeed = 0; - cookie->getSpiParameters(spiMode, spiSpeed, nullptr); - comIf->setSpiSpeedAndMode(fileDescriptor, spiMode, spiSpeed); - - result = mutex->lockMutex(timeoutType, timeoutMs); + const std::string& dev = comIf->getSpiDev(); + result = openSpi(dev, O_RDWR, gpioIF, gpioId, mutex, timeoutType, timeoutMs, fileDescriptor); if (result != HasReturnvaluesIF::RETURN_OK) { - sif::debug << "rwSpiCallback::spiCallback: Failed to lock mutex" << std::endl; return result; } - /** Sending frame start sign */ - writeBuffer[0] = 0x7E; - writeSize = 1; - - // Pull SPI CS low. For now, no support for active high given - if (gpioId != gpio::NO_GPIO) { - if (gpioIF->pullLow(gpioId) != HasReturnvaluesIF::RETURN_OK) { - sif::error << "rwSpiCallback::spiCallback: Failed to pull chip select low" << std::endl; - } + spi::SpiModes spiMode = spi::SpiModes::MODE_0; + uint32_t spiSpeed = 0; + cookie->getSpiParameters(spiMode, spiSpeed, nullptr); + // We are in protected section, so we can use the static variable here without issues. + // We don't need to set the speed because a SPI core is used, but the mode has to be set once + // correctly for all RWs + if (not MODE_SET) { + comIf->setSpiSpeedAndMode(fileDescriptor, spiMode, spiSpeed); + MODE_SET = true; } + /** Sending frame start sign */ + writeBuffer[0] = FLAG_BYTE; + writeSize = 1; + if (write(fileDescriptor, writeBuffer, writeSize) != static_cast(writeSize)) { sif::error << "rwSpiCallback::spiCallback: Write failed!" << std::endl; - closeSpi(gpioId, gpioIF, mutex); + closeSpi(fileDescriptor, gpioId, gpioIF, mutex); return RwHandler::SPI_WRITE_FAILURE; } @@ -87,33 +100,39 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sen } if (write(fileDescriptor, writeBuffer, writeSize) != static_cast(writeSize)) { sif::error << "rwSpiCallback::spiCallback: Write failed!" << std::endl; - closeSpi(gpioId, gpioIF, mutex); + closeSpi(fileDescriptor, gpioId, gpioIF, mutex); return RwHandler::SPI_WRITE_FAILURE; } idx++; } /** Sending frame end sign */ - writeBuffer[0] = 0x7E; + writeBuffer[0] = FLAG_BYTE; writeSize = 1; if (write(fileDescriptor, writeBuffer, writeSize) != static_cast(writeSize)) { sif::error << "rwSpiCallback::spiCallback: Write failed!" << std::endl; - closeSpi(gpioId, gpioIF, mutex); + closeSpi(fileDescriptor, gpioId, gpioIF, mutex); return RwHandler::SPI_WRITE_FAILURE; } uint8_t* rxBuf = nullptr; result = comIf->getReadBuffer(cookie->getSpiAddress(), &rxBuf); if (result != HasReturnvaluesIF::RETURN_OK) { - closeSpi(gpioId, gpioIF, mutex); + closeSpi(fileDescriptor, gpioId, gpioIF, mutex); return result; } size_t replyBufferSize = cookie->getMaxBufferSize(); - /** There must be a delay of at least 20 ms after sending the command */ + // There must be a delay of at least 20 ms after sending the command. + // Delay for 70 ms here and release the SPI bus for that duration. + closeSpi(fileDescriptor, gpioId, gpioIF, mutex); usleep(RwDefinitions::SPI_REPLY_DELAY); + result = openSpi(dev, O_RDWR, gpioIF, gpioId, mutex, timeoutType, timeoutMs, fileDescriptor); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } /** * The reaction wheel responds with empty frames while preparing the reply data. @@ -123,13 +142,13 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sen for (int idx = 0; idx < 10; idx++) { if (read(fileDescriptor, &byteRead, 1) != 1) { sif::error << "rwSpiCallback::spiCallback: Read failed" << std::endl; - closeSpi(gpioId, gpioIF, mutex); + closeSpi(fileDescriptor, gpioId, gpioIF, mutex); return RwHandler::SPI_READ_FAILURE; } if (idx == 0) { if (byteRead != FLAG_BYTE) { sif::error << "Invalid data, expected start marker" << std::endl; - closeSpi(gpioId, gpioIF, mutex); + closeSpi(fileDescriptor, gpioId, gpioIF, mutex); return RwHandler::NO_START_MARKER; } } @@ -140,7 +159,7 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sen if (idx == 9) { sif::error << "rwSpiCallback::spiCallback: Empty frame timeout" << std::endl; - closeSpi(gpioId, gpioIF, mutex); + closeSpi(fileDescriptor, gpioId, gpioIF, mutex); return RwHandler::NO_REPLY; } } @@ -180,7 +199,7 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sen continue; } else { sif::error << "rwSpiCallback::spiCallback: Invalid substitute" << std::endl; - closeSpi(gpioId, gpioIF, mutex); + closeSpi(fileDescriptor, gpioId, gpioIF, mutex); result = RwHandler::INVALID_SUBSTITUTE; break; } @@ -201,8 +220,9 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sen result = RwHandler::SPI_READ_FAILURE; break; } - if (byteRead != 0x7E) { - sif::error << "rwSpiCallback::spiCallback: Missing end sign 0x7E" << std::endl; + if (byteRead != FLAG_BYTE) { + sif::error << "rwSpiCallback::spiCallback: Missing end sign " << static_cast(FLAG_BYTE) + << std::endl; decodedFrameLen--; result = RwHandler::MISSING_END_SIGN; break; @@ -213,12 +233,40 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sen cookie->setTransferSize(decodedFrameLen); - closeSpi(gpioId, gpioIF, mutex); + closeSpi(fileDescriptor, gpioId, gpioIF, mutex); return result; } -void closeSpi(gpioId_t gpioId, GpioIF* gpioIF, MutexIF* mutex) { +namespace { + +ReturnValue_t openSpi(const std::string& devname, int flags, GpioIF* gpioIF, gpioId_t gpioId, + MutexIF* mutex, MutexIF::TimeoutType timeoutType, uint32_t timeoutMs, + int& fd) { + ReturnValue_t result = mutex->lockMutex(timeoutType, timeoutMs); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::debug << "rwSpiCallback::spiCallback: Failed to lock mutex" << std::endl; + return result; + } + + fd = open(devname.c_str(), flags); + if (fd < 0) { + sif::error << "rwSpiCallback::spiCallback: Failed to open device file" << std::endl; + return SpiComIF::OPENING_FILE_FAILED; + } + + // Pull SPI CS low. For now, no support for active high given + if (gpioId != gpio::NO_GPIO) { + result = gpioIF->pullLow(gpioId); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "rwSpiCallback::spiCallback: Failed to pull chip select low" << std::endl; + return result; + } + } + return HasReturnvaluesIF::RETURN_OK; +} +void closeSpi(int fd, gpioId_t gpioId, GpioIF* gpioIF, MutexIF* mutex) { + close(fd); if (gpioId != gpio::NO_GPIO) { if (gpioIF->pullHigh(gpioId) != HasReturnvaluesIF::RETURN_OK) { sif::error << "closeSpi: Failed to pull chip select high" << std::endl; @@ -229,4 +277,7 @@ void closeSpi(gpioId_t gpioId, GpioIF* gpioIF, MutexIF* mutex) { ; } } + +} // namespace + } // namespace rwSpiCallback diff --git a/bsp_q7s/callbacks/rwSpiCallback.h b/bsp_q7s/callbacks/rwSpiCallback.h index 843d5b80..4a5389a3 100644 --- a/bsp_q7s/callbacks/rwSpiCallback.h +++ b/bsp_q7s/callbacks/rwSpiCallback.h @@ -33,14 +33,5 @@ static constexpr uint8_t FLAG_BYTE = 0x7E; ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sendData, size_t sendLen, void* args); -/** - * @brief This function closes a spi session. Pulls the chip select to high an releases the - * mutex. - * @param gpioId Gpio ID of chip select - * @param gpioIF Pointer to gpio interface to drive the chip select - * @param mutex The spi mutex - */ -void closeSpi(gpioId_t gpioId, GpioIF* gpioIF, MutexIF* mutex); - } // namespace rwSpiCallback #endif /* BSP_Q7S_RW_SPI_CALLBACK_H_ */ diff --git a/bsp_q7s/comIF/CMakeLists.txt b/bsp_q7s/comIF/CMakeLists.txt index fe4910f2..431972e8 100644 --- a/bsp_q7s/comIF/CMakeLists.txt +++ b/bsp_q7s/comIF/CMakeLists.txt @@ -1,6 +1 @@ -target_sources(${OBSW_NAME} PRIVATE -) - - - - +target_sources(${OBSW_NAME} PRIVATE) diff --git a/bsp_q7s/core/CMakeLists.txt b/bsp_q7s/core/CMakeLists.txt index e5668acc..b4050d73 100644 --- a/bsp_q7s/core/CMakeLists.txt +++ b/bsp_q7s/core/CMakeLists.txt @@ -1,8 +1,4 @@ -target_sources(${OBSW_NAME} PRIVATE - CoreController.cpp - InitMission.cpp -) +target_sources(${OBSW_NAME} PRIVATE CoreController.cpp InitMission.cpp + ObjectFactory.cpp) -target_sources(${SIMPLE_OBSW_NAME} PRIVATE - InitMission.cpp -) +target_sources(${SIMPLE_OBSW_NAME} PRIVATE InitMission.cpp) diff --git a/bsp_q7s/core/CoreController.cpp b/bsp_q7s/core/CoreController.cpp index 208999c2..e387aa71 100644 --- a/bsp_q7s/core/CoreController.cpp +++ b/bsp_q7s/core/CoreController.cpp @@ -56,6 +56,7 @@ CoreController::CoreController(object_id_t objectId) } catch (const std::filesystem::filesystem_error &e) { sif::error << "CoreController::CoreController: Failed with exception " << e.what() << std::endl; } + sdCardCheckCd.timeOut(); eventQueue = QueueFactory::instance()->createMessageQueue(5, EventMessage::MAX_MESSAGE_SIZE); } @@ -77,6 +78,10 @@ void CoreController::performControlOperation() { performWatchdogControlOperation(); sdStateMachine(); performMountedSdCardOperations(); + if (sdCardCheckCd.hasTimedOut()) { + performSdCardCheck(); + sdCardCheckCd.resetTimer(); + } readHkData(); opDivider5.checkAndIncrement(); opDivider10.checkAndIncrement(); @@ -87,6 +92,7 @@ ReturnValue_t CoreController::initializeLocalDataPool(localpool::DataPool &local localDataPoolMap.emplace(core::TEMPERATURE, new PoolEntry({0})); localDataPoolMap.emplace(core::PS_VOLTAGE, new PoolEntry({0})); localDataPoolMap.emplace(core::PL_VOLTAGE, new PoolEntry({0})); + poolManager.subscribeForPeriodicPacket(hkSet.getSid(), false, 10.0, false); return HasReturnvaluesIF::RETURN_OK; } @@ -133,6 +139,9 @@ ReturnValue_t CoreController::initialize() { ReturnValue_t CoreController::initializeAfterTaskCreation() { ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + sdInfo.pref = sdcMan->getPreferredSdCard(); + sdcMan->setActiveSdCard(sdInfo.pref); + currMntPrefix = sdcMan->getCurrentMountPrefix(); if (BLOCKING_SD_INIT) { ReturnValue_t result = initSdCardBlocking(); if (result != HasReturnvaluesIF::RETURN_OK and result != SdCardManager::ALREADY_MOUNTED) { @@ -164,7 +173,7 @@ ReturnValue_t CoreController::executeAction(ActionId_t actionId, MessageQueueId_ if (size < 1) { return HasActionsIF::INVALID_PARAMETERS; } - std::string path = sdcMan->getCurrentMountPrefix(sdInfo.pref) + REBOOT_FILE; + std::string path = sdcMan->getCurrentMountPrefix() + REBOOT_FILE; // Disable the reboot file mechanism parseRebootFile(path, rebootFile); if (data[0] == 0) { @@ -204,15 +213,20 @@ ReturnValue_t CoreController::executeAction(ActionId_t actionId, MessageQueueId_ if (size < 1) { return HasActionsIF::INVALID_PARAMETERS; } - std::string path = sdcMan->getCurrentMountPrefix(sdInfo.pref) + REBOOT_FILE; + std::string path = sdcMan->getCurrentMountPrefix() + REBOOT_FILE; // Disable the reboot file mechanism parseRebootFile(path, rebootFile); rebootFile.maxCount = data[0]; rewriteRebootFile(rebootFile); return HasActionsIF::EXECUTION_FINISHED; } + case (XSC_REBOOT_OBC): { + // Warning: This function will never return, because it reboots the system + return actionXscReboot(data, size); + } case (REBOOT_OBC): { - return actionPerformReboot(data, size); + // Warning: This function will never return, because it reboots the system + return actionReboot(data, size); } default: { return HasActionsIF::INVALID_ACTION_ID; @@ -236,13 +250,12 @@ ReturnValue_t CoreController::initSdCardBlocking() { return HasReturnvaluesIF::RETURN_OK; #else - result = sdcMan->getSdCardActiveStatus(sdInfo.currentState); + result = sdcMan->getSdCardsStatus(sdInfo.currentState); if (result != HasReturnvaluesIF::RETURN_OK) { sif::warning << "Getting SD card activity status failed" << std::endl; } #if Q7S_SD_CARD_CONFIG == Q7S_SD_COLD_REDUNDANT - determinePreferredSdCard(); updateSdInfoOther(); sif::info << "Cold redundant SD card configuration, preferred SD card: " << static_cast(sdInfo.pref) << std::endl; @@ -323,8 +336,8 @@ ReturnValue_t CoreController::sdStateMachine() { if (sdInfo.state == SdStates::SET_STATE_SELF) { if (not sdInfo.commandExecuted) { - result = sdcMan->getSdCardActiveStatus(sdInfo.currentState); - determinePreferredSdCard(); + result = sdcMan->getSdCardsStatus(sdInfo.currentState); + sdInfo.pref = sdcMan->getPreferredSdCard(); updateSdInfoOther(); if (sdInfo.pref != sd::SdCard::SLOT_0 and sdInfo.pref != sd::SdCard::SLOT_1) { sif::warning << "Preferred SD card invalid. Setting to card 0.." << std::endl; @@ -467,7 +480,7 @@ ReturnValue_t CoreController::sdStateMachine() { sdInfo.state = SdStates::IDLE; sdInfo.cycleCount = 0; sdcMan->setBlocking(false); - sdcMan->getSdCardActiveStatus(sdInfo.currentState); + sdcMan->getSdCardsStatus(sdInfo.currentState); if (not sdInfo.initFinished) { updateSdInfoOther(); sdInfo.initFinished = true; @@ -844,25 +857,18 @@ void CoreController::initPrint() { #endif } -ReturnValue_t CoreController::actionPerformReboot(const uint8_t *data, size_t size) { +ReturnValue_t CoreController::actionXscReboot(const uint8_t *data, size_t size) { if (size < 1) { return HasActionsIF::INVALID_PARAMETERS; } bool rebootSameBootCopy = data[0]; - bool protOpPerformed; + bool protOpPerformed = false; + SdCardManager::instance()->setBlocking(true); if (rebootSameBootCopy) { #if OBSW_VERBOSE_LEVEL >= 1 sif::info << "CoreController::actionPerformReboot: Rebooting on current image" << std::endl; #endif - // Attempt graceful shutdown by unmounting and switching off SD cards - SdCardManager::instance()->switchOffSdCard(sd::SdCard::SLOT_0); - SdCardManager::instance()->switchOffSdCard(sd::SdCard::SLOT_1); - // If any boot copies are unprotected - ReturnValue_t retval = setBootCopyProtection(xsc::Chip::SELF_CHIP, xsc::Copy::SELF_COPY, true, - protOpPerformed, false); - if (retval == HasReturnvaluesIF::RETURN_OK and protOpPerformed) { - sif::info << "Running slot was writeprotected before reboot" << std::endl; - } + gracefulShutdownTasks(xsc::Chip::SELF_CHIP, xsc::Copy::SELF_COPY, protOpPerformed); int result = std::system("xsc_boot_copy -r"); if (result != 0) { utility::handleSystemError(result, "CoreController::executeAction"); @@ -884,12 +890,8 @@ ReturnValue_t CoreController::actionPerformReboot(const uint8_t *data, size_t si auto tgtChip = static_cast(data[1]); auto tgtCopy = static_cast(data[2]); - ReturnValue_t retval = - setBootCopyProtection(static_cast(data[1]), static_cast(data[2]), true, - protOpPerformed, false); - if (retval == HasReturnvaluesIF::RETURN_OK and protOpPerformed) { - sif::info << "Target slot was writeprotected before reboot" << std::endl; - } + // This function can not really fail + gracefulShutdownTasks(tgtChip, tgtCopy, protOpPerformed); switch (tgtChip) { case (xsc::Chip::CHIP_0): { @@ -930,27 +932,32 @@ ReturnValue_t CoreController::actionPerformReboot(const uint8_t *data, size_t si return HasReturnvaluesIF::RETURN_FAILED; } -CoreController::~CoreController() {} - -void CoreController::determinePreferredSdCard() { - if (sdInfo.pref == sd::SdCard::NONE) { - ReturnValue_t result = sdcMan->getPreferredSdCard(sdInfo.pref); - if (result != HasReturnvaluesIF::RETURN_OK) { - if (result == scratch::KEY_NOT_FOUND) { - sif::warning << "CoreController::sdCardInit: " - "Preferred SD card not set. Setting to 0" - << std::endl; - sdcMan->setPreferredSdCard(sd::SdCard::SLOT_0); - sdInfo.pref = sd::SdCard::SLOT_0; - } else { - sif::warning << "CoreController::sdCardInit: Could not get preferred SD card" - "information from the scratch buffer" - << std::endl; - } - } - } +ReturnValue_t CoreController::actionReboot(const uint8_t *data, size_t size) { + bool protOpPerformed = false; + gracefulShutdownTasks(xsc::Chip::CHIP_0, xsc::Copy::COPY_0, protOpPerformed); + std::system("reboot"); + return RETURN_OK; } +ReturnValue_t CoreController::gracefulShutdownTasks(xsc::Chip chip, xsc::Copy copy, + bool &protOpPerformed) { + sdcMan->setBlocking(true); + // Attempt graceful shutdown by unmounting and switching off SD cards + sdcMan->switchOffSdCard(sd::SdCard::SLOT_0); + sdcMan->switchOffSdCard(sd::SdCard::SLOT_1); + // If any boot copies are unprotected + ReturnValue_t result = setBootCopyProtection(xsc::Chip::SELF_CHIP, xsc::Copy::SELF_COPY, true, + protOpPerformed, false); + if (result == HasReturnvaluesIF::RETURN_OK and protOpPerformed) { + // TODO: Would be nice to notify operator. But we can't use the filesystem anymore + // and a reboot is imminent. Use scratch buffer? + sif::info << "Running slot was writeprotected before reboot" << std::endl; + } + return result; +} + +CoreController::~CoreController() {} + void CoreController::updateSdInfoOther() { if (sdInfo.pref == sd::SdCard::SLOT_0) { sdInfo.prefChar = "0"; @@ -1234,24 +1241,73 @@ void CoreController::performWatchdogControlOperation() { } void CoreController::performMountedSdCardOperations() { - currMntPrefix = sdcMan->getCurrentMountPrefix(); - if (doPerformMountedSdCardOps) { - bool sdCardMounted = false; - sdCardMounted = sdcMan->isSdCardMounted(sdInfo.pref); - if (sdCardMounted) { - std::string path = currMntPrefix + "/" + CONF_FOLDER; - if (not std::filesystem::exists(path)) { - std::filesystem::create_directory(path); + auto mountedSdCardOp = [&](bool &mntSwitch, sd::SdCard sdCard, std::string mntPoint) { + if (mntSwitch) { + bool sdCardMounted = sdcMan->isSdCardMounted(sdCard); + if (sdCardMounted and not performOneShotSdCardOpsSwitch) { + std::ostringstream path; + path << mntPoint << "/" << CONF_FOLDER; + if (not std::filesystem::exists(path.str())) { + std::filesystem::create_directory(path.str()); + } + initVersionFile(); + initClockFromTimeFile(); + performRebootFileHandling(false); + performOneShotSdCardOpsSwitch = true; } - initVersionFile(); - initClockFromTimeFile(); - performRebootFileHandling(false); - doPerformMountedSdCardOps = false; + mntSwitch = false; } + }; + if (sdInfo.pref == sd::SdCard::SLOT_1) { + mountedSdCardOp(sdInfo.mountSwitch.second, sd::SdCard::SLOT_1, SdCardManager::SD_1_MOUNT_POINT); + mountedSdCardOp(sdInfo.mountSwitch.first, sd::SdCard::SLOT_0, SdCardManager::SD_0_MOUNT_POINT); + } else { + mountedSdCardOp(sdInfo.mountSwitch.first, sd::SdCard::SLOT_0, SdCardManager::SD_0_MOUNT_POINT); + mountedSdCardOp(sdInfo.mountSwitch.second, sd::SdCard::SLOT_1, SdCardManager::SD_1_MOUNT_POINT); } timeFileHandler(); } +ReturnValue_t CoreController::performSdCardCheck() { + bool mountedReadOnly = false; + SdCardManager::SdStatePair active; + sdcMan->getSdCardsStatus(active); + auto sdCardCheck = [&](sd::SdCard sdCard) { + ReturnValue_t result = sdcMan->isSdCardMountedReadOnly(sdCard, mountedReadOnly); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "CoreController::performSdCardCheck: Could not check " + "read-only mount state" + << std::endl; + mountedReadOnly = true; + } + if (mountedReadOnly) { + int linuxErrno = 0; + result = sdcMan->performFsck(sdCard, true, linuxErrno); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "CoreController::performSdCardCheck: fsck command on SD Card " + << static_cast(sdCard) << " failed with code " << linuxErrno << " | " + << strerror(linuxErrno); + } + result = sdcMan->remountReadWrite(sdCard); + if (result == HasReturnvaluesIF::RETURN_OK) { + sif::warning << "CoreController::performSdCardCheck: Remounted SD Card " + << static_cast(sdCard) << " read-write"; + } else { + sif::error << "CoreController::performSdCardCheck: Remounting SD Card " + << static_cast(sdCard) << " read-write failed"; + } + } + }; + if (active.first == sd::SdState::MOUNTED) { + sdCardCheck(sd::SdCard::SLOT_0); + } + if (active.second == sd::SdState::MOUNTED) { + sdCardCheck(sd::SdCard::SLOT_1); + } + + return RETURN_OK; +} + void CoreController::performRebootFileHandling(bool recreateFile) { using namespace std; std::string path = currMntPrefix + REBOOT_FILE; @@ -1677,7 +1733,7 @@ void CoreController::rewriteRebootFile(RebootFile file) { } void CoreController::setRebootMechanismLock(bool lock, xsc::Chip tgtChip, xsc::Copy tgtCopy) { - std::string path = sdcMan->getCurrentMountPrefix(sdInfo.pref) + REBOOT_FILE; + std::string path = currMntPrefix + REBOOT_FILE; // Disable the reboot file mechanism parseRebootFile(path, rebootFile); if (tgtChip == xsc::CHIP_0) { diff --git a/bsp_q7s/core/CoreController.h b/bsp_q7s/core/CoreController.h index dee06530..2ebdd4ec 100644 --- a/bsp_q7s/core/CoreController.h +++ b/bsp_q7s/core/CoreController.h @@ -67,13 +67,16 @@ class CoreController : public ExtendedControllerBase { static constexpr ActionId_t SWITCH_IMG_LOCK = 7; static constexpr ActionId_t SET_MAX_REBOOT_CNT = 8; - static constexpr ActionId_t REBOOT_OBC = 32; + //! Reboot using the xsc_boot_copy command + static constexpr ActionId_t XSC_REBOOT_OBC = 32; static constexpr ActionId_t MOUNT_OTHER_COPY = 33; + //! Reboot using the reboot command + static constexpr ActionId_t REBOOT_OBC = 34; static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::CORE; static constexpr Event ALLOC_FAILURE = event::makeEvent(SUBSYSTEM_ID, 0, severity::MEDIUM); - //! [EXPORT] : [COMMENT] Software reboot occured. Can also be a systemd reboot. + //! [EXPORT] : [COMMENT] Software reboot occurred. Can also be a systemd reboot. //! P1: Current Chip, P2: Current Copy static constexpr Event REBOOT_SW = event::makeEvent(SUBSYSTEM_ID, 1, severity::MEDIUM); //! [EXPORT] : [COMMENT] The reboot mechanism was triggered. @@ -159,11 +162,12 @@ class CoreController : public ExtendedControllerBase { struct SdInfo { sd::SdCard pref = sd::SdCard::NONE; - sd::SdState prefState = sd::SdState::OFF; sd::SdCard other = sd::SdCard::NONE; + sd::SdState prefState = sd::SdState::OFF; sd::SdState otherState = sd::SdState::OFF; std::string prefChar = "0"; std::string otherChar = "1"; + std::pair mountSwitch = {true, true}; SdStates state = SdStates::START; // Used to track whether a command was executed bool commandExecuted = true; @@ -179,7 +183,7 @@ class CoreController : public ExtendedControllerBase { } sdInfo; RebootFile rebootFile = {}; std::string currMntPrefix; - bool doPerformMountedSdCardOps = true; + bool performOneShotSdCardOpsSwitch = true; /** * Index 0: Chip 0 Copy 0 @@ -195,12 +199,14 @@ class CoreController : public ExtendedControllerBase { ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, LocalDataPoolManager& poolManager) override; + Countdown sdCardCheckCd = Countdown(120000); LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override; ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, uint32_t* msToReachTheMode); void performMountedSdCardOperations(); ReturnValue_t initVersionFile(); ReturnValue_t initClockFromTimeFile(); + ReturnValue_t performSdCardCheck(); ReturnValue_t timeFileHandler(); ReturnValue_t initBootCopy(); ReturnValue_t initWatchdogFifo(); @@ -214,14 +220,16 @@ class CoreController : public ExtendedControllerBase { ReturnValue_t sdColdRedundantBlockingInit(); void currentStateSetter(sd::SdCard sdCard, sd::SdState newState); - void determinePreferredSdCard(); void executeNextExternalSdCommand(); void checkExternalSdCommandStatus(); void performRebootFileHandling(bool recreateFile); ReturnValue_t actionListDirectoryIntoFile(ActionId_t actionId, MessageQueueId_t commandedBy, const uint8_t* data, size_t size); - ReturnValue_t actionPerformReboot(const uint8_t* data, size_t size); + ReturnValue_t actionXscReboot(const uint8_t* data, size_t size); + ReturnValue_t actionReboot(const uint8_t* data, size_t size); + + ReturnValue_t gracefulShutdownTasks(xsc::Chip chip, xsc::Copy copy, bool& protOpPerformed); void performWatchdogControlOperation(); diff --git a/bsp_q7s/core/InitMission.cpp b/bsp_q7s/core/InitMission.cpp index 6fd2d723..f2090666 100644 --- a/bsp_q7s/core/InitMission.cpp +++ b/bsp_q7s/core/InitMission.cpp @@ -1,5 +1,7 @@ #include "bsp_q7s/core/InitMission.h" +#include + #include #include @@ -13,6 +15,7 @@ #include "fsfw/tasks/FixedTimeslotTaskIF.h" #include "fsfw/tasks/PeriodicTaskIF.h" #include "fsfw/tasks/TaskFactory.h" +#include "mission/devices/devicedefinitions/Max31865Definitions.h" #include "mission/utility/InitMission.h" #include "pollingsequence/pollingSequenceFactory.h" @@ -33,8 +36,16 @@ ObjectManagerIF* objectManager = nullptr; void initmission::initMission() { sif::info << "Building global objects.." << std::endl; - /* Instantiate global object manager and also create all objects */ - ObjectManager::instance()->setObjectFactoryFunction(ObjectFactory::produce, nullptr); + try { + /* Instantiate global object manager and also create all objects */ + ObjectManager::instance()->setObjectFactoryFunction(ObjectFactory::produce, nullptr); + } catch (const std::invalid_argument& e) { + sif::error << "initmission::initMission: Object Construction failed with an " + "invalid argument: " + << e.what(); + std::exit(1); + } + sif::info << "Initializing all objects.." << std::endl; ObjectManager::instance()->initialize(); @@ -115,30 +126,72 @@ void initmission::initTasks() { #if OBSW_ADD_ACS_HANDLERS == 1 PeriodicTaskIF* acsTask = factory->createPeriodicTask( - "ACS_CTRL", 45, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.4, missedDeadlineFunc); + "ACS_TASK", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.4, missedDeadlineFunc); result = acsTask->addComponent(objects::GPS_CONTROLLER); if (result != HasReturnvaluesIF::RETURN_OK) { initmission::printAddObjectError("GPS_CTRL", objects::GPS_CONTROLLER); } - #endif /* OBSW_ADD_ACS_HANDLERS */ PeriodicTaskIF* sysTask = factory->createPeriodicTask( "SYS_TASK", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.4, missedDeadlineFunc); + static_cast(sysTask); +#if OBSW_ADD_ACS_HANDLERS == 1 result = sysTask->addComponent(objects::ACS_BOARD_ASS); if (result != HasReturnvaluesIF::RETURN_OK) { initmission::printAddObjectError("ACS_BOARD_ASS", objects::ACS_BOARD_ASS); } +#endif /* OBSW_ADD_ACS_HANDLERS */ +#if OBSW_ADD_RW == 1 + result = sysTask->addComponent(objects::RW_ASS); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("RW_ASS", objects::RW_ASS); + } +#endif #if OBSW_ADD_SUS_BOARD_ASS == 1 result = sysTask->addComponent(objects::SUS_BOARD_ASS); if (result != HasReturnvaluesIF::RETURN_OK) { initmission::printAddObjectError("SUS_BOARD_ASS", objects::SUS_BOARD_ASS); } #endif - result = sysTask->addComponent(objects::TCS_BOARD_ASS); + +#if OBSW_ADD_RTD_DEVICES == 1 + PeriodicTaskIF* tcsPollingTask = factory->createPeriodicTask( + "TCS_POLLING_TASK", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.5, missedDeadlineFunc); + result = tcsPollingTask->addComponent(objects::SPI_RTD_COM_IF); if (result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("TCS_BOARD_ASS", objects::TCS_BOARD_ASS); + initmission::printAddObjectError("SPI_RTD_POLLING", objects::SPI_RTD_COM_IF); } + PeriodicTaskIF* tcsTask = factory->createPeriodicTask( + "TCS_TASK", 45, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc); + std::array rtdIds = { + objects::RTD_0_IC3_PLOC_HEATSPREADER, + objects::RTD_1_IC4_PLOC_MISSIONBOARD, + objects::RTD_2_IC5_4K_CAMERA, + objects::RTD_3_IC6_DAC_HEATSPREADER, + objects::RTD_4_IC7_STARTRACKER, + objects::RTD_5_IC8_RW1_MX_MY, + objects::RTD_6_IC9_DRO, + objects::RTD_7_IC10_SCEX, + objects::RTD_8_IC11_X8, + objects::RTD_9_IC12_HPA, + objects::RTD_10_IC13_PL_TX, + objects::RTD_11_IC14_MPA, + objects::RTD_12_IC15_ACU, + objects::RTD_13_IC16_PLPCDU_HEATSPREADER, + objects::RTD_14_IC17_TCS_BOARD, + objects::RTD_15_IC18_IMTQ, + }; + tcsTask->addComponent(objects::TCS_BOARD_ASS); + tcsTask->addComponent(objects::THERMAL_CONTROLLER); + for (const auto& rtd : rtdIds) { + tcsTask->addComponent(rtd, DeviceHandlerIF::PERFORM_OPERATION); + tcsTask->addComponent(rtd, DeviceHandlerIF::SEND_WRITE); + tcsTask->addComponent(rtd, DeviceHandlerIF::GET_WRITE); + tcsTask->addComponent(rtd, DeviceHandlerIF::SEND_READ); + tcsTask->addComponent(rtd, DeviceHandlerIF::GET_READ); + } +#endif /* OBSW_ADD_RTD_DEVICES */ // FS task, task interval does not matter because it runs in permanent loop, priority low // because it is a non-essential background task @@ -167,6 +220,15 @@ void initmission::initTasks() { } #endif /* OBSW_ADD_PLOC_MPSOC */ +#if OBSW_ADD_PLOC_SUPERVISOR == 1 + PeriodicTaskIF* supvHelperTask = factory->createPeriodicTask( + "PLOC_SUPV_HELPER", 10, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, missedDeadlineFunc); + result = supvHelperTask->addComponent(objects::PLOC_SUPERVISOR_HELPER); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PLOC_SUPV_HELPER", objects::PLOC_SUPERVISOR_HELPER); + } +#endif /* OBSW_ADD_PLOC_SUPERVISOR */ + #if OBSW_TEST_CCSDS_BRIDGE == 1 PeriodicTaskIF* ptmeTestTask = factory->createPeriodicTask( "PTME_TEST", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); @@ -228,9 +290,15 @@ void initmission::initTasks() { #if OBSW_ADD_ACS_HANDLERS == 1 acsTask->startTask(); -#endif +#endif /* OBSW_ADD_ACS_HANDLERS == 1 */ sysTask->startTask(); - +#if OBSW_ADD_RTD_DEVICES == 1 + tcsPollingTask->startTask(); + tcsTask->startTask(); +#endif /* OBSW_ADD_RTD_DEVICES == 1 */ +#if OBSW_ADD_PLOC_SUPERVISOR == 1 + supvHelperTask->startTask(); +#endif /* OBSW_ADD_PLOC_SUPERVISOR == 1 */ sif::info << "Tasks started.." << std::endl; } @@ -241,7 +309,7 @@ void initmission::createPstTasks(TaskFactory& factory, /* Polling Sequence Table Default */ #if OBSW_ADD_SPI_TEST_CODE == 0 FixedTimeslotTaskIF* spiPst = factory.createFixedTimeslotTask( - "PST_TASK_DEFAULT", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.5, missedDeadlineFunc); + "MAIN_SPI", 75, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.5, missedDeadlineFunc); result = pst::pstSpi(spiPst); if (result != HasReturnvaluesIF::RETURN_OK) { if (result == FixedTimeslotTaskIF::SLOT_LIST_EMPTY) { @@ -254,8 +322,23 @@ void initmission::createPstTasks(TaskFactory& factory, } #endif +#if OBSW_ADD_RW == 1 + FixedTimeslotTaskIF* rwPstTask = factory.createFixedTimeslotTask( + "RW_SPI", 65, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 1.0, missedDeadlineFunc); + result = pst::pstSpiRw(rwPstTask); + if (result != HasReturnvaluesIF::RETURN_OK) { + if (result == FixedTimeslotTaskIF::SLOT_LIST_EMPTY) { + sif::warning << "InitMission::initTasks: SPI PST is empty" << std::endl; + } else { + sif::error << "InitMission::initTasks: Creating SPI PST failed!" << std::endl; + } + } else { + taskVec.push_back(rwPstTask); + } +#endif + FixedTimeslotTaskIF* uartPst = factory.createFixedTimeslotTask( - "UART_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.2, missedDeadlineFunc); + "UART_PST", 65, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.2, missedDeadlineFunc); result = pst::pstUart(uartPst); if (result != HasReturnvaluesIF::RETURN_OK) { if (result == FixedTimeslotTaskIF::SLOT_LIST_EMPTY) { @@ -268,7 +351,7 @@ void initmission::createPstTasks(TaskFactory& factory, } FixedTimeslotTaskIF* gpioPst = factory.createFixedTimeslotTask( - "GPIO_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.2, missedDeadlineFunc); + "GPIO_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.2, missedDeadlineFunc); result = pst::pstGpio(gpioPst); if (result != HasReturnvaluesIF::RETURN_OK) { if (result == FixedTimeslotTaskIF::SLOT_LIST_EMPTY) { @@ -281,7 +364,7 @@ void initmission::createPstTasks(TaskFactory& factory, } #if OBSW_ADD_I2C_TEST_CODE == 0 FixedTimeslotTaskIF* i2cPst = factory.createFixedTimeslotTask( - "I2C_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.2, missedDeadlineFunc); + "I2C_PST", 65, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.2, missedDeadlineFunc); result = pst::pstI2c(i2cPst); if (result != HasReturnvaluesIF::RETURN_OK) { if (result == FixedTimeslotTaskIF::SLOT_LIST_EMPTY) { @@ -346,21 +429,30 @@ void initmission::createPusTasks(TaskFactory& factory, PeriodicTaskIF* pusMedPrio = factory.createPeriodicTask( "PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc); + + result = pusMedPrio->addComponent(objects::PUS_SERVICE_3_HOUSEKEEPING); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_3", objects::PUS_SERVICE_3_HOUSEKEEPING); + } result = pusMedPrio->addComponent(objects::PUS_SERVICE_8_FUNCTION_MGMT); if (result != HasReturnvaluesIF::RETURN_OK) { initmission::printAddObjectError("PUS_8", objects::PUS_SERVICE_8_FUNCTION_MGMT); } - result = pusMedPrio->addComponent(objects::PUS_SERVICE_3_HOUSEKEEPING); + result = pusMedPrio->addComponent(objects::PUS_SERVICE_11_TC_SCHEDULER); if (result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "Object add component failed" << std::endl; + initmission::printAddObjectError("PUS_11", objects::PUS_SERVICE_11_TC_SCHEDULER); + } + result = pusMedPrio->addComponent(objects::PUS_SERVICE_20_PARAMETERS); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_20", objects::PUS_SERVICE_20_PARAMETERS); } result = pusMedPrio->addComponent(objects::PUS_SERVICE_200_MODE_MGMT); if (result != HasReturnvaluesIF::RETURN_OK) { initmission::printAddObjectError("PUS_200", objects::PUS_SERVICE_200_MODE_MGMT); } - result = pusMedPrio->addComponent(objects::PUS_SERVICE_20_PARAMETERS); + result = pusMedPrio->addComponent(objects::PUS_SERVICE_201_HEALTH); if (result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS_20", objects::PUS_SERVICE_20_PARAMETERS); + initmission::printAddObjectError("PUS_201", objects::PUS_SERVICE_201_HEALTH); } taskVec.push_back(pusMedPrio); diff --git a/bsp_q7s/core/InitMission.h b/bsp_q7s/core/InitMission.h index 5c509b79..e0b1d8f2 100644 --- a/bsp_q7s/core/InitMission.h +++ b/bsp_q7s/core/InitMission.h @@ -3,7 +3,7 @@ #include -#include "fsfw/tasks/Typedef.h" +#include "fsfw/tasks/definitions.h" class PeriodicTaskIF; class TaskFactory; diff --git a/bsp_q7s/fm/fmObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp similarity index 82% rename from bsp_q7s/fm/fmObjectFactory.cpp rename to bsp_q7s/core/ObjectFactory.cpp index 226be660..7f50d6bf 100644 --- a/bsp_q7s/fm/fmObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -1,5 +1,4 @@ -#include -#include +#include "ObjectFactory.h" #include "OBSWConfig.h" #include "bsp_q7s/boardtest/Q7STestTask.h" @@ -7,8 +6,6 @@ #include "bsp_q7s/callbacks/pcduSwitchCb.h" #include "bsp_q7s/callbacks/q7sGpioCallbacks.h" #include "bsp_q7s/callbacks/rwSpiCallback.h" -#include "bsp_q7s/core/CoreController.h" -#include "bsp_q7s/core/ObjectFactory.h" #include "bsp_q7s/memory/FileSystemHandler.h" #include "busConf.h" #include "ccsdsConfig.h" @@ -31,7 +28,6 @@ #include "linux/devices/ploc/PlocMPSoCHelper.h" #include "linux/devices/ploc/PlocMemoryDumper.h" #include "linux/devices/ploc/PlocSupervisorHandler.h" -#include "linux/devices/ploc/PlocUpdater.h" #include "linux/devices/startracker/StarTrackerHandler.h" #include "linux/devices/startracker/StrHelper.h" #include "linux/obc/AxiPtmeConfig.h" @@ -39,11 +35,12 @@ #include "linux/obc/PdecHandler.h" #include "linux/obc/Ptme.h" #include "linux/obc/PtmeConfig.h" -#include "mission/system/SusAssembly.h" -#include "mission/system/TcsBoardAssembly.h" +#include "mission/system/RwAssembly.h" #include "mission/system/fdir/AcsBoardFdir.h" +#include "mission/system/fdir/GomspacePowerFdir.h" #include "mission/system/fdir/RtdFdir.h" #include "mission/system/fdir/SusFdir.h" +#include "mission/system/fdir/SyrlinksFdir.h" #include "tmtc/apid.h" #include "tmtc/pusIds.h" #if OBSW_TEST_LIBGPIOD == 1 @@ -82,24 +79,20 @@ #include "mission/devices/RadiationSensorHandler.h" #include "mission/devices/RwHandler.h" #include "mission/devices/SolarArrayDeploymentHandler.h" -#include "mission/devices/SusHandler.h" #include "mission/devices/SyrlinksHkHandler.h" #include "mission/devices/Tmp1075Handler.h" #include "mission/devices/devicedefinitions/GomspaceDefinitions.h" #include "mission/devices/devicedefinitions/Max31865Definitions.h" #include "mission/devices/devicedefinitions/RadSensorDefinitions.h" #include "mission/devices/devicedefinitions/RwDefinitions.h" -#include "mission/devices/devicedefinitions/SusDefinitions.h" #include "mission/devices/devicedefinitions/SyrlinksDefinitions.h" #include "mission/devices/devicedefinitions/payloadPcduDefinitions.h" #include "mission/system/AcsBoardAssembly.h" #include "mission/tmtc/CCSDSHandler.h" +#include "mission/tmtc/TmFunnel.h" #include "mission/tmtc/VirtualChannel.h" -#include "mission/utility/TmFunnel.h" -ResetArgs resetArgsGnss0; -ResetArgs resetArgsGnss1; -void ObjectFactory::setStatics() { Factory::setStaticFrameworkObjectIds(); } +ResetArgs RESET_ARGS_GNSS; void Factory::setStaticFrameworkObjectIds() { PusServiceBase::packetSource = objects::PUS_PACKET_DISTRIBUTOR; @@ -108,8 +101,12 @@ void Factory::setStaticFrameworkObjectIds() { CommandingServiceBase::defaultPacketSource = objects::PUS_PACKET_DISTRIBUTOR; CommandingServiceBase::defaultPacketDestination = objects::TM_FUNNEL; +#if OBSW_Q7S_EM == 1 + DeviceHandlerBase::powerSwitcherId = objects::NO_OBJECT; +#else DeviceHandlerBase::powerSwitcherId = objects::PCDU_HANDLER; - // DeviceHandlerBase::powerSwitcherId = objects::NO_OBJECT; +#endif /* OBSW_Q7S_EM == 1 */ + #if OBSW_TM_TO_PTME == 1 TmFunnel::downlinkDestination = objects::CCSDS_HANDLER; #else @@ -124,87 +121,7 @@ void Factory::setStaticFrameworkObjectIds() { TmPacketBase::timeStamperId = objects::TIME_STAMPER; } -void ObjectFactory::produce(void* args) { - ObjectFactory::setStatics(); - ObjectFactory::produceGenericObjects(); - - LinuxLibgpioIF* gpioComIF = nullptr; - UartComIF* uartComIF = nullptr; - SpiComIF* spiComIF = nullptr; - I2cComIF* i2cComIF = nullptr; - PowerSwitchIF* pwrSwitcher = nullptr; - createCommunicationInterfaces(&gpioComIF, &uartComIF, &spiComIF, &i2cComIF); - createTmpComponents(); - new CoreController(objects::CORE_CONTROLLER); - - gpioCallbacks::disableAllDecoder(gpioComIF); - createPcduComponents(gpioComIF, &pwrSwitcher); - createRadSensorComponent(gpioComIF); - createSunSensorComponents(gpioComIF, spiComIF, pwrSwitcher, q7s::SPI_DEFAULT_DEV); - -#if OBSW_ADD_ACS_BOARD == 1 - createAcsBoardComponents(gpioComIF, uartComIF, pwrSwitcher); -#endif - createHeaterComponents(); - createSolarArrayDeploymentComponents(); - createPlPcduComponents(gpioComIF, spiComIF, pwrSwitcher); -#if OBSW_ADD_SYRLINKS == 1 - createSyrlinksComponents(pwrSwitcher); -#endif /* OBSW_ADD_SYRLINKS == 1 */ - createRtdComponents(q7s::SPI_DEFAULT_DEV, gpioComIF, pwrSwitcher); - createPayloadComponents(gpioComIF); - -#if OBSW_ADD_MGT == 1 - I2cCookie* imtqI2cCookie = - new I2cCookie(addresses::IMTQ, IMTQ::MAX_REPLY_SIZE, q7s::I2C_DEFAULT_DEV); - auto imtqHandler = new IMTQHandler(objects::IMTQ_HANDLER, objects::I2C_COM_IF, imtqI2cCookie, - pcdu::Switches::PDU1_CH3_MGT_5V); - imtqHandler->setPowerSwitcher(pwrSwitcher); - static_cast(imtqHandler); -#if OBSW_TEST_IMTQ == 1 - imtqHandler->setStartUpImmediately(); - imtqHandler->setToGoToNormal(true); -#endif -#if OBSW_DEBUG_IMTQ == 1 - imtqHandler->setDebugMode(true); -#endif -#endif - createReactionWheelComponents(gpioComIF); - -#if OBSW_ADD_BPX_BATTERY_HANDLER == 1 - I2cCookie* bpxI2cCookie = new I2cCookie(addresses::BPX_BATTERY, 100, q7s::I2C_DEFAULT_DEV); - BpxBatteryHandler* bpxHandler = - new BpxBatteryHandler(objects::BPX_BATT_HANDLER, objects::I2C_COM_IF, bpxI2cCookie); - bpxHandler->setStartUpImmediately(); - bpxHandler->setToGoToNormalMode(true); -#if OBSW_DEBUG_BPX_BATT == 1 - bpxHandler->setDebugMode(true); -#endif -#endif - new FileSystemHandler(objects::FILE_SYSTEM_HANDLER); - -#if OBSW_ADD_STAR_TRACKER == 1 - UartCookie* starTrackerCookie = - new UartCookie(objects::STAR_TRACKER, q7s::UART_STAR_TRACKER_DEV, uart::STAR_TRACKER_BAUD, - startracker::MAX_FRAME_SIZE * 2 + 2, UartModes::NON_CANONICAL); - starTrackerCookie->setNoFixedSizeReply(); - StrHelper* strHelper = new StrHelper(objects::STR_HELPER); - auto starTracker = - new StarTrackerHandler(objects::STAR_TRACKER, objects::UART_COM_IF, starTrackerCookie, - strHelper, pcdu::PDU1_CH2_STAR_TRACKER_5V); - starTracker->setPowerSwitcher(pwrSwitcher); - -#endif /* OBSW_ADD_STAR_TRACKER == 1 */ -#if OBSW_USE_CCSDS_IP_CORE == 1 - createCcsdsComponents(gpioComIF); -#endif /* OBSW_USE_CCSDS_IP_CORE == 1 */ - /* Test Task */ -#if OBSW_ADD_TEST_CODE == 1 - createTestComponents(gpioComIF); -#endif /* OBSW_ADD_TEST_CODE == 1 */ - new PlocUpdater(objects::PLOC_UPDATER); - new PlocMemoryDumper(objects::PLOC_MEMORY_DUMPER); -} +void ObjectFactory::setStatics() { Factory::setStaticFrameworkObjectIds(); } void ObjectFactory::createTmpComponents() { I2cCookie* i2cCookieTmp1075tcs1 = @@ -222,8 +139,10 @@ void ObjectFactory::createTmpComponents() { } void ObjectFactory::createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF, UartComIF** uartComIF, - SpiComIF** spiComIF, I2cComIF** i2cComIF) { - if (gpioComIF == nullptr or uartComIF == nullptr or spiComIF == nullptr) { + SpiComIF** spiMainComIF, I2cComIF** i2cComIF, + SpiComIF** spiRWComIF) { + if (gpioComIF == nullptr or uartComIF == nullptr or spiMainComIF == nullptr or + spiRWComIF == nullptr) { sif::error << "ObjectFactory::createCommunicationInterfaces: Invalid passed ComIF pointer" << std::endl; } @@ -233,8 +152,8 @@ void ObjectFactory::createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF, Ua new CspComIF(objects::CSP_COM_IF); *i2cComIF = new I2cComIF(objects::I2C_COM_IF); *uartComIF = new UartComIF(objects::UART_COM_IF); - *spiComIF = new SpiComIF(objects::SPI_COM_IF, *gpioComIF); - + *spiMainComIF = new SpiComIF(objects::SPI_MAIN_COM_IF, q7s::SPI_DEFAULT_DEV, *gpioComIF); + *spiRWComIF = new SpiComIF(objects::SPI_RW_COM_IF, q7s::SPI_RW_DEV, *gpioComIF); /* Adding gpios for chip select decoding to the gpioComIf */ q7s::gpioCallbacks::initSpiCsDecoder(*gpioComIF); } @@ -292,12 +211,13 @@ void ObjectFactory::createRadSensorComponent(LinuxLibgpioIF* gpioComIF) { gpio = new GpiodRegularByLineName(q7s::gpioNames::ENABLE_RADFET, consumer.str(), Direction::OUT, Levels::LOW); gpioCookieRadSensor->addGpio(gpioIds::ENABLE_RADFET, gpio); - gpioComIF->addGpios(gpioCookieRadSensor); + gpioChecker(gpioComIF->addGpios(gpioCookieRadSensor), "RAD sensor"); - SpiCookie* spiCookieRadSensor = new SpiCookie( - addresses::RAD_SENSOR, gpioIds::CS_RAD_SENSOR, std::string(q7s::SPI_DEFAULT_DEV), - RAD_SENSOR::READ_SIZE, spi::DEFAULT_MAX_1227_MODE, spi::DEFAULT_MAX_1227_SPEED); - auto radSensor = new RadiationSensorHandler(objects::RAD_SENSOR, objects::SPI_COM_IF, + SpiCookie* spiCookieRadSensor = + new SpiCookie(addresses::RAD_SENSOR, gpioIds::CS_RAD_SENSOR, RAD_SENSOR::READ_SIZE, + spi::DEFAULT_MAX_1227_MODE, spi::DEFAULT_MAX_1227_SPEED); + spiCookieRadSensor->setMutexParams(MutexIF::TimeoutType::WAITING, spi::RAD_SENSOR_CS_TIMEOUT); + auto radSensor = new RadiationSensorHandler(objects::RAD_SENSOR, objects::SPI_MAIN_COM_IF, spiCookieRadSensor, gpioComIF); static_cast(radSensor); // The radiation sensor ADC is powered by the 5V stack connector which should always be on @@ -408,16 +328,16 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComI gpio = new GpiodRegularByLineName(q7s::gpioNames::GNSS_SELECT, consumer.str(), Direction::OUT, Levels::LOW); gpioCookieAcsBoard->addGpio(gpioIds::GNSS_SELECT, gpio); - gpioComIF->addGpios(gpioCookieAcsBoard); + gpioChecker(gpioComIF->addGpios(gpioCookieAcsBoard), "ACS Board"); AcsBoardFdir* fdir = nullptr; static_cast(fdir); #if OBSW_ADD_ACS_HANDLERS == 1 std::string spiDev = q7s::SPI_DEFAULT_DEV; SpiCookie* spiCookie = - new SpiCookie(addresses::MGM_0_LIS3, gpioIds::MGM_0_LIS3_CS, spiDev, - MGMLIS3MDL::MAX_BUFFER_SIZE, spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED); - auto mgmLis3Handler = new MgmLIS3MDLHandler(objects::MGM_0_LIS3_HANDLER, objects::SPI_COM_IF, + new SpiCookie(addresses::MGM_0_LIS3, gpioIds::MGM_0_LIS3_CS, MGMLIS3MDL::MAX_BUFFER_SIZE, + spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED); + auto mgmLis3Handler = new MgmLIS3MDLHandler(objects::MGM_0_LIS3_HANDLER, objects::SPI_MAIN_COM_IF, spiCookie, spi::LIS3_TRANSITION_DELAY); fdir = new AcsBoardFdir(objects::MGM_0_LIS3_HANDLER); mgmLis3Handler->setCustomFdir(fdir); @@ -430,10 +350,11 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComI mgmLis3Handler->enablePeriodicPrintouts(true, 10); #endif spiCookie = - new SpiCookie(addresses::MGM_1_RM3100, gpioIds::MGM_1_RM3100_CS, spiDev, - RM3100::MAX_BUFFER_SIZE, spi::DEFAULT_RM3100_MODE, spi::DEFAULT_RM3100_SPEED); - auto mgmRm3100Handler = new MgmRM3100Handler(objects::MGM_1_RM3100_HANDLER, objects::SPI_COM_IF, - spiCookie, spi::RM3100_TRANSITION_DELAY); + new SpiCookie(addresses::MGM_1_RM3100, gpioIds::MGM_1_RM3100_CS, RM3100::MAX_BUFFER_SIZE, + spi::DEFAULT_RM3100_MODE, spi::DEFAULT_RM3100_SPEED); + auto mgmRm3100Handler = + new MgmRM3100Handler(objects::MGM_1_RM3100_HANDLER, objects::SPI_MAIN_COM_IF, spiCookie, + spi::RM3100_TRANSITION_DELAY); fdir = new AcsBoardFdir(objects::MGM_1_RM3100_HANDLER); mgmRm3100Handler->setCustomFdir(fdir); mgmRm3100Handler->setParent(objects::ACS_BOARD_ASS); @@ -446,9 +367,9 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComI mgmRm3100Handler->enablePeriodicPrintouts(true, 10); #endif spiCookie = - new SpiCookie(addresses::MGM_2_LIS3, gpioIds::MGM_2_LIS3_CS, spiDev, - MGMLIS3MDL::MAX_BUFFER_SIZE, spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED); - mgmLis3Handler = new MgmLIS3MDLHandler(objects::MGM_2_LIS3_HANDLER, objects::SPI_COM_IF, + new SpiCookie(addresses::MGM_2_LIS3, gpioIds::MGM_2_LIS3_CS, MGMLIS3MDL::MAX_BUFFER_SIZE, + spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED); + mgmLis3Handler = new MgmLIS3MDLHandler(objects::MGM_2_LIS3_HANDLER, objects::SPI_MAIN_COM_IF, spiCookie, spi::LIS3_TRANSITION_DELAY); fdir = new AcsBoardFdir(objects::MGM_2_LIS3_HANDLER); mgmLis3Handler->setCustomFdir(fdir); @@ -462,9 +383,9 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComI mgmLis3Handler->enablePeriodicPrintouts(true, 10); #endif spiCookie = - new SpiCookie(addresses::MGM_3_RM3100, gpioIds::MGM_3_RM3100_CS, spiDev, - RM3100::MAX_BUFFER_SIZE, spi::DEFAULT_RM3100_MODE, spi::DEFAULT_RM3100_SPEED); - mgmRm3100Handler = new MgmRM3100Handler(objects::MGM_3_RM3100_HANDLER, objects::SPI_COM_IF, + new SpiCookie(addresses::MGM_3_RM3100, gpioIds::MGM_3_RM3100_CS, RM3100::MAX_BUFFER_SIZE, + spi::DEFAULT_RM3100_MODE, spi::DEFAULT_RM3100_SPEED); + mgmRm3100Handler = new MgmRM3100Handler(objects::MGM_3_RM3100_HANDLER, objects::SPI_MAIN_COM_IF, spiCookie, spi::RM3100_TRANSITION_DELAY); fdir = new AcsBoardFdir(objects::MGM_3_RM3100_HANDLER); mgmRm3100Handler->setCustomFdir(fdir); @@ -478,11 +399,12 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComI #endif // Commented until ACS board V2 in in clean room again // Gyro 0 Side A - spiCookie = new SpiCookie(addresses::GYRO_0_ADIS, gpioIds::GYRO_0_ADIS_CS, spiDev, - ADIS1650X::MAXIMUM_REPLY_SIZE, spi::DEFAULT_ADIS16507_MODE, - spi::DEFAULT_ADIS16507_SPEED); - auto adisHandler = new GyroADIS1650XHandler(objects::GYRO_0_ADIS_HANDLER, objects::SPI_COM_IF, - spiCookie, ADIS1650X::Type::ADIS16505); + spiCookie = + new SpiCookie(addresses::GYRO_0_ADIS, gpioIds::GYRO_0_ADIS_CS, ADIS1650X::MAXIMUM_REPLY_SIZE, + spi::DEFAULT_ADIS16507_MODE, spi::DEFAULT_ADIS16507_SPEED); + auto adisHandler = + new GyroADIS1650XHandler(objects::GYRO_0_ADIS_HANDLER, objects::SPI_MAIN_COM_IF, spiCookie, + ADIS1650X::Type::ADIS16505); fdir = new AcsBoardFdir(objects::GYRO_0_ADIS_HANDLER); adisHandler->setCustomFdir(fdir); adisHandler->setParent(objects::ACS_BOARD_ASS); @@ -495,11 +417,10 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComI adisHandler->enablePeriodicPrintouts(true, 10); #endif // Gyro 1 Side A - spiCookie = - new SpiCookie(addresses::GYRO_1_L3G, gpioIds::GYRO_1_L3G_CS, spiDev, L3GD20H::MAX_BUFFER_SIZE, - spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED); - auto gyroL3gHandler = new GyroHandlerL3GD20H(objects::GYRO_1_L3G_HANDLER, objects::SPI_COM_IF, - spiCookie, spi::L3G_TRANSITION_DELAY); + spiCookie = new SpiCookie(addresses::GYRO_1_L3G, gpioIds::GYRO_1_L3G_CS, L3GD20H::MAX_BUFFER_SIZE, + spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED); + auto gyroL3gHandler = new GyroHandlerL3GD20H( + objects::GYRO_1_L3G_HANDLER, objects::SPI_MAIN_COM_IF, spiCookie, spi::L3G_TRANSITION_DELAY); fdir = new AcsBoardFdir(objects::GYRO_1_L3G_HANDLER); gyroL3gHandler->setCustomFdir(fdir); gyroL3gHandler->setParent(objects::ACS_BOARD_ASS); @@ -512,10 +433,10 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComI gyroL3gHandler->enablePeriodicPrintouts(true, 10); #endif // Gyro 2 Side B - spiCookie = new SpiCookie(addresses::GYRO_2_ADIS, gpioIds::GYRO_2_ADIS_CS, spiDev, - ADIS1650X::MAXIMUM_REPLY_SIZE, spi::DEFAULT_ADIS16507_MODE, - spi::DEFAULT_ADIS16507_SPEED); - adisHandler = new GyroADIS1650XHandler(objects::GYRO_2_ADIS_HANDLER, objects::SPI_COM_IF, + spiCookie = + new SpiCookie(addresses::GYRO_2_ADIS, gpioIds::GYRO_2_ADIS_CS, ADIS1650X::MAXIMUM_REPLY_SIZE, + spi::DEFAULT_ADIS16507_MODE, spi::DEFAULT_ADIS16507_SPEED); + adisHandler = new GyroADIS1650XHandler(objects::GYRO_2_ADIS_HANDLER, objects::SPI_MAIN_COM_IF, spiCookie, ADIS1650X::Type::ADIS16505); fdir = new AcsBoardFdir(objects::GYRO_2_ADIS_HANDLER); adisHandler->setCustomFdir(fdir); @@ -525,10 +446,9 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComI adisHandler->setToGoToNormalModeImmediately(); #endif // Gyro 3 Side B - spiCookie = - new SpiCookie(addresses::GYRO_3_L3G, gpioIds::GYRO_3_L3G_CS, spiDev, L3GD20H::MAX_BUFFER_SIZE, - spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED); - gyroL3gHandler = new GyroHandlerL3GD20H(objects::GYRO_3_L3G_HANDLER, objects::SPI_COM_IF, + spiCookie = new SpiCookie(addresses::GYRO_3_L3G, gpioIds::GYRO_3_L3G_CS, L3GD20H::MAX_BUFFER_SIZE, + spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED); + gyroL3gHandler = new GyroHandlerL3GD20H(objects::GYRO_3_L3G_HANDLER, objects::SPI_MAIN_COM_IF, spiCookie, spi::L3G_TRANSITION_DELAY); fdir = new AcsBoardFdir(objects::GYRO_3_L3G_HANDLER); gyroL3gHandler->setCustomFdir(fdir); @@ -544,15 +464,11 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComI #if OBSW_DEBUG_GPS == 1 debugGps = true; #endif - resetArgsGnss1.gnss1 = true; - resetArgsGnss1.gpioComIF = gpioComIF; - resetArgsGnss1.waitPeriodMs = 100; - resetArgsGnss0.gnss1 = false; - resetArgsGnss0.gpioComIF = gpioComIF; - resetArgsGnss0.waitPeriodMs = 100; - auto gpsHandler0 = + RESET_ARGS_GNSS.gpioComIF = gpioComIF; + RESET_ARGS_GNSS.waitPeriodMs = 100; + auto gpsCtrl = new GPSHyperionLinuxController(objects::GPS_CONTROLLER, objects::NO_OBJECT, debugGps); - gpsHandler0->setResetPinTriggerFunction(gps::triggerGpioResetPin, &resetArgsGnss0); + gpsCtrl->setResetPinTriggerFunction(gps::triggerGpioResetPin, &RESET_ARGS_GNSS); AcsBoardHelper acsBoardHelper = AcsBoardHelper( objects::MGM_0_LIS3_HANDLER, objects::MGM_1_RM3100_HANDLER, objects::MGM_2_LIS3_HANDLER, @@ -562,9 +478,14 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComI acsBoardHelper, gpioComIF); static_cast(acsAss); #endif /* OBSW_ADD_ACS_HANDLERS == 1 */ + +#if OBSW_USE_CCSDS_IP_CORE == 1 + createCcsdsComponents(gpioComIF); +#endif /* OBSW_USE_CCSDS_IP_CORE == 1 */ } -void ObjectFactory::createHeaterComponents() { +void ObjectFactory::createHeaterComponents(GpioIF* gpioIF, PowerSwitchIF* pwrSwitcher, + HealthTableIF* healthTable) { using namespace gpio; GpioCookie* heaterGpiosCookie = new GpioCookie; GpiodRegularByLineName* gpio = nullptr; @@ -605,8 +526,21 @@ void ObjectFactory::createHeaterComponents() { Levels::LOW); heaterGpiosCookie->addGpio(gpioIds::HEATER_7, gpio); - new HeaterHandler(objects::HEATER_HANDLER, objects::GPIO_IF, heaterGpiosCookie, - objects::PCDU_HANDLER, pcdu::Switches::PDU2_CH3_TCS_BOARD_HEATER_IN_8V); + gpioIF->addGpios(heaterGpiosCookie); + + HeaterHelper helper({{ + {new HealthDevice(objects::HEATER_0_PLOC_PROC_BRD, MessageQueueIF::NO_QUEUE), + gpioIds::HEATER_0}, + {new HealthDevice(objects::HEATER_1_PCDU_BRD, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_1}, + {new HealthDevice(objects::HEATER_2_ACS_BRD, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_2}, + {new HealthDevice(objects::HEATER_3_OBC_BRD, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_3}, + {new HealthDevice(objects::HEATER_4_CAMERA, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_4}, + {new HealthDevice(objects::HEATER_5_STR, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_5}, + {new HealthDevice(objects::HEATER_6_DRO, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_6}, + {new HealthDevice(objects::HEATER_7_HPA, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_7}, + }}); + new HeaterHandler(objects::HEATER_HANDLER, gpioIF, helper, pwrSwitcher, + pcdu::Switches::PDU2_CH3_TCS_BOARD_HEATER_IN_8V); } void ObjectFactory::createSolarArrayDeploymentComponents() { @@ -655,7 +589,7 @@ void ObjectFactory::createPayloadComponents(LinuxLibgpioIF* gpioComIF) { consumer.str(), Direction::OUT, Levels::HIGH); auto mpsocGpioCookie = new GpioCookie; mpsocGpioCookie->addGpio(gpioIds::ENABLE_MPSOC_UART, gpioConfigMPSoC); - gpioComIF->addGpios(mpsocGpioCookie); + gpioChecker(gpioComIF->addGpios(mpsocGpioCookie), "PLOC MPSoC"); auto mpsocCookie = new UartCookie(objects::PLOC_MPSOC_HANDLER, q7s::UART_PLOC_MPSOC_DEV, uart::PLOC_MPSOC_BAUD, mpsoc::MAX_REPLY_SIZE, UartModes::NON_CANONICAL); @@ -668,22 +602,24 @@ void ObjectFactory::createPayloadComponents(LinuxLibgpioIF* gpioComIF) { #if OBSW_ADD_PLOC_SUPERVISOR == 1 consumer << "0x" << std::hex << objects::PLOC_SUPERVISOR_HANDLER; auto gpioConfigSupv = new GpiodRegularByLineName(q7s::gpioNames::ENABLE_SUPV_UART, consumer.str(), - Direction::OUT, Levels::HIGH); + Direction::OUT, Levels::LOW); auto supvGpioCookie = new GpioCookie; supvGpioCookie->addGpio(gpioIds::ENABLE_SUPV_UART, gpioConfigSupv); gpioComIF->addGpios(supvGpioCookie); - auto supervisorCookie = new UartCookie(objects::PLOC_SUPERVISOR_HANDLER, - q7s::UART_PLOC_SUPERVSIOR_DEV, uart::PLOC_SUPERVISOR_BAUD, - supv::MAX_PACKET_SIZE * 20, UartModes::NON_CANONICAL); + auto supervisorCookie = + new UartCookie(objects::PLOC_SUPERVISOR_HANDLER, q7s::UART_PLOC_SUPERVSIOR_DEV, + uart::PLOC_SUPV_BAUD, supv::MAX_PACKET_SIZE * 20, UartModes::NON_CANONICAL); supervisorCookie->setNoFixedSizeReply(); + auto supvHelper = new PlocSupvHelper(objects::PLOC_SUPERVISOR_HELPER); new PlocSupervisorHandler(objects::PLOC_SUPERVISOR_HANDLER, objects::UART_COM_IF, supervisorCookie, Gpio(gpioIds::ENABLE_SUPV_UART, gpioComIF), - pcdu::PDU1_CH6_PLOC_12V); + pcdu::PDU1_CH6_PLOC_12V, supvHelper); #endif /* OBSW_ADD_PLOC_SUPERVISOR == 1 */ static_cast(consumer); } -void ObjectFactory::createReactionWheelComponents(LinuxLibgpioIF* gpioComIF) { +void ObjectFactory::createReactionWheelComponents(LinuxLibgpioIF* gpioComIF, + PowerSwitchIF* pwrSwitcher) { using namespace gpio; GpioCookie* gpioCookieRw = new GpioCookie; GpioCallback* csRw1 = @@ -725,50 +661,38 @@ void ObjectFactory::createReactionWheelComponents(LinuxLibgpioIF* gpioComIF) { Levels::LOW); gpioCookieRw->addGpio(gpioIds::EN_RW4, gpio); - gpioComIF->addGpios(gpioCookieRw); + gpioChecker(gpioComIF->addGpios(gpioCookieRw), "RWs"); #if OBSW_ADD_RW == 1 - auto rw1SpiCookie = - new SpiCookie(addresses::RW1, gpioIds::CS_RW1, q7s::SPI_RW_DEV, RwDefinitions::MAX_REPLY_SIZE, - spi::RW_MODE, spi::RW_SPEED, &rwSpiCallback::spiCallback, nullptr); - auto rw2SpiCookie = - new SpiCookie(addresses::RW2, gpioIds::CS_RW2, q7s::SPI_RW_DEV, RwDefinitions::MAX_REPLY_SIZE, - spi::RW_MODE, spi::RW_SPEED, &rwSpiCallback::spiCallback, nullptr); - auto rw3SpiCookie = - new SpiCookie(addresses::RW3, gpioIds::CS_RW3, q7s::SPI_RW_DEV, RwDefinitions::MAX_REPLY_SIZE, - spi::RW_MODE, spi::RW_SPEED, &rwSpiCallback::spiCallback, nullptr); - auto rw4SpiCookie = - new SpiCookie(addresses::RW4, gpioIds::CS_RW4, q7s::SPI_RW_DEV, RwDefinitions::MAX_REPLY_SIZE, - spi::RW_MODE, spi::RW_SPEED, &rwSpiCallback::spiCallback, nullptr); + std::array, 4> rwCookieParams = { + {{addresses::RW1, gpioIds::CS_RW1}, + {addresses::RW2, gpioIds::CS_RW2}, + {addresses::RW3, gpioIds::CS_RW3}, + {addresses::RW4, gpioIds::CS_RW4}}}; + std::array rwCookies = {}; + std::array rwIds = {objects::RW1, objects::RW2, objects::RW3, objects::RW4}; + std::array rwGpioIds = {gpioIds::EN_RW1, gpioIds::EN_RW2, gpioIds::EN_RW3, + gpioIds::EN_RW4}; + std::array rws = {}; + for (uint8_t idx = 0; idx < rwCookies.size(); idx++) { + rwCookies[idx] = new SpiCookie(rwCookieParams[idx].first, rwCookieParams[idx].second, + RwDefinitions::MAX_REPLY_SIZE, spi::RW_MODE, spi::RW_SPEED, + &rwSpiCallback::spiCallback, nullptr); + rws[idx] = new RwHandler(rwIds[idx], objects::SPI_RW_COM_IF, rwCookies[idx], gpioComIF, + rwGpioIds[idx]); + rwCookies[idx]->setCallbackArgs(rws[idx]); +#if OBSW_TEST_RW == 1 + rws[idx]->setStartUpImmediately(); +#endif +#if OBSW_DEBUG_RW == 1 + rws[idx]->setDebugMode(true); +#endif + } - auto rwHandler1 = - new RwHandler(objects::RW1, objects::SPI_COM_IF, rw1SpiCookie, gpioComIF, gpioIds::EN_RW1); - rw1SpiCookie->setCallbackArgs(rwHandler1); -#if OBSW_DEBUG_RW == 1 - rwHandler1->setStartUpImmediately(); - rwHandler1->setDebugMode(true); -#endif - auto rwHandler2 = - new RwHandler(objects::RW2, objects::SPI_COM_IF, rw2SpiCookie, gpioComIF, gpioIds::EN_RW2); - rw2SpiCookie->setCallbackArgs(rwHandler2); -#if OBSW_DEBUG_RW == 1 - rwHandler2->setStartUpImmediately(); - rwHandler2->setDebugMode(true); -#endif - auto rwHandler3 = - new RwHandler(objects::RW3, objects::SPI_COM_IF, rw3SpiCookie, gpioComIF, gpioIds::EN_RW3); - rw3SpiCookie->setCallbackArgs(rwHandler3); -#if OBSW_DEBUG_RW == 1 - rwHandler3->setStartUpImmediately(); - rwHandler3->setDebugMode(true); -#endif - auto rwHandler4 = - new RwHandler(objects::RW4, objects::SPI_COM_IF, rw4SpiCookie, gpioComIF, gpioIds::EN_RW4); - rw4SpiCookie->setCallbackArgs(rwHandler4); -#if OBSW_DEBUG_RW == 1 - rwHandler4->setStartUpImmediately(); - rwHandler4->setDebugMode(true); -#endif + RwHelper rwHelper(rwIds); + auto* rwAss = new RwAssembly(objects::RW_ASS, objects::NO_OBJECT, pwrSwitcher, + pcdu::Switches::PDU2_CH2_RW_5V, rwHelper); + static_cast(rwAss); #endif /* OBSW_ADD_RW == 1 */ } @@ -806,9 +730,7 @@ void ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF) { consumer.str("PAPB VC 3"); gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_EMPTY_SIGNAL_VC3, consumer.str()); gpioCookiePtmeIp->addGpio(gpioIds::VC3_PAPB_EMPTY, gpio); - - gpioComIF->addGpios(gpioCookiePtmeIp); - + gpioChecker(gpioComIF->addGpios(gpioCookiePtmeIp), "PTME PAPB VCs"); // Creating virtual channel interfaces VcInterfaceIF* vc0 = new PapbVcInterface(gpioComIF, gpioIds::VC0_PAPB_BUSY, gpioIds::VC0_PAPB_EMPTY, q7s::UIO_PTME, @@ -822,14 +744,12 @@ void ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF) { VcInterfaceIF* vc3 = new PapbVcInterface(gpioComIF, gpioIds::VC3_PAPB_BUSY, gpioIds::VC3_PAPB_EMPTY, q7s::UIO_PTME, q7s::uiomapids::PTME_VC3); - // Creating ptme object and adding virtual channel interfaces Ptme* ptme = new Ptme(objects::PTME); ptme->addVcInterface(ccsds::VC0, vc0); ptme->addVcInterface(ccsds::VC1, vc1); ptme->addVcInterface(ccsds::VC2, vc2); ptme->addVcInterface(ccsds::VC3, vc3); - AxiPtmeConfig* axiPtmeConfig = new AxiPtmeConfig(objects::AXI_PTME_CONFIG, q7s::UIO_PTME, q7s::uiomapids::PTME_CONFIG); PtmeConfig* ptmeConfig = new PtmeConfig(objects::PTME_CONFIG, axiPtmeConfig); @@ -842,7 +762,6 @@ void ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF) { CCSDSHandler* ccsdsHandler = new CCSDSHandler( objects::CCSDS_HANDLER, objects::PTME, objects::CCSDS_PACKET_DISTRIBUTOR, ptmeConfig, gpioComIF, gpioIds::RS485_EN_TX_CLOCK, gpioIds::RS485_EN_TX_DATA, TRANSMITTER_TIMEOUT); - VirtualChannel* vc = nullptr; vc = new VirtualChannel(ccsds::VC0, common::VC0_QUEUE_SIZE, objects::CCSDS_HANDLER); ccsdsHandler->addVirtualChannel(ccsds::VC0, vc); @@ -852,7 +771,6 @@ void ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF) { ccsdsHandler->addVirtualChannel(ccsds::VC2, vc); vc = new VirtualChannel(ccsds::VC3, common::VC3_QUEUE_SIZE, objects::CCSDS_HANDLER); ccsdsHandler->addVirtualChannel(ccsds::VC3, vc); - GpioCookie* gpioCookiePdec = new GpioCookie; consumer.str(""); consumer << "0x" << std::hex << objects::PDEC_HANDLER; @@ -860,12 +778,9 @@ void ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF) { gpio = new GpiodRegularByLineName(q7s::gpioNames::PDEC_RESET, consumer.str(), Direction::OUT, Levels::LOW); gpioCookiePdec->addGpio(gpioIds::PDEC_RESET, gpio); - - gpioComIF->addGpios(gpioCookiePdec); - + gpioChecker(gpioComIF->addGpios(gpioCookiePdec), "PDEC"); new PdecHandler(objects::PDEC_HANDLER, objects::CCSDS_HANDLER, gpioComIF, gpioIds::PDEC_RESET, q7s::UIO_PDEC_CONFIG_MEMORY, q7s::UIO_PDEC_RAM, q7s::UIO_PDEC_REGISTERS); - GpioCookie* gpioRS485Chip = new GpioCookie; gpio = new GpiodRegularByLineName(q7s::gpioNames::RS485_EN_TX_CLOCK, "RS485 Transceiver", Direction::OUT, Levels::LOW); @@ -873,7 +788,6 @@ void ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF) { gpio = new GpiodRegularByLineName(q7s::gpioNames::RS485_EN_TX_DATA, "RS485 Transceiver", Direction::OUT, Levels::LOW); gpioRS485Chip->addGpio(gpioIds::RS485_EN_TX_DATA, gpio); - // Default configuration enables RX channels (RXEN = LOW) gpio = new GpiodRegularByLineName(q7s::gpioNames::RS485_EN_RX_CLOCK, "RS485 Transceiver", Direction::OUT, Levels::LOW); @@ -881,8 +795,7 @@ void ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF) { gpio = new GpiodRegularByLineName(q7s::gpioNames::RS485_EN_RX_DATA, "RS485 Transceiver", Direction::OUT, Levels::LOW); gpioRS485Chip->addGpio(gpioIds::RS485_EN_RX_DATA, gpio); - - gpioComIF->addGpios(gpioRS485Chip); + gpioChecker(gpioComIF->addGpios(gpioRS485Chip), "RS485 Transceiver"); } void ObjectFactory::createPlPcduComponents(LinuxLibgpioIF* gpioComIF, SpiComIF* spiComIF, @@ -927,14 +840,14 @@ void ObjectFactory::createPlPcduComponents(LinuxLibgpioIF* gpioComIF, SpiComIF* gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ADC_CS, consumer, Direction::OUT, gpio::Levels::HIGH); plPcduGpios->addGpio(gpioIds::PLPCDU_ADC_CS, gpio); - gpioComIF->addGpios(plPcduGpios); - SpiCookie* spiCookie = new SpiCookie(addresses::PLPCDU_ADC, gpioIds::PLPCDU_ADC_CS, - q7s::SPI_DEFAULT_DEV, plpcdu::MAX_ADC_REPLY_SIZE, - spi::DEFAULT_MAX_1227_MODE, spi::PL_PCDU_MAX_1227_SPEED); + gpioChecker(gpioComIF->addGpios(plPcduGpios), "PL PCDU"); + SpiCookie* spiCookie = + new SpiCookie(addresses::PLPCDU_ADC, gpioIds::PLPCDU_ADC_CS, plpcdu::MAX_ADC_REPLY_SIZE, + spi::DEFAULT_MAX_1227_MODE, spi::PL_PCDU_MAX_1227_SPEED); // Create device handler components auto plPcduHandler = new PayloadPcduHandler( - objects::PLPCDU_HANDLER, objects::SPI_COM_IF, spiCookie, gpioComIF, SdCardManager::instance(), - pwrSwitcher, pcdu::Switches::PDU2_CH1_PL_PCDU_BATT_0_14V8, + objects::PLPCDU_HANDLER, objects::SPI_MAIN_COM_IF, spiCookie, gpioComIF, + SdCardManager::instance(), pwrSwitcher, pcdu::Switches::PDU2_CH1_PL_PCDU_BATT_0_14V8, pcdu::Switches::PDU2_CH6_PL_PCDU_BATT_1_14V8, false); spiCookie->setCallbackMode(PayloadPcduHandler::extConvAsTwoCallback, plPcduHandler); // plPcduHandler->enablePeriodicPrintout(true, 5); @@ -961,6 +874,50 @@ void ObjectFactory::createTestComponents(LinuxLibgpioIF* gpioComIF) { #endif } +void ObjectFactory::createStrComponents(PowerSwitchIF* pwrSwitcher) { + UartCookie* starTrackerCookie = + new UartCookie(objects::STAR_TRACKER, q7s::UART_STAR_TRACKER_DEV, uart::STAR_TRACKER_BAUD, + startracker::MAX_FRAME_SIZE * 2 + 2, UartModes::NON_CANONICAL); + starTrackerCookie->setNoFixedSizeReply(); + StrHelper* strHelper = new StrHelper(objects::STR_HELPER); + auto starTracker = + new StarTrackerHandler(objects::STAR_TRACKER, objects::UART_COM_IF, starTrackerCookie, + strHelper, pcdu::PDU1_CH2_STAR_TRACKER_5V); + starTracker->setPowerSwitcher(pwrSwitcher); +} + +void ObjectFactory::createImtqComponents(PowerSwitchIF* pwrSwitcher) { + I2cCookie* imtqI2cCookie = + new I2cCookie(addresses::IMTQ, IMTQ::MAX_REPLY_SIZE, q7s::I2C_DEFAULT_DEV); + auto imtqHandler = new IMTQHandler(objects::IMTQ_HANDLER, objects::I2C_COM_IF, imtqI2cCookie, + pcdu::Switches::PDU1_CH3_MGT_5V); + imtqHandler->setPowerSwitcher(pwrSwitcher); + static_cast(imtqHandler); +#if OBSW_TEST_IMTQ == 1 + imtqHandler->setStartUpImmediately(); + imtqHandler->setToGoToNormal(true); +#endif +#if OBSW_DEBUG_IMTQ == 1 + imtqHandler->setDebugMode(true); +#endif +} + +void ObjectFactory::createBpxBatteryComponent() { + I2cCookie* bpxI2cCookie = new I2cCookie(addresses::BPX_BATTERY, 100, q7s::I2C_DEFAULT_DEV); + BpxBatteryHandler* bpxHandler = + new BpxBatteryHandler(objects::BPX_BATT_HANDLER, objects::I2C_COM_IF, bpxI2cCookie); + bpxHandler->setStartUpImmediately(); + bpxHandler->setToGoToNormalMode(true); +#if OBSW_DEBUG_BPX_BATT == 1 + bpxHandler->setDebugMode(true); +#endif +} + +void ObjectFactory::createMiscComponents() { + new FileSystemHandler(objects::FILE_SYSTEM_HANDLER); + new PlocMemoryDumper(objects::PLOC_MEMORY_DUMPER); +} + void ObjectFactory::testAcsBrdAss(AcsBoardAssembly* acsAss) { CommandMessage msg; ModeMessage::setModeMessage(&msg, ModeMessage::CMD_MODE_COMMAND, DeviceHandlerIF::MODE_NORMAL, diff --git a/bsp_q7s/core/ObjectFactory.h b/bsp_q7s/core/ObjectFactory.h index a812be35..e6a68cf2 100644 --- a/bsp_q7s/core/ObjectFactory.h +++ b/bsp_q7s/core/ObjectFactory.h @@ -1,12 +1,18 @@ #ifndef BSP_Q7S_OBJECTFACTORY_H_ #define BSP_Q7S_OBJECTFACTORY_H_ +#include + +#include + class LinuxLibgpioIF; class UartComIF; class SpiComIF; class I2cComIF; class PowerSwitchIF; +class HealthTableIF; class AcsBoardAssembly; +class GpioIF; namespace ObjectFactory { @@ -14,7 +20,8 @@ void setStatics(); void produce(void* args); void createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF, UartComIF** uartComIF, - SpiComIF** spiComIF, I2cComIF** i2cComIF); + SpiComIF** spiMainComIF, I2cComIF** i2cComIF, + SpiComIF** spiRwComIF); void createPcduComponents(LinuxLibgpioIF* gpioComIF, PowerSwitchIF** pwrSwitcher); void createPlPcduComponents(LinuxLibgpioIF* gpioComIF, SpiComIF* spiComIF, PowerSwitchIF* pwrSwitcher); @@ -22,12 +29,17 @@ void createTmpComponents(); void createRadSensorComponent(LinuxLibgpioIF* gpioComIF); void createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComIF* uartComIF, PowerSwitchIF* pwrSwitcher); -void createHeaterComponents(); +void createHeaterComponents(GpioIF* gpioIF, PowerSwitchIF* pwrSwitcher, HealthTableIF* healthTable); +void createImtqComponents(PowerSwitchIF* pwrSwitcher); +void createBpxBatteryComponent(); +void createStrComponents(PowerSwitchIF* pwrSwitcher); void createSolarArrayDeploymentComponents(); void createSyrlinksComponents(PowerSwitchIF* pwrSwitcher); void createPayloadComponents(LinuxLibgpioIF* gpioComIF); -void createReactionWheelComponents(LinuxLibgpioIF* gpioComIF); +void createReactionWheelComponents(LinuxLibgpioIF* gpioComIF, PowerSwitchIF* pwrSwitcher); void createCcsdsComponents(LinuxLibgpioIF* gpioComIF); +void createMiscComponents(); + void createTestComponents(LinuxLibgpioIF* gpioComIF); void testAcsBrdAss(AcsBoardAssembly* assAss); diff --git a/bsp_q7s/em/CMakeLists.txt b/bsp_q7s/em/CMakeLists.txt index 066b807f..5ac6819f 100644 --- a/bsp_q7s/em/CMakeLists.txt +++ b/bsp_q7s/em/CMakeLists.txt @@ -1,3 +1 @@ -target_sources(${OBSW_NAME} PRIVATE - emObjectFactory.cpp -) +target_sources(${OBSW_NAME} PRIVATE emObjectFactory.cpp) diff --git a/bsp_q7s/em/emObjectFactory.cpp b/bsp_q7s/em/emObjectFactory.cpp index 226be660..9301f6d3 100644 --- a/bsp_q7s/em/emObjectFactory.cpp +++ b/bsp_q7s/em/emObjectFactory.cpp @@ -1,199 +1,63 @@ -#include -#include +#include #include "OBSWConfig.h" -#include "bsp_q7s/boardtest/Q7STestTask.h" -#include "bsp_q7s/callbacks/gnssCallback.h" -#include "bsp_q7s/callbacks/pcduSwitchCb.h" -#include "bsp_q7s/callbacks/q7sGpioCallbacks.h" -#include "bsp_q7s/callbacks/rwSpiCallback.h" #include "bsp_q7s/core/CoreController.h" #include "bsp_q7s/core/ObjectFactory.h" -#include "bsp_q7s/memory/FileSystemHandler.h" #include "busConf.h" -#include "ccsdsConfig.h" +#include "commonObjects.h" #include "devConf.h" -#include "devices/addresses.h" -#include "devices/gpioIds.h" -#include "devices/powerSwitcherList.h" -#include "fsfw/ipc/QueueFactory.h" -#include "linux/ObjectFactory.h" -#include "linux/boardtest/I2cTestClass.h" -#include "linux/boardtest/SpiTestClass.h" -#include "linux/boardtest/UartTestClass.h" -#include "linux/callbacks/gpioCallbacks.h" -#include "linux/csp/CspComIF.h" -#include "linux/csp/CspCookie.h" -#include "linux/devices/GPSHyperionLinuxController.h" -#include "linux/devices/devicedefinitions/PlocMPSoCDefinitions.h" -#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h" -#include "linux/devices/ploc/PlocMPSoCHandler.h" -#include "linux/devices/ploc/PlocMPSoCHelper.h" -#include "linux/devices/ploc/PlocMemoryDumper.h" -#include "linux/devices/ploc/PlocSupervisorHandler.h" -#include "linux/devices/ploc/PlocUpdater.h" -#include "linux/devices/startracker/StarTrackerHandler.h" -#include "linux/devices/startracker/StrHelper.h" -#include "linux/obc/AxiPtmeConfig.h" -#include "linux/obc/PapbVcInterface.h" -#include "linux/obc/PdecHandler.h" -#include "linux/obc/Ptme.h" -#include "linux/obc/PtmeConfig.h" -#include "mission/system/SusAssembly.h" -#include "mission/system/TcsBoardAssembly.h" -#include "mission/system/fdir/AcsBoardFdir.h" -#include "mission/system/fdir/RtdFdir.h" -#include "mission/system/fdir/SusFdir.h" -#include "tmtc/apid.h" -#include "tmtc/pusIds.h" -#if OBSW_TEST_LIBGPIOD == 1 -#include "linux/boardtest/LibgpiodTest.h" -#endif -#include - -#include "fsfw/datapoollocal/LocalDataPoolManager.h" -#include "fsfw/tmtcpacket/pus/tm.h" -#include "fsfw/tmtcservices/CommandingServiceBase.h" -#include "fsfw/tmtcservices/PusServiceBase.h" -#include "fsfw_hal/common/gpio/GpioCookie.h" -#include "fsfw_hal/common/gpio/gpioDefinitions.h" -#include "fsfw_hal/devicehandlers/GyroL3GD20Handler.h" -#include "fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h" -#include "fsfw_hal/devicehandlers/MgmRM3100Handler.h" #include "fsfw_hal/linux/gpio/LinuxLibgpioIF.h" -#include "fsfw_hal/linux/i2c/I2cComIF.h" -#include "fsfw_hal/linux/i2c/I2cCookie.h" -#include "fsfw_hal/linux/spi/SpiComIF.h" -#include "fsfw_hal/linux/spi/SpiCookie.h" -#include "fsfw_hal/linux/uart/UartComIF.h" -#include "fsfw_hal/linux/uart/UartCookie.h" +#include "linux/ObjectFactory.h" +#include "linux/callbacks/gpioCallbacks.h" #include "mission/core/GenericFactory.h" -#include "mission/devices/ACUHandler.h" -#include "mission/devices/BpxBatteryHandler.h" -#include "mission/devices/GyroADIS1650XHandler.h" -#include "mission/devices/HeaterHandler.h" -#include "mission/devices/IMTQHandler.h" -#include "mission/devices/Max31865PT1000Handler.h" -#include "mission/devices/P60DockHandler.h" -#include "mission/devices/PCDUHandler.h" -#include "mission/devices/PDU1Handler.h" -#include "mission/devices/PDU2Handler.h" -#include "mission/devices/PayloadPcduHandler.h" -#include "mission/devices/RadiationSensorHandler.h" -#include "mission/devices/RwHandler.h" -#include "mission/devices/SolarArrayDeploymentHandler.h" -#include "mission/devices/SusHandler.h" -#include "mission/devices/SyrlinksHkHandler.h" -#include "mission/devices/Tmp1075Handler.h" -#include "mission/devices/devicedefinitions/GomspaceDefinitions.h" -#include "mission/devices/devicedefinitions/Max31865Definitions.h" -#include "mission/devices/devicedefinitions/RadSensorDefinitions.h" -#include "mission/devices/devicedefinitions/RwDefinitions.h" -#include "mission/devices/devicedefinitions/SusDefinitions.h" -#include "mission/devices/devicedefinitions/SyrlinksDefinitions.h" -#include "mission/devices/devicedefinitions/payloadPcduDefinitions.h" -#include "mission/system/AcsBoardAssembly.h" -#include "mission/tmtc/CCSDSHandler.h" -#include "mission/tmtc/VirtualChannel.h" -#include "mission/utility/TmFunnel.h" -ResetArgs resetArgsGnss0; -ResetArgs resetArgsGnss1; - -void ObjectFactory::setStatics() { Factory::setStaticFrameworkObjectIds(); } - -void Factory::setStaticFrameworkObjectIds() { - PusServiceBase::packetSource = objects::PUS_PACKET_DISTRIBUTOR; - PusServiceBase::packetDestination = objects::TM_FUNNEL; - - CommandingServiceBase::defaultPacketSource = objects::PUS_PACKET_DISTRIBUTOR; - CommandingServiceBase::defaultPacketDestination = objects::TM_FUNNEL; - - DeviceHandlerBase::powerSwitcherId = objects::PCDU_HANDLER; - // DeviceHandlerBase::powerSwitcherId = objects::NO_OBJECT; -#if OBSW_TM_TO_PTME == 1 - TmFunnel::downlinkDestination = objects::CCSDS_HANDLER; -#else - TmFunnel::downlinkDestination = objects::TMTC_BRIDGE; -#endif /* OBSW_TM_TO_PTME == 1 */ - // No storage object for now. - TmFunnel::storageDestination = objects::NO_OBJECT; - - LocalDataPoolManager::defaultHkDestination = objects::PUS_SERVICE_3_HOUSEKEEPING; - - VerificationReporter::messageReceiver = objects::PUS_SERVICE_1_VERIFICATION; - TmPacketBase::timeStamperId = objects::TIME_STAMPER; -} void ObjectFactory::produce(void* args) { ObjectFactory::setStatics(); - ObjectFactory::produceGenericObjects(); + HealthTableIF* healthTable = nullptr; + ObjectFactory::produceGenericObjects(&healthTable); LinuxLibgpioIF* gpioComIF = nullptr; UartComIF* uartComIF = nullptr; - SpiComIF* spiComIF = nullptr; + SpiComIF* spiMainComIF = nullptr; I2cComIF* i2cComIF = nullptr; PowerSwitchIF* pwrSwitcher = nullptr; - createCommunicationInterfaces(&gpioComIF, &uartComIF, &spiComIF, &i2cComIF); + SpiComIF* spiRwComIF = nullptr; + createCommunicationInterfaces(&gpioComIF, &uartComIF, &spiMainComIF, &i2cComIF, &spiRwComIF); createTmpComponents(); new CoreController(objects::CORE_CONTROLLER); gpioCallbacks::disableAllDecoder(gpioComIF); createPcduComponents(gpioComIF, &pwrSwitcher); createRadSensorComponent(gpioComIF); - createSunSensorComponents(gpioComIF, spiComIF, pwrSwitcher, q7s::SPI_DEFAULT_DEV); + createSunSensorComponents(gpioComIF, spiMainComIF, pwrSwitcher, q7s::SPI_DEFAULT_DEV); #if OBSW_ADD_ACS_BOARD == 1 createAcsBoardComponents(gpioComIF, uartComIF, pwrSwitcher); #endif - createHeaterComponents(); + createHeaterComponents(gpioComIF, pwrSwitcher, healthTable); createSolarArrayDeploymentComponents(); - createPlPcduComponents(gpioComIF, spiComIF, pwrSwitcher); + createPlPcduComponents(gpioComIF, spiMainComIF, pwrSwitcher); #if OBSW_ADD_SYRLINKS == 1 +#if OBSW_Q7S_EM == 1 + createSyrlinksComponents(nullptr); +#else createSyrlinksComponents(pwrSwitcher); +#endif /* OBSW_Q7S_EM == 1 */ #endif /* OBSW_ADD_SYRLINKS == 1 */ - createRtdComponents(q7s::SPI_DEFAULT_DEV, gpioComIF, pwrSwitcher); + createRtdComponents(q7s::SPI_DEFAULT_DEV, gpioComIF, pwrSwitcher, spiMainComIF); createPayloadComponents(gpioComIF); #if OBSW_ADD_MGT == 1 - I2cCookie* imtqI2cCookie = - new I2cCookie(addresses::IMTQ, IMTQ::MAX_REPLY_SIZE, q7s::I2C_DEFAULT_DEV); - auto imtqHandler = new IMTQHandler(objects::IMTQ_HANDLER, objects::I2C_COM_IF, imtqI2cCookie, - pcdu::Switches::PDU1_CH3_MGT_5V); - imtqHandler->setPowerSwitcher(pwrSwitcher); - static_cast(imtqHandler); -#if OBSW_TEST_IMTQ == 1 - imtqHandler->setStartUpImmediately(); - imtqHandler->setToGoToNormal(true); + createImtqComponents(pwrSwitcher); #endif -#if OBSW_DEBUG_IMTQ == 1 - imtqHandler->setDebugMode(true); -#endif -#endif - createReactionWheelComponents(gpioComIF); + createReactionWheelComponents(gpioComIF, pwrSwitcher); #if OBSW_ADD_BPX_BATTERY_HANDLER == 1 - I2cCookie* bpxI2cCookie = new I2cCookie(addresses::BPX_BATTERY, 100, q7s::I2C_DEFAULT_DEV); - BpxBatteryHandler* bpxHandler = - new BpxBatteryHandler(objects::BPX_BATT_HANDLER, objects::I2C_COM_IF, bpxI2cCookie); - bpxHandler->setStartUpImmediately(); - bpxHandler->setToGoToNormalMode(true); -#if OBSW_DEBUG_BPX_BATT == 1 - bpxHandler->setDebugMode(true); + createBpxBatteryComponent(); #endif -#endif - new FileSystemHandler(objects::FILE_SYSTEM_HANDLER); #if OBSW_ADD_STAR_TRACKER == 1 - UartCookie* starTrackerCookie = - new UartCookie(objects::STAR_TRACKER, q7s::UART_STAR_TRACKER_DEV, uart::STAR_TRACKER_BAUD, - startracker::MAX_FRAME_SIZE * 2 + 2, UartModes::NON_CANONICAL); - starTrackerCookie->setNoFixedSizeReply(); - StrHelper* strHelper = new StrHelper(objects::STR_HELPER); - auto starTracker = - new StarTrackerHandler(objects::STAR_TRACKER, objects::UART_COM_IF, starTrackerCookie, - strHelper, pcdu::PDU1_CH2_STAR_TRACKER_5V); - starTracker->setPowerSwitcher(pwrSwitcher); - + createStrComponents(pwrSwitcher); #endif /* OBSW_ADD_STAR_TRACKER == 1 */ #if OBSW_USE_CCSDS_IP_CORE == 1 createCcsdsComponents(gpioComIF); @@ -202,771 +66,6 @@ void ObjectFactory::produce(void* args) { #if OBSW_ADD_TEST_CODE == 1 createTestComponents(gpioComIF); #endif /* OBSW_ADD_TEST_CODE == 1 */ - new PlocUpdater(objects::PLOC_UPDATER); - new PlocMemoryDumper(objects::PLOC_MEMORY_DUMPER); -} - -void ObjectFactory::createTmpComponents() { - I2cCookie* i2cCookieTmp1075tcs1 = - new I2cCookie(addresses::TMP1075_TCS_1, TMP1075::MAX_REPLY_LENGTH, q7s::I2C_DEFAULT_DEV); - I2cCookie* i2cCookieTmp1075tcs2 = - new I2cCookie(addresses::TMP1075_TCS_2, TMP1075::MAX_REPLY_LENGTH, q7s::I2C_DEFAULT_DEV); - - /* Temperature sensors */ - Tmp1075Handler* tmp1075Handler_1 = - new Tmp1075Handler(objects::TMP1075_HANDLER_1, objects::I2C_COM_IF, i2cCookieTmp1075tcs1); - (void)tmp1075Handler_1; - Tmp1075Handler* tmp1075Handler_2 = - new Tmp1075Handler(objects::TMP1075_HANDLER_2, objects::I2C_COM_IF, i2cCookieTmp1075tcs2); - (void)tmp1075Handler_2; -} - -void ObjectFactory::createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF, UartComIF** uartComIF, - SpiComIF** spiComIF, I2cComIF** i2cComIF) { - if (gpioComIF == nullptr or uartComIF == nullptr or spiComIF == nullptr) { - sif::error << "ObjectFactory::createCommunicationInterfaces: Invalid passed ComIF pointer" - << std::endl; - } - *gpioComIF = new LinuxLibgpioIF(objects::GPIO_IF); - - /* Communication interfaces */ - new CspComIF(objects::CSP_COM_IF); - *i2cComIF = new I2cComIF(objects::I2C_COM_IF); - *uartComIF = new UartComIF(objects::UART_COM_IF); - *spiComIF = new SpiComIF(objects::SPI_COM_IF, *gpioComIF); - - /* Adding gpios for chip select decoding to the gpioComIf */ - q7s::gpioCallbacks::initSpiCsDecoder(*gpioComIF); -} - -void ObjectFactory::createPcduComponents(LinuxLibgpioIF* gpioComIF, PowerSwitchIF** pwrSwitcher) { - CspCookie* p60DockCspCookie = new CspCookie(P60Dock::MAX_REPLY_LENGTH, addresses::P60DOCK); - CspCookie* pdu1CspCookie = new CspCookie(PDU::MAX_REPLY_LENGTH, addresses::PDU1); - CspCookie* pdu2CspCookie = new CspCookie(PDU::MAX_REPLY_LENGTH, addresses::PDU2); - CspCookie* acuCspCookie = new CspCookie(ACU::MAX_REPLY_LENGTH, addresses::ACU); - - auto p60Fdir = new GomspacePowerFdir(objects::P60DOCK_HANDLER); - P60DockHandler* p60dockhandler = - new P60DockHandler(objects::P60DOCK_HANDLER, objects::CSP_COM_IF, p60DockCspCookie, p60Fdir); - - auto pdu1Fdir = new GomspacePowerFdir(objects::PDU1_HANDLER); - PDU1Handler* pdu1handler = - new PDU1Handler(objects::PDU1_HANDLER, objects::CSP_COM_IF, pdu1CspCookie, pdu1Fdir); - - auto pdu2Fdir = new GomspacePowerFdir(objects::PDU2_HANDLER); - PDU2Handler* pdu2handler = - new PDU2Handler(objects::PDU2_HANDLER, objects::CSP_COM_IF, pdu2CspCookie, pdu2Fdir); - - auto acuFdir = new GomspacePowerFdir(objects::ACU_HANDLER); - ACUHandler* acuhandler = - new ACUHandler(objects::ACU_HANDLER, objects::CSP_COM_IF, acuCspCookie, acuFdir); - auto pcduHandler = new PCDUHandler(objects::PCDU_HANDLER, 50); - - /** - * Setting PCDU devices to mode normal immediately after start up because PCDU is always - * running. - */ - p60dockhandler->setModeNormal(); - pdu1handler->setModeNormal(); - pdu2handler->setModeNormal(); - acuhandler->setModeNormal(); - if (pwrSwitcher != nullptr) { - *pwrSwitcher = pcduHandler; - } -#if OBSW_DEBUG_P60DOCK == 1 - p60dockhandler->setDebugMode(true); -#endif -#if OBSW_DEBUG_ACU == 1 - acuhandler->setDebugMode(true); -#endif -} - -void ObjectFactory::createRadSensorComponent(LinuxLibgpioIF* gpioComIF) { - using namespace gpio; - GpioCookie* gpioCookieRadSensor = new GpioCookie; - std::stringstream consumer; - consumer << "0x" << std::hex << objects::RAD_SENSOR; - GpiodRegularByLineName* gpio = new GpiodRegularByLineName( - q7s::gpioNames::RAD_SENSOR_CHIP_SELECT, consumer.str(), Direction::OUT, Levels::HIGH); - gpioCookieRadSensor->addGpio(gpioIds::CS_RAD_SENSOR, gpio); - gpio = new GpiodRegularByLineName(q7s::gpioNames::ENABLE_RADFET, consumer.str(), Direction::OUT, - Levels::LOW); - gpioCookieRadSensor->addGpio(gpioIds::ENABLE_RADFET, gpio); - gpioComIF->addGpios(gpioCookieRadSensor); - - SpiCookie* spiCookieRadSensor = new SpiCookie( - addresses::RAD_SENSOR, gpioIds::CS_RAD_SENSOR, std::string(q7s::SPI_DEFAULT_DEV), - RAD_SENSOR::READ_SIZE, spi::DEFAULT_MAX_1227_MODE, spi::DEFAULT_MAX_1227_SPEED); - auto radSensor = new RadiationSensorHandler(objects::RAD_SENSOR, objects::SPI_COM_IF, - spiCookieRadSensor, gpioComIF); - static_cast(radSensor); - // The radiation sensor ADC is powered by the 5V stack connector which should always be on - radSensor->setStartUpImmediately(); - // It's a simple sensor, so just to to normal mode immediately - radSensor->setToGoToNormalModeImmediately(); -#if OBSW_DEBUG_RAD_SENSOR == 1 - radSensor->enablePeriodicDataPrint(true); -#endif -} - -void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComIF* uartComIF, - PowerSwitchIF* pwrSwitcher) { - using namespace gpio; - GpioCookie* gpioCookieAcsBoard = new GpioCookie(); - - std::stringstream consumer; - GpiodRegularByLineName* gpio = nullptr; - consumer << "0x" << std::hex << objects::GYRO_0_ADIS_HANDLER; - gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_0_ADIS_CS, consumer.str(), Direction::OUT, - Levels::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio); - - consumer.str(""); - consumer << "0x" << std::hex << objects::GYRO_1_L3G_HANDLER; - gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_1_L3G_CS, consumer.str(), Direction::OUT, - Levels::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::GYRO_1_L3G_CS, gpio); - - consumer.str(""); - consumer << "0x" << std::hex << objects::GYRO_2_ADIS_HANDLER; - gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_2_ADIS_CS, consumer.str(), Direction::OUT, - Levels::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::GYRO_2_ADIS_CS, gpio); - - consumer.str(""); - consumer << "0x" << std::hex << objects::GYRO_3_L3G_HANDLER; - gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_3_L3G_CS, consumer.str(), Direction::OUT, - Levels::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::GYRO_3_L3G_CS, gpio); - - consumer.str(""); - consumer << "0x" << std::hex << objects::MGM_0_LIS3_HANDLER; - gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_0_CS, consumer.str(), Direction::OUT, - Levels::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::MGM_0_LIS3_CS, gpio); - - consumer.str(""); - consumer << "0x" << std::hex << objects::MGM_1_RM3100_HANDLER; - gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_1_CS, consumer.str(), Direction::OUT, - Levels::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::MGM_1_RM3100_CS, gpio); - - consumer.str(""); - consumer << "0x" << std::hex << objects::MGM_2_LIS3_HANDLER; - gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_2_CS, consumer.str(), Direction::OUT, - Levels::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::MGM_2_LIS3_CS, gpio); - - consumer.str(""); - consumer << "0x" << std::hex << objects::MGM_3_RM3100_HANDLER; - gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_3_CS, consumer.str(), Direction::OUT, - Levels::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::MGM_3_RM3100_CS, gpio); - - consumer.str(""); - consumer << "0x" << std::hex << objects::GPS_CONTROLLER; - // GNSS reset pins are active low - gpio = new GpiodRegularByLineName(q7s::gpioNames::RESET_GNSS_0, consumer.str(), Direction::OUT, - Levels::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::GNSS_0_NRESET, gpio); - - consumer.str(""); - consumer << "0x" << std::hex << objects::GPS_CONTROLLER; - gpio = new GpiodRegularByLineName(q7s::gpioNames::RESET_GNSS_1, consumer.str(), Direction::OUT, - Levels::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::GNSS_1_NRESET, gpio); - - consumer.str(""); - consumer << "0x" << std::hex << objects::GYRO_0_ADIS_HANDLER; - // Enable pins must be pulled low for regular operations - gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_0_ENABLE, consumer.str(), Direction::OUT, - Levels::LOW); - gpioCookieAcsBoard->addGpio(gpioIds::GYRO_0_ENABLE, gpio); - - consumer.str(""); - consumer << "0x" << std::hex << objects::GYRO_2_ADIS_HANDLER; - gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_2_ENABLE, consumer.str(), Direction::OUT, - Levels::LOW); - gpioCookieAcsBoard->addGpio(gpioIds::GYRO_2_ENABLE, gpio); - - // Enable pins for GNSS - consumer.str(""); - consumer << "0x" << std::hex << objects::GPS_CONTROLLER; - gpio = new GpiodRegularByLineName(q7s::gpioNames::GNSS_0_ENABLE, consumer.str(), Direction::OUT, - Levels::LOW); - gpioCookieAcsBoard->addGpio(gpioIds::GNSS_0_ENABLE, gpio); - - consumer.str(""); - consumer << "0x" << std::hex << objects::GPS_CONTROLLER; - gpio = new GpiodRegularByLineName(q7s::gpioNames::GNSS_1_ENABLE, consumer.str(), Direction::OUT, - Levels::LOW); - gpioCookieAcsBoard->addGpio(gpioIds::GNSS_1_ENABLE, gpio); - - // Select pin. 0 for GPS side A, 1 for GPS side B - consumer.str(""); - consumer << "0x" << std::hex << objects::GPS_CONTROLLER; - gpio = new GpiodRegularByLineName(q7s::gpioNames::GNSS_SELECT, consumer.str(), Direction::OUT, - Levels::LOW); - gpioCookieAcsBoard->addGpio(gpioIds::GNSS_SELECT, gpio); - gpioComIF->addGpios(gpioCookieAcsBoard); - AcsBoardFdir* fdir = nullptr; - static_cast(fdir); - -#if OBSW_ADD_ACS_HANDLERS == 1 - std::string spiDev = q7s::SPI_DEFAULT_DEV; - SpiCookie* spiCookie = - new SpiCookie(addresses::MGM_0_LIS3, gpioIds::MGM_0_LIS3_CS, spiDev, - MGMLIS3MDL::MAX_BUFFER_SIZE, spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED); - auto mgmLis3Handler = new MgmLIS3MDLHandler(objects::MGM_0_LIS3_HANDLER, objects::SPI_COM_IF, - spiCookie, spi::LIS3_TRANSITION_DELAY); - fdir = new AcsBoardFdir(objects::MGM_0_LIS3_HANDLER); - mgmLis3Handler->setCustomFdir(fdir); - static_cast(mgmLis3Handler); -#if OBSW_TEST_ACS == 1 - mgmLis3Handler->setStartUpImmediately(); - mgmLis3Handler->setToGoToNormalMode(true); -#endif -#if OBSW_DEBUG_ACS == 1 - mgmLis3Handler->enablePeriodicPrintouts(true, 10); -#endif - spiCookie = - new SpiCookie(addresses::MGM_1_RM3100, gpioIds::MGM_1_RM3100_CS, spiDev, - RM3100::MAX_BUFFER_SIZE, spi::DEFAULT_RM3100_MODE, spi::DEFAULT_RM3100_SPEED); - auto mgmRm3100Handler = new MgmRM3100Handler(objects::MGM_1_RM3100_HANDLER, objects::SPI_COM_IF, - spiCookie, spi::RM3100_TRANSITION_DELAY); - fdir = new AcsBoardFdir(objects::MGM_1_RM3100_HANDLER); - mgmRm3100Handler->setCustomFdir(fdir); - mgmRm3100Handler->setParent(objects::ACS_BOARD_ASS); - static_cast(mgmRm3100Handler); -#if OBSW_TEST_ACS == 1 - mgmRm3100Handler->setStartUpImmediately(); - mgmRm3100Handler->setToGoToNormalMode(true); -#endif -#if OBSW_DEBUG_ACS == 1 - mgmRm3100Handler->enablePeriodicPrintouts(true, 10); -#endif - spiCookie = - new SpiCookie(addresses::MGM_2_LIS3, gpioIds::MGM_2_LIS3_CS, spiDev, - MGMLIS3MDL::MAX_BUFFER_SIZE, spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED); - mgmLis3Handler = new MgmLIS3MDLHandler(objects::MGM_2_LIS3_HANDLER, objects::SPI_COM_IF, - spiCookie, spi::LIS3_TRANSITION_DELAY); - fdir = new AcsBoardFdir(objects::MGM_2_LIS3_HANDLER); - mgmLis3Handler->setCustomFdir(fdir); - mgmLis3Handler->setParent(objects::ACS_BOARD_ASS); - static_cast(mgmLis3Handler); -#if OBSW_TEST_ACS == 1 - mgmLis3Handler->setStartUpImmediately(); - mgmLis3Handler->setToGoToNormalMode(true); -#endif -#if OBSW_DEBUG_ACS == 1 - mgmLis3Handler->enablePeriodicPrintouts(true, 10); -#endif - spiCookie = - new SpiCookie(addresses::MGM_3_RM3100, gpioIds::MGM_3_RM3100_CS, spiDev, - RM3100::MAX_BUFFER_SIZE, spi::DEFAULT_RM3100_MODE, spi::DEFAULT_RM3100_SPEED); - mgmRm3100Handler = new MgmRM3100Handler(objects::MGM_3_RM3100_HANDLER, objects::SPI_COM_IF, - spiCookie, spi::RM3100_TRANSITION_DELAY); - fdir = new AcsBoardFdir(objects::MGM_3_RM3100_HANDLER); - mgmRm3100Handler->setCustomFdir(fdir); - mgmRm3100Handler->setParent(objects::ACS_BOARD_ASS); -#if OBSW_TEST_ACS == 1 - mgmRm3100Handler->setStartUpImmediately(); - mgmRm3100Handler->setToGoToNormalMode(true); -#endif -#if OBSW_DEBUG_ACS == 1 - mgmRm3100Handler->enablePeriodicPrintouts(true, 10); -#endif - // Commented until ACS board V2 in in clean room again - // Gyro 0 Side A - spiCookie = new SpiCookie(addresses::GYRO_0_ADIS, gpioIds::GYRO_0_ADIS_CS, spiDev, - ADIS1650X::MAXIMUM_REPLY_SIZE, spi::DEFAULT_ADIS16507_MODE, - spi::DEFAULT_ADIS16507_SPEED); - auto adisHandler = new GyroADIS1650XHandler(objects::GYRO_0_ADIS_HANDLER, objects::SPI_COM_IF, - spiCookie, ADIS1650X::Type::ADIS16505); - fdir = new AcsBoardFdir(objects::GYRO_0_ADIS_HANDLER); - adisHandler->setCustomFdir(fdir); - adisHandler->setParent(objects::ACS_BOARD_ASS); - static_cast(adisHandler); -#if OBSW_TEST_ACS == 1 - adisHandler->setStartUpImmediately(); - adisHandler->setToGoToNormalModeImmediately(); -#endif -#if OBSW_DEBUG_ACS == 1 - adisHandler->enablePeriodicPrintouts(true, 10); -#endif - // Gyro 1 Side A - spiCookie = - new SpiCookie(addresses::GYRO_1_L3G, gpioIds::GYRO_1_L3G_CS, spiDev, L3GD20H::MAX_BUFFER_SIZE, - spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED); - auto gyroL3gHandler = new GyroHandlerL3GD20H(objects::GYRO_1_L3G_HANDLER, objects::SPI_COM_IF, - spiCookie, spi::L3G_TRANSITION_DELAY); - fdir = new AcsBoardFdir(objects::GYRO_1_L3G_HANDLER); - gyroL3gHandler->setCustomFdir(fdir); - gyroL3gHandler->setParent(objects::ACS_BOARD_ASS); - static_cast(gyroL3gHandler); -#if OBSW_TEST_ACS == 1 - gyroL3gHandler->setStartUpImmediately(); - gyroL3gHandler->setToGoToNormalMode(true); -#endif -#if OBSW_DEBUG_ACS == 1 - gyroL3gHandler->enablePeriodicPrintouts(true, 10); -#endif - // Gyro 2 Side B - spiCookie = new SpiCookie(addresses::GYRO_2_ADIS, gpioIds::GYRO_2_ADIS_CS, spiDev, - ADIS1650X::MAXIMUM_REPLY_SIZE, spi::DEFAULT_ADIS16507_MODE, - spi::DEFAULT_ADIS16507_SPEED); - adisHandler = new GyroADIS1650XHandler(objects::GYRO_2_ADIS_HANDLER, objects::SPI_COM_IF, - spiCookie, ADIS1650X::Type::ADIS16505); - fdir = new AcsBoardFdir(objects::GYRO_2_ADIS_HANDLER); - adisHandler->setCustomFdir(fdir); - adisHandler->setParent(objects::ACS_BOARD_ASS); -#if OBSW_TEST_ACS == 1 - adisHandler->setStartUpImmediately(); - adisHandler->setToGoToNormalModeImmediately(); -#endif - // Gyro 3 Side B - spiCookie = - new SpiCookie(addresses::GYRO_3_L3G, gpioIds::GYRO_3_L3G_CS, spiDev, L3GD20H::MAX_BUFFER_SIZE, - spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED); - gyroL3gHandler = new GyroHandlerL3GD20H(objects::GYRO_3_L3G_HANDLER, objects::SPI_COM_IF, - spiCookie, spi::L3G_TRANSITION_DELAY); - fdir = new AcsBoardFdir(objects::GYRO_3_L3G_HANDLER); - gyroL3gHandler->setCustomFdir(fdir); - gyroL3gHandler->setParent(objects::ACS_BOARD_ASS); -#if OBSW_TEST_ACS == 1 - gyroL3gHandler->setStartUpImmediately(); - gyroL3gHandler->setToGoToNormalMode(true); -#endif -#if OBSW_DEBUG_ACS == 1 - gyroL3gHandler->enablePeriodicPrintouts(true, 10); -#endif - bool debugGps = false; -#if OBSW_DEBUG_GPS == 1 - debugGps = true; -#endif - resetArgsGnss1.gnss1 = true; - resetArgsGnss1.gpioComIF = gpioComIF; - resetArgsGnss1.waitPeriodMs = 100; - resetArgsGnss0.gnss1 = false; - resetArgsGnss0.gpioComIF = gpioComIF; - resetArgsGnss0.waitPeriodMs = 100; - auto gpsHandler0 = - new GPSHyperionLinuxController(objects::GPS_CONTROLLER, objects::NO_OBJECT, debugGps); - gpsHandler0->setResetPinTriggerFunction(gps::triggerGpioResetPin, &resetArgsGnss0); - - AcsBoardHelper acsBoardHelper = AcsBoardHelper( - objects::MGM_0_LIS3_HANDLER, objects::MGM_1_RM3100_HANDLER, objects::MGM_2_LIS3_HANDLER, - objects::MGM_3_RM3100_HANDLER, objects::GYRO_0_ADIS_HANDLER, objects::GYRO_1_L3G_HANDLER, - objects::GYRO_2_ADIS_HANDLER, objects::GYRO_3_L3G_HANDLER, objects::GPS_CONTROLLER); - auto acsAss = new AcsBoardAssembly(objects::ACS_BOARD_ASS, objects::NO_OBJECT, pwrSwitcher, - acsBoardHelper, gpioComIF); - static_cast(acsAss); -#endif /* OBSW_ADD_ACS_HANDLERS == 1 */ -} - -void ObjectFactory::createHeaterComponents() { - using namespace gpio; - GpioCookie* heaterGpiosCookie = new GpioCookie; - GpiodRegularByLineName* gpio = nullptr; - - std::stringstream consumer; - consumer << "0x" << std::hex << objects::HEATER_HANDLER; - /* Pin H2-11 on stack connector */ - gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_0, consumer.str(), Direction::OUT, - Levels::LOW); - heaterGpiosCookie->addGpio(gpioIds::HEATER_0, gpio); - /* Pin H2-12 on stack connector */ - gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_1, consumer.str(), Direction::OUT, - Levels::LOW); - heaterGpiosCookie->addGpio(gpioIds::HEATER_1, gpio); - - /* Pin H2-13 on stack connector */ - gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_2, consumer.str(), Direction::OUT, - Levels::LOW); - heaterGpiosCookie->addGpio(gpioIds::HEATER_2, gpio); - - gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_3, consumer.str(), Direction::OUT, - Levels::LOW); - heaterGpiosCookie->addGpio(gpioIds::HEATER_3, gpio); - - gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_4, consumer.str(), Direction::OUT, - Levels::LOW); - heaterGpiosCookie->addGpio(gpioIds::HEATER_4, gpio); - - gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_5, consumer.str(), Direction::OUT, - Levels::LOW); - heaterGpiosCookie->addGpio(gpioIds::HEATER_5, gpio); - - gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_6, consumer.str(), Direction::OUT, - Levels::LOW); - heaterGpiosCookie->addGpio(gpioIds::HEATER_6, gpio); - - gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_7, consumer.str(), Direction::OUT, - Levels::LOW); - heaterGpiosCookie->addGpio(gpioIds::HEATER_7, gpio); - - new HeaterHandler(objects::HEATER_HANDLER, objects::GPIO_IF, heaterGpiosCookie, - objects::PCDU_HANDLER, pcdu::Switches::PDU2_CH3_TCS_BOARD_HEATER_IN_8V); -} - -void ObjectFactory::createSolarArrayDeploymentComponents() { - using namespace gpio; - GpioCookie* solarArrayDeplCookie = new GpioCookie; - GpiodRegularByLineName* gpio = nullptr; - - std::stringstream consumer; - consumer << "0x" << std::hex << objects::SOLAR_ARRAY_DEPL_HANDLER; - gpio = new GpiodRegularByLineName(q7s::gpioNames::SA_DPL_PIN_0, consumer.str(), Direction::OUT, - Levels::LOW); - solarArrayDeplCookie->addGpio(gpioIds::DEPLSA1, gpio); - gpio = new GpiodRegularByLineName(q7s::gpioNames::SA_DPL_PIN_1, consumer.str(), Direction::OUT, - Levels::LOW); - solarArrayDeplCookie->addGpio(gpioIds::DEPLSA2, gpio); - - // TODO: Find out burn time. For now set to 1000 ms. - new SolarArrayDeploymentHandler(objects::SOLAR_ARRAY_DEPL_HANDLER, objects::GPIO_IF, - solarArrayDeplCookie, objects::PCDU_HANDLER, - pcdu::Switches::PDU2_CH5_DEPLOYMENT_MECHANISM_8V, - gpioIds::DEPLSA1, gpioIds::DEPLSA2, 1000); -} - -void ObjectFactory::createSyrlinksComponents(PowerSwitchIF* pwrSwitcher) { - UartCookie* syrlinksUartCookie = - new UartCookie(objects::SYRLINKS_HK_HANDLER, q7s::UART_SYRLINKS_DEV, uart::SYRLINKS_BAUD, - syrlinks::MAX_REPLY_SIZE, UartModes::NON_CANONICAL); - syrlinksUartCookie->setParityEven(); - - auto syrlinksFdir = new SyrlinksFdir(objects::SYRLINKS_HK_HANDLER); - auto syrlinksHandler = - new SyrlinksHkHandler(objects::SYRLINKS_HK_HANDLER, objects::UART_COM_IF, syrlinksUartCookie, - pcdu::PDU1_CH1_SYRLINKS_12V, syrlinksFdir); - syrlinksHandler->setPowerSwitcher(pwrSwitcher); -#if OBSW_DEBUG_SYRLINKS == 1 - syrlinksHandler->setDebugMode(true); -#endif -} - -void ObjectFactory::createPayloadComponents(LinuxLibgpioIF* gpioComIF) { - using namespace gpio; - std::stringstream consumer; -#if OBSW_ADD_PLOC_MPSOC == 1 - consumer << "0x" << std::hex << objects::PLOC_MPSOC_HANDLER; - auto gpioConfigMPSoC = new GpiodRegularByLineName(q7s::gpioNames::ENABLE_MPSOC_UART, - consumer.str(), Direction::OUT, Levels::HIGH); - auto mpsocGpioCookie = new GpioCookie; - mpsocGpioCookie->addGpio(gpioIds::ENABLE_MPSOC_UART, gpioConfigMPSoC); - gpioComIF->addGpios(mpsocGpioCookie); - auto mpsocCookie = - new UartCookie(objects::PLOC_MPSOC_HANDLER, q7s::UART_PLOC_MPSOC_DEV, uart::PLOC_MPSOC_BAUD, - mpsoc::MAX_REPLY_SIZE, UartModes::NON_CANONICAL); - mpsocCookie->setNoFixedSizeReply(); - auto plocMpsocHelper = new PlocMPSoCHelper(objects::PLOC_MPSOC_HELPER); - new PlocMPSoCHandler(objects::PLOC_MPSOC_HANDLER, objects::UART_COM_IF, mpsocCookie, - plocMpsocHelper, Gpio(gpioIds::ENABLE_MPSOC_UART, gpioComIF), - objects::PLOC_SUPERVISOR_HANDLER); -#endif /* OBSW_ADD_PLOC_MPSOC == 1 */ -#if OBSW_ADD_PLOC_SUPERVISOR == 1 - consumer << "0x" << std::hex << objects::PLOC_SUPERVISOR_HANDLER; - auto gpioConfigSupv = new GpiodRegularByLineName(q7s::gpioNames::ENABLE_SUPV_UART, consumer.str(), - Direction::OUT, Levels::HIGH); - auto supvGpioCookie = new GpioCookie; - supvGpioCookie->addGpio(gpioIds::ENABLE_SUPV_UART, gpioConfigSupv); - gpioComIF->addGpios(supvGpioCookie); - auto supervisorCookie = new UartCookie(objects::PLOC_SUPERVISOR_HANDLER, - q7s::UART_PLOC_SUPERVSIOR_DEV, uart::PLOC_SUPERVISOR_BAUD, - supv::MAX_PACKET_SIZE * 20, UartModes::NON_CANONICAL); - supervisorCookie->setNoFixedSizeReply(); - new PlocSupervisorHandler(objects::PLOC_SUPERVISOR_HANDLER, objects::UART_COM_IF, - supervisorCookie, Gpio(gpioIds::ENABLE_SUPV_UART, gpioComIF), - pcdu::PDU1_CH6_PLOC_12V); -#endif /* OBSW_ADD_PLOC_SUPERVISOR == 1 */ - static_cast(consumer); -} - -void ObjectFactory::createReactionWheelComponents(LinuxLibgpioIF* gpioComIF) { - using namespace gpio; - GpioCookie* gpioCookieRw = new GpioCookie; - GpioCallback* csRw1 = - new GpioCallback("Chip select reaction wheel 1", Direction::OUT, Levels::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - gpioCookieRw->addGpio(gpioIds::CS_RW1, csRw1); - GpioCallback* csRw2 = - new GpioCallback("Chip select reaction wheel 2", Direction::OUT, Levels::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - gpioCookieRw->addGpio(gpioIds::CS_RW2, csRw2); - GpioCallback* csRw3 = - new GpioCallback("Chip select reaction wheel 3", Direction::OUT, Levels::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - gpioCookieRw->addGpio(gpioIds::CS_RW3, csRw3); - GpioCallback* csRw4 = - new GpioCallback("Chip select reaction wheel 4", Direction::OUT, Levels::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - gpioCookieRw->addGpio(gpioIds::CS_RW4, csRw4); - - std::stringstream consumer; - GpiodRegularByLineName* gpio = nullptr; - consumer << "0x" << std::hex << objects::RW1; - gpio = new GpiodRegularByLineName(q7s::gpioNames::EN_RW_1, consumer.str(), Direction::OUT, - Levels::LOW); - gpioCookieRw->addGpio(gpioIds::EN_RW1, gpio); - consumer.str(""); - consumer << "0x" << std::hex << objects::RW2; - gpio = new GpiodRegularByLineName(q7s::gpioNames::EN_RW_2, consumer.str(), Direction::OUT, - Levels::LOW); - gpioCookieRw->addGpio(gpioIds::EN_RW2, gpio); - consumer.str(""); - consumer << "0x" << std::hex << objects::RW3; - gpio = new GpiodRegularByLineName(q7s::gpioNames::EN_RW_3, consumer.str(), Direction::OUT, - Levels::LOW); - gpioCookieRw->addGpio(gpioIds::EN_RW3, gpio); - consumer.str(""); - consumer << "0x" << std::hex << objects::RW4; - gpio = new GpiodRegularByLineName(q7s::gpioNames::EN_RW_4, consumer.str(), Direction::OUT, - Levels::LOW); - gpioCookieRw->addGpio(gpioIds::EN_RW4, gpio); - - gpioComIF->addGpios(gpioCookieRw); - -#if OBSW_ADD_RW == 1 - auto rw1SpiCookie = - new SpiCookie(addresses::RW1, gpioIds::CS_RW1, q7s::SPI_RW_DEV, RwDefinitions::MAX_REPLY_SIZE, - spi::RW_MODE, spi::RW_SPEED, &rwSpiCallback::spiCallback, nullptr); - auto rw2SpiCookie = - new SpiCookie(addresses::RW2, gpioIds::CS_RW2, q7s::SPI_RW_DEV, RwDefinitions::MAX_REPLY_SIZE, - spi::RW_MODE, spi::RW_SPEED, &rwSpiCallback::spiCallback, nullptr); - auto rw3SpiCookie = - new SpiCookie(addresses::RW3, gpioIds::CS_RW3, q7s::SPI_RW_DEV, RwDefinitions::MAX_REPLY_SIZE, - spi::RW_MODE, spi::RW_SPEED, &rwSpiCallback::spiCallback, nullptr); - auto rw4SpiCookie = - new SpiCookie(addresses::RW4, gpioIds::CS_RW4, q7s::SPI_RW_DEV, RwDefinitions::MAX_REPLY_SIZE, - spi::RW_MODE, spi::RW_SPEED, &rwSpiCallback::spiCallback, nullptr); - - auto rwHandler1 = - new RwHandler(objects::RW1, objects::SPI_COM_IF, rw1SpiCookie, gpioComIF, gpioIds::EN_RW1); - rw1SpiCookie->setCallbackArgs(rwHandler1); -#if OBSW_DEBUG_RW == 1 - rwHandler1->setStartUpImmediately(); - rwHandler1->setDebugMode(true); -#endif - auto rwHandler2 = - new RwHandler(objects::RW2, objects::SPI_COM_IF, rw2SpiCookie, gpioComIF, gpioIds::EN_RW2); - rw2SpiCookie->setCallbackArgs(rwHandler2); -#if OBSW_DEBUG_RW == 1 - rwHandler2->setStartUpImmediately(); - rwHandler2->setDebugMode(true); -#endif - auto rwHandler3 = - new RwHandler(objects::RW3, objects::SPI_COM_IF, rw3SpiCookie, gpioComIF, gpioIds::EN_RW3); - rw3SpiCookie->setCallbackArgs(rwHandler3); -#if OBSW_DEBUG_RW == 1 - rwHandler3->setStartUpImmediately(); - rwHandler3->setDebugMode(true); -#endif - auto rwHandler4 = - new RwHandler(objects::RW4, objects::SPI_COM_IF, rw4SpiCookie, gpioComIF, gpioIds::EN_RW4); - rw4SpiCookie->setCallbackArgs(rwHandler4); -#if OBSW_DEBUG_RW == 1 - rwHandler4->setStartUpImmediately(); - rwHandler4->setDebugMode(true); -#endif -#endif /* OBSW_ADD_RW == 1 */ -} - -void ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF) { - using namespace gpio; - // GPIO definitions of signals connected to the virtual channel interfaces of the PTME IP Core - GpioCookie* gpioCookiePtmeIp = new GpioCookie; - GpiodRegularByLineName* gpio = nullptr; - std::stringstream consumer; - consumer.str("PAPB VC0"); - gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_BUSY_SIGNAL_VC0, consumer.str()); - gpioCookiePtmeIp->addGpio(gpioIds::VC0_PAPB_BUSY, gpio); - consumer.str("PAPB VC0"); - gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_EMPTY_SIGNAL_VC0, consumer.str()); - gpioCookiePtmeIp->addGpio(gpioIds::VC0_PAPB_EMPTY, gpio); - consumer.str("PAPB VC 1"); - gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_BUSY_SIGNAL_VC1, consumer.str()); - gpioCookiePtmeIp->addGpio(gpioIds::VC1_PAPB_BUSY, gpio); - consumer.str(""); - consumer.str("PAPB VC 1"); - gpioCookiePtmeIp->addGpio(gpioIds::VC1_PAPB_EMPTY, gpio); - consumer.str(""); - consumer.str("PAPB VC 2"); - gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_BUSY_SIGNAL_VC2, consumer.str()); - gpioCookiePtmeIp->addGpio(gpioIds::VC2_PAPB_BUSY, gpio); - consumer.str(""); - consumer.str("PAPB VC 2"); - gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_EMPTY_SIGNAL_VC2, consumer.str()); - gpioCookiePtmeIp->addGpio(gpioIds::VC2_PAPB_EMPTY, gpio); - consumer.str(""); - consumer.str("PAPB VC 3"); - gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_BUSY_SIGNAL_VC3, consumer.str()); - gpioCookiePtmeIp->addGpio(gpioIds::VC3_PAPB_BUSY, gpio); - consumer.str(""); - consumer.str("PAPB VC 3"); - gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_EMPTY_SIGNAL_VC3, consumer.str()); - gpioCookiePtmeIp->addGpio(gpioIds::VC3_PAPB_EMPTY, gpio); - - gpioComIF->addGpios(gpioCookiePtmeIp); - - // Creating virtual channel interfaces - VcInterfaceIF* vc0 = - new PapbVcInterface(gpioComIF, gpioIds::VC0_PAPB_BUSY, gpioIds::VC0_PAPB_EMPTY, q7s::UIO_PTME, - q7s::uiomapids::PTME_VC0); - VcInterfaceIF* vc1 = - new PapbVcInterface(gpioComIF, gpioIds::VC1_PAPB_BUSY, gpioIds::VC1_PAPB_EMPTY, q7s::UIO_PTME, - q7s::uiomapids::PTME_VC1); - VcInterfaceIF* vc2 = - new PapbVcInterface(gpioComIF, gpioIds::VC2_PAPB_BUSY, gpioIds::VC2_PAPB_EMPTY, q7s::UIO_PTME, - q7s::uiomapids::PTME_VC2); - VcInterfaceIF* vc3 = - new PapbVcInterface(gpioComIF, gpioIds::VC3_PAPB_BUSY, gpioIds::VC3_PAPB_EMPTY, q7s::UIO_PTME, - q7s::uiomapids::PTME_VC3); - - // Creating ptme object and adding virtual channel interfaces - Ptme* ptme = new Ptme(objects::PTME); - ptme->addVcInterface(ccsds::VC0, vc0); - ptme->addVcInterface(ccsds::VC1, vc1); - ptme->addVcInterface(ccsds::VC2, vc2); - ptme->addVcInterface(ccsds::VC3, vc3); - - AxiPtmeConfig* axiPtmeConfig = - new AxiPtmeConfig(objects::AXI_PTME_CONFIG, q7s::UIO_PTME, q7s::uiomapids::PTME_CONFIG); - PtmeConfig* ptmeConfig = new PtmeConfig(objects::PTME_CONFIG, axiPtmeConfig); -#if OBSW_ENABLE_SYRLINKS_TRANSMIT_TIMEOUT == 1 - // Set to high value when not sending via syrlinks - static const uint32_t TRANSMITTER_TIMEOUT = 86400000; // 1 day -#else - static const uint32_t TRANSMITTER_TIMEOUT = 900000; // 15 minutes -#endif - CCSDSHandler* ccsdsHandler = new CCSDSHandler( - objects::CCSDS_HANDLER, objects::PTME, objects::CCSDS_PACKET_DISTRIBUTOR, ptmeConfig, - gpioComIF, gpioIds::RS485_EN_TX_CLOCK, gpioIds::RS485_EN_TX_DATA, TRANSMITTER_TIMEOUT); - - VirtualChannel* vc = nullptr; - vc = new VirtualChannel(ccsds::VC0, common::VC0_QUEUE_SIZE, objects::CCSDS_HANDLER); - ccsdsHandler->addVirtualChannel(ccsds::VC0, vc); - vc = new VirtualChannel(ccsds::VC1, common::VC1_QUEUE_SIZE, objects::CCSDS_HANDLER); - ccsdsHandler->addVirtualChannel(ccsds::VC1, vc); - vc = new VirtualChannel(ccsds::VC2, common::VC2_QUEUE_SIZE, objects::CCSDS_HANDLER); - ccsdsHandler->addVirtualChannel(ccsds::VC2, vc); - vc = new VirtualChannel(ccsds::VC3, common::VC3_QUEUE_SIZE, objects::CCSDS_HANDLER); - ccsdsHandler->addVirtualChannel(ccsds::VC3, vc); - - GpioCookie* gpioCookiePdec = new GpioCookie; - consumer.str(""); - consumer << "0x" << std::hex << objects::PDEC_HANDLER; - // GPIO also low after linux boot (specified by device-tree) - gpio = new GpiodRegularByLineName(q7s::gpioNames::PDEC_RESET, consumer.str(), Direction::OUT, - Levels::LOW); - gpioCookiePdec->addGpio(gpioIds::PDEC_RESET, gpio); - - gpioComIF->addGpios(gpioCookiePdec); - - new PdecHandler(objects::PDEC_HANDLER, objects::CCSDS_HANDLER, gpioComIF, gpioIds::PDEC_RESET, - q7s::UIO_PDEC_CONFIG_MEMORY, q7s::UIO_PDEC_RAM, q7s::UIO_PDEC_REGISTERS); - - GpioCookie* gpioRS485Chip = new GpioCookie; - gpio = new GpiodRegularByLineName(q7s::gpioNames::RS485_EN_TX_CLOCK, "RS485 Transceiver", - Direction::OUT, Levels::LOW); - gpioRS485Chip->addGpio(gpioIds::RS485_EN_TX_CLOCK, gpio); - gpio = new GpiodRegularByLineName(q7s::gpioNames::RS485_EN_TX_DATA, "RS485 Transceiver", - Direction::OUT, Levels::LOW); - gpioRS485Chip->addGpio(gpioIds::RS485_EN_TX_DATA, gpio); - - // Default configuration enables RX channels (RXEN = LOW) - gpio = new GpiodRegularByLineName(q7s::gpioNames::RS485_EN_RX_CLOCK, "RS485 Transceiver", - Direction::OUT, Levels::LOW); - gpioRS485Chip->addGpio(gpioIds::RS485_EN_RX_CLOCK, gpio); - gpio = new GpiodRegularByLineName(q7s::gpioNames::RS485_EN_RX_DATA, "RS485 Transceiver", - Direction::OUT, Levels::LOW); - gpioRS485Chip->addGpio(gpioIds::RS485_EN_RX_DATA, gpio); - - gpioComIF->addGpios(gpioRS485Chip); -} - -void ObjectFactory::createPlPcduComponents(LinuxLibgpioIF* gpioComIF, SpiComIF* spiComIF, - PowerSwitchIF* pwrSwitcher) { - using namespace gpio; - // Create all GPIO components first - GpioCookie* plPcduGpios = new GpioCookie; - GpiodRegularByLineName* gpio = nullptr; - std::string consumer; - // Switch pins are active high - consumer = "PLPCDU_ENB_VBAT_0"; - gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ENABLE_VBAT0, consumer, Direction::OUT, - gpio::Levels::LOW); - plPcduGpios->addGpio(gpioIds::PLPCDU_ENB_VBAT0, gpio); - consumer = "PLPCDU_ENB_VBAT_1"; - gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ENABLE_VBAT1, consumer, Direction::OUT, - gpio::Levels::LOW); - plPcduGpios->addGpio(gpioIds::PLPCDU_ENB_VBAT1, gpio); - consumer = "PLPCDU_ENB_DRO"; - gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ENABLE_DRO, consumer, Direction::OUT, - gpio::Levels::LOW); - plPcduGpios->addGpio(gpioIds::PLPCDU_ENB_DRO, gpio); - consumer = "PLPCDU_ENB_X8"; - gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ENABLE_X8, consumer, Direction::OUT, - gpio::Levels::LOW); - plPcduGpios->addGpio(gpioIds::PLPCDU_ENB_X8, gpio); - consumer = "PLPCDU_ENB_TX"; - gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ENABLE_TX, consumer, Direction::OUT, - gpio::Levels::LOW); - plPcduGpios->addGpio(gpioIds::PLPCDU_ENB_TX, gpio); - consumer = "PLPCDU_ENB_MPA"; - gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ENABLE_MPA, consumer, Direction::OUT, - gpio::Levels::LOW); - plPcduGpios->addGpio(gpioIds::PLPCDU_ENB_MPA, gpio); - consumer = "PLPCDU_ENB_HPA"; - gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ENABLE_HPA, consumer, Direction::OUT, - gpio::Levels::LOW); - plPcduGpios->addGpio(gpioIds::PLPCDU_ENB_HPA, gpio); - - // Chip select pin is active low - consumer = "PLPCDU_ADC_CS"; - gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ADC_CS, consumer, Direction::OUT, - gpio::Levels::HIGH); - plPcduGpios->addGpio(gpioIds::PLPCDU_ADC_CS, gpio); - gpioComIF->addGpios(plPcduGpios); - SpiCookie* spiCookie = new SpiCookie(addresses::PLPCDU_ADC, gpioIds::PLPCDU_ADC_CS, - q7s::SPI_DEFAULT_DEV, plpcdu::MAX_ADC_REPLY_SIZE, - spi::DEFAULT_MAX_1227_MODE, spi::PL_PCDU_MAX_1227_SPEED); - // Create device handler components - auto plPcduHandler = new PayloadPcduHandler( - objects::PLPCDU_HANDLER, objects::SPI_COM_IF, spiCookie, gpioComIF, SdCardManager::instance(), - pwrSwitcher, pcdu::Switches::PDU2_CH1_PL_PCDU_BATT_0_14V8, - pcdu::Switches::PDU2_CH6_PL_PCDU_BATT_1_14V8, false); - spiCookie->setCallbackMode(PayloadPcduHandler::extConvAsTwoCallback, plPcduHandler); -// plPcduHandler->enablePeriodicPrintout(true, 5); -// static_cast(plPcduHandler); -#if OBSW_TEST_PL_PCDU == 1 - plPcduHandler->setStartUpImmediately(); -#endif -#if OBSW_DEBUG_PL_PCDU == 1 - plPcduHandler->setToGoToNormalModeImmediately(true); - plPcduHandler->enablePeriodicPrintout(true, 10); -#endif -} - -void ObjectFactory::createTestComponents(LinuxLibgpioIF* gpioComIF) { - new Q7STestTask(objects::TEST_TASK); -#if OBSW_ADD_SPI_TEST_CODE == 1 - new SpiTestClass(objects::SPI_TEST, gpioComIF); -#endif -#if OBSW_ADD_I2C_TEST_CODE == 1 - new I2cTestClass(objects::I2C_TEST, q7s::I2C_DEFAULT_DEV); -#endif -#if OBSW_ADD_UART_TEST_CODE == 1 - new UartTestClass(objects::UART_TEST); -#endif -} - -void ObjectFactory::testAcsBrdAss(AcsBoardAssembly* acsAss) { - CommandMessage msg; - ModeMessage::setModeMessage(&msg, ModeMessage::CMD_MODE_COMMAND, DeviceHandlerIF::MODE_NORMAL, - duallane::A_SIDE); - ReturnValue_t result = MessageQueueSenderIF::sendMessage(acsAss->getCommandQueue(), &msg); - if (result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "Sending mode command failed" << std::endl; - } + + createMiscComponents(); } diff --git a/bsp_q7s/fm/CMakeLists.txt b/bsp_q7s/fm/CMakeLists.txt deleted file mode 100644 index 5d20a118..00000000 --- a/bsp_q7s/fm/CMakeLists.txt +++ /dev/null @@ -1,3 +0,0 @@ -target_sources(${OBSW_NAME} PRIVATE - fmObjectFactory.cpp -) diff --git a/bsp_q7s/fmObjectFactory.cpp b/bsp_q7s/fmObjectFactory.cpp new file mode 100644 index 00000000..56c0a62a --- /dev/null +++ b/bsp_q7s/fmObjectFactory.cpp @@ -0,0 +1,66 @@ +#include "OBSWConfig.h" +#include "bsp_q7s/core/CoreController.h" +#include "bsp_q7s/core/ObjectFactory.h" +#include "busConf.h" +#include "commonObjects.h" +#include "devConf.h" +#include "fsfw_hal/linux/gpio/LinuxLibgpioIF.h" +#include "linux/ObjectFactory.h" +#include "linux/callbacks/gpioCallbacks.h" +#include "mission/core/GenericFactory.h" + +void ObjectFactory::produce(void* args) { + ObjectFactory::setStatics(); + HealthTableIF* healthTable = nullptr; + ObjectFactory::produceGenericObjects(&healthTable); + + LinuxLibgpioIF* gpioComIF = nullptr; + UartComIF* uartComIF = nullptr; + SpiComIF* spiMainComIF = nullptr; + I2cComIF* i2cComIF = nullptr; + PowerSwitchIF* pwrSwitcher = nullptr; + SpiComIF* spiRwComIF = nullptr; + createCommunicationInterfaces(&gpioComIF, &uartComIF, &spiMainComIF, &i2cComIF, &spiRwComIF); + createTmpComponents(); + new CoreController(objects::CORE_CONTROLLER); + + gpioCallbacks::disableAllDecoder(gpioComIF); + createPcduComponents(gpioComIF, &pwrSwitcher); + createRadSensorComponent(gpioComIF); + createSunSensorComponents(gpioComIF, spiMainComIF, pwrSwitcher, q7s::SPI_DEFAULT_DEV); + +#if OBSW_ADD_ACS_BOARD == 1 + createAcsBoardComponents(gpioComIF, uartComIF, pwrSwitcher); +#endif + createHeaterComponents(gpioComIF, pwrSwitcher, healthTable); + createSolarArrayDeploymentComponents(); + createPlPcduComponents(gpioComIF, spiMainComIF, pwrSwitcher); +#if OBSW_ADD_SYRLINKS == 1 + createSyrlinksComponents(pwrSwitcher); +#endif /* OBSW_ADD_SYRLINKS == 1 */ + createRtdComponents(q7s::SPI_DEFAULT_DEV, gpioComIF, pwrSwitcher, spiMainComIF); + createPayloadComponents(gpioComIF); + +#if OBSW_ADD_MGT == 1 + createImtqComponents(pwrSwitcher); +#endif + createReactionWheelComponents(gpioComIF, pwrSwitcher); + +#if OBSW_ADD_BPX_BATTERY_HANDLER == 1 + createBpxBatteryComponent(); +#endif + +#if OBSW_ADD_STAR_TRACKER == 1 + createStrComponents(pwrSwitcher); +#endif /* OBSW_ADD_STAR_TRACKER == 1 */ +#if OBSW_USE_CCSDS_IP_CORE == 1 + createCcsdsComponents(gpioComIF); +#endif /* OBSW_USE_CCSDS_IP_CORE == 1 */ + /* Test Task */ +#if OBSW_ADD_TEST_CODE == 1 + createTestComponents(gpioComIF); +#endif /* OBSW_ADD_TEST_CODE == 1 */ + + createMiscComponents(); + createThermalController(); +} diff --git a/bsp_q7s/memory/CMakeLists.txt b/bsp_q7s/memory/CMakeLists.txt index a0d4f66f..d8ba4347 100644 --- a/bsp_q7s/memory/CMakeLists.txt +++ b/bsp_q7s/memory/CMakeLists.txt @@ -1,6 +1,2 @@ -target_sources(${OBSW_NAME} PRIVATE - FileSystemHandler.cpp - SdCardManager.cpp - scratchApi.cpp - FilesystemHelper.cpp -) \ No newline at end of file +target_sources(${OBSW_NAME} PRIVATE FileSystemHandler.cpp SdCardManager.cpp + scratchApi.cpp FilesystemHelper.cpp) diff --git a/bsp_q7s/memory/FileSystemHandler.cpp b/bsp_q7s/memory/FileSystemHandler.cpp index 7a4a791c..33849fbe 100644 --- a/bsp_q7s/memory/FileSystemHandler.cpp +++ b/bsp_q7s/memory/FileSystemHandler.cpp @@ -70,9 +70,8 @@ void FileSystemHandler::fileSystemHandlerLoop() { void FileSystemHandler::fileSystemCheckup() { SdCardManager::SdStatePair statusPair; - sdcMan->getSdCardActiveStatus(statusPair); - sd::SdCard preferredSdCard; - sdcMan->getPreferredSdCard(preferredSdCard); + sdcMan->getSdCardsStatus(statusPair); + sd::SdCard preferredSdCard = sdcMan->getPreferredSdCard(); if ((preferredSdCard == sd::SdCard::SLOT_0) and (statusPair.first == sd::SdState::MOUNTED)) { currentMountPrefix = SdCardManager::SD_0_MOUNT_POINT; } else if ((preferredSdCard == sd::SdCard::SLOT_1) and @@ -109,11 +108,7 @@ ReturnValue_t FileSystemHandler::initialize() { << std::endl; } sdcMan = SdCardManager::instance(); - sd::SdCard preferredSdCard; - ReturnValue_t result = sdcMan->getPreferredSdCard(preferredSdCard); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + sd::SdCard preferredSdCard = sdcMan->getPreferredSdCard(); if (preferredSdCard == sd::SdCard::SLOT_0) { currentMountPrefix = SdCardManager::SD_0_MOUNT_POINT; } else if (preferredSdCard == sd::SdCard::SLOT_1) { diff --git a/bsp_q7s/memory/FilesystemHelper.cpp b/bsp_q7s/memory/FilesystemHelper.cpp index 4b9140f1..c4b8fa16 100644 --- a/bsp_q7s/memory/FilesystemHelper.cpp +++ b/bsp_q7s/memory/FilesystemHelper.cpp @@ -8,8 +8,6 @@ FilesystemHelper::FilesystemHelper() {} -FilesystemHelper::~FilesystemHelper() {} - ReturnValue_t FilesystemHelper::checkPath(std::string path) { SdCardManager* sdcMan = SdCardManager::instance(); if (sdcMan == nullptr) { diff --git a/bsp_q7s/memory/FilesystemHelper.h b/bsp_q7s/memory/FilesystemHelper.h index cb8e27a8..efdf5c6a 100644 --- a/bsp_q7s/memory/FilesystemHelper.h +++ b/bsp_q7s/memory/FilesystemHelper.h @@ -7,7 +7,7 @@ #include "fsfw/returnvalues/HasReturnvaluesIF.h" /** - * @brief This class implements often used functions concerning the file system management. + * @brief This class implements often used functions related to the file system management. * * @author J. Meier */ @@ -20,11 +20,8 @@ class FilesystemHelper : public HasReturnvaluesIF { //! [EXPORT] : [COMMENT] Specified file does not exist on filesystem static const ReturnValue_t FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xA1); - FilesystemHelper(); - virtual ~FilesystemHelper(); - /** - * @brief In case the path points to a directory on the sd card the function checks if the + * @brief In case the path points to a directory on the sd card, the function checks if the * appropriate SD card is mounted. * * @param path Path to check @@ -39,11 +36,14 @@ class FilesystemHelper : public HasReturnvaluesIF { /** * @brief Checks if the file exists on the filesystem. * - * param file File to check + * @param file File to check * - * @return RETURN_OK if fiel exists, otherwise return error code. + * @return RETURN_OK if file exists, otherwise return error code. */ static ReturnValue_t fileExists(std::string file); + + private: + FilesystemHelper(); }; #endif /* BSP_Q7S_MEMORY_FILESYSTEMHELPER_H_ */ diff --git a/bsp_q7s/memory/SdCardManager.cpp b/bsp_q7s/memory/SdCardManager.cpp index 4ca11787..cfd4f490 100644 --- a/bsp_q7s/memory/SdCardManager.cpp +++ b/bsp_q7s/memory/SdCardManager.cpp @@ -16,23 +16,51 @@ #include "linux/utility/utility.h" #include "scratchApi.h" -SdCardManager* SdCardManager::factoryInstance = nullptr; +SdCardManager* SdCardManager::INSTANCE = nullptr; SdCardManager::SdCardManager() : SystemObject(objects::SDC_MANAGER), cmdExecutor(256) { mutex = MutexFactory::instance()->createMutex(); + ReturnValue_t result = mutex->lockMutex(); + if (result != RETURN_OK) { + sif::error << "SdCardManager::SdCardManager: Mutex lock failed" << std::endl; + } + uint8_t prefSdRaw = 0; + result = scratch::readNumber(scratch::PREFERED_SDC_KEY, prefSdRaw); + result = mutex->unlockMutex(); + if (result != RETURN_OK) { + sif::error << "SdCardManager::SdCardManager: Mutex unlock failed" << std::endl; + } + + if (result != HasReturnvaluesIF::RETURN_OK) { + if (result == scratch::KEY_NOT_FOUND) { + sif::warning << "CoreController::sdCardInit: " + "Preferred SD card not set. Setting to 0" + << std::endl; + setPreferredSdCard(sd::SdCard::SLOT_0); + sdInfo.pref = sd::SdCard::SLOT_0; + } else { + // Should not happen. + // TODO: Maybe trigger event? + sif::error << "SdCardManager::SdCardManager: Reading preferred SD card from scratch" + "buffer failed" + << std::endl; + sdInfo.pref = sd::SdCard::SLOT_0; + } + } + sdInfo.pref = static_cast(prefSdRaw); } SdCardManager::~SdCardManager() {} void SdCardManager::create() { - if (factoryInstance == nullptr) { - factoryInstance = new SdCardManager(); + if (INSTANCE == nullptr) { + INSTANCE = new SdCardManager(); } } SdCardManager* SdCardManager::instance() { SdCardManager::create(); - return SdCardManager::factoryInstance; + return SdCardManager::INSTANCE; } ReturnValue_t SdCardManager::switchOnSdCard(sd::SdCard sdCard, bool doMountSdCard, @@ -51,7 +79,7 @@ ReturnValue_t SdCardManager::switchOnSdCard(sd::SdCard sdCard, bool doMountSdCar if (statusPair == nullptr) { sdStatusPtr = std::make_unique(); statusPair = sdStatusPtr.get(); - result = getSdCardActiveStatus(*statusPair); + result = getSdCardsStatus(*statusPair); if (result != HasReturnvaluesIF::RETURN_OK) { return result; } @@ -98,7 +126,7 @@ ReturnValue_t SdCardManager::switchOnSdCard(sd::SdCard sdCard, bool doMountSdCar ReturnValue_t SdCardManager::switchOffSdCard(sd::SdCard sdCard, bool doUnmountSdCard, SdStatePair* statusPair) { std::pair active; - ReturnValue_t result = getSdCardActiveStatus(active); + ReturnValue_t result = getSdCardsStatus(active); if (result != HasReturnvaluesIF::RETURN_OK) { return result; } @@ -165,7 +193,7 @@ ReturnValue_t SdCardManager::setSdCardState(sd::SdCard sdCard, bool on) { return result; } -ReturnValue_t SdCardManager::getSdCardActiveStatus(SdStatePair& active) { +ReturnValue_t SdCardManager::getSdCardsStatus(SdStatePair& active) { using namespace std; MutexGuard mg(mutex); if (not filesystem::exists(SD_STATE_FILE)) { @@ -273,14 +301,14 @@ ReturnValue_t SdCardManager::sanitizeState(SdStatePair* statusPair, sd::SdCard p resetNonBlockingState = true; } if (prefSdCard == sd::SdCard::NONE) { - result = getPreferredSdCard(prefSdCard); + result = getPreferredSdCard(); if (result != HasReturnvaluesIF::RETURN_OK) { } } if (statusPair == nullptr) { sdStatusPtr = std::make_unique(); statusPair = sdStatusPtr.get(); - getSdCardActiveStatus(*statusPair); + getSdCardsStatus(*statusPair); } if (statusPair->first == sd::SdState::ON) { @@ -351,20 +379,21 @@ void SdCardManager::processSdStatusLine(std::pair& act idx++; } -ReturnValue_t SdCardManager::getPreferredSdCard(sd::SdCard& sdCard) const { - uint8_t prefSdCard = 0; - ReturnValue_t result = scratch::readNumber(scratch::PREFERED_SDC_KEY, prefSdCard); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; +sd::SdCard SdCardManager::getPreferredSdCard() const { + MutexGuard mg(mutex); + auto res = mg.getLockResult(); + if (res != RETURN_OK) { + sif::error << "SdCardManager::getPreferredSdCard: Lock error" << std::endl; } - sdCard = static_cast(prefSdCard); - return HasReturnvaluesIF::RETURN_OK; + return sdInfo.pref; } ReturnValue_t SdCardManager::setPreferredSdCard(sd::SdCard sdCard) { + MutexGuard mg(mutex); if (sdCard == sd::SdCard::BOTH) { return HasReturnvaluesIF::RETURN_FAILED; } + sdInfo.pref = sdCard; return scratch::writeNumber(scratch::PREFERED_SDC_KEY, static_cast(sdCard)); } @@ -383,14 +412,9 @@ ReturnValue_t SdCardManager::updateSdCardStateFile() { return result; } -std::string SdCardManager::getCurrentMountPrefix(sd::SdCard prefSdCard) { - if (prefSdCard == sd::SdCard::NONE) { - ReturnValue_t result = getPreferredSdCard(prefSdCard); - if (result != HasReturnvaluesIF::RETURN_OK) { - return SD_0_MOUNT_POINT; - } - } - if (prefSdCard == sd::SdCard::SLOT_0) { +std::string SdCardManager::getCurrentMountPrefix() const { + MutexGuard mg(mutex); + if (sdInfo.active == sd::SdCard::SLOT_0) { return SD_0_MOUNT_POINT; } else { return SD_1_MOUNT_POINT; @@ -443,7 +467,7 @@ void SdCardManager::setPrintCommandOutput(bool print) { this->printCmdOutput = p bool SdCardManager::isSdCardMounted(sd::SdCard sdCard) { SdCardManager::SdStatePair active; - ReturnValue_t result = this->getSdCardActiveStatus(active); + ReturnValue_t result = this->getSdCardsStatus(active); if (result != HasReturnvaluesIF::RETURN_OK) { sif::debug << "SdCardManager::isSdCardMounted: Failed to get SD card active state"; @@ -466,3 +490,68 @@ bool SdCardManager::isSdCardMounted(sd::SdCard sdCard) { } return false; } + +ReturnValue_t SdCardManager::isSdCardMountedReadOnly(sd::SdCard sdcard, bool& readOnly) { + std::ostringstream command; + if (sdcard == sd::SdCard::SLOT_0) { + command << "grep -q '" << SD_0_MOUNT_POINT << " vfat ro,' /proc/mounts"; + } else { + command << "grep -q '" << SD_1_MOUNT_POINT << " vfat ro,' /proc/mounts"; + } + ReturnValue_t result = cmdExecutor.load(command.str(), true, false); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = cmdExecutor.execute(); + if (result != HasReturnvaluesIF::RETURN_OK) { + int exitStatus = cmdExecutor.getLastError(); + if (exitStatus == 1) { + readOnly = false; + return RETURN_OK; + } + return result; + } + auto& readVec = cmdExecutor.getReadVector(); + size_t readLen = strnlen(readVec.data(), readVec.size()); + if (readLen == 0) { + readOnly = false; + } + readOnly = true; + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t SdCardManager::remountReadWrite(sd::SdCard sdcard) { + std::ostringstream command; + if (sdcard == sd::SdCard::SLOT_0) { + command << "mount -o remount,rw " << SD_0_DEV_NAME << " " << SD_0_MOUNT_POINT; + } else { + command << "mount -o remount,rw " << SD_1_DEV_NAME << " " << SD_1_MOUNT_POINT; + } + ReturnValue_t result = cmdExecutor.load(command.str(), true, false); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return cmdExecutor.execute(); +} + +ReturnValue_t SdCardManager::performFsck(sd::SdCard sdcard, bool printOutput, int& linuxError) { + std::ostringstream command; + if (sdcard == sd::SdCard::SLOT_0) { + command << "fsck -y " << SD_0_DEV_NAME; + } else { + command << "fsck -y " << SD_1_DEV_NAME; + } + ReturnValue_t result = cmdExecutor.load(command.str(), true, printOutput); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = cmdExecutor.execute(); + if (result != HasReturnvaluesIF::RETURN_OK) { + linuxError = cmdExecutor.getLastError(); + } + return result; +} + +void SdCardManager::setActiveSdCard(sd::SdCard sdCard) { sdInfo.active = sdCard; } + +sd::SdCard SdCardManager::getActiveSdCard() const { return sdInfo.active; } diff --git a/bsp_q7s/memory/SdCardManager.h b/bsp_q7s/memory/SdCardManager.h index 37660f75..84d2d97b 100644 --- a/bsp_q7s/memory/SdCardManager.h +++ b/bsp_q7s/memory/SdCardManager.h @@ -24,7 +24,7 @@ class MutexIF; * @brief Manages handling of SD cards like switching them on or off or getting the current * state */ -class SdCardManager : public SystemObject, public SdCardMountedIF { +class SdCardManager : public SystemObject, public HasReturnvaluesIF, public SdCardMountedIF { friend class SdCardAccess; public: @@ -36,6 +36,12 @@ class SdCardManager : public SystemObject, public SdCardMountedIF { using SdStatePair = std::pair; + struct SdInfo { + sd::SdCard pref = sd::SdCard::NONE; + sd::SdCard other = sd::SdCard::NONE; + sd::SdCard active = sd::SdCard::NONE; + } sdInfo; + static constexpr uint8_t INTERFACE_ID = CLASS_ID::SD_CARD_MANAGER; static constexpr ReturnValue_t OP_ONGOING = HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 0); @@ -91,7 +97,7 @@ class SdCardManager : public SystemObject, public SdCardMountedIF { * @param sdCard * @return */ - ReturnValue_t getPreferredSdCard(sd::SdCard& sdCard) const override; + sd::SdCard getPreferredSdCard() const override; /** * Switch on the specified SD card. @@ -138,7 +144,7 @@ class SdCardManager : public SystemObject, public SdCardMountedIF { * should call #updateSdCardStateFile again in that case * - STATUS_FILE_NEXISTS if the status file does not exist */ - ReturnValue_t getSdCardActiveStatus(SdStatePair& active); + ReturnValue_t getSdCardsStatus(SdStatePair& active); /** * Mount the specified SD card. This is necessary to use it. @@ -146,6 +152,20 @@ class SdCardManager : public SystemObject, public SdCardMountedIF { * @return */ ReturnValue_t mountSdCard(sd::SdCard sdCard); + + /** + * Set the currently active SD card. This does not necessarily mean that the SD card is on or + * mounted + * @param sdCard + */ + void setActiveSdCard(sd::SdCard sdCard) override; + /** + * Get the currently active SD card. This does not necessarily mean that the SD card is on or + * mounted + * @return + */ + sd::SdCard getActiveSdCard() const override; + /** * Unmount the specified SD card. This is recommended before switching it off. The SD card * can't be used after it has been unmounted. @@ -173,7 +193,7 @@ class SdCardManager : public SystemObject, public SdCardMountedIF { * @param prefSdCardPtr * @return */ - std::string getCurrentMountPrefix(sd::SdCard prefSdCardPtr = sd::SdCard::NONE) override; + std::string getCurrentMountPrefix() const override; OpStatus checkCurrentOp(Operations& currentOp); @@ -194,6 +214,12 @@ class SdCardManager : public SystemObject, public SdCardMountedIF { */ bool isSdCardMounted(sd::SdCard sdCard) override; + ReturnValue_t isSdCardMountedReadOnly(sd::SdCard sdcard, bool& readOnly); + + ReturnValue_t remountReadWrite(sd::SdCard sdcard); + + ReturnValue_t performFsck(sd::SdCard sdcard, bool printOutput, int& linuxError); + private: CommandExecutor cmdExecutor; Operations currentOp = Operations::IDLE; @@ -210,7 +236,7 @@ class SdCardManager : public SystemObject, public SdCardMountedIF { std::string currentPrefix; - static SdCardManager* factoryInstance; + static SdCardManager* INSTANCE; }; #endif /* BSP_Q7S_MEMORY_SDCARDACCESSMANAGER_H_ */ diff --git a/bsp_q7s/memory/scratchApi.h b/bsp_q7s/memory/scratchApi.h index 96264995..cd76fca1 100644 --- a/bsp_q7s/memory/scratchApi.h +++ b/bsp_q7s/memory/scratchApi.h @@ -76,12 +76,12 @@ ReturnValue_t readToFile(std::string name, std::ifstream& file, std::string& fil int result = std::system(oss.str().c_str()); if (result != 0) { if (WEXITSTATUS(result) == 1) { - sif::warning << "scratch::readNumber: Key " << name << " does not exist" << std::endl; + sif::warning << "scratch::readToFile: Key " << name << " does not exist" << std::endl; // Could not find value std::remove(filename.c_str()); return KEY_NOT_FOUND; } else { - utility::handleSystemError(result, "scratch::readNumber"); + utility::handleSystemError(result, "scratch::readToFile"); std::remove(filename.c_str()); return HasReturnvaluesIF::RETURN_FAILED; } diff --git a/bsp_q7s/obsw.cpp b/bsp_q7s/obsw.cpp index 74a1b300..530c4904 100644 --- a/bsp_q7s/obsw.cpp +++ b/bsp_q7s/obsw.cpp @@ -8,14 +8,19 @@ #include "core/InitMission.h" #include "fsfw/tasks/TaskFactory.h" #include "fsfw/version.h" +#include "q7sConfig.h" #include "watchdog/definitions.h" static int OBSW_ALREADY_RUNNING = -2; - +#if OBSW_Q7S_EM == 0 +static const char* DEV_STRING = "Xiphos Q7S FM"; +#else +static const char* DEV_STRING = "Xiphos Q7S EM"; +#endif int obsw::obsw() { using namespace fsfw; std::cout << "-- EIVE OBSW --" << std::endl; - std::cout << "-- Compiled for Linux (Xiphos Q7S) --" << std::endl; + std::cout << "-- Compiled for Linux (" << DEV_STRING << ") --" << std::endl; std::cout << "-- OBSW v" << common::OBSW_VERSION << " | FSFW v" << fsfw::FSFW_VERSION << " --" << std::endl; std::cout << "-- " << __DATE__ << " " << __TIME__ << " --" << std::endl; diff --git a/bsp_q7s/simple/CMakeLists.txt b/bsp_q7s/simple/CMakeLists.txt index 77cbd076..b5c44433 100644 --- a/bsp_q7s/simple/CMakeLists.txt +++ b/bsp_q7s/simple/CMakeLists.txt @@ -1,3 +1 @@ -target_sources(${SIMPLE_OBSW_NAME} PRIVATE - simple.cpp -) +target_sources(${SIMPLE_OBSW_NAME} PRIVATE simple.cpp) diff --git a/bsp_q7s/xadc/CMakeLists.txt b/bsp_q7s/xadc/CMakeLists.txt index 0f2ea7df..a8d61811 100644 --- a/bsp_q7s/xadc/CMakeLists.txt +++ b/bsp_q7s/xadc/CMakeLists.txt @@ -1,3 +1 @@ -target_sources(${OBSW_NAME} PRIVATE - Xadc.cpp -) \ No newline at end of file +target_sources(${OBSW_NAME} PRIVATE Xadc.cpp) diff --git a/bsp_te0720_1cfa/InitMission.cpp b/bsp_te0720_1cfa/InitMission.cpp index f1809bca..dd6a3aa0 100644 --- a/bsp_te0720_1cfa/InitMission.cpp +++ b/bsp_te0720_1cfa/InitMission.cpp @@ -89,13 +89,42 @@ void initmission::initTasks() { } pstTasks.push_back(pst); +#if OBSW_ADD_PLOC_MPSOC == 1 PeriodicTaskIF* mpsocHelperTask = factory->createPeriodicTask( "PLOC_MPSOC_HELPER", 20, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); result = mpsocHelperTask->addComponent(objects::PLOC_MPSOC_HELPER); if (result != HasReturnvaluesIF::RETURN_OK) { initmission::printAddObjectError("PLOC_MPSOC_HELPER", objects::PLOC_MPSOC_HELPER); } - pstTasks.push_back(mpsocHelperTask); +#endif /* OBSW_ADD_PLOC_MPSOC == 1*/ + +#if OBSW_ADD_PLOC_SUPERVISOR == 1 + PeriodicTaskIF* supvHelperTask = factory->createPeriodicTask( + "PLOC_SUPV_HELPER", 20, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); + result = supvHelperTask->addComponent(objects::PLOC_SUPERVISOR_HELPER); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PLOC_SUPV_HELPER", objects::PLOC_SUPERVISOR_HELPER); + } +#endif /* OBSW_ADD_PLOC_SUPERVISOR == 1 */ + +#if OBSW_USE_CCSDS_IP_CORE == 1 + PeriodicTaskIF* ccsdsHandlerTask = factory->createPeriodicTask( + "CCSDS_HANDLER", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); + result = ccsdsHandlerTask->addComponent(objects::CCSDS_HANDLER); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("CCSDS Handler", objects::CCSDS_HANDLER); + } + + // Minimal distance between two received TCs amounts to 0.6 seconds + // If a command has not been read before the next one arrives, the old command will be + // overwritten by the PDEC. + PeriodicTaskIF* pdecHandlerTask = factory->createPeriodicTask( + "PDEC_HANDLER", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, missedDeadlineFunc); + result = pdecHandlerTask->addComponent(objects::PDEC_HANDLER); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PDEC Handler", objects::PDEC_HANDLER); + } +#endif /* OBSW_USE_CCSDS_IP_CORE == 1 */ auto taskStarter = [](std::vector& taskVector, std::string name) { for (const auto& task : taskVector) { @@ -111,6 +140,16 @@ void initmission::initTasks() { tmtcDistributor->startTask(); tmtcBridgeTask->startTask(); tmtcPollingTask->startTask(); +#if OBSW_USE_CCSDS_IP_CORE == 1 + pdecHandlerTask->startTask(); + ccsdsHandlerTask->startTask(); +#endif /* #if OBSW_USE_CCSDS_IP_CORE == 1 */ +#if OBSW_ADD_PLOC_SUPERVISOR == 1 + supvHelperTask->startTask(); +#endif /* OBSW_ADD_PLOC_SUPERVISOR == 1 */ +#if OBSW_ADD_PLOC_MPSOC == 1 + mpsocHelperTask->startTask(); +#endif /* OBSW_ADD_PLOC_MPSOC == 1 */ taskStarter(pstTasks, "PST Tasks"); taskStarter(pusTasks, "PUS Tasks"); diff --git a/bsp_te0720_1cfa/InitMission.h b/bsp_te0720_1cfa/InitMission.h index c3ba58ec..a939987f 100644 --- a/bsp_te0720_1cfa/InitMission.h +++ b/bsp_te0720_1cfa/InitMission.h @@ -3,7 +3,7 @@ #include -#include "fsfw/tasks/Typedef.h" +#include "fsfw/tasks/definitions.h" class PeriodicTaskIF; class TaskFactory; diff --git a/bsp_te0720_1cfa/OBSWConfig.h.in b/bsp_te0720_1cfa/OBSWConfig.h.in index 14867682..2f887daa 100644 --- a/bsp_te0720_1cfa/OBSWConfig.h.in +++ b/bsp_te0720_1cfa/OBSWConfig.h.in @@ -37,7 +37,6 @@ #define OBSW_ENABLE_SYRLINKS_TRANSMIT_TIMEOUT 0 #define OBSW_SYRLINKS_SIMULATED 1 #define OBSW_STAR_TRACKER_GROUND_CONFIG 1 -#define OBSW_ENABLE_PERIODIC_HK 0 #define OBSW_PRINT_CORE_HK 0 #define OBSW_INITIALIZE_SWITCHES 0 diff --git a/bsp_te0720_1cfa/ObjectFactory.cpp b/bsp_te0720_1cfa/ObjectFactory.cpp index eb6c4fa4..fe699e50 100644 --- a/bsp_te0720_1cfa/ObjectFactory.cpp +++ b/bsp_te0720_1cfa/ObjectFactory.cpp @@ -1,27 +1,38 @@ #include "ObjectFactory.h" -#include -#include "fsfw_hal/linux/uart/UartComIF.h" -#include "fsfw_hal/linux/i2c/I2cComIF.h" -#include "fsfw_hal/linux/uart/UartCookie.h" - #include "OBSWConfig.h" #include "busConf.h" #include "devConf.h" +#include "ccsdsConfig.h" +#include "devices/addresses.h" +#include "devices/gpioIds.h" #include "fsfw/datapoollocal/LocalDataPoolManager.h" #include "fsfw/tmtcpacket/pus/tm.h" #include "fsfw/tmtcservices/CommandingServiceBase.h" #include "fsfw/tmtcservices/PusServiceBase.h" +#include "fsfw_hal/linux/i2c/I2cComIF.h" #include "fsfw_hal/linux/i2c/I2cCookie.h" +#include "fsfw_hal/linux/uart/UartComIF.h" +#include "fsfw_hal/linux/uart/UartCookie.h" +#include "fsfw_hal/common/gpio/GpioCookie.h" +#include "linux/ObjectFactory.h" #include "linux/devices/ploc/PlocMPSoCHandler.h" #include "linux/devices/ploc/PlocMPSoCHelper.h" -#include "mission/devices/Tmp1075Handler.h" +#include "linux/devices/ploc/PlocMemoryDumper.h" +#include "linux/devices/ploc/PlocSupervisorHandler.h" +#include "linux/devices/ploc/PlocSupvHelper.h" +#include "linux/obc/AxiPtmeConfig.h" +#include "linux/obc/PapbVcInterface.h" +#include "linux/obc/PdecHandler.h" +#include "linux/obc/Ptme.h" +#include "linux/obc/PtmeConfig.h" #include "mission/core/GenericFactory.h" -#include "mission/utility/TmFunnel.h" -#include "test/gpio/DummyGpioIF.h" +#include "mission/devices/Tmp1075Handler.h" +#include "mission/tmtc/TmFunnel.h" +#include "mission/tmtc/CCSDSHandler.h" +#include "mission/tmtc/VirtualChannel.h" #include "objects/systemObjectList.h" -#include "devices/addresses.h" -#include "devices/gpioIds.h" +#include "test/gpio/DummyGpioIF.h" #include "tmtc/apid.h" #include "tmtc/pusIds.h" @@ -32,7 +43,11 @@ void Factory::setStaticFrameworkObjectIds() { CommandingServiceBase::defaultPacketSource = objects::PUS_PACKET_DISTRIBUTOR; CommandingServiceBase::defaultPacketDestination = objects::TM_FUNNEL; +#if OBSW_TM_TO_PTME == 1 + TmFunnel::downlinkDestination = objects::CCSDS_HANDLER; +#else TmFunnel::downlinkDestination = objects::TMTC_BRIDGE; +#endif TmFunnel::storageDestination = objects::NO_OBJECT; VerificationReporter::messageReceiver = objects::PUS_SERVICE_1_VERIFICATION; @@ -43,12 +58,14 @@ void ObjectFactory::produce(void* args) { Factory::setStaticFrameworkObjectIds(); ObjectFactory::produceGenericObjects(); + LinuxLibgpioIF* gpioComIF = new LinuxLibgpioIF(objects::GPIO_IF);; + new UartComIF(objects::UART_COM_IF); + #if OBSW_ADD_PLOC_MPSOC == 1 UartCookie* mpsocUartCookie = new UartCookie(objects::PLOC_MPSOC_HANDLER, te0720_1cfa::MPSOC_UART, uart::PLOC_MPSOC_BAUD, mpsoc::MAX_REPLY_SIZE); mpsocUartCookie->setNoFixedSizeReply(); PlocMPSoCHelper* plocMpsocHelper = new PlocMPSoCHelper(objects::PLOC_MPSOC_HELPER); - new UartComIF(objects::UART_COM_IF); auto dummyGpioIF = new DummyGpioIF(); PlocMPSoCHandler* plocMPSoCHandler = new PlocMPSoCHandler( objects::PLOC_MPSOC_HANDLER, objects::UART_COM_IF, mpsocUartCookie, plocMpsocHelper, @@ -56,6 +73,21 @@ void ObjectFactory::produce(void* args) { plocMPSoCHandler->setStartUpImmediately(); #endif /* OBSW_ADD_PLOC_MPSOC == 1 */ +#if OBSW_ADD_PLOC_SUPERVISOR == 1 + UartCookie* supervisorCookie = + new UartCookie(objects::PLOC_SUPERVISOR_HANDLER, std::string("/dev/ttyPS1"), + uart::PLOC_SUPV_BAUD, supv::MAX_PACKET_SIZE * 20); + supervisorCookie->setNoFixedSizeReply(); + auto supvGpioIF = new DummyGpioIF(); + auto supvHelper = new PlocSupvHelper(objects::PLOC_SUPERVISOR_HELPER); + new PlocSupervisorHandler(objects::PLOC_SUPERVISOR_HANDLER, objects::UART_COM_IF, + supervisorCookie, Gpio(gpioIds::ENABLE_SUPV_UART, supvGpioIF), + pcdu::PDU1_CH6_PLOC_12V, supvHelper); + +#endif + + new PlocMemoryDumper(objects::PLOC_MEMORY_DUMPER); + #if OBSW_TEST_LIBGPIOD == 1 #if OBSW_TEST_GPIO_OPEN_BYLABEL == 1 /* Configure MIO0 as input */ @@ -86,21 +118,6 @@ void ObjectFactory::produce(void* args) { new SusHandler(objects::SUS_0, objects::SPI_COM_IF, spiCookieSus, gpioComIF, gpioIds::CS_SUS_0); #endif -#if OBSW_TEST_CCSDS_BRIDGE == 1 - GpioCookie* gpioCookieCcsdsIp = new GpioCookie; - GpiodRegular* papbBusyN = - new GpiodRegular(std::string("gpiochip0"), 0, std::string("PAPBBusy_VC0")); - gpioCookieCcsdsIp->addGpio(gpioIds::PAPB_BUSY_N, papbBusyN); - GpiodRegular* papbEmpty = - new GpiodRegular(std::string("gpiochip0"), 1, std::string("PAPBEmpty_VC0")); - gpioCookieCcsdsIp->addGpio(gpioIds::PAPB_EMPTY, papbEmpty); - gpioComIF->addGpios(gpioCookieCcsdsIp); - - new CCSDSIPCoreBridge(objects::CCSDS_IP_CORE_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR, - objects::TM_STORE, objects::TC_STORE, gpioComIF, std::string("/dev/uio0"), - gpioIds::PAPB_BUSY_N, gpioIds::PAPB_EMPTY); -#endif - #if OBSW_TEST_RAD_SENSOR == 1 GpioCookie* gpioCookieRadSensor = new GpioCookie; GpiodRegular* chipSelectRadSensor = new GpiodRegular( @@ -124,28 +141,19 @@ void ObjectFactory::produce(void* args) { GpioCookie* gpioCookie = new GpioCookie; gpioCookie->addGpio(gpioIds::HEATER_0, heaterGpio); new HeaterHandler(objects::HEATER_HANDLER, objects::GPIO_IF, gpioCookie, objects::PCDU_HANDLER, - pcduSwitches::TCS_BOARD_8V_HEATER_IN); + pcdu::TCS_BOARD_8V_HEATER_IN); #endif -#if OBSW_ADD_PLOC_SUPERVISOR == 1 - /* Configuration for MIO0 on TE0720-03-1CFA */ - UartCookie* plocSupervisorCookie = - new UartCookie(objects::PLOC_SUPERVISOR_HANDLER, std::string("/dev/ttyPS1"), - UartModes::NON_CANONICAL, 115200, PLOC_SPV::MAX_PACKET_SIZE * 20); - plocSupervisorCookie->setNoFixedSizeReply(); - PlocSupervisorHandler* plocSupervisor = new PlocSupervisorHandler( - objects::PLOC_SUPERVISOR_HANDLER, objects::UART_COM_IF, plocSupervisorCookie); - plocSupervisor->setStartUpImmediately(); -#endif + new I2cComIF(objects::I2C_COM_IF); -new I2cComIF(objects::I2C_COM_IF); + I2cCookie* i2cCookieTmp1075tcs1 = + new I2cCookie(addresses::TMP1075_TCS_1, TMP1075::MAX_REPLY_LENGTH, std::string("/dev/i2c-0")); + I2cCookie* i2cCookieTmp1075tcs2 = + new I2cCookie(addresses::TMP1075_TCS_2, TMP1075::MAX_REPLY_LENGTH, std::string("/dev/i2c-0")); -I2cCookie* i2cCookieTmp1075tcs1 = - new I2cCookie(addresses::TMP1075_TCS_1, TMP1075::MAX_REPLY_LENGTH, std::string("/dev/i2c-0")); -I2cCookie* i2cCookieTmp1075tcs2 = - new I2cCookie(addresses::TMP1075_TCS_2, TMP1075::MAX_REPLY_LENGTH, std::string("/dev/i2c-0")); + /* Temperature sensors */ + new Tmp1075Handler(objects::TMP1075_HANDLER_1, objects::I2C_COM_IF, i2cCookieTmp1075tcs1); + new Tmp1075Handler(objects::TMP1075_HANDLER_2, objects::I2C_COM_IF, i2cCookieTmp1075tcs2); -/* Temperature sensors */ -new Tmp1075Handler(objects::TMP1075_HANDLER_1, objects::I2C_COM_IF, i2cCookieTmp1075tcs1); -new Tmp1075Handler(objects::TMP1075_HANDLER_2, objects::I2C_COM_IF, i2cCookieTmp1075tcs2); + static_cast(gpioComIF); } diff --git a/bsp_te0720_1cfa/ObjectFactory.h b/bsp_te0720_1cfa/ObjectFactory.h index b24dd321..828f5d36 100644 --- a/bsp_te0720_1cfa/ObjectFactory.h +++ b/bsp_te0720_1cfa/ObjectFactory.h @@ -1,7 +1,11 @@ #ifndef BSP_LINUX_OBJECTFACTORY_H_ #define BSP_LINUX_OBJECTFACTORY_H_ +#include +#include + namespace ObjectFactory { +static const uint32_t TRANSMITTER_TIMEOUT = 86400000; // 1 day void produce(void* args); }; // namespace ObjectFactory diff --git a/bsp_te0720_1cfa/boardconfig/busConf.h b/bsp_te0720_1cfa/boardconfig/busConf.h index 893014c1..7b51ab3e 100644 --- a/bsp_te0720_1cfa/boardconfig/busConf.h +++ b/bsp_te0720_1cfa/boardconfig/busConf.h @@ -3,9 +3,37 @@ namespace te0720_1cfa { static constexpr char MPSOC_UART[] = "/dev/ttyPS1"; -namespace baudrate { +static constexpr char UIO_PDEC_REGISTERS[] = "/dev/uio0"; +static constexpr char UIO_PTME[] = "/dev/uio1"; +static constexpr char UIO_PDEC_CONFIG_MEMORY[] = "/dev/uio2"; +static constexpr char UIO_PDEC_RAM[] = "/dev/uio3"; +static constexpr int MAP_ID_PTME_CONFIG = 3; + +namespace uiomapids { +static const int PTME_VC0 = 0; +static const int PTME_VC1 = 1; +static const int PTME_VC2 = 2; +static const int PTME_VC3 = 3; +static const int PTME_CONFIG = 4; +} // namespace uiomapids + +namespace gpioNames { + static constexpr char PAPB_BUSY_SIGNAL_VC0[] = "papb_busy_signal_vc0"; + static constexpr char PAPB_EMPTY_SIGNAL_VC0[] = "papb_empty_signal_vc0"; + static constexpr char PAPB_BUSY_SIGNAL_VC1[] = "papb_busy_signal_vc1"; + static constexpr char PAPB_EMPTY_SIGNAL_VC1[] = "papb_empty_signal_vc1"; + static constexpr char PAPB_BUSY_SIGNAL_VC2[] = "papb_busy_signal_vc2"; + static constexpr char PAPB_EMPTY_SIGNAL_VC2[] = "papb_empty_signal_vc2"; + static constexpr char PAPB_BUSY_SIGNAL_VC3[] = "papb_busy_signal_vc3"; + static constexpr char PAPB_EMPTY_SIGNAL_VC3[] = "papb_empty_signal_vc3"; + static constexpr char RS485_EN_TX_CLOCK[] = "tx_clock_enable_ltc2872"; + static constexpr char RS485_EN_TX_DATA[] = "tx_data_enable_ltc2872"; + static constexpr char RS485_EN_RX_CLOCK[] = "rx_clock_enable_ltc2872"; + static constexpr char RS485_EN_RX_DATA[] = "rx_data_enable_ltc2872"; + static constexpr char PDEC_RESET[] = "pdec_reset"; } + } #endif /* BSP_EGSE_BOARDCONFIG_BUSCONF_H_ */ diff --git a/cmake/HardwareOsPostConfig.cmake b/cmake/HardwareOsPostConfig.cmake index 5146de98..111e859a 100644 --- a/cmake/HardwareOsPostConfig.cmake +++ b/cmake/HardwareOsPostConfig.cmake @@ -33,6 +33,10 @@ add_compile_options( set(STRIPPED_OBSW_NAME ${OBSW_BIN_NAME}-stripped) set(STRIPPED_WATCHDOG_NAME eive-watchdog-stripped) +if(EIVE_CREATE_UNIQUE_OBSW_BIN) + set(UNIQUE_OBSW_BIN_NAME ${OBSW_BIN_NAME}-$ENV{USERNAME}) +endif() + add_custom_command( TARGET ${OBSW_NAME} POST_BUILD @@ -41,6 +45,16 @@ add_custom_command( COMMENT "Generating stripped executable ${STRIPPED_OBSW_NAME}.." ) +if(UNIQUE_OBSW_BIN_NAME) + add_custom_command( + TARGET ${OBSW_NAME} + POST_BUILD + COMMAND ${CMAKE_COMMAND} -E copy + ${CMAKE_CURRENT_BINARY_DIR}/${OBSW_BIN_NAME} + ${CMAKE_CURRENT_BINARY_DIR}/${UNIQUE_OBSW_BIN_NAME} + COMMENT "Generating unique EIVE OBSW binary ${UNIQUE_OBSW_BIN_NAME}") +endif() + add_custom_command( TARGET ${WATCHDOG_NAME} POST_BUILD diff --git a/cmake/scripts/q7s/q7s-make-release.sh b/cmake/scripts/q7s/q7s-make-release.sh index d9b74bc3..b86ca873 100755 --- a/cmake/scripts/q7s/q7s-make-release.sh +++ b/cmake/scripts/q7s/q7s-make-release.sh @@ -20,7 +20,7 @@ else cfg_script_name="${EIVE_OBSW_ROOT}/cmake/scripts/${cfg_script_name}" fi -if [[ -z "${EIVE_Q7S_EM}" ]]; then +if [ ! -z "${EIVE_Q7S_EM}" ]; then build_defs="EIVE_Q7S_EM=ON" fi diff --git a/cmake/scripts/q7s/q7s-ninja-debug.sh b/cmake/scripts/q7s/q7s-ninja-debug.sh index bf880a28..ad50b6a6 100755 --- a/cmake/scripts/q7s/q7s-ninja-debug.sh +++ b/cmake/scripts/q7s/q7s-ninja-debug.sh @@ -20,7 +20,7 @@ else cfg_script_name="${EIVE_OBSW_ROOT}/cmake/scripts/${cfg_script_name}" fi -if [[ -z "${EIVE_Q7S_EM}" ]]; then +if [ ! -z "${EIVE_Q7S_EM}" ]; then build_defs="EIVE_Q7S_EM=ON" fi diff --git a/cmake/scripts/q7s/q7s-ninja-release.sh b/cmake/scripts/q7s/q7s-ninja-release.sh index 4dfaa210..f0587f5c 100755 --- a/cmake/scripts/q7s/q7s-ninja-release.sh +++ b/cmake/scripts/q7s/q7s-ninja-release.sh @@ -20,7 +20,7 @@ else cfg_script_name="${EIVE_OBSW_ROOT}/cmake/scripts/${cfg_script_name}" fi -if [[ -z "${EIVE_Q7S_EM}" ]]; then +if [ ! -z "${EIVE_Q7S_EM}" ]; then build_defs="EIVE_Q7S_EM=ON" fi diff --git a/common/config/CMakeLists.txt b/common/config/CMakeLists.txt index 00848561..ca296222 100644 --- a/common/config/CMakeLists.txt +++ b/common/config/CMakeLists.txt @@ -1,7 +1,3 @@ -target_include_directories(${OBSW_NAME} PRIVATE - ${CMAKE_CURRENT_SOURCE_DIR} -) +target_include_directories(${OBSW_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}) -target_sources(${OBSW_NAME} PRIVATE - commonConfig.cpp -) \ No newline at end of file +target_sources(${OBSW_NAME} PRIVATE commonConfig.cpp) diff --git a/common/config/OBSWVersion.h b/common/config/OBSWVersion.h index 1e5dd04b..1ec87590 100644 --- a/common/config/OBSWVersion.h +++ b/common/config/OBSWVersion.h @@ -4,7 +4,7 @@ const char* const SW_NAME = "eive"; #define SW_VERSION 1 -#define SW_SUBVERSION 10 -#define SW_REVISION 1 +#define SW_SUBVERSION 12 +#define SW_REVISION 0 #endif /* COMMON_CONFIG_OBSWVERSION_H_ */ diff --git a/common/config/ccsdsConfig.h b/common/config/ccsdsConfig.h index 8466a9fa..9736ae56 100644 --- a/common/config/ccsdsConfig.h +++ b/common/config/ccsdsConfig.h @@ -2,14 +2,7 @@ #define COMMON_CONFIG_CCSDSCONFIG_H_ namespace ccsds { -enum { - VC0, - VC1, - VC2, - VC3 -}; +enum { VC0, VC1, VC2, VC3 }; } - - #endif /* COMMON_CONFIG_CCSDSCONFIG_H_ */ diff --git a/common/config/commonClassIds.h b/common/config/commonClassIds.h index 03d51888..aeb05815 100644 --- a/common/config/commonClassIds.h +++ b/common/config/commonClassIds.h @@ -2,37 +2,40 @@ #define COMMON_CONFIG_COMMONCLASSIDS_H_ #include + #include namespace CLASS_ID { -enum commonClassIds: uint8_t { - COMMON_CLASS_ID_START = FW_CLASS_ID_COUNT, - PCDU_HANDLER, //PCDU - HEATER_HANDLER, //HEATER - SYRLINKS_HANDLER, //SYRLINKS - IMTQ_HANDLER, //IMTQ - RW_HANDLER, //RWHA - STR_HANDLER, //STRH - DWLPWRON_CMD, //DWLPWRON - MPSOC_TM, //MPTM - PLOC_SUPERVISOR_HANDLER, //PLSV - SUS_HANDLER, //SUSS - CCSDS_IP_CORE_BRIDGE, //IPCI - PTME, //PTME - PLOC_UPDATER, //PLUD - STR_HELPER, //STRHLP - GOM_SPACE_HANDLER, //GOMS - PLOC_MEMORY_DUMPER, //PLMEMDUMP - PDEC_HANDLER, //PDEC - CCSDS_HANDLER, //CCSDS - RATE_SETTER, //RS - ARCSEC_JSON_BASE, //JSONBASE - NVM_PARAM_BASE, //NVMB - FILE_SYSTEM_HELPER, //FSHLP - PLOC_MPSOC_HELPER, // PLMPHLP - SA_DEPL_HANDLER, //SADPL - MPSOC_RETURN_VALUES_IF, //MPSOCRTVIF - COMMON_CLASS_ID_END // [EXPORT] : [END] +enum commonClassIds : uint8_t { + COMMON_CLASS_ID_START = FW_CLASS_ID_COUNT, + PCDU_HANDLER, // PCDU + HEATER_HANDLER, // HEATER + SYRLINKS_HANDLER, // SYRLINKS + IMTQ_HANDLER, // IMTQ + RW_HANDLER, // RWHA + STR_HANDLER, // STRH + DWLPWRON_CMD, // DWLPWRON + MPSOC_TM, // MPTM + PLOC_SUPERVISOR_HANDLER, // PLSV + PLOC_SUPV_HELPER, // PLSPVhLP + SUS_HANDLER, // SUSS + CCSDS_IP_CORE_BRIDGE, // IPCI + PTME, // PTME + PLOC_UPDATER, // PLUD + STR_HELPER, // STRHLP + GOM_SPACE_HANDLER, // GOMS + PLOC_MEMORY_DUMPER, // PLMEMDUMP + PDEC_HANDLER, // PDEC + CCSDS_HANDLER, // CCSDS + RATE_SETTER, // RS + ARCSEC_JSON_BASE, // JSONBASE + NVM_PARAM_BASE, // NVMB + FILE_SYSTEM_HELPER, // FSHLP + PLOC_MPSOC_HELPER, // PLMPHLP + SA_DEPL_HANDLER, // SADPL + MPSOC_RETURN_VALUES_IF, // MPSOCRTVIF + SUPV_RETURN_VALUES_IF, // SPVRTVIF + COMMON_CLASS_ID_END // [EXPORT] : [END] }; } diff --git a/common/config/commonConfig.cpp b/common/config/commonConfig.cpp index cb2b9666..0fd78a61 100644 --- a/common/config/commonConfig.cpp +++ b/common/config/commonConfig.cpp @@ -1,6 +1,8 @@ #include "commonConfig.h" -#include "tmtc/apid.h" -#include "fsfw/tmtcpacket/SpacePacket.h" -const Version common::OBSW_VERSION { OBSW_VERSION_MAJOR, OBSW_VERSION_MINOR, OBSW_VERSION_REVISION, OBSW_VERSION_CST_GIT_SHA1 }; +#include "fsfw/tmtcpacket/SpacePacket.h" +#include "tmtc/apid.h" + +const fsfw::Version common::OBSW_VERSION{OBSW_VERSION_MAJOR, OBSW_VERSION_MINOR, + OBSW_VERSION_REVISION, OBSW_VERSION_CST_GIT_SHA1}; const uint16_t common::PUS_PACKET_ID = spacepacket::getTcSpacePacketIdFromApid(apid::EIVE_OBSW); diff --git a/common/config/commonConfig.h.in b/common/config/commonConfig.h.in index ebd6563b..9581e751 100644 --- a/common/config/commonConfig.h.in +++ b/common/config/commonConfig.h.in @@ -33,7 +33,10 @@ static constexpr uint8_t OBSW_VERSION_REVISION = @OBSW_VERSION_REVISION@; // CST: Commits since tag static const char OBSW_VERSION_CST_GIT_SHA1[] = "@OBSW_VERSION_CST_GIT_SHA1@"; -extern const Version OBSW_VERSION; + +static constexpr uint32_t OBSW_MAX_SCHEDULED_TCS = @OBSW_MAX_SCHEDULED_TCS@; + +extern const fsfw::Version OBSW_VERSION; extern const uint16_t PUS_PACKET_ID; diff --git a/common/config/commonObjects.h b/common/config/commonObjects.h index a4f3319e..4a4594f4 100644 --- a/common/config/commonObjects.h +++ b/common/config/commonObjects.h @@ -4,102 +4,125 @@ #include namespace objects { -enum commonObjects: uint32_t { - /* First Byte 0x50-0x52 reserved for PUS Services **/ - CCSDS_PACKET_DISTRIBUTOR = 0x50000100, - PUS_PACKET_DISTRIBUTOR = 0x50000200, - TMTC_BRIDGE = 0x50000300, - TMTC_POLLING_TASK = 0x50000400, - FILE_SYSTEM_HANDLER = 0x50000500, - SDC_MANAGER = 0x50000550, - PTME = 0x50000600, - PDEC_HANDLER = 0x50000700, - CCSDS_HANDLER = 0x50000800, +enum commonObjects : uint32_t { + /* First Byte 0x50-0x52 reserved for PUS Services **/ + CCSDS_PACKET_DISTRIBUTOR = 0x50000100, + PUS_PACKET_DISTRIBUTOR = 0x50000200, + TMTC_BRIDGE = 0x50000300, + TMTC_POLLING_TASK = 0x50000400, + FILE_SYSTEM_HANDLER = 0x50000500, + SDC_MANAGER = 0x50000550, + PTME = 0x50000600, + PDEC_HANDLER = 0x50000700, + CCSDS_HANDLER = 0x50000800, - /* 0x43 ('C') for Controllers */ - THERMAL_CONTROLLER = 0x43400001, - ACS_CONTROLLER = 0x43100002, - CORE_CONTROLLER = 0x43000003, + /* 0x43 ('C') for Controllers */ + THERMAL_CONTROLLER = 0x43400001, + ACS_CONTROLLER = 0x43100002, + CORE_CONTROLLER = 0x43000003, - /* 0x44 ('D') for device handlers */ - P60DOCK_HANDLER = 0x44250000, - PDU1_HANDLER = 0x44250001, - PDU2_HANDLER = 0x44250002, - ACU_HANDLER = 0x44250003, - BPX_BATT_HANDLER = 0x44260000, - TMP1075_HANDLER_1 = 0x44420004, - TMP1075_HANDLER_2 = 0x44420005, - MGM_0_LIS3_HANDLER = 0x44120006, - MGM_1_RM3100_HANDLER = 0x44120107, - MGM_2_LIS3_HANDLER = 0x44120208, - MGM_3_RM3100_HANDLER = 0x44120309, - GYRO_0_ADIS_HANDLER = 0x44120010, - GYRO_1_L3G_HANDLER = 0x44120111, - GYRO_2_ADIS_HANDLER = 0x44120212, - GYRO_3_L3G_HANDLER = 0x44120313, - PLPCDU_HANDLER = 0x44300000, + /* 0x44 ('D') for device handlers */ + MGM_0_LIS3_HANDLER = 0x44120006, + MGM_1_RM3100_HANDLER = 0x44120107, + MGM_2_LIS3_HANDLER = 0x44120208, + MGM_3_RM3100_HANDLER = 0x44120309, + GYRO_0_ADIS_HANDLER = 0x44120010, + GYRO_1_L3G_HANDLER = 0x44120111, + GYRO_2_ADIS_HANDLER = 0x44120212, + GYRO_3_L3G_HANDLER = 0x44120313, + RW1 = 0x44120047, + RW2 = 0x44120148, + RW3 = 0x44120249, + RW4 = 0x44120350, + STAR_TRACKER = 0x44130001, + GPS_CONTROLLER = 0x44130045, - IMTQ_HANDLER = 0x44140014, - PLOC_MPSOC_HANDLER = 0x44330015, - PLOC_SUPERVISOR_HANDLER = 0x44330016, - PLOC_SUPERVISOR_HELPER = 0x44330017, + IMTQ_HANDLER = 0x44140014, + TMP1075_HANDLER_1 = 0x44420004, + TMP1075_HANDLER_2 = 0x44420005, + PCDU_HANDLER = 0x442000A1, + P60DOCK_HANDLER = 0x44250000, + PDU1_HANDLER = 0x44250001, + PDU2_HANDLER = 0x44250002, + ACU_HANDLER = 0x44250003, + BPX_BATT_HANDLER = 0x44260000, + PLPCDU_HANDLER = 0x44300000, + RAD_SENSOR = 0x443200A5, + PLOC_UPDATER = 0x44330000, + PLOC_MEMORY_DUMPER = 0x44330001, + STR_HELPER = 0x44330002, + PLOC_MPSOC_HELPER = 0x44330003, + AXI_PTME_CONFIG = 0x44330004, + PTME_CONFIG = 0x44330005, + PLOC_MPSOC_HANDLER = 0x44330015, + PLOC_SUPERVISOR_HANDLER = 0x44330016, + PLOC_SUPERVISOR_HELPER = 0x44330017, + SOLAR_ARRAY_DEPL_HANDLER = 0x444100A2, + HEATER_HANDLER = 0x444100A4, - /** - * Not yet specified which pt1000 will measure which device/location in the satellite. - * Therefore object ids are named according to the IC naming of the RTDs in the schematic. - */ - RTD_IC_3 = 0x44420016, - RTD_IC_4 = 0x44420017, - RTD_IC_5 = 0x44420018, - RTD_IC_6 = 0x44420019, - RTD_IC_7 = 0x44420020, - RTD_IC_8 = 0x44420021, - RTD_IC_9 = 0x44420022, - RTD_IC_10 = 0x44420023, - RTD_IC_11 = 0x44420024, - RTD_IC_12 = 0x44420025, - RTD_IC_13 = 0x44420026, - RTD_IC_14 = 0x44420027, - RTD_IC_15 = 0x44420028, - RTD_IC_16 = 0x44420029, - RTD_IC_17 = 0x44420030, - RTD_IC_18 = 0x44420031, + /** + * Not yet specified which pt1000 will measure which device/location in the satellite. + * Therefore object ids are named according to the IC naming of the RTDs in the schematic. + */ + RTD_0_IC3_PLOC_HEATSPREADER = 0x44420016, + RTD_1_IC4_PLOC_MISSIONBOARD = 0x44420017, + RTD_2_IC5_4K_CAMERA = 0x44420018, + RTD_3_IC6_DAC_HEATSPREADER = 0x44420019, + RTD_4_IC7_STARTRACKER = 0x44420020, + RTD_5_IC8_RW1_MX_MY = 0x44420021, + RTD_6_IC9_DRO = 0x44420022, + RTD_7_IC10_SCEX = 0x44420023, + RTD_8_IC11_X8 = 0x44420024, + RTD_9_IC12_HPA = 0x44420025, + RTD_10_IC13_PL_TX = 0x44420026, + RTD_11_IC14_MPA = 0x44420027, + RTD_12_IC15_ACU = 0x44420028, + RTD_13_IC16_PLPCDU_HEATSPREADER = 0x44420029, + RTD_14_IC17_TCS_BOARD = 0x44420030, + RTD_15_IC18_IMTQ = 0x44420031, - SUS_0 = 0x44120032, - SUS_1 = 0x44120033, - SUS_2 = 0x44120034, - SUS_3 = 0x44120035, - SUS_4 = 0x44120036, - SUS_5 = 0x44120037, - SUS_6 = 0x44120038, - SUS_7 = 0x44120039, - SUS_8 = 0x44120040, - SUS_9 = 0x44120041, - SUS_10 = 0x44120042, - SUS_11 = 0x44120043, + // Name convention for SUS devices + // SUS___LOC_XYZ_PT_ + // LOC: Location + // PT: Pointing + // N/R: Nominal/Redundant + // F/M/B: Forward/Middle/Backwards + SUS_0_N_LOC_XFYFZM_PT_XF = 0x44120032, + SUS_6_R_LOC_XFYBZM_PT_XF = 0x44120038, - GPS_CONTROLLER = 0x44130045, + SUS_1_N_LOC_XBYFZM_PT_XB = 0x44120033, + SUS_7_R_LOC_XBYBZM_PT_XB = 0x44120039, - RW1 = 0x44120047, - RW2 = 0x44120148, - RW3 = 0x44120249, - RW4 = 0x44120350, + SUS_2_N_LOC_XFYBZB_PT_YB = 0x44120034, + SUS_8_R_LOC_XBYBZB_PT_YB = 0x44120040, - STAR_TRACKER = 0x44130001, + SUS_3_N_LOC_XFYBZF_PT_YF = 0x44120035, + SUS_9_R_LOC_XBYBZB_PT_YF = 0x44120041, - PLOC_UPDATER = 0x44330000, - PLOC_MEMORY_DUMPER = 0x44330001, - STR_HELPER = 0x44330002, - PLOC_MPSOC_HELPER = 0x44330003, - AXI_PTME_CONFIG = 44330004, - PTME_CONFIG = 44330005, + SUS_4_N_LOC_XMYFZF_PT_ZF = 0x44120036, + SUS_10_N_LOC_XMYBZF_PT_ZF = 0x44120042, - // 0x73 ('s') for assemblies and system/subsystem components - ACS_BOARD_ASS = 0x73000001, - SUS_BOARD_ASS = 0x73000002, - TCS_BOARD_ASS = 0x73000003 + SUS_5_N_LOC_XFYMZB_PT_ZB = 0x44120037, + SUS_11_R_LOC_XBYMZB_PT_ZB = 0x44120043, + + SYRLINKS_HK_HANDLER = 0x445300A3, + + // 0x60 for other stuff + HEATER_0_PLOC_PROC_BRD = 0x60000000, + HEATER_1_PCDU_BRD = 0x60000001, + HEATER_2_ACS_BRD = 0x60000002, + HEATER_3_OBC_BRD = 0x60000003, + HEATER_4_CAMERA = 0x60000004, + HEATER_5_STR = 0x60000005, + HEATER_6_DRO = 0x60000006, + HEATER_7_HPA = 0x60000007, + + // 0x73 ('s') for assemblies and system/subsystem components + ACS_BOARD_ASS = 0x73000001, + SUS_BOARD_ASS = 0x73000002, + TCS_BOARD_ASS = 0x73000003, + RW_ASS = 0x73000004 }; } - #endif /* COMMON_CONFIG_COMMONOBJECTS_H_ */ diff --git a/common/config/commonSubsystemIds.h b/common/config/commonSubsystemIds.h index c3e6c5a2..001f6d50 100644 --- a/common/config/commonSubsystemIds.h +++ b/common/config/commonSubsystemIds.h @@ -4,36 +4,36 @@ #include namespace SUBSYSTEM_ID { -enum: uint8_t { - COMMON_SUBSYSTEM_ID_START = FW_SUBSYSTEM_ID_RANGE, - ACS_SUBSYSTEM = 112, - PCDU_HANDLER = 113, - HEATER_HANDLER = 114, - SA_DEPL_HANDLER = 115, - PLOC_MPSOC_HANDLER = 116, - IMTQ_HANDLER = 117, - RW_HANDLER = 118, - STR_HANDLER = 119, - PLOC_SUPERVISOR_HANDLER = 120, - FILE_SYSTEM = 121, - PLOC_UPDATER = 122, - PLOC_MEMORY_DUMPER = 123, - PDEC_HANDLER = 124, - STR_HELPER = 125, - PLOC_MPSOC_HELPER = 126, - PL_PCDU_HANDLER = 127, - ACS_BOARD_ASS = 128, - SUS_BOARD_ASS = 129, - TCS_BOARD_ASS = 130, - GPS_HANDLER = 131, - P60_DOCK_HANDLER = 132, - PDU1_HANDLER = 133, - PDU2_HANDLER = 134, - ACU_HANDLER = 135, - SYRLINKS = 136, - COMMON_SUBSYSTEM_ID_END +enum : uint8_t { + COMMON_SUBSYSTEM_ID_START = FW_SUBSYSTEM_ID_RANGE, + ACS_SUBSYSTEM = 112, + PCDU_HANDLER = 113, + HEATER_HANDLER = 114, + SA_DEPL_HANDLER = 115, + PLOC_MPSOC_HANDLER = 116, + IMTQ_HANDLER = 117, + RW_HANDLER = 118, + STR_HANDLER = 119, + PLOC_SUPERVISOR_HANDLER = 120, + FILE_SYSTEM = 121, + PLOC_UPDATER = 122, + PLOC_MEMORY_DUMPER = 123, + PDEC_HANDLER = 124, + STR_HELPER = 125, + PLOC_MPSOC_HELPER = 126, + PL_PCDU_HANDLER = 127, + ACS_BOARD_ASS = 128, + SUS_BOARD_ASS = 129, + TCS_BOARD_ASS = 130, + GPS_HANDLER = 131, + P60_DOCK_HANDLER = 132, + PDU1_HANDLER = 133, + PDU2_HANDLER = 134, + ACU_HANDLER = 135, + PLOC_SUPV_HELPER = 136, + SYRLINKS = 137, + COMMON_SUBSYSTEM_ID_END }; } - #endif /* COMMON_CONFIG_COMMONSUBSYSTEMIDS_H_ */ diff --git a/common/config/devConf.h b/common/config/devConf.h index abb3b3e1..51da9011 100644 --- a/common/config/devConf.h +++ b/common/config/devConf.h @@ -2,8 +2,10 @@ #define COMMON_CONFIG_DEVCONF_H_ #include -#include -#include + +#include "fsfw/timemanager/clockDefinitions.h" +#include "fsfw_hal/linux/spi/spiDefinitions.h" +#include "fsfw_hal/linux/uart/UartCookie.h" /** * SPI configuration will be contained here to let the device handlers remain independent @@ -31,6 +33,7 @@ static constexpr spi::SpiModes DEFAULT_L3G_MODE = spi::SpiModes::MODE_3; static const uint32_t SUS_MAX1227_SPI_FREQ = 976'000; static constexpr spi::SpiModes SUS_MAX_1227_MODE = spi::SpiModes::MODE_3; +static constexpr dur_millis_t RAD_SENSOR_CS_TIMEOUT = 120; static constexpr uint32_t DEFAULT_MAX_1227_SPEED = 976'000; static constexpr spi::SpiModes DEFAULT_MAX_1227_MODE = spi::SpiModes::MODE_3; @@ -42,10 +45,11 @@ static constexpr spi::SpiModes DEFAULT_ADIS16507_MODE = spi::SpiModes::MODE_3; static constexpr uint32_t RW_SPEED = 300'000; static constexpr spi::SpiModes RW_MODE = spi::SpiModes::MODE_0; +static constexpr dur_millis_t RTD_CS_TIMEOUT = 50; static constexpr uint32_t RTD_SPEED = 2'000'000; static constexpr spi::SpiModes RTD_MODE = spi::SpiModes::MODE_3; -} +} // namespace spi namespace uart { @@ -53,9 +57,9 @@ static constexpr size_t HYPERION_GPS_REPLY_MAX_BUFFER = 1024; static constexpr UartBaudRate SYRLINKS_BAUD = UartBaudRate::RATE_38400; static constexpr UartBaudRate GNSS_BAUD = UartBaudRate::RATE_9600; static constexpr UartBaudRate PLOC_MPSOC_BAUD = UartBaudRate::RATE_115200; -static constexpr UartBaudRate PLOC_SUPERVISOR_BAUD = UartBaudRate::RATE_115200; +static constexpr UartBaudRate PLOC_SUPV_BAUD = UartBaudRate::RATE_115200; static constexpr UartBaudRate STAR_TRACKER_BAUD = UartBaudRate::RATE_921600; -} +} // namespace uart #endif /* COMMON_CONFIG_DEVCONF_H_ */ diff --git a/common/config/devices/heaterSwitcherList.h b/common/config/devices/heaterSwitcherList.h index 014e795c..68034117 100644 --- a/common/config/devices/heaterSwitcherList.h +++ b/common/config/devices/heaterSwitcherList.h @@ -3,18 +3,18 @@ #include -namespace heaterSwitches { - enum switcherList: uint8_t { - HEATER_0, - HEATER_1, - HEATER_2, - HEATER_3, - HEATER_4, - HEATER_5, - HEATER_6, - HEATER_7, - NUMBER_OF_SWITCHES - }; +namespace heater { +enum Switchers : uint8_t { + HEATER_0_OBC_BRD, + HEATER_1_PLOC_PROC_BRD, + HEATER_2_ACS_BRD, + HEATER_3_PCDU_PDU, + HEATER_4_CAMERA, + HEATER_5_STR, + HEATER_6_DRO, + HEATER_7_HPA, + NUMBER_OF_SWITCHES +}; } #endif /* FSFWCONFIG_DEVICES_HEATERSWITCHERLIST_H_ */ diff --git a/common/config/eive/definitions.h b/common/config/eive/definitions.h index db430540..6a7bad05 100644 --- a/common/config/eive/definitions.h +++ b/common/config/eive/definitions.h @@ -19,7 +19,6 @@ static constexpr uint8_t LIVE_TM = 0; static constexpr uint32_t MAX_PATH_SIZE = 100; static constexpr uint32_t MAX_FILENAME_SIZE = 50; -} - +} // namespace config #endif /* COMMON_CONFIG_DEFINITIONS_H_ */ diff --git a/common/config/tmtc/apid.h b/common/config/tmtc/apid.h index 00aabee1..8fbb4203 100644 --- a/common/config/tmtc/apid.h +++ b/common/config/tmtc/apid.h @@ -12,8 +12,7 @@ * APID is a 11 bit number */ namespace apid { - static const uint16_t EIVE_OBSW = 0x65; +static const uint16_t EIVE_OBSW = 0x65; } - #endif /* FSFWCONFIG_TMTC_APID_H_ */ diff --git a/bsp_hosted/fsfwconfig/tmtc/pusIds.h b/common/config/tmtc/pusIds.h similarity index 71% rename from bsp_hosted/fsfwconfig/tmtc/pusIds.h rename to common/config/tmtc/pusIds.h index 37503786..0891992d 100644 --- a/bsp_hosted/fsfwconfig/tmtc/pusIds.h +++ b/common/config/tmtc/pusIds.h @@ -1,5 +1,5 @@ -#ifndef CONFIG_TMTC_PUSIDS_HPP_ -#define CONFIG_TMTC_PUSIDS_HPP_ +#ifndef COMMON_CONFIG_TMTC_PUSIDS_H_ +#define COMMON_CONFIG_TMTC_PUSIDS_H_ namespace pus { enum Ids { @@ -11,6 +11,7 @@ enum Ids { PUS_SERVICE_6 = 6, PUS_SERVICE_8 = 8, PUS_SERVICE_9 = 9, + PUS_SERVICE_11 = 11, PUS_SERVICE_17 = 17, PUS_SERVICE_19 = 19, PUS_SERVICE_20 = 20, @@ -20,4 +21,4 @@ enum Ids { }; }; -#endif /* CONFIG_TMTC_PUSIDS_HPP_ */ +#endif /* COMMON_CONFIG_TMTC_PUSIDS_H_ */ diff --git a/dummies/AcuDummy.cpp b/dummies/AcuDummy.cpp new file mode 100644 index 00000000..dc0c974d --- /dev/null +++ b/dummies/AcuDummy.cpp @@ -0,0 +1,42 @@ +#include "AcuDummy.h" + +#include + +AcuDummy::AcuDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie) + : DeviceHandlerBase(objectId, comif, comCookie) {} + +AcuDummy::~AcuDummy() {} + +void AcuDummy::doStartUp() {} + +void AcuDummy::doShutDown() {} + +ReturnValue_t AcuDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { return NOTHING_TO_SEND; } + +ReturnValue_t AcuDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) { + return NOTHING_TO_SEND; +} + +ReturnValue_t AcuDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t *commandData, size_t commandDataLen) { + return RETURN_OK; +} + +ReturnValue_t AcuDummy::scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) { + return RETURN_OK; +} + +ReturnValue_t AcuDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) { + return RETURN_OK; +} + +void AcuDummy::fillCommandAndReplyMap() {} + +uint32_t AcuDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; } + +ReturnValue_t AcuDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) { + localDataPoolMap.emplace(P60System::pool::ACU_TEMPERATURES, new PoolEntry(3)); + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/dummies/AcuDummy.h b/dummies/AcuDummy.h new file mode 100644 index 00000000..d5527222 --- /dev/null +++ b/dummies/AcuDummy.h @@ -0,0 +1,33 @@ +#ifndef DUMMIES_ACUDUMMY_H_ +#define DUMMIES_ACUDUMMY_H_ + +#include + +class AcuDummy : public DeviceHandlerBase { + public: + static const DeviceCommandId_t SIMPLE_COMMAND = 1; + static const DeviceCommandId_t PERIODIC_REPLY = 2; + + static const uint8_t SIMPLE_COMMAND_DATA = 1; + static const uint8_t PERIODIC_REPLY_DATA = 2; + + AcuDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie); + virtual ~AcuDummy(); + + protected: + void doStartUp() override; + void doShutDown() override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData, + size_t commandDataLen) override; + ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) override; + ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override; + void fillCommandAndReplyMap() override; + uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) override; +}; + +#endif /* DUMMIES_ACUDUMMY_H_ */ diff --git a/dummies/BpxDummy.cpp b/dummies/BpxDummy.cpp new file mode 100644 index 00000000..974a6a30 --- /dev/null +++ b/dummies/BpxDummy.cpp @@ -0,0 +1,55 @@ +#include "BpxDummy.h" + +#include + +BpxDummy::BpxDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie) + : DeviceHandlerBase(objectId, comif, comCookie) {} + +BpxDummy::~BpxDummy() {} + +void BpxDummy::doStartUp() {} + +void BpxDummy::doShutDown() {} + +ReturnValue_t BpxDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { return NOTHING_TO_SEND; } + +ReturnValue_t BpxDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) { + return NOTHING_TO_SEND; +} + +ReturnValue_t BpxDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t *commandData, size_t commandDataLen) { + return RETURN_OK; +} + +ReturnValue_t BpxDummy::scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) { + return RETURN_OK; +} + +ReturnValue_t BpxDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) { + return RETURN_OK; +} + +void BpxDummy::fillCommandAndReplyMap() {} + +uint32_t BpxDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; } + +ReturnValue_t BpxDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) { + localDataPoolMap.emplace(BpxBattery::BATT_TEMP_1, &battTemp1); + localDataPoolMap.emplace(BpxBattery::BATT_TEMP_2, &battTemp2); + localDataPoolMap.emplace(BpxBattery::BATT_TEMP_3, &battTemp3); + localDataPoolMap.emplace(BpxBattery::BATT_TEMP_4, &battTemp4); + localDataPoolMap.emplace(BpxBattery::CHARGE_CURRENT, &chargeCurrent); + localDataPoolMap.emplace(BpxBattery::DISCHARGE_CURRENT, &dischargeCurrent); + localDataPoolMap.emplace(BpxBattery::HEATER_CURRENT, &heaterCurrent); + localDataPoolMap.emplace(BpxBattery::BATT_VOLTAGE, &battVolt); + localDataPoolMap.emplace(BpxBattery::REBOOT_COUNTER, &rebootCounter); + localDataPoolMap.emplace(BpxBattery::BOOTCAUSE, &bootCause); + + localDataPoolMap.emplace(BpxBattery::BATTERY_HEATER_MODE, &battheatMode); + localDataPoolMap.emplace(BpxBattery::BATTHEAT_LOW_LIMIT, &battheatLow); + localDataPoolMap.emplace(BpxBattery::BATTHEAT_HIGH_LIMIT, &battheatHigh); + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/dummies/BpxDummy.h b/dummies/BpxDummy.h new file mode 100644 index 00000000..1332f36b --- /dev/null +++ b/dummies/BpxDummy.h @@ -0,0 +1,48 @@ +#ifndef DUMMIES_BPXDUMMY_H_ +#define DUMMIES_BPXDUMMY_H_ + +#include + +class BpxDummy : public DeviceHandlerBase { + public: + static const DeviceCommandId_t SIMPLE_COMMAND = 1; + static const DeviceCommandId_t PERIODIC_REPLY = 2; + + static const uint8_t SIMPLE_COMMAND_DATA = 1; + static const uint8_t PERIODIC_REPLY_DATA = 2; + + BpxDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie); + virtual ~BpxDummy(); + + protected: + void doStartUp() override; + void doShutDown() override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData, + size_t commandDataLen) override; + ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) override; + ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override; + void fillCommandAndReplyMap() override; + uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) override; + + private: + PoolEntry chargeCurrent = PoolEntry({0}); + PoolEntry dischargeCurrent = PoolEntry({0}); + PoolEntry heaterCurrent = PoolEntry({0}); + PoolEntry battVolt = PoolEntry({0}); + PoolEntry battTemp1 = PoolEntry({0}); + PoolEntry battTemp2 = PoolEntry({0}); + PoolEntry battTemp3 = PoolEntry({0}); + PoolEntry battTemp4 = PoolEntry({0}); + PoolEntry rebootCounter = PoolEntry({0}); + PoolEntry bootCause = PoolEntry({0}); + PoolEntry battheatMode = PoolEntry({0}); + PoolEntry battheatLow = PoolEntry({0}); + PoolEntry battheatHigh = PoolEntry({0}); +}; + +#endif /* DUMMIES_BPXDUMMY_H_ */ diff --git a/dummies/CMakeLists.txt b/dummies/CMakeLists.txt new file mode 100644 index 00000000..d855b155 --- /dev/null +++ b/dummies/CMakeLists.txt @@ -0,0 +1,19 @@ +target_sources( + ${LIB_DUMMIES} + PUBLIC TemperatureSensorsDummy.cpp + SusDummy.cpp + BpxDummy.cpp + ComIFDummy.cpp + ComCookieDummy.cpp + RwDummy.cpp + StarTrackerDummy.cpp + SyrlinksDummy.cpp + ImtqDummy.cpp + AcuDummy.cpp + PduDummy.cpp + P60DockDummy.cpp + GyroAdisDummy.cpp + GyroL3GD20Dummy.cpp + MgmLIS3MDLDummy.cpp + PlPcduDummy.cpp + CoreControllerDummy.cpp) diff --git a/dummies/ComCookieDummy.cpp b/dummies/ComCookieDummy.cpp new file mode 100644 index 00000000..2e2edf99 --- /dev/null +++ b/dummies/ComCookieDummy.cpp @@ -0,0 +1,5 @@ +#include "ComCookieDummy.h" + +ComCookieDummy::ComCookieDummy() {} + +ComCookieDummy::~ComCookieDummy() {} diff --git a/dummies/ComCookieDummy.h b/dummies/ComCookieDummy.h new file mode 100644 index 00000000..e4e2086e --- /dev/null +++ b/dummies/ComCookieDummy.h @@ -0,0 +1,12 @@ +#ifndef TESTS_SRC_FSFW_TESTS_UNIT_DEVICEHANDLER_COMCOOKIEDUMMY_H_ +#define TESTS_SRC_FSFW_TESTS_UNIT_DEVICEHANDLER_COMCOOKIEDUMMY_H_ + +#include "fsfw/devicehandlers/CookieIF.h" + +class ComCookieDummy : public CookieIF { + public: + ComCookieDummy(); + virtual ~ComCookieDummy(); +}; + +#endif /* TESTS_SRC_FSFW_TESTS_UNIT_DEVICEHANDLER_COMCOOKIEDUMMY_H_ */ diff --git a/dummies/ComIFDummy.cpp b/dummies/ComIFDummy.cpp new file mode 100644 index 00000000..e1552fca --- /dev/null +++ b/dummies/ComIFDummy.cpp @@ -0,0 +1,21 @@ +#include "ComIFDummy.h" + +ComIFDummy::ComIFDummy(object_id_t objectId) : SystemObject(objectId) {} + +ComIFDummy::~ComIFDummy() {} + +ReturnValue_t ComIFDummy::initializeInterface(CookieIF *cookie) { return RETURN_OK; } + +ReturnValue_t ComIFDummy::sendMessage(CookieIF *cookie, const uint8_t *sendData, size_t sendLen) { + return RETURN_OK; +} + +ReturnValue_t ComIFDummy::getSendSuccess(CookieIF *cookie) { return RETURN_OK; } + +ReturnValue_t ComIFDummy::requestReceiveMessage(CookieIF *cookie, size_t requestLen) { + return RETURN_OK; +} + +ReturnValue_t ComIFDummy::readReceivedMessage(CookieIF *cookie, uint8_t **buffer, size_t *size) { + return RETURN_OK; +} diff --git a/dummies/ComIFDummy.h b/dummies/ComIFDummy.h new file mode 100644 index 00000000..499c2c48 --- /dev/null +++ b/dummies/ComIFDummy.h @@ -0,0 +1,26 @@ +#ifndef DUMMIES_COMIFDUMMY_H_ +#define DUMMIES_COMIFDUMMY_H_ + +#include +#include + +/** + * @brief The ComIFMock supports the simulation of various device communication error cases + * like incomplete or wrong replies and can be used to test the + * DeviceHandlerBase. + */ +class ComIFDummy : public DeviceCommunicationIF, public SystemObject { + public: + ComIFDummy(object_id_t objectId); + virtual ~ComIFDummy(); + + virtual ReturnValue_t initializeInterface(CookieIF *cookie) override; + virtual ReturnValue_t sendMessage(CookieIF *cookie, const uint8_t *sendData, + size_t sendLen) override; + virtual ReturnValue_t getSendSuccess(CookieIF *cookie) override; + virtual ReturnValue_t requestReceiveMessage(CookieIF *cookie, size_t requestLen) override; + virtual ReturnValue_t readReceivedMessage(CookieIF *cookie, uint8_t **buffer, + size_t *size) override; +}; + +#endif /* DUMMIES_COMIFDUMMY_H_ */ diff --git a/dummies/CoreControllerDummy.cpp b/dummies/CoreControllerDummy.cpp new file mode 100644 index 00000000..b8aa270c --- /dev/null +++ b/dummies/CoreControllerDummy.cpp @@ -0,0 +1,55 @@ +#include "CoreControllerDummy.h" + +#include +#include + +#include +#include + +CoreControllerDummy::CoreControllerDummy(object_id_t objectId) + : ExtendedControllerBase(objectId, objects::NO_OBJECT) {} + +ReturnValue_t CoreControllerDummy::initialize() { + static bool done = false; + if (not done) { + done = true; + ReturnValue_t result = ExtendedControllerBase::initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + } + + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t CoreControllerDummy::handleCommandMessage(CommandMessage* message) { + return RETURN_FAILED; +} + +void CoreControllerDummy::performControlOperation() { return; } + +ReturnValue_t CoreControllerDummy::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) { + localDataPoolMap.emplace(core::TEMPERATURE, new PoolEntry({0})); + localDataPoolMap.emplace(core::PS_VOLTAGE, new PoolEntry({0})); + localDataPoolMap.emplace(core::PL_VOLTAGE, new PoolEntry({0})); + return HasReturnvaluesIF::RETURN_OK; +} + +LocalPoolDataSetBase* CoreControllerDummy::getDataSetHandle(sid_t sid) { + switch (sid.ownerSetId) { + default: + return nullptr; + } +} + +ReturnValue_t CoreControllerDummy::checkModeCommand(Mode_t mode, Submode_t submode, + uint32_t* msToReachTheMode) { + if (submode != SUBMODE_NONE) { + return INVALID_SUBMODE; + } + if ((mode != MODE_OFF) && (mode != MODE_ON) && (mode != MODE_NORMAL)) { + return INVALID_MODE; + } + return RETURN_OK; +} diff --git a/dummies/CoreControllerDummy.h b/dummies/CoreControllerDummy.h new file mode 100644 index 00000000..1b4eeaf8 --- /dev/null +++ b/dummies/CoreControllerDummy.h @@ -0,0 +1,21 @@ +#pragma once + +#include +#include + +class CoreControllerDummy : public ExtendedControllerBase { + public: + CoreControllerDummy(object_id_t objectId); + + ReturnValue_t initialize() override; + + protected: + virtual ReturnValue_t handleCommandMessage(CommandMessage* message) override; + virtual void performControlOperation() override; + virtual ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) override; + virtual LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override; + + virtual ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, + uint32_t* msToReachTheMode) override; +}; diff --git a/dummies/GyroAdisDummy.cpp b/dummies/GyroAdisDummy.cpp new file mode 100644 index 00000000..6b760e79 --- /dev/null +++ b/dummies/GyroAdisDummy.cpp @@ -0,0 +1,45 @@ +#include "GyroAdisDummy.h" + +#include "mission/devices/devicedefinitions/GyroADIS1650XDefinitions.h" + +GyroAdisDummy::GyroAdisDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie) + : DeviceHandlerBase(objectId, comif, comCookie) {} + +GyroAdisDummy::~GyroAdisDummy() {} + +void GyroAdisDummy::doStartUp() {} + +void GyroAdisDummy::doShutDown() {} + +ReturnValue_t GyroAdisDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { + return NOTHING_TO_SEND; +} + +ReturnValue_t GyroAdisDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) { + return NOTHING_TO_SEND; +} + +ReturnValue_t GyroAdisDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t *commandData, + size_t commandDataLen) { + return RETURN_OK; +} + +ReturnValue_t GyroAdisDummy::scanForReply(const uint8_t *start, size_t len, + DeviceCommandId_t *foundId, size_t *foundLen) { + return RETURN_OK; +} + +ReturnValue_t GyroAdisDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) { + return RETURN_OK; +} + +void GyroAdisDummy::fillCommandAndReplyMap() {} + +uint32_t GyroAdisDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; } + +ReturnValue_t GyroAdisDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) { + localDataPoolMap.emplace(ADIS1650X::TEMPERATURE, new PoolEntry({0.0})); + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/dummies/GyroAdisDummy.h b/dummies/GyroAdisDummy.h new file mode 100644 index 00000000..89f7c06e --- /dev/null +++ b/dummies/GyroAdisDummy.h @@ -0,0 +1,33 @@ +#ifndef DUMMIES_GYROADISDUMMY_H_ +#define DUMMIES_GYROADISDUMMY_H_ + +#include + +class GyroAdisDummy : public DeviceHandlerBase { + public: + static const DeviceCommandId_t SIMPLE_COMMAND = 1; + static const DeviceCommandId_t PERIODIC_REPLY = 2; + + static const uint8_t SIMPLE_COMMAND_DATA = 1; + static const uint8_t PERIODIC_REPLY_DATA = 2; + + GyroAdisDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie); + virtual ~GyroAdisDummy(); + + protected: + void doStartUp() override; + void doShutDown() override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData, + size_t commandDataLen) override; + ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) override; + ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override; + void fillCommandAndReplyMap() override; + uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) override; +}; + +#endif /* DUMMIES_GYROADISDUMMY_H_ */ diff --git a/dummies/GyroL3GD20Dummy.cpp b/dummies/GyroL3GD20Dummy.cpp new file mode 100644 index 00000000..7023870f --- /dev/null +++ b/dummies/GyroL3GD20Dummy.cpp @@ -0,0 +1,48 @@ +#include "GyroL3GD20Dummy.h" + +#include "fsfw_hal/devicehandlers/devicedefinitions/GyroL3GD20Definitions.h" + +GyroL3GD20Dummy::GyroL3GD20Dummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie) + : DeviceHandlerBase(objectId, comif, comCookie) {} + +GyroL3GD20Dummy::~GyroL3GD20Dummy() {} + +void GyroL3GD20Dummy::doStartUp() {} + +void GyroL3GD20Dummy::doShutDown() {} + +ReturnValue_t GyroL3GD20Dummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { + return NOTHING_TO_SEND; +} + +ReturnValue_t GyroL3GD20Dummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) { + return NOTHING_TO_SEND; +} + +ReturnValue_t GyroL3GD20Dummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t *commandData, + size_t commandDataLen) { + return RETURN_OK; +} + +ReturnValue_t GyroL3GD20Dummy::scanForReply(const uint8_t *start, size_t len, + DeviceCommandId_t *foundId, size_t *foundLen) { + return RETURN_OK; +} + +ReturnValue_t GyroL3GD20Dummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) { + return RETURN_OK; +} + +void GyroL3GD20Dummy::fillCommandAndReplyMap() {} + +uint32_t GyroL3GD20Dummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; } + +ReturnValue_t GyroL3GD20Dummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) { + localDataPoolMap.emplace(L3GD20H::ANG_VELOC_X, new PoolEntry({0.0})); + localDataPoolMap.emplace(L3GD20H::ANG_VELOC_Y, new PoolEntry({0.0})); + localDataPoolMap.emplace(L3GD20H::ANG_VELOC_Z, new PoolEntry({0.0})); + localDataPoolMap.emplace(L3GD20H::TEMPERATURE, new PoolEntry({0.0})); + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/dummies/GyroL3GD20Dummy.h b/dummies/GyroL3GD20Dummy.h new file mode 100644 index 00000000..7af69f50 --- /dev/null +++ b/dummies/GyroL3GD20Dummy.h @@ -0,0 +1,33 @@ +#ifndef DUMMIES_GYROL3GD20DUMMY_H_ +#define DUMMIES_GYROL3GD20DUMMY_H_ + +#include + +class GyroL3GD20Dummy : public DeviceHandlerBase { + public: + static const DeviceCommandId_t SIMPLE_COMMAND = 1; + static const DeviceCommandId_t PERIODIC_REPLY = 2; + + static const uint8_t SIMPLE_COMMAND_DATA = 1; + static const uint8_t PERIODIC_REPLY_DATA = 2; + + GyroL3GD20Dummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie); + virtual ~GyroL3GD20Dummy(); + + protected: + void doStartUp() override; + void doShutDown() override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData, + size_t commandDataLen) override; + ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) override; + ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override; + void fillCommandAndReplyMap() override; + uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) override; +}; + +#endif /* DUMMIES_GYROL3GD20DUMMY_H_ */ diff --git a/dummies/ImtqDummy.cpp b/dummies/ImtqDummy.cpp new file mode 100644 index 00000000..0af9ef83 --- /dev/null +++ b/dummies/ImtqDummy.cpp @@ -0,0 +1,43 @@ +#include "ImtqDummy.h" + +#include + +ImtqDummy::ImtqDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie) + : DeviceHandlerBase(objectId, comif, comCookie) {} + +ImtqDummy::~ImtqDummy() {} + +void ImtqDummy::doStartUp() {} + +void ImtqDummy::doShutDown() {} + +ReturnValue_t ImtqDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { return NOTHING_TO_SEND; } + +ReturnValue_t ImtqDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) { + return NOTHING_TO_SEND; +} + +ReturnValue_t ImtqDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t *commandData, + size_t commandDataLen) { + return RETURN_OK; +} + +ReturnValue_t ImtqDummy::scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) { + return RETURN_OK; +} + +ReturnValue_t ImtqDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) { + return RETURN_OK; +} + +void ImtqDummy::fillCommandAndReplyMap() {} + +uint32_t ImtqDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; } + +ReturnValue_t ImtqDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) { + localDataPoolMap.emplace(IMTQ::MCU_TEMPERATURE, new PoolEntry({0})); + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/dummies/ImtqDummy.h b/dummies/ImtqDummy.h new file mode 100644 index 00000000..4b5557ef --- /dev/null +++ b/dummies/ImtqDummy.h @@ -0,0 +1,33 @@ +#ifndef DUMMIES_IMTQDUMMY_H_ +#define DUMMIES_IMTQDUMMY_H_ + +#include + +class ImtqDummy : public DeviceHandlerBase { + public: + static const DeviceCommandId_t SIMPLE_COMMAND = 1; + static const DeviceCommandId_t PERIODIC_REPLY = 2; + + static const uint8_t SIMPLE_COMMAND_DATA = 1; + static const uint8_t PERIODIC_REPLY_DATA = 2; + + ImtqDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie); + virtual ~ImtqDummy(); + + protected: + void doStartUp() override; + void doShutDown() override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData, + size_t commandDataLen) override; + ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) override; + ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override; + void fillCommandAndReplyMap() override; + uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) override; +}; + +#endif /* DUMMIES_IMTQDUMMY_H_ */ diff --git a/dummies/MgmLIS3MDLDummy.cpp b/dummies/MgmLIS3MDLDummy.cpp new file mode 100644 index 00000000..0fb0edba --- /dev/null +++ b/dummies/MgmLIS3MDLDummy.cpp @@ -0,0 +1,45 @@ +#include "MgmLIS3MDLDummy.h" + +#include "fsfw_hal/devicehandlers/devicedefinitions/MgmLIS3HandlerDefs.h" + +MgmLIS3MDLDummy::MgmLIS3MDLDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie) + : DeviceHandlerBase(objectId, comif, comCookie) {} + +MgmLIS3MDLDummy::~MgmLIS3MDLDummy() {} + +void MgmLIS3MDLDummy::doStartUp() {} + +void MgmLIS3MDLDummy::doShutDown() {} + +ReturnValue_t MgmLIS3MDLDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { + return NOTHING_TO_SEND; +} + +ReturnValue_t MgmLIS3MDLDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) { + return NOTHING_TO_SEND; +} + +ReturnValue_t MgmLIS3MDLDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t *commandData, + size_t commandDataLen) { + return RETURN_OK; +} + +ReturnValue_t MgmLIS3MDLDummy::scanForReply(const uint8_t *start, size_t len, + DeviceCommandId_t *foundId, size_t *foundLen) { + return RETURN_OK; +} + +ReturnValue_t MgmLIS3MDLDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) { + return RETURN_OK; +} + +void MgmLIS3MDLDummy::fillCommandAndReplyMap() {} + +uint32_t MgmLIS3MDLDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; } + +ReturnValue_t MgmLIS3MDLDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) { + localDataPoolMap.emplace(MGMLIS3MDL::TEMPERATURE_CELCIUS, new PoolEntry({0.0})); + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/dummies/MgmLIS3MDLDummy.h b/dummies/MgmLIS3MDLDummy.h new file mode 100644 index 00000000..86b3e433 --- /dev/null +++ b/dummies/MgmLIS3MDLDummy.h @@ -0,0 +1,33 @@ +#ifndef DUMMIES_MGMLIS3MDLDUMMY_H_ +#define DUMMIES_MGMLIS3MDLDUMMY_H_ + +#include + +class MgmLIS3MDLDummy : public DeviceHandlerBase { + public: + static const DeviceCommandId_t SIMPLE_COMMAND = 1; + static const DeviceCommandId_t PERIODIC_REPLY = 2; + + static const uint8_t SIMPLE_COMMAND_DATA = 1; + static const uint8_t PERIODIC_REPLY_DATA = 2; + + MgmLIS3MDLDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie); + virtual ~MgmLIS3MDLDummy(); + + protected: + void doStartUp() override; + void doShutDown() override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData, + size_t commandDataLen) override; + ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) override; + ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override; + void fillCommandAndReplyMap() override; + uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) override; +}; + +#endif /* DUMMIES_MGMLIS3MDLDUMMY_H_ */ diff --git a/dummies/P60DockDummy.cpp b/dummies/P60DockDummy.cpp new file mode 100644 index 00000000..04f5e5af --- /dev/null +++ b/dummies/P60DockDummy.cpp @@ -0,0 +1,46 @@ +#include "P60DockDummy.h" + +#include + +P60DockDummy::P60DockDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie) + : DeviceHandlerBase(objectId, comif, comCookie) {} + +P60DockDummy::~P60DockDummy() {} + +void P60DockDummy::doStartUp() {} + +void P60DockDummy::doShutDown() {} + +ReturnValue_t P60DockDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { + return NOTHING_TO_SEND; +} + +ReturnValue_t P60DockDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) { + return NOTHING_TO_SEND; +} + +ReturnValue_t P60DockDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t *commandData, + size_t commandDataLen) { + return RETURN_OK; +} + +ReturnValue_t P60DockDummy::scanForReply(const uint8_t *start, size_t len, + DeviceCommandId_t *foundId, size_t *foundLen) { + return RETURN_OK; +} + +ReturnValue_t P60DockDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) { + return RETURN_OK; +} + +void P60DockDummy::fillCommandAndReplyMap() {} + +uint32_t P60DockDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; } + +ReturnValue_t P60DockDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) { + localDataPoolMap.emplace(P60System::pool::P60DOCK_TEMPERATURE_1, new PoolEntry({0})); + localDataPoolMap.emplace(P60System::pool::P60DOCK_TEMPERATURE_2, new PoolEntry({0})); + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/dummies/P60DockDummy.h b/dummies/P60DockDummy.h new file mode 100644 index 00000000..9b67b155 --- /dev/null +++ b/dummies/P60DockDummy.h @@ -0,0 +1,33 @@ +#ifndef DUMMIES_P60DOCKDUMMY_H_ +#define DUMMIES_P60DOCKDUMMY_H_ + +#include + +class P60DockDummy : public DeviceHandlerBase { + public: + static const DeviceCommandId_t SIMPLE_COMMAND = 1; + static const DeviceCommandId_t PERIODIC_REPLY = 2; + + static const uint8_t SIMPLE_COMMAND_DATA = 1; + static const uint8_t PERIODIC_REPLY_DATA = 2; + + P60DockDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie); + virtual ~P60DockDummy(); + + protected: + void doStartUp() override; + void doShutDown() override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData, + size_t commandDataLen) override; + ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) override; + ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override; + void fillCommandAndReplyMap() override; + uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) override; +}; + +#endif /* DUMMIES_P60DOCKDUMMY_H_ */ diff --git a/dummies/PduDummy.cpp b/dummies/PduDummy.cpp new file mode 100644 index 00000000..e955d401 --- /dev/null +++ b/dummies/PduDummy.cpp @@ -0,0 +1,42 @@ +#include "PduDummy.h" + +#include + +PduDummy::PduDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie) + : DeviceHandlerBase(objectId, comif, comCookie) {} + +PduDummy::~PduDummy() {} + +void PduDummy::doStartUp() {} + +void PduDummy::doShutDown() {} + +ReturnValue_t PduDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { return NOTHING_TO_SEND; } + +ReturnValue_t PduDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) { + return NOTHING_TO_SEND; +} + +ReturnValue_t PduDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t *commandData, size_t commandDataLen) { + return RETURN_OK; +} + +ReturnValue_t PduDummy::scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) { + return RETURN_OK; +} + +ReturnValue_t PduDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) { + return RETURN_OK; +} + +void PduDummy::fillCommandAndReplyMap() {} + +uint32_t PduDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; } + +ReturnValue_t PduDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) { + localDataPoolMap.emplace(P60System::pool::PDU_TEMPERATURE, new PoolEntry({0})); + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/dummies/PduDummy.h b/dummies/PduDummy.h new file mode 100644 index 00000000..3e193e7c --- /dev/null +++ b/dummies/PduDummy.h @@ -0,0 +1,33 @@ +#ifndef DUMMIES_PDUDUMMY_H_ +#define DUMMIES_PDUDUMMY_H_ + +#include + +class PduDummy : public DeviceHandlerBase { + public: + static const DeviceCommandId_t SIMPLE_COMMAND = 1; + static const DeviceCommandId_t PERIODIC_REPLY = 2; + + static const uint8_t SIMPLE_COMMAND_DATA = 1; + static const uint8_t PERIODIC_REPLY_DATA = 2; + + PduDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie); + virtual ~PduDummy(); + + protected: + void doStartUp() override; + void doShutDown() override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData, + size_t commandDataLen) override; + ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) override; + ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override; + void fillCommandAndReplyMap() override; + uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) override; +}; + +#endif /* DUMMIES_PDUDUMMY_H_ */ diff --git a/dummies/PlPcduDummy.cpp b/dummies/PlPcduDummy.cpp new file mode 100644 index 00000000..75f98825 --- /dev/null +++ b/dummies/PlPcduDummy.cpp @@ -0,0 +1,45 @@ +#include "PlPcduDummy.h" + +#include + +PlPcduDummy::PlPcduDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie) + : DeviceHandlerBase(objectId, comif, comCookie) {} + +PlPcduDummy::~PlPcduDummy() {} + +void PlPcduDummy::doStartUp() {} + +void PlPcduDummy::doShutDown() {} + +ReturnValue_t PlPcduDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { + return NOTHING_TO_SEND; +} + +ReturnValue_t PlPcduDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) { + return NOTHING_TO_SEND; +} + +ReturnValue_t PlPcduDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t *commandData, + size_t commandDataLen) { + return RETURN_OK; +} + +ReturnValue_t PlPcduDummy::scanForReply(const uint8_t *start, size_t len, + DeviceCommandId_t *foundId, size_t *foundLen) { + return RETURN_OK; +} + +ReturnValue_t PlPcduDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) { + return RETURN_OK; +} + +void PlPcduDummy::fillCommandAndReplyMap() {} + +uint32_t PlPcduDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; } + +ReturnValue_t PlPcduDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) { + localDataPoolMap.emplace(plpcdu::PlPcduPoolIds::TEMP, new PoolEntry({0.0})); + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/dummies/PlPcduDummy.h b/dummies/PlPcduDummy.h new file mode 100644 index 00000000..227eedf8 --- /dev/null +++ b/dummies/PlPcduDummy.h @@ -0,0 +1,34 @@ +#ifndef DUMMIES_PLPCDUDUMMY_H_ +#define DUMMIES_PLPCDUDUMMY_H_ + +#include +#include + +class PlPcduDummy : public DeviceHandlerBase { + public: + static const DeviceCommandId_t SIMPLE_COMMAND = 1; + static const DeviceCommandId_t PERIODIC_REPLY = 2; + + static const uint8_t SIMPLE_COMMAND_DATA = 1; + static const uint8_t PERIODIC_REPLY_DATA = 2; + + PlPcduDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie); + virtual ~PlPcduDummy(); + + protected: + void doStartUp() override; + void doShutDown() override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData, + size_t commandDataLen) override; + ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) override; + ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override; + void fillCommandAndReplyMap() override; + uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) override; +}; + +#endif /* DUMMIES_PLPCDUDUMMY_H_ */ diff --git a/dummies/RwDummy.cpp b/dummies/RwDummy.cpp new file mode 100644 index 00000000..d41728eb --- /dev/null +++ b/dummies/RwDummy.cpp @@ -0,0 +1,75 @@ +#include "RwDummy.h" + +#include + +RwDummy::RwDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie) + : DeviceHandlerBase(objectId, comif, comCookie) {} + +RwDummy::~RwDummy() {} + +void RwDummy::doStartUp() {} + +void RwDummy::doShutDown() {} + +ReturnValue_t RwDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { return NOTHING_TO_SEND; } + +ReturnValue_t RwDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) { + return NOTHING_TO_SEND; +} + +ReturnValue_t RwDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t *commandData, size_t commandDataLen) { + return RETURN_OK; +} + +ReturnValue_t RwDummy::scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) { + return RETURN_OK; +} + +ReturnValue_t RwDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) { + return RETURN_OK; +} + +void RwDummy::fillCommandAndReplyMap() {} + +uint32_t RwDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; } + +ReturnValue_t RwDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) { + localDataPoolMap.emplace(RwDefinitions::TEMPERATURE_C, new PoolEntry({0})); + + localDataPoolMap.emplace(RwDefinitions::CURR_SPEED, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::REFERENCE_SPEED, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::STATE, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::CLC_MODE, new PoolEntry({0})); + + localDataPoolMap.emplace(RwDefinitions::LAST_RESET_STATUS, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::CURRRENT_RESET_STATUS, new PoolEntry({0})); + + localDataPoolMap.emplace(RwDefinitions::TM_LAST_RESET_STATUS, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::TM_MCU_TEMPERATURE, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::PRESSURE_SENSOR_TEMPERATURE, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::PRESSURE, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::TM_RW_STATE, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::TM_CLC_MODE, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::TM_RW_CURR_SPEED, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::TM_RW_REF_SPEED, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::INVALID_CRC_PACKETS, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::INVALID_LEN_PACKETS, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::INVALID_CMD_PACKETS, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::EXECUTED_REPLIES, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::COMMAND_REPLIES, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::UART_BYTES_WRITTEN, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::UART_BYTES_READ, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::UART_PARITY_ERRORS, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::UART_NOISE_ERRORS, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::UART_FRAME_ERRORS, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::UART_REG_OVERRUN_ERRORS, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::UART_TOTAL_ERRORS, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::SPI_BYTES_WRITTEN, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::SPI_BYTES_READ, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::SPI_REG_OVERRUN_ERRORS, new PoolEntry({0})); + localDataPoolMap.emplace(RwDefinitions::SPI_TOTAL_ERRORS, new PoolEntry({0})); + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/dummies/RwDummy.h b/dummies/RwDummy.h new file mode 100644 index 00000000..e5738420 --- /dev/null +++ b/dummies/RwDummy.h @@ -0,0 +1,33 @@ +#ifndef DUMMIES_RWDUMMY_H_ +#define DUMMIES_RWDUMMY_H_ + +#include + +class RwDummy : public DeviceHandlerBase { + public: + static const DeviceCommandId_t SIMPLE_COMMAND = 1; + static const DeviceCommandId_t PERIODIC_REPLY = 2; + + static const uint8_t SIMPLE_COMMAND_DATA = 1; + static const uint8_t PERIODIC_REPLY_DATA = 2; + + RwDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie); + virtual ~RwDummy(); + + protected: + void doStartUp() override; + void doShutDown() override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData, + size_t commandDataLen) override; + ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) override; + ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override; + void fillCommandAndReplyMap() override; + uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) override; +}; + +#endif /* DUMMIES_RWDUMMY_H_ */ diff --git a/dummies/StarTrackerDummy.cpp b/dummies/StarTrackerDummy.cpp new file mode 100644 index 00000000..4432bb5e --- /dev/null +++ b/dummies/StarTrackerDummy.cpp @@ -0,0 +1,45 @@ +#include "StarTrackerDummy.h" + +#include + +StarTrackerDummy::StarTrackerDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie) + : DeviceHandlerBase(objectId, comif, comCookie) {} + +StarTrackerDummy::~StarTrackerDummy() {} + +void StarTrackerDummy::doStartUp() {} + +void StarTrackerDummy::doShutDown() {} + +ReturnValue_t StarTrackerDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { + return NOTHING_TO_SEND; +} + +ReturnValue_t StarTrackerDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) { + return NOTHING_TO_SEND; +} + +ReturnValue_t StarTrackerDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t *commandData, + size_t commandDataLen) { + return RETURN_OK; +} + +ReturnValue_t StarTrackerDummy::scanForReply(const uint8_t *start, size_t len, + DeviceCommandId_t *foundId, size_t *foundLen) { + return RETURN_OK; +} + +ReturnValue_t StarTrackerDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) { + return RETURN_OK; +} + +void StarTrackerDummy::fillCommandAndReplyMap() {} + +uint32_t StarTrackerDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; } + +ReturnValue_t StarTrackerDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) { + localDataPoolMap.emplace(startracker::MCU_TEMPERATURE, new PoolEntry({0})); + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/dummies/StarTrackerDummy.h b/dummies/StarTrackerDummy.h new file mode 100644 index 00000000..bc5534c7 --- /dev/null +++ b/dummies/StarTrackerDummy.h @@ -0,0 +1,33 @@ +#ifndef DUMMIES_STARTRACKERDUMMY_H_ +#define DUMMIES_STARTRACKERDUMMY_H_ + +#include + +class StarTrackerDummy : public DeviceHandlerBase { + public: + static const DeviceCommandId_t SIMPLE_COMMAND = 1; + static const DeviceCommandId_t PERIODIC_REPLY = 2; + + static const uint8_t SIMPLE_COMMAND_DATA = 1; + static const uint8_t PERIODIC_REPLY_DATA = 2; + + StarTrackerDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie); + virtual ~StarTrackerDummy(); + + protected: + void doStartUp() override; + void doShutDown() override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData, + size_t commandDataLen) override; + ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) override; + ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override; + void fillCommandAndReplyMap() override; + uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) override; +}; + +#endif /* DUMMIES_STARTRACKERDUMMY_H_ */ diff --git a/dummies/SusDummy.cpp b/dummies/SusDummy.cpp new file mode 100644 index 00000000..58b2ac8d --- /dev/null +++ b/dummies/SusDummy.cpp @@ -0,0 +1,78 @@ +#include "SusDummy.h" + +#include + +#include +#include + +SusDummy::SusDummy() + : ExtendedControllerBase(objects::SUS_0_N_LOC_XFYFZM_PT_XF, objects::NO_OBJECT), susSet(this) { + ObjectManager::instance()->insert(objects::SUS_6_R_LOC_XFYBZM_PT_XF, this); + ObjectManager::instance()->insert(objects::SUS_1_N_LOC_XBYFZM_PT_XB, this); + ObjectManager::instance()->insert(objects::SUS_7_R_LOC_XBYBZM_PT_XB, this); + ObjectManager::instance()->insert(objects::SUS_2_N_LOC_XFYBZB_PT_YB, this); + ObjectManager::instance()->insert(objects::SUS_8_R_LOC_XBYBZB_PT_YB, this); + ObjectManager::instance()->insert(objects::SUS_3_N_LOC_XFYBZF_PT_YF, this); + ObjectManager::instance()->insert(objects::SUS_9_R_LOC_XBYBZB_PT_YF, this); + ObjectManager::instance()->insert(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, this); + ObjectManager::instance()->insert(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, this); + ObjectManager::instance()->insert(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, this); + ObjectManager::instance()->insert(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, this); +} + +ReturnValue_t SusDummy::initialize() { + static bool done = false; + if (not done) { + done = true; + ReturnValue_t result = ExtendedControllerBase::initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + } + + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t SusDummy::handleCommandMessage(CommandMessage* message) { return RETURN_FAILED; } + +void SusDummy::performControlOperation() { + iteration++; + value = sin(iteration / 80. * M_PI + 10) * 10 - 10; + + susSet.read(); + susSet.temperatureCelcius = value; + if ((iteration % 100) < 20) { + susSet.setValidity(false, true); + } else { + susSet.setValidity(true, true); + } + susSet.commit(); +} + +ReturnValue_t SusDummy::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) { + localDataPoolMap.emplace(SUS::SusPoolIds::TEMPERATURE_C, new PoolEntry({0}, 1, true)); + localDataPoolMap.emplace(SUS::SusPoolIds::CHANNEL_VEC, new PoolEntry({0})); + + return RETURN_OK; +} + +LocalPoolDataSetBase* SusDummy::getDataSetHandle(sid_t sid) { + switch (sid.ownerSetId) { + case SUS::SUS_DATA_SET_ID: + return &susSet; + default: + return nullptr; + } +} + +ReturnValue_t SusDummy::checkModeCommand(Mode_t mode, Submode_t submode, + uint32_t* msToReachTheMode) { + if (submode != SUBMODE_NONE) { + return INVALID_SUBMODE; + } + if ((mode != MODE_OFF) && (mode != MODE_ON) && (mode != MODE_NORMAL)) { + return INVALID_MODE; + } + return RETURN_OK; +} diff --git a/dummies/SusDummy.h b/dummies/SusDummy.h new file mode 100644 index 00000000..bdabaafc --- /dev/null +++ b/dummies/SusDummy.h @@ -0,0 +1,27 @@ +#pragma once + +#include +#include + +class SusDummy : public ExtendedControllerBase { + public: + SusDummy(); + + ReturnValue_t initialize() override; + + protected: + virtual ReturnValue_t handleCommandMessage(CommandMessage* message) override; + virtual void performControlOperation() override; + virtual ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) override; + virtual LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override; + + // Mode abstract functions + virtual ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, + uint32_t* msToReachTheMode) override; + + private: + int iteration = 0; + float value = 0; + SUS::SusDataset susSet; +}; \ No newline at end of file diff --git a/dummies/SyrlinksDummy.cpp b/dummies/SyrlinksDummy.cpp new file mode 100644 index 00000000..275f194c --- /dev/null +++ b/dummies/SyrlinksDummy.cpp @@ -0,0 +1,46 @@ +#include "SyrlinksDummy.h" + +#include + +SyrlinksDummy::SyrlinksDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie) + : DeviceHandlerBase(objectId, comif, comCookie) {} + +SyrlinksDummy::~SyrlinksDummy() {} + +void SyrlinksDummy::doStartUp() {} + +void SyrlinksDummy::doShutDown() {} + +ReturnValue_t SyrlinksDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { + return NOTHING_TO_SEND; +} + +ReturnValue_t SyrlinksDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) { + return NOTHING_TO_SEND; +} + +ReturnValue_t SyrlinksDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t *commandData, + size_t commandDataLen) { + return RETURN_OK; +} + +ReturnValue_t SyrlinksDummy::scanForReply(const uint8_t *start, size_t len, + DeviceCommandId_t *foundId, size_t *foundLen) { + return RETURN_OK; +} + +ReturnValue_t SyrlinksDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) { + return RETURN_OK; +} + +void SyrlinksDummy::fillCommandAndReplyMap() {} + +uint32_t SyrlinksDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; } + +ReturnValue_t SyrlinksDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) { + localDataPoolMap.emplace(syrlinks::TEMP_BASEBAND_BOARD, new PoolEntry({0})); + localDataPoolMap.emplace(syrlinks::TEMP_POWER_AMPLIFIER, new PoolEntry({0})); + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/dummies/SyrlinksDummy.h b/dummies/SyrlinksDummy.h new file mode 100644 index 00000000..02d7095e --- /dev/null +++ b/dummies/SyrlinksDummy.h @@ -0,0 +1,33 @@ +#ifndef DUMMIES_SYRLINKSDUMMY_H_ +#define DUMMIES_SYRLINKSDUMMY_H_ + +#include + +class SyrlinksDummy : public DeviceHandlerBase { + public: + static const DeviceCommandId_t SIMPLE_COMMAND = 1; + static const DeviceCommandId_t PERIODIC_REPLY = 2; + + static const uint8_t SIMPLE_COMMAND_DATA = 1; + static const uint8_t PERIODIC_REPLY_DATA = 2; + + SyrlinksDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie); + virtual ~SyrlinksDummy(); + + protected: + void doStartUp() override; + void doShutDown() override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData, + size_t commandDataLen) override; + ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) override; + ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override; + void fillCommandAndReplyMap() override; + uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) override; +}; + +#endif /* DUMMIES_SYRLINKSDUMMY_H_ */ diff --git a/dummies/TemperatureSensorsDummy.cpp b/dummies/TemperatureSensorsDummy.cpp new file mode 100644 index 00000000..129b20bd --- /dev/null +++ b/dummies/TemperatureSensorsDummy.cpp @@ -0,0 +1,98 @@ +#include "TemperatureSensorsDummy.h" + +#include + +#include +#include + +TemperatureSensorsDummy::TemperatureSensorsDummy() + : ExtendedControllerBase(objects::RTD_0_IC3_PLOC_HEATSPREADER, objects::NO_OBJECT), + max31865Set(this, MAX31865::MAX31865_SET_ID) { + ObjectManager::instance()->insert(objects::RTD_1_IC4_PLOC_MISSIONBOARD, this); + ObjectManager::instance()->insert(objects::RTD_2_IC5_4K_CAMERA, this); + ObjectManager::instance()->insert(objects::RTD_3_IC6_DAC_HEATSPREADER, this); + ObjectManager::instance()->insert(objects::RTD_4_IC7_STARTRACKER, this); + ObjectManager::instance()->insert(objects::RTD_5_IC8_RW1_MX_MY, this); + ObjectManager::instance()->insert(objects::RTD_6_IC9_DRO, this); + ObjectManager::instance()->insert(objects::RTD_7_IC10_SCEX, this); + ObjectManager::instance()->insert(objects::RTD_8_IC11_X8, this); + ObjectManager::instance()->insert(objects::RTD_9_IC12_HPA, this); + ObjectManager::instance()->insert(objects::RTD_10_IC13_PL_TX, this); + ObjectManager::instance()->insert(objects::RTD_11_IC14_MPA, this); + ObjectManager::instance()->insert(objects::RTD_12_IC15_ACU, this); + ObjectManager::instance()->insert(objects::RTD_13_IC16_PLPCDU_HEATSPREADER, this); + ObjectManager::instance()->insert(objects::RTD_14_IC17_TCS_BOARD, this); + ObjectManager::instance()->insert(objects::RTD_15_IC18_IMTQ, this); + ObjectManager::instance()->insert(objects::TMP1075_HANDLER_1, this); + ObjectManager::instance()->insert(objects::TMP1075_HANDLER_2, this); +} + +ReturnValue_t TemperatureSensorsDummy::initialize() { + static bool done = false; + if (not done) { + done = true; + ReturnValue_t result = ExtendedControllerBase::initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + } + + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t TemperatureSensorsDummy::handleCommandMessage(CommandMessage* message) { + return RETURN_FAILED; +} + +void TemperatureSensorsDummy::performControlOperation() { + iteration++; + value = sin(iteration / 80. * M_PI) * 10; + + ReturnValue_t result = max31865Set.read(); + if (result != RETURN_OK) { + sif::warning << "Failed to read temperature from MAX31865 dataset" << std::endl; + } + max31865Set.rtdValue = value - 5; + max31865Set.temperatureCelcius = value; + if ((iteration % 100) < 20) { + max31865Set.setValidity(false, true); + } else { + max31865Set.setValidity(true, true); + } + max31865Set.commit(); +} + +ReturnValue_t TemperatureSensorsDummy::initializeLocalDataPool( + localpool::DataPool& localDataPoolMap, LocalDataPoolManager& poolManager) { + localDataPoolMap.emplace(static_cast(MAX31865::PoolIds::RTD_VALUE), + new PoolEntry({0})); + localDataPoolMap.emplace(static_cast(MAX31865::PoolIds::TEMPERATURE_C), + new PoolEntry({0})); + localDataPoolMap.emplace(static_cast(MAX31865::PoolIds::LAST_FAULT_BYTE), + new PoolEntry({0})); + localDataPoolMap.emplace(static_cast(MAX31865::PoolIds::FAULT_BYTE), + new PoolEntry({0})); + + return RETURN_OK; +} + +LocalPoolDataSetBase* TemperatureSensorsDummy::getDataSetHandle(sid_t sid) { + sif::debug << "getHandle" << std::endl; + switch (sid.ownerSetId) { + case MAX31865::MAX31865_SET_ID: + return &max31865Set; + default: + return nullptr; + } +} + +ReturnValue_t TemperatureSensorsDummy::checkModeCommand(Mode_t mode, Submode_t submode, + uint32_t* msToReachTheMode) { + if (submode != SUBMODE_NONE) { + return INVALID_SUBMODE; + } + if ((mode != MODE_OFF) && (mode != MODE_ON) && (mode != MODE_NORMAL)) { + return INVALID_MODE; + } + return RETURN_OK; +} diff --git a/dummies/TemperatureSensorsDummy.h b/dummies/TemperatureSensorsDummy.h new file mode 100644 index 00000000..e41a9af0 --- /dev/null +++ b/dummies/TemperatureSensorsDummy.h @@ -0,0 +1,29 @@ +#pragma once + +#include +#include + +class TemperatureSensorsDummy : public ExtendedControllerBase { + public: + TemperatureSensorsDummy(); + + ReturnValue_t initialize() override; + + protected: + virtual ReturnValue_t handleCommandMessage(CommandMessage* message) override; + virtual void performControlOperation() override; + virtual ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) override; + virtual LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override; + + // Mode abstract functions + virtual ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, + uint32_t* msToReachTheMode) override; + + private: + int iteration = 0; + float value = 0; + MAX31865::Max31865Set max31865Set; + + void noise(); +}; diff --git a/fsfw b/fsfw index 80cb0e68..5abbf42e 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 80cb0e682fb423b4e7b8f45b66b3b5b7249e0d48 +Subproject commit 5abbf42e9f9b48cc244faabe88dc845e66cd0d24 diff --git a/generators/bsp_q7s_events.csv b/generators/bsp_q7s_events.csv index d48ca211..7adf38da 100644 --- a/generators/bsp_q7s_events.csv +++ b/generators/bsp_q7s_events.csv @@ -1,3 +1,4 @@ +Event ID (dec); Event ID (hex); Name; Severity; Description; File Path 2200;0x0898;STORE_SEND_WRITE_FAILED;LOW;;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h 2201;0x0899;STORE_WRITE_FAILED;LOW;;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h 2202;0x089a;STORE_SEND_READ_FAILED;LOW;;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h @@ -75,17 +76,21 @@ 7905;0x1ee1;FRAME_PROCESSING_FAILED;LOW;The CCSDS Board could not interpret a TC;fsfw/src/fsfw/datalinklayer/DataLinkLayer.h 8900;0x22c4;CLOCK_SET;INFO;;fsfw/src/fsfw/pus/Service9TimeManagement.h 8901;0x22c5;CLOCK_SET_FAILURE;LOW;;fsfw/src/fsfw/pus/Service9TimeManagement.h +9100;0x238c;TC_DELETION_FAILED;MEDIUM;Deletion of a TC from the map failed. P1: First 32 bit of request ID, P2. Last 32 bit of Request ID;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 9700;0x25e4;TEST;INFO;;fsfw/src/fsfw/pus/Service17Test.h 10600;0x2968;CHANGE_OF_SETUP_PARAMETER;LOW;;fsfw/hal/src/fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h 11300;0x2c24;SWITCH_CMD_SENT;INFO;Indicates that a FSFW object requested setting a switch P1: 1 if on was requested, 0 for off | P2: Switch Index;mission/devices/devicedefinitions/powerDefinitions.h -11301;0x2c25;SWITCH_HAS_CHANGED;INFO;Indicated that a swithc state has changed P1: New switch state, 1 for on, 0 for off | P2: Switch Index;mission/devices/devicedefinitions/powerDefinitions.h +11301;0x2c25;SWITCH_HAS_CHANGED;INFO;Indicated that a switch state has changed P1: New switch state, 1 for on, 0 for off | P2: Switch Index;mission/devices/devicedefinitions/powerDefinitions.h 11302;0x2c26;SWITCHING_Q7S_DENIED;MEDIUM;;mission/devices/devicedefinitions/powerDefinitions.h 11303;0x2c27;FDIR_REACTION_IGNORED;MEDIUM;;mission/devices/devicedefinitions/powerDefinitions.h 11400;0x2c88;GPIO_PULL_HIGH_FAILED;LOW;;mission/devices/HeaterHandler.h 11401;0x2c89;GPIO_PULL_LOW_FAILED;LOW;;mission/devices/HeaterHandler.h -11402;0x2c8a;SWITCH_ALREADY_ON;LOW;;mission/devices/HeaterHandler.h -11403;0x2c8b;SWITCH_ALREADY_OFF;LOW;;mission/devices/HeaterHandler.h -11404;0x2c8c;MAIN_SWITCH_TIMEOUT;LOW;;mission/devices/HeaterHandler.h +11402;0x2c8a;HEATER_WENT_ON;INFO;;mission/devices/HeaterHandler.h +11403;0x2c8b;HEATER_WENT_OFF;INFO;;mission/devices/HeaterHandler.h +11404;0x2c8c;SWITCH_ALREADY_ON;LOW;;mission/devices/HeaterHandler.h +11405;0x2c8d;SWITCH_ALREADY_OFF;LOW;;mission/devices/HeaterHandler.h +11406;0x2c8e;MAIN_SWITCH_TIMEOUT;MEDIUM;;mission/devices/HeaterHandler.h +11407;0x2c8f;FAULTY_HEATER_WAS_ON;LOW;;mission/devices/HeaterHandler.h 11500;0x2cec;MAIN_SWITCH_ON_TIMEOUT;LOW;;mission/devices/SolarArrayDeploymentHandler.h 11501;0x2ced;MAIN_SWITCH_OFF_TIMEOUT;LOW;;mission/devices/SolarArrayDeploymentHandler.h 11502;0x2cee;DEPLOYMENT_FAILED;HIGH;;mission/devices/SolarArrayDeploymentHandler.h @@ -95,7 +100,7 @@ 11602;0x2d52;ACK_FAILURE;LOW;PLOC receive acknowledgment failure report P1: Command Id which leads the acknowledgment failure report P2: The status field inserted by the MPSoC into the data field;linux/devices/ploc/PlocMPSoCHandler.h 11603;0x2d53;EXE_FAILURE;LOW;PLOC receive execution failure report P1: Command Id which leads the execution failure report P2: The status field inserted by the MPSoC into the data field;linux/devices/ploc/PlocMPSoCHandler.h 11604;0x2d54;MPSOC_HANDLER_CRC_FAILURE;LOW;PLOC reply has invalid crc;linux/devices/ploc/PlocMPSoCHandler.h -11605;0x2d55;MPSOC_HANDLER_SEQ_CNT_MISMATCH;LOW;Packet sequence count in received space packet does not match expected count P1: Expected sequence count P2: Received sequence count;linux/devices/ploc/PlocMPSoCHandler.h +11605;0x2d55;MPSOC_HANDLER_SEQUENCE_COUNT_MISMATCH;LOW;Packet sequence count in received space packet does not match expected count P1: Expected sequence count P2: Received sequence count;linux/devices/ploc/PlocMPSoCHandler.h 11606;0x2d56;MPSOC_SHUTDOWN_FAILED;HIGH;Supervisor fails to shutdown MPSoC. Requires to power off the PLOC and thus also to shutdown the supervisor.;linux/devices/ploc/PlocMPSoCHandler.h 11701;0x2db5;SELF_TEST_I2C_FAILURE;LOW;Get self test result returns I2C failure P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;mission/devices/IMTQHandler.h 11702;0x2db6;SELF_TEST_SPI_FAILURE;LOW;Get self test result returns SPI failure. This concerns the MTM connectivity. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;mission/devices/IMTQHandler.h @@ -105,21 +110,17 @@ 11706;0x2dba;SELF_TEST_MTM_RANGE_FAILURE;LOW;Get self test result returns failure that MTM values were outside of the expected range. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;mission/devices/IMTQHandler.h 11707;0x2dbb;SELF_TEST_COIL_CURRENT_FAILURE;LOW;Get self test result returns failure indicating that the coil current was outside of the expected range P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;mission/devices/IMTQHandler.h 11708;0x2dbc;INVALID_ERROR_BYTE;LOW;Received invalid error byte. This indicates an error of the communication link between IMTQ and OBC.;mission/devices/IMTQHandler.h -11801;0x2e19;ERROR_STATE;HIGH;Reaction wheel signals an error state;mission/devices/RwHandler.h +11801;0x2e19;ERROR_STATE;HIGH;Reaction wheel signals an error state;mission/devices/devicedefinitions/RwDefinitions.h +11802;0x2e1a;RESET_OCCURED;LOW;;mission/devices/devicedefinitions/RwDefinitions.h 11901;0x2e7d;BOOTING_FIRMWARE_FAILED;LOW;Failed to boot firmware;linux/devices/startracker/StarTrackerHandler.h 11902;0x2e7e;BOOTING_BOOTLOADER_FAILED;LOW;Failed to boot star tracker into bootloader mode;linux/devices/startracker/StarTrackerHandler.h 12001;0x2ee1;SUPV_MEMORY_READ_RPT_CRC_FAILURE;LOW;PLOC supervisor crc failure in telemetry packet;linux/devices/ploc/PlocSupervisorHandler.h 12002;0x2ee2;SUPV_ACK_FAILURE;LOW;PLOC supervisor received acknowledgment failure report;linux/devices/ploc/PlocSupervisorHandler.h -12003;0x2ee3;SUPV_EXE_FAILURE;LOW;PLOC received execution failure report;linux/devices/ploc/PlocSupervisorHandler.h +12003;0x2ee3;SUPV_EXE_FAILURE;LOW;PLOC received execution failure report P1: ID of command for which the execution failed P2: Status code sent by the supervisor handler;linux/devices/ploc/PlocSupervisorHandler.h 12004;0x2ee4;SUPV_CRC_FAILURE_EVENT;LOW;PLOC supervisor reply has invalid crc;linux/devices/ploc/PlocSupervisorHandler.h +12005;0x2ee5;SUPV_MPSOC_SHUWDOWN_BUILD_FAILED;LOW;Failed to build the command to shutdown the MPSoC;linux/devices/ploc/PlocSupervisorHandler.h 12100;0x2f44;SANITIZATION_FAILED;LOW;;bsp_q7s/memory/SdCardManager.h 12101;0x2f45;MOUNTED_SD_CARD;INFO;;bsp_q7s/memory/SdCardManager.h -12200;0x2fa8;UPDATE_FILE_NOT_EXISTS;LOW;;linux/devices/ploc/PlocUpdater.h -12201;0x2fa9;ACTION_COMMANDING_FAILED;LOW;Failed to send command to supervisor handler P1: Return value of CommandActionHelper::commandAction P2: Action ID of command to send;linux/devices/ploc/PlocUpdater.h -12202;0x2faa;UPDATE_AVAILABLE_FAILED;LOW;Supervisor handler replied action message indicating a command execution failure of the update available command;linux/devices/ploc/PlocUpdater.h -12203;0x2fab;UPDATE_TRANSFER_FAILED;LOW;Supervisor handler failed to transfer an update space packet. P1: Parameter holds the number of update packets already sent (inclusive the failed packet);linux/devices/ploc/PlocUpdater.h -12204;0x2fac;UPDATE_VERIFY_FAILED;LOW;Supervisor failed to execute the update verify command.;linux/devices/ploc/PlocUpdater.h -12205;0x2fad;UPDATE_FINISHED;INFO;MPSoC update successful completed;linux/devices/ploc/PlocUpdater.h 12300;0x300c;SEND_MRAM_DUMP_FAILED;LOW;Failed to send mram dump command to supervisor handler P1: Return value of commandAction function P2: Start address of MRAM to dump with this command;linux/devices/ploc/PlocMemoryDumper.h 12301;0x300d;MRAM_DUMP_FAILED;LOW;Received completion failure report form PLOC supervisor handler P1: MRAM start address of failing dump command;linux/devices/ploc/PlocMemoryDumper.h 12302;0x300e;MRAM_DUMP_FINISHED;LOW;MRAM dump finished successfully;linux/devices/ploc/PlocMemoryDumper.h @@ -127,6 +128,8 @@ 12402;0x3072;INVALID_FAR;HIGH;Read invalid FAR from PDEC after startup;linux/obc/PdecHandler.h 12403;0x3073;CARRIER_LOCK;INFO;Carrier lock detected;linux/obc/PdecHandler.h 12404;0x3074;BIT_LOCK_PDEC;INFO;Bit lock detected (data valid);linux/obc/PdecHandler.h +12405;0x3075;LOST_CARRIER_LOCK_PDEC;INFO;Lost carrier lock;linux/obc/PdecHandler.h +12406;0x3076;LOST_BIT_LOCK_PDEC;INFO;Lost bit lock;linux/obc/PdecHandler.h 12500;0x30d4;IMAGE_UPLOAD_FAILED;LOW;Image upload failed;linux/devices/startracker/StrHelper.h 12501;0x30d5;IMAGE_DOWNLOAD_FAILED;LOW;Image download failed;linux/devices/startracker/StrHelper.h 12502;0x30d6;IMAGE_UPLOAD_SUCCESSFUL;LOW;Uploading image to star tracker was successfulop;linux/devices/startracker/StrHelper.h @@ -146,15 +149,15 @@ 12516;0x30e4;STR_HELPER_REQUESTING_MSG_FAILED;LOW;;linux/devices/startracker/StrHelper.h 12600;0x3138;MPSOC_FLASH_WRITE_FAILED;LOW;Flash write fails;linux/devices/ploc/PlocMPSoCHelper.h 12601;0x3139;MPSOC_FLASH_WRITE_SUCCESSFUL;LOW;Flash write successful;linux/devices/ploc/PlocMPSoCHelper.h -12602;0x313a;SENDING_COMMAND_FAILED;LOW;;linux/devices/ploc/PlocMPSoCHelper.h +12602;0x313a;MPSOC_SENDING_COMMAND_FAILED;LOW;;linux/devices/ploc/PlocMPSoCHelper.h 12603;0x313b;MPSOC_HELPER_REQUESTING_REPLY_FAILED;LOW;Request receive message of communication interface failed P1: Return value returned by the communication interface requestReceiveMessage function P2: Internal state of MPSoC helper;linux/devices/ploc/PlocMPSoCHelper.h 12604;0x313c;MPSOC_HELPER_READING_REPLY_FAILED;LOW;Reading receive message of communication interface failed P1: Return value returned by the communication interface readingReceivedMessage function P2: Internal state of MPSoC helper;linux/devices/ploc/PlocMPSoCHelper.h -12605;0x313d;MISSING_ACK;LOW;Did not receive acknowledgement report P1: Number of bytes missing P2: Internal state of MPSoC helper;linux/devices/ploc/PlocMPSoCHelper.h -12606;0x313e;MISSING_EXE;LOW;Did not receive execution report P1: Number of bytes missing P2: Internal state of MPSoC helper;linux/devices/ploc/PlocMPSoCHelper.h -12607;0x313f;ACK_FAILURE_REPORT;LOW;Received acknowledgement failure report P1: Internal state of MPSoC;linux/devices/ploc/PlocMPSoCHelper.h -12608;0x3140;EXE_FAILURE_REPORT;LOW;Received execution failure report P1: Internal state of MPSoC;linux/devices/ploc/PlocMPSoCHelper.h -12609;0x3141;ACK_INVALID_APID;LOW;Expected acknowledgement report but received space packet with other apid P1: Apid of received space packet P2: Internal state of MPSoC;linux/devices/ploc/PlocMPSoCHelper.h -12610;0x3142;EXE_INVALID_APID;LOW;Expected execution report but received space packet with other apid P1: Apid of received space packet P2: Internal state of MPSoC;linux/devices/ploc/PlocMPSoCHelper.h +12605;0x313d;MPSOC_MISSING_ACK;LOW;Did not receive acknowledgment report P1: Number of bytes missing P2: Internal state of MPSoC helper;linux/devices/ploc/PlocMPSoCHelper.h +12606;0x313e;MPSOC_MISSING_EXE;LOW;Did not receive execution report P1: Number of bytes missing P2: Internal state of MPSoC helper;linux/devices/ploc/PlocMPSoCHelper.h +12607;0x313f;MPSOC_ACK_FAILURE_REPORT;LOW;Received acknowledgment failure report P1: Internal state of MPSoC;linux/devices/ploc/PlocMPSoCHelper.h +12608;0x3140;MPSOC_EXE_FAILURE_REPORT;LOW;Received execution failure report P1: Internal state of MPSoC;linux/devices/ploc/PlocMPSoCHelper.h +12609;0x3141;MPSOC_ACK_INVALID_APID;LOW;Expected acknowledgment report but received space packet with other apid P1: Apid of received space packet P2: Internal state of MPSoC;linux/devices/ploc/PlocMPSoCHelper.h +12610;0x3142;MPSOC_EXE_INVALID_APID;LOW;Expected execution report but received space packet with other apid P1: Apid of received space packet P2: Internal state of MPSoC;linux/devices/ploc/PlocMPSoCHelper.h 12611;0x3143;MPSOC_HELPER_SEQ_CNT_MISMATCH;LOW;Received sequence count does not match expected sequence count P1: Expected sequence count P2: Received sequence count;linux/devices/ploc/PlocMPSoCHelper.h 12700;0x319c;TRANSITION_BACK_TO_OFF;MEDIUM;Could not transition properly and went back to ALL OFF;mission/devices/PayloadPcduHandler.h 12701;0x319d;NEG_V_OUT_OF_BOUNDS;MEDIUM;P1: 0 -> too low, 1 -> too high P2: Float value;mission/devices/PayloadPcduHandler.h @@ -181,7 +184,27 @@ 13200;0x3390;P60_BOOT_COUNT;INFO;P60 boot count is broadcasted once at SW startup. P1: Boot count;mission/devices/P60DockHandler.h 13201;0x3391;BATT_MODE;INFO;Battery mode is broadcasted at startup. P1: Mode;mission/devices/P60DockHandler.h 13202;0x3392;BATT_MODE_CHANGED;MEDIUM;Battery mode has changed. P1: Old mode. P2: New mode;mission/devices/P60DockHandler.h -13600;0x3520;ALLOC_FAILURE;MEDIUM;;bsp_q7s/core/CoreController.h -13601;0x3521;REBOOT_SW;MEDIUM; Software reboot occured. Can also be a systemd reboot. P1: Current Chip, P2: Current Copy;bsp_q7s/core/CoreController.h -13602;0x3522;REBOOT_MECHANISM_TRIGGERED;MEDIUM;The reboot mechanism was triggered. P1: First 16 bits: Last Chip, Last 16 bits: Last Copy, P2: Each byte is the respective reboot count for the slots;bsp_q7s/core/CoreController.h -13603;0x3523;REBOOT_HW;MEDIUM;;bsp_q7s/core/CoreController.h +13600;0x3520;SUPV_UPDATE_FAILED;LOW;update failed;linux/devices/ploc/PlocSupvHelper.h +13601;0x3521;SUPV_UPDATE_SUCCESSFUL;LOW;update successful;linux/devices/ploc/PlocSupvHelper.h +13602;0x3522;SUPV_CONTINUE_UPDATE_FAILED;LOW;Continue update command failed;linux/devices/ploc/PlocSupvHelper.h +13603;0x3523;SUPV_CONTINUE_UPDATE_SUCCESSFUL;LOW;Continue update command successful;linux/devices/ploc/PlocSupvHelper.h +13604;0x3524;TERMINATED_UPDATE_PROCEDURE;LOW;Terminated update procedure by command;linux/devices/ploc/PlocSupvHelper.h +13605;0x3525;SUPV_EVENT_BUFFER_REQUEST_SUCCESSFUL;LOW;Requesting event buffer was successful;linux/devices/ploc/PlocSupvHelper.h +13606;0x3526;SUPV_EVENT_BUFFER_REQUEST_FAILED;LOW;Requesting event buffer failed;linux/devices/ploc/PlocSupvHelper.h +13607;0x3527;SUPV_EVENT_BUFFER_REQUEST_TERMINATED;LOW;Terminated event buffer request by command P1: Number of packets read before process was terminated;linux/devices/ploc/PlocSupvHelper.h +13608;0x3528;SUPV_SENDING_COMMAND_FAILED;LOW;;linux/devices/ploc/PlocSupvHelper.h +13609;0x3529;SUPV_HELPER_REQUESTING_REPLY_FAILED;LOW;Request receive message of communication interface failed P1: Return value returned by the communication interface requestReceiveMessage function P2: Internal state of supervisor helper;linux/devices/ploc/PlocSupvHelper.h +13610;0x352a;SUPV_HELPER_READING_REPLY_FAILED;LOW;Reading receive message of communication interface failed P1: Return value returned by the communication interface readingReceivedMessage function P2: Internal state of supervisor helper;linux/devices/ploc/PlocSupvHelper.h +13611;0x352b;SUPV_MISSING_ACK;LOW;Did not receive acknowledgement report P1: Number of bytes missing P2: Internal state of MPSoC helper;linux/devices/ploc/PlocSupvHelper.h +13612;0x352c;SUPV_MISSING_EXE;LOW;Supervisor did not receive execution report P1: Number of bytes missing P2: Internal state of supervisor helper;linux/devices/ploc/PlocSupvHelper.h +13613;0x352d;SUPV_ACK_FAILURE_REPORT;LOW;Supervisor received acknowledgment failure report P1: Internal state of supervisor helper;linux/devices/ploc/PlocSupvHelper.h +13614;0x352e;SUPV_EXE_FAILURE_REPORT;LOW;Execution report failure P1:;linux/devices/ploc/PlocSupvHelper.h +13615;0x352f;SUPV_ACK_INVALID_APID;LOW;Supervisor expected acknowledgment report but received space packet with other apid P1: Apid of received space packet P2: Internal state of supervisor helper;linux/devices/ploc/PlocSupvHelper.h +13616;0x3530;SUPV_EXE_INVALID_APID;LOW;Supervisor helper expected execution report but received space packet with other apid P1: Apid of received space packet P2: Internal state of supervisor helper;linux/devices/ploc/PlocSupvHelper.h +13617;0x3531;ACK_RECEPTION_FAILURE;LOW;Failed to receive acknowledgment report P1: Return value P2: Apid of command for which the reception of the acknowledgment report failed;linux/devices/ploc/PlocSupvHelper.h +13618;0x3532;EXE_RECEPTION_FAILURE;LOW;Failed to receive execution report P1: Return value P2: Apid of command for which the reception of the execution report failed;linux/devices/ploc/PlocSupvHelper.h +13619;0x3533;WRITE_MEMORY_FAILED;LOW;Update procedure failed when sending packet with number P1 P1: Packet number for which the memory write command fails;linux/devices/ploc/PlocSupvHelper.h +13700;0x3584;ALLOC_FAILURE;MEDIUM;;bsp_q7s/core/CoreController.h +13701;0x3585;REBOOT_SW;MEDIUM; Software reboot occurred. Can also be a systemd reboot. P1: Current Chip, P2: Current Copy;bsp_q7s/core/CoreController.h +13702;0x3586;REBOOT_MECHANISM_TRIGGERED;MEDIUM;The reboot mechanism was triggered. P1: First 16 bits: Last Chip, Last 16 bits: Last Copy, P2: Each byte is the respective reboot count for the slots;bsp_q7s/core/CoreController.h +13703;0x3587;REBOOT_HW;MEDIUM;;bsp_q7s/core/CoreController.h diff --git a/generators/bsp_q7s_objects.csv b/generators/bsp_q7s_objects.csv index a19c8e77..09a96584 100644 --- a/generators/bsp_q7s_objects.csv +++ b/generators/bsp_q7s_objects.csv @@ -4,18 +4,18 @@ 0x43400001;THERMAL_CONTROLLER 0x44120006;MGM_0_LIS3_HANDLER 0x44120010;GYRO_0_ADIS_HANDLER -0x44120032;SUS_0 -0x44120033;SUS_1 -0x44120034;SUS_2 -0x44120035;SUS_3 -0x44120036;SUS_4 -0x44120037;SUS_5 -0x44120038;SUS_6 -0x44120039;SUS_7 -0x44120040;SUS_8 -0x44120041;SUS_9 -0x44120042;SUS_10 -0x44120043;SUS_11 +0x44120032;SUS_0_N_LOC_XFYFZM_PT_XF +0x44120033;SUS_1_N_LOC_XBYFZM_PT_XB +0x44120034;SUS_2_N_LOC_XFYBZB_PT_YB +0x44120035;SUS_3_N_LOC_XFYBZF_PT_YF +0x44120036;SUS_4_N_LOC_XMYFZF_PT_ZF +0x44120037;SUS_5_N_LOC_XFYMZB_PT_ZB +0x44120038;SUS_6_R_LOC_XFYBZM_PT_XF +0x44120039;SUS_7_R_LOC_XBYBZM_PT_XB +0x44120040;SUS_8_R_LOC_XBYBZB_PT_YB +0x44120041;SUS_9_R_LOC_XBYBZB_PT_YF +0x44120042;SUS_10_N_LOC_XMYBZF_PT_ZF +0x44120043;SUS_11_R_LOC_XBYMZB_PT_ZB 0x44120047;RW1 0x44120107;MGM_1_RM3100_HANDLER 0x44120111;GYRO_1_L3G_HANDLER @@ -41,6 +41,8 @@ 0x44330001;PLOC_MEMORY_DUMPER 0x44330002;STR_HELPER 0x44330003;PLOC_MPSOC_HELPER +0x44330004;AXI_PTME_CONFIG +0x44330005;PTME_CONFIG 0x44330015;PLOC_MPSOC_HANDLER 0x44330016;PLOC_SUPERVISOR_HANDLER 0x44330017;PLOC_SUPERVISOR_HELPER @@ -48,26 +50,28 @@ 0x444100A4;HEATER_HANDLER 0x44420004;TMP1075_HANDLER_1 0x44420005;TMP1075_HANDLER_2 -0x44420016;RTD_IC_3 -0x44420017;RTD_IC_4 -0x44420018;RTD_IC_5 -0x44420019;RTD_IC_6 -0x44420020;RTD_IC_7 -0x44420021;RTD_IC_8 -0x44420022;RTD_IC_9 -0x44420023;RTD_IC_10 -0x44420024;RTD_IC_11 -0x44420025;RTD_IC_12 -0x44420026;RTD_IC_13 -0x44420027;RTD_IC_14 -0x44420028;RTD_IC_15 -0x44420029;RTD_IC_16 -0x44420030;RTD_IC_17 -0x44420031;RTD_IC_18 +0x44420016;RTD_0_IC3_PLOC_HEATSPREADER +0x44420017;RTD_1_IC4_PLOC_MISSIONBOARD +0x44420018;RTD_2_IC5_4K_CAMERA +0x44420019;RTD_3_IC6_DAC_HEATSPREADER +0x44420020;RTD_4_IC7_STARTRACKER +0x44420021;RTD_5_IC8_RW1_MX_MY +0x44420022;RTD_6_IC9_DRO +0x44420023;RTD_7_IC10_SCEX +0x44420024;RTD_8_IC11_X8 +0x44420025;RTD_9_IC12_HPA +0x44420026;RTD_10_IC13_PL_TX +0x44420027;RTD_11_IC14_MPA +0x44420028;RTD_12_IC15_ACU +0x44420029;RTD_13_IC16_PLPCDU_HEATSPREADER +0x44420030;RTD_14_IC17_TCS_BOARD +0x44420031;RTD_15_IC18_IMTQ 0x445300A3;SYRLINKS_HK_HANDLER 0x49000000;ARDUINO_COM_IF 0x49010005;GPIO_IF -0x49020004;SPI_COM_IF +0x49020004;SPI_MAIN_COM_IF +0x49020005;SPI_RW_COM_IF +0x49020006;SPI_RTD_COM_IF 0x49030003;UART_COM_IF 0x49040002;I2C_COM_IF 0x49050001;CSP_COM_IF @@ -88,6 +92,7 @@ 0x53000005;PUS_SERVICE_5_EVENT_REPORTING 0x53000008;PUS_SERVICE_8_FUNCTION_MGMT 0x53000009;PUS_SERVICE_9_TIME_MGMT +0x53000011;PUS_SERVICE_11_TC_SCHEDULER 0x53000017;PUS_SERVICE_17_TEST 0x53000020;PUS_SERVICE_20_PARAMETERS 0x53000200;PUS_SERVICE_200_MODE_MGMT @@ -105,13 +110,23 @@ 0x54000010;SPI_TEST 0x54000020;UART_TEST 0x54000030;I2C_TEST +0x54000040;DUMMY_COM_IF 0x5400AFFE;DUMMY_HANDLER 0x5400CAFE;DUMMY_INTERFACE 0x54123456;LIBGPIOD_TEST 0x54694269;TEST_TASK +0x60000000;HEATER_0_PLOC_PROC_BRD +0x60000001;HEATER_1_PCDU_BRD +0x60000002;HEATER_2_ACS_BRD +0x60000003;HEATER_3_OBC_BRD +0x60000004;HEATER_4_CAMERA +0x60000005;HEATER_5_STR +0x60000006;HEATER_6_DRO +0x60000007;HEATER_7_HPA 0x73000001;ACS_BOARD_ASS 0x73000002;SUS_BOARD_ASS 0x73000003;TCS_BOARD_ASS +0x73000004;RW_ASS 0x73000100;TM_FUNNEL 0x73500000;CCSDS_IP_CORE_BRIDGE 0xFFFFFFFF;NO_OBJECT diff --git a/generators/bsp_q7s_returnvalues.csv b/generators/bsp_q7s_returnvalues.csv index 0081805a..a74cfaa2 100644 --- a/generators/bsp_q7s_returnvalues.csv +++ b/generators/bsp_q7s_returnvalues.csv @@ -1,552 +1,466 @@ -0x0;OK;System-wide code for ok.;RETURN_OK;HasReturnvaluesIF.h;HasReturnvaluesIF -0x1;Failed;Unspecified system-wide code for failed.;RETURN_FAILED;HasReturnvaluesIF.h;HasReturnvaluesIF -0x65a0;NVMB_KeyNotExists;Specified key does not exist in json file;0xA0;mission/memory/NVMParameterBase.h;NVM_PARAM_BASE -0x5aa0;SUSS_ErrorUnlockMutex;;0xA0;mission/devices/SusHandler.h;SUS_HANDLER -0x5aa1;SUSS_ErrorLockMutex;;0xA1;mission/devices/SusHandler.h;SUS_HANDLER -0x68a0;SADPL_CommandNotSupported;;0xA0;mission/devices/SolarArrayDeploymentHandler.h;SA_DEPL_HANDLER -0x68a1;SADPL_DeploymentAlreadyExecuting;;0xA1;mission/devices/SolarArrayDeploymentHandler.h;SA_DEPL_HANDLER -0x68a2;SADPL_MainSwitchTimeoutFailure;;0xA2;mission/devices/SolarArrayDeploymentHandler.h;SA_DEPL_HANDLER -0x68a3;SADPL_SwitchingDeplSa1Failed;;0xA3;mission/devices/SolarArrayDeploymentHandler.h;SA_DEPL_HANDLER -0x68a4;SADPL_SwitchingDeplSa2Failed;;0xA4;mission/devices/SolarArrayDeploymentHandler.h;SA_DEPL_HANDLER -0x55b0;RWHA_SpiWriteFailure;;0xB0;mission/devices/RwHandler.h;RW_HANDLER -0x55b1;RWHA_SpiReadFailure;Used by the spi send function to tell a failing read call;0xB1;mission/devices/RwHandler.h;RW_HANDLER -0x55b2;RWHA_MissingStartSign;Can be used by the HDLC decoding mechanism to inform about a missing start sign 0x7E;0xB2;mission/devices/RwHandler.h;RW_HANDLER -0x55b3;RWHA_InvalidSubstitute;Can be used by the HDLC decoding mechanism to inform about an invalid substitution combination;0xB3;mission/devices/RwHandler.h;RW_HANDLER -0x55b4;RWHA_MissingEndSign;HDLC decoding mechanism never receives the end sign 0x7E;0xB4;mission/devices/RwHandler.h;RW_HANDLER -0x55b5;RWHA_NoReply;Reaction wheel only responds with empty frames.;0xB5;mission/devices/RwHandler.h;RW_HANDLER -0x55b6;RWHA_NoStartMarker;Expected a start marker as first byte;0xB6;mission/devices/RwHandler.h;RW_HANDLER -0x55a0;RWHA_InvalidSpeed;Action Message with invalid speed was received. Valid speeds must be in the range of [-65000; 1000] or [1000; 65000];0xA0;mission/devices/RwHandler.h;RW_HANDLER -0x55a1;RWHA_InvalidRampTime;Action Message with invalid ramp time was received.;0xA1;mission/devices/RwHandler.h;RW_HANDLER -0x55a2;RWHA_SetSpeedCommandInvalidLength;Received set speed command has invalid length. Should be 6.;0xA2;mission/devices/RwHandler.h;RW_HANDLER -0x55a3;RWHA_ExecutionFailed;Command execution failed;0xA3;mission/devices/RwHandler.h;RW_HANDLER -0x55a4;RWHA_CrcError;Reaction wheel reply has invalid crc;0xA4;mission/devices/RwHandler.h;RW_HANDLER -0x5f00;GOMS_PacketTooLong;;0;mission/devices/GomspaceDeviceHandler.h;GOM_SPACE_HANDLER -0x5f01;GOMS_InvalidTableId;;1;mission/devices/GomspaceDeviceHandler.h;GOM_SPACE_HANDLER -0x5f02;GOMS_InvalidAddress;;2;mission/devices/GomspaceDeviceHandler.h;GOM_SPACE_HANDLER -0x5f03;GOMS_InvalidParamSize;;3;mission/devices/GomspaceDeviceHandler.h;GOM_SPACE_HANDLER -0x5f04;GOMS_InvalidPayloadSize;;4;mission/devices/GomspaceDeviceHandler.h;GOM_SPACE_HANDLER -0x5f05;GOMS_UnknownReplyId;;5;mission/devices/GomspaceDeviceHandler.h;GOM_SPACE_HANDLER -0x54a0;IMTQ_InvalidCommandCode;;0xA0;mission/devices/IMTQHandler.h;IMTQ_HANDLER -0x54a1;IMTQ_ParameterMissing;;0xA1;mission/devices/IMTQHandler.h;IMTQ_HANDLER -0x54a2;IMTQ_ParameterInvalid;;0xA2;mission/devices/IMTQHandler.h;IMTQ_HANDLER -0x54a3;IMTQ_CcUnavailable;;0xA3;mission/devices/IMTQHandler.h;IMTQ_HANDLER -0x54a4;IMTQ_InternalProcessingError;;0xA4;mission/devices/IMTQHandler.h;IMTQ_HANDLER -0x54a5;IMTQ_RejectedWithoutReason;;0xA5;mission/devices/IMTQHandler.h;IMTQ_HANDLER -0x54a6;IMTQ_CmdErrUnknown;;0xA6;mission/devices/IMTQHandler.h;IMTQ_HANDLER -0x54a7;IMTQ_UnexpectedSelfTestReply;The status reply to a self test command was received but no self test command has been sent. This should normally never happen.;0xA7;mission/devices/IMTQHandler.h;IMTQ_HANDLER -0x53a0;SYRLINKS_CrcFailure;;0xA0;mission/devices/SyrlinksHkHandler.h;SYRLINKS_HANDLER -0x53a1;SYRLINKS_UartFraminOrParityErrorAck;;0xA1;mission/devices/SyrlinksHkHandler.h;SYRLINKS_HANDLER -0x53a2;SYRLINKS_BadCharacterAck;;0xA2;mission/devices/SyrlinksHkHandler.h;SYRLINKS_HANDLER -0x53a3;SYRLINKS_BadParameterValueAck;;0xA3;mission/devices/SyrlinksHkHandler.h;SYRLINKS_HANDLER -0x53a4;SYRLINKS_BadEndOfFrameAck;;0xA4;mission/devices/SyrlinksHkHandler.h;SYRLINKS_HANDLER -0x53a5;SYRLINKS_UnknownCommandIdAck;;0xA5;mission/devices/SyrlinksHkHandler.h;SYRLINKS_HANDLER -0x53a6;SYRLINKS_BadCrcAck;;0xA6;mission/devices/SyrlinksHkHandler.h;SYRLINKS_HANDLER -0x53a7;SYRLINKS_ReplyWrongSize;;0xA7;mission/devices/SyrlinksHkHandler.h;SYRLINKS_HANDLER -0x53a8;SYRLINKS_MissingStartFrameCharacter;;0xA8;mission/devices/SyrlinksHkHandler.h;SYRLINKS_HANDLER -0x52a1;HEATER_CommandNotSupported;;0xA1;mission/devices/HeaterHandler.h;HEATER_HANDLER -0x52a2;HEATER_InitFailed;;0xA2;mission/devices/HeaterHandler.h;HEATER_HANDLER -0x52a3;HEATER_InvalidSwitchNr;;0xA3;mission/devices/HeaterHandler.h;HEATER_HANDLER -0x52a4;HEATER_MainSwitchSetTimeout;;0xA4;mission/devices/HeaterHandler.h;HEATER_HANDLER -0x52a5;HEATER_CommandAlreadyWaiting;;0xA5;mission/devices/HeaterHandler.h;HEATER_HANDLER -0x62a0;CCSDS_CommandNotImplemented;Received action message with unknown action id;0xA0;mission/tmtc/CCSDSHandler.h;CCSDS_HANDLER -0x2701; SM_DataTooLarge;;1;fsfw/src/fsfw/storagemanager/StorageManagerIF.h;STORAGE_MANAGER_IF -0x2702; SM_DataStorageFull;;2;fsfw/src/fsfw/storagemanager/StorageManagerIF.h;STORAGE_MANAGER_IF -0x2703; SM_IllegalStorageId;;3;fsfw/src/fsfw/storagemanager/StorageManagerIF.h;STORAGE_MANAGER_IF -0x2704; SM_DataDoesNotExist;;4;fsfw/src/fsfw/storagemanager/StorageManagerIF.h;STORAGE_MANAGER_IF -0x2705; SM_IllegalAddress;;5;fsfw/src/fsfw/storagemanager/StorageManagerIF.h;STORAGE_MANAGER_IF -0x2706; SM_PoolTooLarge;;6;fsfw/src/fsfw/storagemanager/StorageManagerIF.h;STORAGE_MANAGER_IF -0x601; PP_DoItMyself;;1;fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x602; PP_PointsToVariable;;2;fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x603; PP_PointsToMemory;;3;fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x604; PP_ActivityCompleted;;4;fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x605; PP_PointsToVectorUint8;;5;fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x606; PP_PointsToVectorUint16;;6;fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x607; PP_PointsToVectorUint32;;7;fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x608; PP_PointsToVectorFloat;;8;fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x6a0; PP_DumpNotSupported;;0xA0;fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x6e0; PP_InvalidSize;;0xE0;fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x6e1; PP_InvalidAddress;;0xE1;fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x6e2; PP_InvalidContent;;0xE2;fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x6e3; PP_UnalignedAccess;;0xE3;fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x6e4; PP_WriteProtected;;0xE4;fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x4100; FILS_GenericFileError;;0;fsfw/src/fsfw/memory/HasFileSystemIF.h;FILE_SYSTEM -0x4101; FILS_IsBusy;;1;fsfw/src/fsfw/memory/HasFileSystemIF.h;FILE_SYSTEM -0x4102; FILS_InvalidParameters;;2;fsfw/src/fsfw/memory/HasFileSystemIF.h;FILE_SYSTEM -0x4105; FILS_FileDoesNotExist;;5;fsfw/src/fsfw/memory/HasFileSystemIF.h;FILE_SYSTEM -0x4106; FILS_FileAlreadyExists;;6;fsfw/src/fsfw/memory/HasFileSystemIF.h;FILE_SYSTEM -0x4107; FILS_FileLocked;;7;fsfw/src/fsfw/memory/HasFileSystemIF.h;FILE_SYSTEM -0x410a; FILS_DirectoryDoesNotExist;;10;fsfw/src/fsfw/memory/HasFileSystemIF.h;FILE_SYSTEM -0x410b; FILS_DirectoryAlreadyExists;;11;fsfw/src/fsfw/memory/HasFileSystemIF.h;FILE_SYSTEM -0x410c; FILS_DirectoryNotEmpty;;12;fsfw/src/fsfw/memory/HasFileSystemIF.h;FILE_SYSTEM -0x410f; FILS_SequencePacketMissingWrite;;15;fsfw/src/fsfw/memory/HasFileSystemIF.h;FILE_SYSTEM -0x4110; FILS_SequencePacketMissingRead;;16;fsfw/src/fsfw/memory/HasFileSystemIF.h;FILE_SYSTEM -0x13e0; MH_UnknownCmd;;0xE0;fsfw/src/fsfw/memory/MemoryHelper.h;MEMORY_HELPER -0x13e1; MH_InvalidAddress;;0xE1;fsfw/src/fsfw/memory/MemoryHelper.h;MEMORY_HELPER -0x13e2; MH_InvalidSize;;0xE2;fsfw/src/fsfw/memory/MemoryHelper.h;MEMORY_HELPER -0x13e3; MH_StateMismatch;;0xE3;fsfw/src/fsfw/memory/MemoryHelper.h;MEMORY_HELPER -0x37a1; SGP4_InvalidEccentricity;;0xA1;fsfw/src/fsfw/coordinates/Sgp4Propagator.h;SGP4PROPAGATOR_CLASS -0x37a2; SGP4_InvalidMeanMotion;;0xA2;fsfw/src/fsfw/coordinates/Sgp4Propagator.h;SGP4PROPAGATOR_CLASS -0x37a3; SGP4_InvalidPerturbationElements;;0xA3;fsfw/src/fsfw/coordinates/Sgp4Propagator.h;SGP4PROPAGATOR_CLASS -0x37a4; SGP4_InvalidSemiLatusRectum;;0xA4;fsfw/src/fsfw/coordinates/Sgp4Propagator.h;SGP4PROPAGATOR_CLASS -0x37a5; SGP4_InvalidEpochElements;;0xA5;fsfw/src/fsfw/coordinates/Sgp4Propagator.h;SGP4PROPAGATOR_CLASS -0x37a6; SGP4_SatelliteHasDecayed;;0xA6;fsfw/src/fsfw/coordinates/Sgp4Propagator.h;SGP4PROPAGATOR_CLASS -0x37b1; SGP4_TleTooOld;;0xB1;fsfw/src/fsfw/coordinates/Sgp4Propagator.h;SGP4PROPAGATOR_CLASS -0x37b2; SGP4_TleNotInitialized;;0xB2;fsfw/src/fsfw/coordinates/Sgp4Propagator.h;SGP4PROPAGATOR_CLASS -0x1101; AL_Full;;0x01;fsfw/src/fsfw/container/ArrayList.h;ARRAY_LIST -0x1501; FM_KeyAlreadyExists;;0x01;fsfw/src/fsfw/container/FixedMap.h;FIXED_MAP -0x1502; FM_MapFull;;0x02;fsfw/src/fsfw/container/FixedMap.h;FIXED_MAP -0x1503; FM_KeyDoesNotExist;;0x03;fsfw/src/fsfw/container/FixedMap.h;FIXED_MAP -0x1801; FF_Full;;1;fsfw/src/fsfw/container/FIFOBase.h;FIFO_CLASS -0x1802; FF_Empty;;2;fsfw/src/fsfw/container/FIFOBase.h;FIFO_CLASS -0x1601; FMM_MapFull;;0x01;fsfw/src/fsfw/container/FixedOrderedMultimap.h;FIXED_MULTIMAP -0x1602; FMM_KeyDoesNotExist;;0x02;fsfw/src/fsfw/container/FixedOrderedMultimap.h;FIXED_MULTIMAP -0x3801; MUX_NotEnoughResources;;1;fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x3802; MUX_InsufficientMemory;;2;fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x3803; MUX_NoPrivilege;;3;fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x3804; MUX_WrongAttributeSetting;;4;fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x3805; MUX_MutexAlreadyLocked;;5;fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x3806; MUX_MutexNotFound;;6;fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x3807; MUX_MutexMaxLocks;;7;fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x3808; MUX_CurrThreadAlreadyOwnsMutex;;8;fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x3809; MUX_CurrThreadDoesNotOwnMutex;;9;fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x380a; MUX_MutexTimeout;;10;fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x380b; MUX_MutexInvalidId;;11;fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x380c; MUX_MutexDestroyedWhileWaiting;;12;fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x3901; MQI_Empty;;1;fsfw/src/fsfw/ipc/MessageQueueIF.h;MESSAGE_QUEUE_IF -0x3902; MQI_Full;No space left for more messages;2;fsfw/src/fsfw/ipc/MessageQueueIF.h;MESSAGE_QUEUE_IF -0x3903; MQI_NoReplyPartner;Returned if a reply method was called without partner;3;fsfw/src/fsfw/ipc/MessageQueueIF.h;MESSAGE_QUEUE_IF -0x3904; MQI_DestinationInvalid;Returned if the target destination is invalid.;4;fsfw/src/fsfw/ipc/MessageQueueIF.h;MESSAGE_QUEUE_IF -0xf01; CM_UnknownCommand;;1;fsfw/src/fsfw/ipc/CommandMessageIF.h;COMMAND_MESSAGE -0xe01; HM_InvalidMode;;0x01;fsfw/src/fsfw/modes/HasModesIF.h;HAS_MODES_IF -0xe02; HM_TransNotAllowed;;0x02;fsfw/src/fsfw/modes/HasModesIF.h;HAS_MODES_IF -0xe03; HM_InTransition;;0x03;fsfw/src/fsfw/modes/HasModesIF.h;HAS_MODES_IF -0xe04; HM_InvalidSubmode;;0x04;fsfw/src/fsfw/modes/HasModesIF.h;HAS_MODES_IF -0xc02; MS_InvalidEntry;;0x02;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h;MODE_STORE_IF -0xc03; MS_TooManyElements;;0x03;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h;MODE_STORE_IF -0xc04; MS_CantStoreEmpty;;0x04;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h;MODE_STORE_IF -0xb01; SB_ChildNotFound;;0x01;fsfw/src/fsfw/subsystem/SubsystemBase.h;SUBSYSTEM_BASE -0xb02; SB_ChildInfoUpdated;;0x02;fsfw/src/fsfw/subsystem/SubsystemBase.h;SUBSYSTEM_BASE -0xb03; SB_ChildDoesntHaveModes;;0x03;fsfw/src/fsfw/subsystem/SubsystemBase.h;SUBSYSTEM_BASE -0xb04; SB_CouldNotInsertChild;;0x04;fsfw/src/fsfw/subsystem/SubsystemBase.h;SUBSYSTEM_BASE -0xb05; SB_TableContainsInvalidObjectId;;0x05;fsfw/src/fsfw/subsystem/SubsystemBase.h;SUBSYSTEM_BASE -0xd01; SS_SequenceAlreadyExists;;0x01;fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xd02; SS_TableAlreadyExists;;0x02;fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xd03; SS_TableDoesNotExist;;0x03;fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xd04; SS_TableOrSequenceLengthInvalid;;0x04;fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xd05; SS_SequenceDoesNotExist;;0x05;fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xd06; SS_TableContainsInvalidObjectId;;0x06;fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xd07; SS_FallbackSequenceDoesNotExist;;0x07;fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xd08; SS_NoTargetTable;;0x08;fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xd09; SS_SequenceOrTableTooLong;;0x09;fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xd0b; SS_IsFallbackSequence;;0x0B;fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xd0c; SS_AccessDenied;;0x0C;fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xd0e; SS_TableInUse;;0x0E;fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xda1; SS_TargetTableNotReached;;0xA1;fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xda2; SS_TableCheckFailed;;0xA2;fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0x2401; EV_ListenerNotFound;;1;fsfw/src/fsfw/events/EventManagerIF.h;EVENT_MANAGER_IF -0x4e1; RMP_CommandNoDescriptorsAvailable;;0xE1;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4e2; RMP_CommandBufferFull;;0xE2;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4e3; RMP_CommandChannelOutOfRange;;0xE3;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4e6; RMP_CommandChannelDeactivated;;0xE6;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4e7; RMP_CommandPortOutOfRange;;0xE7;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4e8; RMP_CommandPortInUse;;0xE8;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4e9; RMP_CommandNoChannel;;0xE9;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4ea; RMP_NoHwCrc;;0xEA;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4d0; RMP_ReplyNoReply;;0xD0;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4d1; RMP_ReplyNotSent;;0xD1;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4d2; RMP_ReplyNotYetSent;;0xD2;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4d3; RMP_ReplyMissmatch;;0xD3;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4d4; RMP_ReplyTimeout;;0xD4;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4c0; RMP_ReplyInterfaceBusy;;0xC0;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4c1; RMP_ReplyTransmissionError;;0xC1;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4c2; RMP_ReplyInvalidData;;0xC2;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4c3; RMP_ReplyNotSupported;;0xC3;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4f0; RMP_LinkDown;;0xF0;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4f1; RMP_SpwCredit;;0xF1;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4f2; RMP_SpwEscape;;0xF2;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4f3; RMP_SpwDisconnect;;0xF3;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4f4; RMP_SpwParity;;0xF4;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4f5; RMP_SpwWriteSync;;0xF5;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4f6; RMP_SpwInvalidAddress;;0xF6;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4f7; RMP_SpwEarlyEop;;0xF7;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4f8; RMP_SpwDma;;0xF8;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4f9; RMP_SpwLinkError;;0xF9;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x400; RMP_ReplyOk;;0;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x401; RMP_ReplyGeneralErrorCode;;1;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x402; RMP_ReplyUnusedPacketTypeOrCommandCode;;2;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x403; RMP_ReplyInvalidKey;;3;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x404; RMP_ReplyInvalidDataCrc;;4;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x405; RMP_ReplyEarlyEop;;5;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x406; RMP_ReplyTooMuchData;;6;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x407; RMP_ReplyEep;;7;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x408; RMP_ReplyReserved;;8;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x409; RMP_ReplyVerifyBufferOverrun;;9;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x40a; RMP_ReplyCommandNotImplementedOrNotAuthorised;;10;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x40b; RMP_ReplyRmwDataLengthError;;11;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x40c; RMP_ReplyInvalidTargetLogicalAddress;;12;fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x1401; SE_BufferTooShort;;1;fsfw/src/fsfw/serialize/SerializeIF.h;SERIALIZE_IF -0x1402; SE_StreamTooShort;;2;fsfw/src/fsfw/serialize/SerializeIF.h;SERIALIZE_IF -0x1403; SE_TooManyElements;;3;fsfw/src/fsfw/serialize/SerializeIF.h;SERIALIZE_IF -0x3ca0; PVA_InvalidReadWriteMode;;0xA0;fsfw/src/fsfw/datapool/PoolVariableIF.h;POOL_VARIABLE_IF -0x3ca1; PVA_InvalidPoolEntry;;0xA1;fsfw/src/fsfw/datapool/PoolVariableIF.h;POOL_VARIABLE_IF -0x801; DPS_InvalidParameterDefinition;;1;fsfw/src/fsfw/datapool/DataSetIF.h;DATA_SET_CLASS -0x802; DPS_SetWasAlreadyRead;;2;fsfw/src/fsfw/datapool/DataSetIF.h;DATA_SET_CLASS -0x803; DPS_CommitingWithoutReading;;3;fsfw/src/fsfw/datapool/DataSetIF.h;DATA_SET_CLASS -0x804; DPS_DataSetUninitialised;;4;fsfw/src/fsfw/datapool/DataSetIF.h;DATA_SET_CLASS -0x805; DPS_DataSetFull;;5;fsfw/src/fsfw/datapool/DataSetIF.h;DATA_SET_CLASS -0x806; DPS_PoolVarNull;;6;fsfw/src/fsfw/datapool/DataSetIF.h;DATA_SET_CLASS -0x1b00; TCC_IllegalApid;;0;fsfw/src/fsfw/tcdistribution/TcPacketCheckPUS.h;TC_PACKET_CHECK -0x1b01; TCC_IncompletePacket;;1;fsfw/src/fsfw/tcdistribution/TcPacketCheckPUS.h;TC_PACKET_CHECK -0x1b02; TCC_IncorrectChecksum;;2;fsfw/src/fsfw/tcdistribution/TcPacketCheckPUS.h;TC_PACKET_CHECK -0x1b03; TCC_IllegalPacketType;;3;fsfw/src/fsfw/tcdistribution/TcPacketCheckPUS.h;TC_PACKET_CHECK -0x1b04; TCC_IllegalPacketSubtype;;4;fsfw/src/fsfw/tcdistribution/TcPacketCheckPUS.h;TC_PACKET_CHECK -0x1b05; TCC_IncorrectPrimaryHeader;;5;fsfw/src/fsfw/tcdistribution/TcPacketCheckPUS.h;TC_PACKET_CHECK -0x1b06; TCC_IncorrectSecondaryHeader;;6;fsfw/src/fsfw/tcdistribution/TcPacketCheckPUS.h;TC_PACKET_CHECK -0x1c01; TCD_PacketLost;;1;fsfw/src/fsfw/tcdistribution/TcDistributor.h;PACKET_DISTRIBUTION -0x1c02; TCD_DestinationNotFound;;2;fsfw/src/fsfw/tcdistribution/TcDistributor.h;PACKET_DISTRIBUTION -0x1c03; TCD_ServiceIdAlreadyExists;;3;fsfw/src/fsfw/tcdistribution/TcDistributor.h;PACKET_DISTRIBUTION -0x2f01; POS_InPowerTransition;;1;fsfw/src/fsfw/power/PowerSwitcher.h;POWER_SWITCHER -0x2f02; POS_SwitchStateMismatch;;2;fsfw/src/fsfw/power/PowerSwitcher.h;POWER_SWITCHER -0x501; PS_SwitchOn;;1;fsfw/src/fsfw/power/PowerSwitchIF.h;POWER_SWITCH_IF -0x500; PS_SwitchOff;;0;fsfw/src/fsfw/power/PowerSwitchIF.h;POWER_SWITCH_IF -0x502; PS_SwitchTimeout;;2;fsfw/src/fsfw/power/PowerSwitchIF.h;POWER_SWITCH_IF -0x503; PS_FuseOn;;3;fsfw/src/fsfw/power/PowerSwitchIF.h;POWER_SWITCH_IF -0x504; PS_FuseOff;;4;fsfw/src/fsfw/power/PowerSwitchIF.h;POWER_SWITCH_IF -0x3a00; SPH_ConnBroken;;0;fsfw/src/fsfw/osal/common/TcpTmTcServer.h;SEMAPHORE_IF -0x2901; IEC_NoConfigurationTable;;0x01;fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2902; IEC_NoCpuTable;;0x02;fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2903; IEC_InvalidWorkspaceAddress;;0x03;fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2904; IEC_TooLittleWorkspace;;0x04;fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2905; IEC_WorkspaceAllocation;;0x05;fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2906; IEC_InterruptStackTooSmall;;0x06;fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2907; IEC_ThreadExitted;;0x07;fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2908; IEC_InconsistentMpInformation;;0x08;fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2909; IEC_InvalidNode;;0x09;fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x290a; IEC_NoMpci;;0x0a;fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x290b; IEC_BadPacket;;0x0b;fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x290c; IEC_OutOfPackets;;0x0c;fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x290d; IEC_OutOfGlobalObjects;;0x0d;fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x290e; IEC_OutOfProxies;;0x0e;fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x290f; IEC_InvalidGlobalId;;0x0f;fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2910; IEC_BadStackHook;;0x10;fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2911; IEC_BadAttributes;;0x11;fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2912; IEC_ImplementationKeyCreateInconsistency;;0x12;fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2913; IEC_ImplementationBlockingOperationCancel;;0x13;fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2914; IEC_MutexObtainFromBadState;;0x14;fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2915; IEC_UnlimitedAndMaximumIs0;;0x15;fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2500; FDI_YourFault;;0;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h;HANDLES_FAILURES_IF -0x2501; FDI_MyFault;;1;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h;HANDLES_FAILURES_IF -0x2502; FDI_ConfirmLater;;2;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h;HANDLES_FAILURES_IF -0x201; OM_InsertionFailed;;1;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h;OBJECT_MANAGER_IF -0x202; OM_NotFound;;2;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h;OBJECT_MANAGER_IF -0x203; OM_ChildInitFailed;;3;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h;OBJECT_MANAGER_IF -0x204; OM_InternalErrReporterUninit;;4;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h;OBJECT_MANAGER_IF -0x2101; TMF_Busy;;1;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h;TM_STORE_FRONTEND_IF -0x2102; TMF_LastPacketFound;;2;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h;TM_STORE_FRONTEND_IF -0x2103; TMF_StopFetch;;3;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h;TM_STORE_FRONTEND_IF -0x2104; TMF_Timeout;;4;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h;TM_STORE_FRONTEND_IF -0x2105; TMF_TmChannelFull;;5;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h;TM_STORE_FRONTEND_IF -0x2106; TMF_NotStored;;6;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h;TM_STORE_FRONTEND_IF -0x2107; TMF_AllDeleted;;7;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h;TM_STORE_FRONTEND_IF -0x2108; TMF_InvalidData;;8;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h;TM_STORE_FRONTEND_IF -0x2109; TMF_NotReady;;9;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h;TM_STORE_FRONTEND_IF -0x2001; TMB_Busy;;1;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x2002; TMB_Full;;2;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x2003; TMB_Empty;;3;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x2004; TMB_NullRequested;;4;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x2005; TMB_TooLarge;;5;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x2006; TMB_NotReady;;6;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x2007; TMB_DumpError;;7;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x2008; TMB_CrcError;;8;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x2009; TMB_Timeout;;9;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x200a; TMB_IdlePacketFound;;10;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x200b; TMB_TelecommandFound;;11;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x200c; TMB_NoPusATm;;12;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x200d; TMB_TooSmall;;13;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x200e; TMB_BlockNotFound;;14;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x200f; TMB_InvalidRequest;;15;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x2c01; PAW_UnknownDatatype;;0x01;fsfw/src/fsfw/parameters/ParameterWrapper.h;PARAMETER_WRAPPER -0x2c02; PAW_DatatypeMissmatch;;0x02;fsfw/src/fsfw/parameters/ParameterWrapper.h;PARAMETER_WRAPPER -0x2c03; PAW_Readonly;;0x03;fsfw/src/fsfw/parameters/ParameterWrapper.h;PARAMETER_WRAPPER -0x2c04; PAW_TooBig;;0x04;fsfw/src/fsfw/parameters/ParameterWrapper.h;PARAMETER_WRAPPER -0x2c05; PAW_SourceNotSet;;0x05;fsfw/src/fsfw/parameters/ParameterWrapper.h;PARAMETER_WRAPPER -0x2c06; PAW_OutOfBounds;;0x06;fsfw/src/fsfw/parameters/ParameterWrapper.h;PARAMETER_WRAPPER -0x2c07; PAW_NotSet;;0x07;fsfw/src/fsfw/parameters/ParameterWrapper.h;PARAMETER_WRAPPER -0x2c08; PAW_ColumnOrRowsZero;;0x08;fsfw/src/fsfw/parameters/ParameterWrapper.h;PARAMETER_WRAPPER -0x2d01; HPA_InvalidIdentifierId;;0x01;fsfw/src/fsfw/parameters/HasParametersIF.h;HAS_PARAMETERS_IF -0x2d02; HPA_InvalidDomainId;;0x02;fsfw/src/fsfw/parameters/HasParametersIF.h;HAS_PARAMETERS_IF -0x2d03; HPA_InvalidValue;;0x03;fsfw/src/fsfw/parameters/HasParametersIF.h;HAS_PARAMETERS_IF -0x2d05; HPA_ReadOnly;;0x05;fsfw/src/fsfw/parameters/HasParametersIF.h;HAS_PARAMETERS_IF -0x3a01; SPH_SemaphoreTimeout;;1;fsfw/src/fsfw/tasks/SemaphoreIF.h;SEMAPHORE_IF -0x3a02; SPH_SemaphoreNotOwned;;2;fsfw/src/fsfw/tasks/SemaphoreIF.h;SEMAPHORE_IF -0x3a03; SPH_SemaphoreInvalid;;3;fsfw/src/fsfw/tasks/SemaphoreIF.h;SEMAPHORE_IF -0x1a01; TRC_NotEnoughSensors;;1;fsfw/src/fsfw/monitoring/TriplexMonitor.h;TRIPLE_REDUNDACY_CHECK -0x1a02; TRC_LowestValueOol;;2;fsfw/src/fsfw/monitoring/TriplexMonitor.h;TRIPLE_REDUNDACY_CHECK -0x1a03; TRC_HighestValueOol;;3;fsfw/src/fsfw/monitoring/TriplexMonitor.h;TRIPLE_REDUNDACY_CHECK -0x1a04; TRC_BothValuesOol;;4;fsfw/src/fsfw/monitoring/TriplexMonitor.h;TRIPLE_REDUNDACY_CHECK -0x1a05; TRC_DuplexOol;;5;fsfw/src/fsfw/monitoring/TriplexMonitor.h;TRIPLE_REDUNDACY_CHECK -0x3001; LIM_Unchecked;;1;fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x3002; LIM_Invalid;;2;fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x3003; LIM_Unselected;;3;fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x3004; LIM_BelowLowLimit;;4;fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x3005; LIM_AboveHighLimit;;5;fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x3006; LIM_UnexpectedValue;;6;fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x3007; LIM_OutOfRange;;7;fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x30a0; LIM_FirstSample;;0xA0;fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x30e0; LIM_InvalidSize;;0xE0;fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x30e1; LIM_WrongType;;0xE1;fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x30e2; LIM_WrongPid;;0xE2;fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x30e3; LIM_WrongLimitId;;0xE3;fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x30ee; LIM_MonitorNotFound;;0xEE;fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x3501; CFDP_InvalidTlvType;;1;fsfw/src/fsfw/cfdp/definitions.h;CFDP -0x3502; CFDP_InvalidDirectiveFields;;2;fsfw/src/fsfw/cfdp/definitions.h;CFDP -0x3503; CFDP_InvalidPduDatafieldLen;;3;fsfw/src/fsfw/cfdp/definitions.h;CFDP -0x3504; CFDP_InvalidAckDirectiveFields;;4;fsfw/src/fsfw/cfdp/definitions.h;CFDP -0x3505; CFDP_MetadataCantParseOptions;;5;fsfw/src/fsfw/cfdp/definitions.h;CFDP -0x3506; CFDP_FinishedCantParseFsResponses;;6;fsfw/src/fsfw/cfdp/definitions.h;CFDP -0x3508; CFDP_FilestoreRequiresSecondFile;;8;fsfw/src/fsfw/cfdp/definitions.h;CFDP -0x3509; CFDP_FilestoreResponseCantParseFsMessage;;9;fsfw/src/fsfw/cfdp/definitions.h;CFDP -0x2b01; CCS_BcIsSetVrCommand;;0x01;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2b02; CCS_BcIsUnlockCommand;;0x02;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bb0; CCS_BcIllegalCommand;;0xB0;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bb1; CCS_BoardReadingNotFinished;;0xB1;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bf0; CCS_NsPositiveW;;0xF0;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bf1; CCS_NsNegativeW;;0xF1;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bf2; CCS_NsLockout;;0xF2;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bf3; CCS_FarmInLockout;;0xF3;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bf4; CCS_FarmInWait;;0xF4;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2be0; CCS_WrongSymbol;;0xE0;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2be1; CCS_DoubleStart;;0xE1;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2be2; CCS_StartSymbolMissed;;0xE2;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2be3; CCS_EndWithoutStart;;0xE3;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2be4; CCS_TooLarge;;0xE4;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2be5; CCS_TooShort;;0xE5;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2be6; CCS_WrongTfVersion;;0xE6;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2be7; CCS_WrongSpacecraftId;;0xE7;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2be8; CCS_NoValidFrameType;;0xE8;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2be9; CCS_CrcFailed;;0xE9;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bea; CCS_VcNotFound;;0xEA;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2beb; CCS_ForwardingFailed;;0xEB;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bec; CCS_ContentTooLarge;;0xEC;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bed; CCS_ResidualData;;0xED;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bee; CCS_DataCorrupted;;0xEE;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bef; CCS_IllegalSegmentationFlag;;0xEF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bd0; CCS_IllegalFlagCombination;;0xD0;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bd1; CCS_ShorterThanHeader;;0xD1;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bd2; CCS_TooShortBlockedPacket;;0xD2;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bd3; CCS_TooShortMapExtraction;;0xD3;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x3301; DC_NoReplyReceived;;0x01;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h;DEVICE_COMMUNICATION_IF -0x3302; DC_ProtocolError;;0x02;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h;DEVICE_COMMUNICATION_IF -0x3303; DC_Nullpointer;;0x03;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h;DEVICE_COMMUNICATION_IF -0x3304; DC_InvalidCookieType;;0x04;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h;DEVICE_COMMUNICATION_IF -0x3305; DC_NotActive;;0x05;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h;DEVICE_COMMUNICATION_IF -0x3306; DC_TooMuchData;;0x06;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h;DEVICE_COMMUNICATION_IF -0x3a0; DHB_InvalidChannel;;0xA0;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h;DEVICE_HANDLER_BASE -0x3b0; DHB_AperiodicReply;;0xB0;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h;DEVICE_HANDLER_BASE -0x3b1; DHB_IgnoreReplyData;;0xB1;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h;DEVICE_HANDLER_BASE -0x3b2; DHB_IgnoreFullPacket;;0xB2;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h;DEVICE_HANDLER_BASE -0x3c0; DHB_NothingToSend;;0xC0;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h;DEVICE_HANDLER_BASE -0x3c2; DHB_CommandMapError;;0xC2;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h;DEVICE_HANDLER_BASE -0x3d0; DHB_NoSwitch;;0xD0;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h;DEVICE_HANDLER_BASE -0x3e0; DHB_ChildTimeout;;0xE0;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h;DEVICE_HANDLER_BASE -0x3e1; DHB_SwitchFailed;;0xE1;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h;DEVICE_HANDLER_BASE -0x1201; AB_NeedSecondStep;;0x01;fsfw/src/fsfw/devicehandlers/AssemblyBase.h;ASSEMBLY_BASE -0x1202; AB_NeedToReconfigure;;0x02;fsfw/src/fsfw/devicehandlers/AssemblyBase.h;ASSEMBLY_BASE -0x1203; AB_ModeFallback;;0x03;fsfw/src/fsfw/devicehandlers/AssemblyBase.h;ASSEMBLY_BASE -0x1204; AB_ChildNotCommandable;;0x04;fsfw/src/fsfw/devicehandlers/AssemblyBase.h;ASSEMBLY_BASE -0x1205; AB_NeedToChangeHealth;;0x05;fsfw/src/fsfw/devicehandlers/AssemblyBase.h;ASSEMBLY_BASE -0x12a1; AB_NotEnoughChildrenInCorrectState;;0xa1;fsfw/src/fsfw/devicehandlers/AssemblyBase.h;ASSEMBLY_BASE -0x26a0; DHI_NoCommandData;;0xA0;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26a1; DHI_CommandNotSupported;;0xA1;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26a2; DHI_CommandAlreadySent;;0xA2;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26a3; DHI_CommandWasNotSent;;0xA3;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26a4; DHI_CantSwitchAddress;;0xA4;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26a5; DHI_WrongModeForCommand;;0xA5;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26a6; DHI_Timeout;;0xA6;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26a7; DHI_Busy;;0xA7;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26a8; DHI_NoReplyExpected;;0xA8;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26a9; DHI_NonOpTemperature;;0xA9;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26aa; DHI_CommandNotImplemented;;0xAA;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26b0; DHI_ChecksumError;;0xB0;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26b1; DHI_LengthMissmatch;;0xB1;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26b2; DHI_InvalidData;;0xB2;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26b3; DHI_ProtocolError;;0xB3;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26c0; DHI_DeviceDidNotExecute;;0xC0;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26c1; DHI_DeviceReportedError;;0xC1;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26c2; DHI_UnknownDeviceReply;;0xC2;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26c3; DHI_DeviceReplyInvalid;;0xC3;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26d0; DHI_InvalidCommandParameter;;0xD0;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26d1; DHI_InvalidNumberOrLengthOfParameters;;0xD1;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x2301; MT_TooDetailedRequest;;1;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h;MATCH_TREE_CLASS -0x2302; MT_TooGeneralRequest;;2;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h;MATCH_TREE_CLASS -0x2303; MT_NoMatch;;3;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h;MATCH_TREE_CLASS -0x2304; MT_Full;;4;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h;MATCH_TREE_CLASS -0x2305; MT_NewNodeCreated;;5;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h;MATCH_TREE_CLASS -0x3e01; DLEE_StreamTooShort;;0x01;fsfw/src/fsfw/globalfunctions/DleEncoder.h;DLE_ENCODER -0x3e02; DLEE_DecodingError;;0x02;fsfw/src/fsfw/globalfunctions/DleEncoder.h;DLE_ENCODER -0x2e01; ASC_TooLongForTargetType;;1;fsfw/src/fsfw/globalfunctions/AsciiConverter.h;ASCII_CONVERTER -0x2e02; ASC_InvalidCharacters;;2;fsfw/src/fsfw/globalfunctions/AsciiConverter.h;ASCII_CONVERTER -0x2e03; ASC_BufferTooSmall;;0x3;fsfw/src/fsfw/globalfunctions/AsciiConverter.h;ASCII_CONVERTER -0x1701; HHI_ObjectNotHealthy;;1;fsfw/src/fsfw/health/HasHealthIF.h;HAS_HEALTH_IF -0x1702; HHI_InvalidHealthState;;2;fsfw/src/fsfw/health/HasHealthIF.h;HAS_HEALTH_IF -0x3101; CF_ObjectHasNoFunctions;;1;fsfw/src/fsfw/action/CommandsActionsIF.h;COMMANDS_ACTIONS_IF -0x3102; CF_AlreadyCommanding;;2;fsfw/src/fsfw/action/CommandsActionsIF.h;COMMANDS_ACTIONS_IF -0x3201; HF_IsBusy;;1;fsfw/src/fsfw/action/HasActionsIF.h;HAS_ACTIONS_IF -0x3202; HF_InvalidParameters;;2;fsfw/src/fsfw/action/HasActionsIF.h;HAS_ACTIONS_IF -0x3203; HF_ExecutionFinished;;3;fsfw/src/fsfw/action/HasActionsIF.h;HAS_ACTIONS_IF -0x3204; HF_InvalidActionId;;4;fsfw/src/fsfw/action/HasActionsIF.h;HAS_ACTIONS_IF -0x3601; TSI_BadTimestamp;;1;fsfw/src/fsfw/timemanager/TimeStamperIF.h;TIME_STAMPER_IF -0x1000; TIM_UnsupportedTimeFormat;;0;fsfw/src/fsfw/timemanager/CCSDSTime.h;CCSDS_TIME_HELPER_CLASS -0x1001; TIM_NotEnoughInformationForTargetFormat;;1;fsfw/src/fsfw/timemanager/CCSDSTime.h;CCSDS_TIME_HELPER_CLASS -0x1002; TIM_LengthMismatch;;2;fsfw/src/fsfw/timemanager/CCSDSTime.h;CCSDS_TIME_HELPER_CLASS -0x1003; TIM_InvalidTimeFormat;;3;fsfw/src/fsfw/timemanager/CCSDSTime.h;CCSDS_TIME_HELPER_CLASS -0x1004; TIM_InvalidDayOfYear;;4;fsfw/src/fsfw/timemanager/CCSDSTime.h;CCSDS_TIME_HELPER_CLASS -0x1005; TIM_TimeDoesNotFitFormat;;5;fsfw/src/fsfw/timemanager/CCSDSTime.h;CCSDS_TIME_HELPER_CLASS -0x3b00; LPIF_PoolEntryNotFound;;0x00;fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h;LOCAL_POOL_OWNER_IF -0x3b01; LPIF_PoolEntryTypeConflict;;0x01;fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h;LOCAL_POOL_OWNER_IF -0x3d00; HKM_QueueOrDestinationInvalid;;0;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h;HOUSEKEEPING_MANAGER -0x3d01; HKM_WrongHkPacketType;;1;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h;HOUSEKEEPING_MANAGER -0x3d02; HKM_ReportingStatusUnchanged;;2;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h;HOUSEKEEPING_MANAGER -0x3d03; HKM_PeriodicHelperInvalid;;3;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h;HOUSEKEEPING_MANAGER -0x3d04; HKM_PoolobjectNotFound;;4;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h;HOUSEKEEPING_MANAGER -0x3d05; HKM_DatasetNotFound;;5;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h;HOUSEKEEPING_MANAGER -0x2801; TC_InvalidTargetState;;1;fsfw/src/fsfw/thermal/ThermalComponentIF.h;THERMAL_COMPONENT_IF -0x28f1; TC_AboveOperationalLimit;;0xF1;fsfw/src/fsfw/thermal/ThermalComponentIF.h;THERMAL_COMPONENT_IF -0x28f2; TC_BelowOperationalLimit;;0xF2;fsfw/src/fsfw/thermal/ThermalComponentIF.h;THERMAL_COMPONENT_IF -0x1f01; CSB_ExecutionComplete;;1;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h;COMMAND_SERVICE_BASE -0x1f02; CSB_NoStepMessage;;2;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h;COMMAND_SERVICE_BASE -0x1f03; CSB_ObjectBusy;;3;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h;COMMAND_SERVICE_BASE -0x1f04; CSB_Busy;;4;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h;COMMAND_SERVICE_BASE -0x1f05; CSB_InvalidTc;;5;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h;COMMAND_SERVICE_BASE -0x1f06; CSB_InvalidObject;;6;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h;COMMAND_SERVICE_BASE -0x1f07; CSB_InvalidReply;;7;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h;COMMAND_SERVICE_BASE -0x4a00; SPPA_NoPacketFound;;0x00;fsfw/src/fsfw/tmtcservices/SpacePacketParser.h;SPACE_PACKET_PARSER -0x4a01; SPPA_SplitPacket;;0x01;fsfw/src/fsfw/tmtcservices/SpacePacketParser.h;SPACE_PACKET_PARSER -0x1d01; PUS_ActivityStarted;;1;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h;ACCEPTS_TELECOMMANDS_IF -0x1d02; PUS_InvalidSubservice;;2;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h;ACCEPTS_TELECOMMANDS_IF -0x1d03; PUS_IllegalApplicationData;;3;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h;ACCEPTS_TELECOMMANDS_IF -0x1d04; PUS_SendTmFailed;;4;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h;ACCEPTS_TELECOMMANDS_IF -0x1d05; PUS_Timeout;;5;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h;ACCEPTS_TELECOMMANDS_IF -0x4300; HSPI_OpeningFileFailed;;0;fsfw/hal/src/fsfw_hal/linux/spi/SpiComIF.h;HAL_SPI -0x4301; HSPI_FullDuplexTransferFailed;;1;fsfw/hal/src/fsfw_hal/linux/spi/SpiComIF.h;HAL_SPI -0x4302; HSPI_HalfDuplexTransferFailed;;2;fsfw/hal/src/fsfw_hal/linux/spi/SpiComIF.h;HAL_SPI -0x4601; HGIO_UnknownGpioId;;1;fsfw/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h;HAL_GPIO -0x4602; HGIO_DriveGpioFailure;;2;fsfw/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h;HAL_GPIO -0x4603; HGIO_GpioTypeFailure;;3;fsfw/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h;HAL_GPIO -0x4604; HGIO_GpioInvalidInstance;;4;fsfw/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h;HAL_GPIO -0x4605; HGIO_GpioDuplicateDetected;;5;fsfw/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h;HAL_GPIO -0x4606; HGIO_GpioInitFailed;;6;fsfw/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h;HAL_GPIO -0x4401; HURT_UartReadFailure;;1;fsfw/hal/src/fsfw_hal/linux/uart/UartComIF.h;HAL_UART -0x4402; HURT_UartReadSizeMissmatch;;2;fsfw/hal/src/fsfw_hal/linux/uart/UartComIF.h;HAL_UART -0x4403; HURT_UartRxBufferTooSmall;;3;fsfw/hal/src/fsfw_hal/linux/uart/UartComIF.h;HAL_UART -0x4200; UXOS_ExecutionFinished;Execution of the current command has finished;0;fsfw/hal/src/fsfw_hal/linux/CommandExecutor.h;LINUX_OSAL -0x4201; UXOS_CommandPending;Command is pending. This will also be returned if the user tries to load another command but a command is still pending;1;fsfw/hal/src/fsfw_hal/linux/CommandExecutor.h;LINUX_OSAL -0x4202; UXOS_BytesRead;Some bytes have been read from the executing process;2;fsfw/hal/src/fsfw_hal/linux/CommandExecutor.h;LINUX_OSAL -0x4203; UXOS_CommandError;Command execution failed;3;fsfw/hal/src/fsfw_hal/linux/CommandExecutor.h;LINUX_OSAL -0x4204; UXOS_NoCommandLoadedOrPending;;4;fsfw/hal/src/fsfw_hal/linux/CommandExecutor.h;LINUX_OSAL -0x4206; UXOS_PcloseCallError;;6;fsfw/hal/src/fsfw_hal/linux/CommandExecutor.h;LINUX_OSAL -0x7100; SCBU_KeyNotFound;;0;bsp_q7s/memory/scratchApi.h;SCRATCH_BUFFER -0x66a0;FSHLP_SdNotMounted;SD card specified with path string not mounted;0xA0;bsp_q7s/memory/FilesystemHelper.h;FILE_SYSTEM_HELPER -0x66a1;FSHLP_FileNotExists;Specified file does not exist on filesystem;0xA1;bsp_q7s/memory/FilesystemHelper.h;FILE_SYSTEM_HELPER -0x7000; SDMA_OpOngoing;;0;bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER -0x7001; SDMA_AlreadyOn;;1;bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER -0x7002; SDMA_AlreadyMounted;;2;bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER -0x7003; SDMA_AlreadyOff;;3;bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER -0x700a; SDMA_StatusFileNexists;;10;bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER -0x700b; SDMA_StatusFileFormatInvalid;;11;bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER -0x700c; SDMA_MountError;;12;bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER -0x700d; SDMA_UnmountError;;13;bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER -0x700e; SDMA_SystemCallError;;14;bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER -0x700f; SDMA_PopenCallError;;15;bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER -0x67a0; PLMPHLP_FileClosedAccidentally;File accidentally close;0xA0;linux/devices/ploc/PlocMPSoCHelper.h;PLOC_MPSOC_HELPER -0x59a0;PLSV_CrcFailure;Space Packet received from PLOC supervisor has invalid CRC;0xA0;linux/devices/ploc/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x59a1;PLSV_ReceivedAckFailure;Received ACK failure reply from PLOC supervisor;0xA1;linux/devices/ploc/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x59a2;PLSV_ReceivedExeFailure;Received execution failure reply from PLOC supervisor;0xA2;linux/devices/ploc/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x59a3;PLSV_InvalidApid;Received space packet with invalid APID from PLOC supervisor;0xA3;linux/devices/ploc/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x59a4;PLSV_GetTimeFailure;Failed to read current system time;0xA4;linux/devices/ploc/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x59a5;PLSV_InvalidWatchdog;Received command with invalid watchdog parameter. Valid watchdogs are 0 for PS, 1 for PL and 2 for INT;0xA5;linux/devices/ploc/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x59a6;PLSV_InvalidWatchdogTimeout;Received watchdog timeout config command with invalid timeout. Valid timeouts must be in the range between 1000 and 360000 ms.;0xA6;linux/devices/ploc/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x59a7;PLSV_InvalidLatchupId;Received latchup config command with invalid latchup ID;0xA7;linux/devices/ploc/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x59a8;PLSV_SweepPeriodTooSmall;Received set adc sweep period command with invalid sweep period. Must be larger than 21.;0xA8;linux/devices/ploc/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x59a9;PLSV_InvalidTestParam;Receive auto EM test command with invalid test param. Valid params are 1 and 2.;0xA9;linux/devices/ploc/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x59aa;PLSV_MramPacketParsingFailure;Returned when scanning for MRAM dump packets failed.;0xAA;linux/devices/ploc/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x59ab;PLSV_InvalidMramAddresses;Returned when the start and stop addresses of the MRAM dump or MRAM wipe commands are invalid (e.g. start address bigger than stop address);0xAB;linux/devices/ploc/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x59ac;PLSV_NoMramPacket;Expect reception of an MRAM dump packet but received space packet with other apid.;0xAC;linux/devices/ploc/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x59ad;PLSV_PathDoesNotExist;Path to PLOC directory on SD card does not exist;0xAD;linux/devices/ploc/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x59ae;PLSV_MramFileNotExists;MRAM dump file does not exists. The file should actually already have been created with the reception of the first dump packet.;0xAE;linux/devices/ploc/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x5da0;PLUD_UpdaterBusy;Updater is already performing an update;0xA0;linux/devices/ploc/PlocUpdater.h;PLOC_UPDATER -0x5da1;PLUD_NameTooLong;Received update command with invalid path string (too long).;0xA1;linux/devices/ploc/PlocUpdater.h;PLOC_UPDATER -0x5da2;PLUD_SdNotMounted;Received command to initiate update but SD card with update image not mounted.;0xA2;linux/devices/ploc/PlocUpdater.h;PLOC_UPDATER -0x5da3;PLUD_FileNotExists;Update file received with update command does not exist.;0xA3;linux/devices/ploc/PlocUpdater.h;PLOC_UPDATER -0x60a0;PLMEMDUMP_MramAddressTooHigh;The capacity of the MRAM amounts to 512 kB. Thus the maximum address must not be higher than 0x7d000.;0xA0;linux/devices/ploc/PlocMemoryDumper.h;PLOC_MEMORY_DUMPER -0x60a1;PLMEMDUMP_MramInvalidAddressCombination;The specified end address is lower than the start address;0xA1;linux/devices/ploc/PlocMemoryDumper.h;PLOC_MEMORY_DUMPER -0x69a0;MPSOCRTVIF_CrcFailure;Space Packet received from PLOC has invalid CRC;0xA0;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h;MPSOC_RETURN_VALUES_IF -0x69a1;MPSOCRTVIF_ReceivedAckFailure;Received ACK failure reply from PLOC;0xA1;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h;MPSOC_RETURN_VALUES_IF -0x69a2;MPSOCRTVIF_ReceivedExeFailure;Received execution failure reply from PLOC;0xA2;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h;MPSOC_RETURN_VALUES_IF -0x69a3;MPSOCRTVIF_InvalidApid;Received space packet with invalid APID from PLOC;0xA3;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h;MPSOC_RETURN_VALUES_IF -0x69a4;MPSOCRTVIF_InvalidLength;Received command with invalid length;0xA4;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h;MPSOC_RETURN_VALUES_IF -0x69a5;MPSOCRTVIF_FilenameTooLong;Filename of file in OBC filesystem is too long;0xA5;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h;MPSOC_RETURN_VALUES_IF -0x69a6;MPSOCRTVIF_MpsocHelperExecuting;MPSoC helper is currently executing a command;0xA6;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h;MPSOC_RETURN_VALUES_IF -0x69a7;MPSOCRTVIF_MpsocFilenameTooLong;Filename of MPSoC file is to long (max. 256 bytes);0xA7;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h;MPSOC_RETURN_VALUES_IF -0x69a8;MPSOCRTVIF_InvalidParameter;Command has invalid parameter;0xA8;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h;MPSOC_RETURN_VALUES_IF -0x69a9;MPSOCRTVIF_NameTooLong;Received command has file string with invalid length;0xA9;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h;MPSOC_RETURN_VALUES_IF -0x57e0;DWLPWRON_InvalidMode;Received command has invalid JESD mode (valid modes are 0 - 5);0xE0;linux/devices/devicedefinitions/PlocMPSoCDefinitions.h;DWLPWRON_CMD -0x57e1;DWLPWRON_InvalidLaneRate;Received command has invalid lane rate (valid lane rate are 0 - 9);0xE1;linux/devices/devicedefinitions/PlocMPSoCDefinitions.h;DWLPWRON_CMD -0x6401;JSONBASE_JsonFileNotExists;Specified json file does not exist;1;linux/devices/startracker/ArcsecJsonParamBase.h;ARCSEC_JSON_BASE -0x6402;JSONBASE_SetNotExists;Requested set does not exist in json file;2;linux/devices/startracker/ArcsecJsonParamBase.h;ARCSEC_JSON_BASE -0x6403;JSONBASE_ParamNotExists;Requested parameter does not exist in json file;3;linux/devices/startracker/ArcsecJsonParamBase.h;ARCSEC_JSON_BASE -0x56a0;STRH_TemperatureReqFailed;Status in temperature reply signals error;0xA0;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56a1;STRH_PingFailed;Ping command failed;0xA1;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56a2;STRH_VersionReqFailed;Status in version reply signals error;0xA2;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x5ea0;STRHLP_SdNotMounted;SD card specified in path string not mounted;0xA0;linux/devices/startracker/StrHelper.h;STR_HELPER -0x5ea1;STRHLP_FileNotExists;Specified file does not exist on filesystem;0xA1;linux/devices/startracker/StrHelper.h;STR_HELPER -0x5ea2;STRHLP_PathNotExists;Specified path does not exist;0xA2;linux/devices/startracker/StrHelper.h;STR_HELPER -0x5ea3;STRHLP_FileCreationFailed;Failed to create download image or read flash file;0xA3;linux/devices/startracker/StrHelper.h;STR_HELPER -0x5ea4;STRHLP_RegionMismatch;Region in flash write/read reply does not match expected region;0xA4;linux/devices/startracker/StrHelper.h;STR_HELPER -0x5ea5;STRHLP_AddressMismatch;Address in flash write/read reply does not match expected address;0xA5;linux/devices/startracker/StrHelper.h;STR_HELPER -0x5ea6;STRHLP_LengthMismatch;Length in flash write/read reply does not match expected length;0xA6;linux/devices/startracker/StrHelper.h;STR_HELPER -0x5ea7;STRHLP_StatusError;Status field in reply signals error;0xA7;linux/devices/startracker/StrHelper.h;STR_HELPER -0x5ea8;STRHLP_InvalidTypeId;Reply has invalid type ID (should be of action reply type);0xA8;linux/devices/startracker/StrHelper.h;STR_HELPER -0x56a3;STRH_InterfaceReqFailed;Status in interface reply signals error;0xA3;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56a4;STRH_PowerReqFailed;Status in power reply signals error;0xA4;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56a5;STRH_SetParamFailed;Status of reply to parameter set command signals error;0xA5;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56a6;STRH_ActionFailed;Status of reply to action command signals error;0xA6;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56a7;STRH_FilePathTooLong;Received invalid path string. Exceeds allowed length;0xA7;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56a8;STRH_FilenameTooLong;Name of file received with command is too long;0xA8;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56a9;STRH_InvalidProgram;Received version reply with invalid program ID;0xA9;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56aa;STRH_ReplyError;Status field reply signals error;0xAA;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56ab;STRH_CommandTooShort;Received command which is too short (some data is missing for proper execution);0xAB;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56ac;STRH_InvalidLength;Received command with invalid length (too few or too many parameters);0xAC;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56ad;STRH_RegionMismatch;Region mismatch between send and received data;0xAD;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56ae;STRH_AddressMismatch;Address mismatch between send and received data;0xAE;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56af;STRH_LengthMismatch;Length field mismatch between send and received data;0xAF;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56b0;STRH_FileNotExists;Specified file does not exist;0xB0;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56b1;STRH_InvalidType;Download blob pixel command has invalid type field;0xB1;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56b2;STRH_InvalidId;Received FPGA action command with invalid ID;0xB2;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56b3;STRH_ReplyTooShort;Received reply is too short;0xB3;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56b4;STRH_CrcFailure;Received reply with invalid CRC;0xB4;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56b5;STRH_StrHelperExecuting;Star tracker handler currently executing a command and using the communication interface;0xB5;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56b6;STRH_StartrackerAlreadyBooted;Star tracker is already in firmware mode;0xB6;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56b7;STRH_StartrackerRunningFirmware;Star tracker is in firmware mode but must be in bootloader mode to execute this command;0xB7;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x56b8;STRH_StartrackerRunningBootloader;Star tracker is in bootloader mode but must be in firmware mode to execute this command;0xB8;linux/devices/startracker/StarTrackerHandler.h;STR_HANDLER -0x5ca0;PTME_UnknownVcId;;0xA0;linux/obc/Ptme.h;PTME -0x61a0;PDEC_AbandonedCltu;;0xA0;linux/obc/PdecHandler.h;PDEC_HANDLER -0x61a1;PDEC_FrameDirty;;0xA1;linux/obc/PdecHandler.h;PDEC_HANDLER -0x61a2;PDEC_FrameIllegalMultipleReasons;;0xA2;linux/obc/PdecHandler.h;PDEC_HANDLER -0x61a3;PDEC_AdDiscardedLockout;;0xA3;linux/obc/PdecHandler.h;PDEC_HANDLER -0x61a4;PDEC_AdDiscardedWait;;0xA4;linux/obc/PdecHandler.h;PDEC_HANDLER -0x61a5;PDEC_AdDiscardedNsVs;;0xA5;linux/obc/PdecHandler.h;PDEC_HANDLER -0x61b0;PDEC_CommandNotImplemented;Received action message with unknown action id;0xB0;linux/obc/PdecHandler.h;PDEC_HANDLER -0x61a6;PDEC_NoReport;;0xA6;linux/obc/PdecHandler.h;PDEC_HANDLER -0x61a7;PDEC_ErrorVersionNumber;;0xA7;linux/obc/PdecHandler.h;PDEC_HANDLER -0x61a8;PDEC_IllegalCombination;;0xA8;linux/obc/PdecHandler.h;PDEC_HANDLER -0x61a9;PDEC_InvalidScId;;0xA9;linux/obc/PdecHandler.h;PDEC_HANDLER -0x61aa;PDEC_InvalidVcIdMsb;;0xAA;linux/obc/PdecHandler.h;PDEC_HANDLER -0x61ab;PDEC_InvalidVcIdLsb;;0xAB;linux/obc/PdecHandler.h;PDEC_HANDLER -0x61ac;PDEC_NsNotZero;;0xAC;linux/obc/PdecHandler.h;PDEC_HANDLER -0x61ae;PDEC_InvalidBcCc;;0xAE;linux/obc/PdecHandler.h;PDEC_HANDLER -0x63a0;RS_RateNotSupported;The commanded rate is not supported by the current FPGA design;0xA0;linux/obc/PtmeConfig.h;RATE_SETTER -0x63a1;RS_BadBitRate;Bad bitrate has been commanded (e.g. 0);0xA1;linux/obc/PtmeConfig.h;RATE_SETTER -0x63a2;RS_ClkInversionFailed;Failed to invert clock and thus change the time the data is updated with respect to the tx clock;0xA2;linux/obc/PtmeConfig.h;RATE_SETTER -0x63a3;RS_TxManipulatorConfigFailed;Failed to change configuration bit of tx clock manipulator;0xA3;linux/obc/PtmeConfig.h;RATE_SETTER -0x5ba0;IPCI_PapbBusy;;0xA0;linux/obc/PapbVcInterface.h;CCSDS_IP_CORE_BRIDGE +Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path +0x0000;OK;System-wide code for ok.;0;HasReturnvaluesIF;fsfw/returnvalues/HasReturnvaluesIF.h +0x0001;Failed;Unspecified system-wide code for failed.;1;HasReturnvaluesIF;fsfw/returnvalues/HasReturnvaluesIF.h +0x6100;GOMS_PacketTooLong;;0;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x6101;GOMS_InvalidTableId;;1;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x6102;GOMS_InvalidAddress;;2;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x6103;GOMS_InvalidParamSize;;3;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x6104;GOMS_InvalidPayloadSize;;4;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x6105;GOMS_UnknownReplyId;;5;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x53a1;HEATER_CommandNotSupported;;161;HEATER_HANDLER;mission/devices/HeaterHandler.h +0x53a2;HEATER_InitFailed;;162;HEATER_HANDLER;mission/devices/HeaterHandler.h +0x53a3;HEATER_InvalidSwitchNr;;163;HEATER_HANDLER;mission/devices/HeaterHandler.h +0x53a4;HEATER_MainSwitchSetTimeout;;164;HEATER_HANDLER;mission/devices/HeaterHandler.h +0x53a5;HEATER_CommandAlreadyWaiting;;165;HEATER_HANDLER;mission/devices/HeaterHandler.h +0x55a0;IMTQ_InvalidCommandCode;;160;IMTQ_HANDLER;mission/devices/IMTQHandler.h +0x55a1;IMTQ_ParameterMissing;;161;IMTQ_HANDLER;mission/devices/IMTQHandler.h +0x55a2;IMTQ_ParameterInvalid;;162;IMTQ_HANDLER;mission/devices/IMTQHandler.h +0x55a3;IMTQ_CcUnavailable;;163;IMTQ_HANDLER;mission/devices/IMTQHandler.h +0x55a4;IMTQ_InternalProcessingError;;164;IMTQ_HANDLER;mission/devices/IMTQHandler.h +0x55a5;IMTQ_RejectedWithoutReason;;165;IMTQ_HANDLER;mission/devices/IMTQHandler.h +0x55a6;IMTQ_CmdErrUnknown;;166;IMTQ_HANDLER;mission/devices/IMTQHandler.h +0x55a7;IMTQ_UnexpectedSelfTestReply;The status reply to a self test command was received but no self test command has been sent. This should normally never happen.;167;IMTQ_HANDLER;mission/devices/IMTQHandler.h +0x56b0;RWHA_SpiWriteFailure;;176;RW_HANDLER;mission/devices/RwHandler.h +0x56b1;RWHA_SpiReadFailure;Used by the spi send function to tell a failing read call;177;RW_HANDLER;mission/devices/RwHandler.h +0x56b2;RWHA_MissingStartSign;Can be used by the HDLC decoding mechanism to inform about a missing start sign 0x7E;178;RW_HANDLER;mission/devices/RwHandler.h +0x56b3;RWHA_InvalidSubstitute;Can be used by the HDLC decoding mechanism to inform about an invalid substitution combination;179;RW_HANDLER;mission/devices/RwHandler.h +0x56b4;RWHA_MissingEndSign;HDLC decoding mechanism never receives the end sign 0x7E;180;RW_HANDLER;mission/devices/RwHandler.h +0x56b5;RWHA_NoReply;Reaction wheel only responds with empty frames.;181;RW_HANDLER;mission/devices/RwHandler.h +0x56b6;RWHA_NoStartMarker;Expected a start marker as first byte;182;RW_HANDLER;mission/devices/RwHandler.h +0x56a0;RWHA_InvalidSpeed;Action Message with invalid speed was received. Valid speeds must be in the range of [-65000, 1000] or [1000, 65000];160;RW_HANDLER;mission/devices/RwHandler.h +0x56a1;RWHA_InvalidRampTime;Action Message with invalid ramp time was received.;161;RW_HANDLER;mission/devices/RwHandler.h +0x56a2;RWHA_SetSpeedCommandInvalidLength;Received set speed command has invalid length. Should be 6.;162;RW_HANDLER;mission/devices/RwHandler.h +0x56a3;RWHA_ExecutionFailed;Command execution failed;163;RW_HANDLER;mission/devices/RwHandler.h +0x56a4;RWHA_CrcError;Reaction wheel reply has invalid crc;164;RW_HANDLER;mission/devices/RwHandler.h +0x6aa0;SADPL_CommandNotSupported;;160;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h +0x6aa1;SADPL_DeploymentAlreadyExecuting;;161;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h +0x6aa2;SADPL_MainSwitchTimeoutFailure;;162;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h +0x6aa3;SADPL_SwitchingDeplSa1Failed;;163;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h +0x6aa4;SADPL_SwitchingDeplSa2Failed;;164;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h +0x5ca0;SUSS_ErrorUnlockMutex;;160;SUS_HANDLER;mission/devices/SusHandler.h +0x5ca1;SUSS_ErrorLockMutex;;161;SUS_HANDLER;mission/devices/SusHandler.h +0x54a0;SYRLINKS_CrcFailure;;160;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h +0x54a1;SYRLINKS_UartFraminOrParityErrorAck;;161;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h +0x54a2;SYRLINKS_BadCharacterAck;;162;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h +0x54a3;SYRLINKS_BadParameterValueAck;;163;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h +0x54a4;SYRLINKS_BadEndOfFrameAck;;164;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h +0x54a5;SYRLINKS_UnknownCommandIdAck;;165;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h +0x54a6;SYRLINKS_BadCrcAck;;166;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h +0x54a7;SYRLINKS_ReplyWrongSize;;167;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h +0x54a8;SYRLINKS_MissingStartFrameCharacter;;168;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h +0x67a0;NVMB_KeyNotExists;Specified key does not exist in json file;160;NVM_PARAM_BASE;mission/memory/NVMParameterBase.h +0x64a0;CCSDS_CommandNotImplemented;Received action message with unknown action id;160;CCSDS_HANDLER;mission/tmtc/CCSDSHandler.h +0x4701;HGIO_UnknownGpioId;;1;HAL_GPIO;fsfw/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4702;HGIO_DriveGpioFailure;;2;HAL_GPIO;fsfw/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4703;HGIO_GpioTypeFailure;;3;HAL_GPIO;fsfw/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4704;HGIO_GpioInvalidInstance;;4;HAL_GPIO;fsfw/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4705;HGIO_GpioDuplicateDetected;;5;HAL_GPIO;fsfw/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4706;HGIO_GpioInitFailed;;6;HAL_GPIO;fsfw/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4707;HGIO_GpioGetValueFailed;;7;HAL_GPIO;fsfw/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4400;HSPI_HalTimeoutRetval;;0;HAL_SPI;fsfw/hal/src/fsfw_hal/stm32h7/spi/spiDefinitions.h +0x4401;HSPI_HalBusyRetval;;1;HAL_SPI;fsfw/hal/src/fsfw_hal/stm32h7/spi/spiDefinitions.h +0x4402;HSPI_HalErrorRetval;;2;HAL_SPI;fsfw/hal/src/fsfw_hal/stm32h7/spi/spiDefinitions.h +0x4501;HURT_UartReadFailure;;1;HAL_UART;fsfw/hal/src/fsfw_hal/linux/uart/UartComIF.h +0x4502;HURT_UartReadSizeMissmatch;;2;HAL_UART;fsfw/hal/src/fsfw_hal/linux/uart/UartComIF.h +0x4503;HURT_UartRxBufferTooSmall;;3;HAL_UART;fsfw/hal/src/fsfw_hal/linux/uart/UartComIF.h +0x4300;UXOS_ExecutionFinished;Execution of the current command has finished;0;LINUX_OSAL;fsfw/hal/src/fsfw_hal/linux/CommandExecutor.h +0x4301;UXOS_CommandPending;Command is pending. This will also be returned if the user tries to load another command but a command is still pending;1;LINUX_OSAL;fsfw/hal/src/fsfw_hal/linux/CommandExecutor.h +0x4302;UXOS_BytesRead;Some bytes have been read from the executing process;2;LINUX_OSAL;fsfw/hal/src/fsfw_hal/linux/CommandExecutor.h +0x4303;UXOS_CommandError;Command execution failed;3;LINUX_OSAL;fsfw/hal/src/fsfw_hal/linux/CommandExecutor.h +0x4304;UXOS_NoCommandLoadedOrPending;;4;LINUX_OSAL;fsfw/hal/src/fsfw_hal/linux/CommandExecutor.h +0x4306;UXOS_PcloseCallError;;6;LINUX_OSAL;fsfw/hal/src/fsfw_hal/linux/CommandExecutor.h +0x3101;CF_ObjectHasNoFunctions;;1;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h +0x3102;CF_AlreadyCommanding;;2;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h +0x3201;HF_IsBusy;;1;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h +0x3202;HF_InvalidParameters;;2;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h +0x3203;HF_ExecutionFinished;;3;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h +0x3204;HF_InvalidActionId;;4;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h +0x3501;CFDP_InvalidTlvType;;1;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3502;CFDP_InvalidDirectiveFields;;2;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3503;CFDP_InvalidPduDatafieldLen;;3;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3504;CFDP_InvalidAckDirectiveFields;;4;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3505;CFDP_MetadataCantParseOptions;;5;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3506;CFDP_FinishedCantParseFsResponses;;6;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3508;CFDP_FilestoreRequiresSecondFile;;8;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3509;CFDP_FilestoreResponseCantParseFsMessage;;9;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x1101;AL_Full;;1;ARRAY_LIST;fsfw/src/fsfw/container/ArrayList.h +0x1801;FF_Full;;1;FIFO_CLASS;fsfw/src/fsfw/container/FIFOBase.h +0x1802;FF_Empty;;2;FIFO_CLASS;fsfw/src/fsfw/container/FIFOBase.h +0x1501;FM_KeyAlreadyExists;;1;FIXED_MAP;fsfw/src/fsfw/container/FixedMap.h +0x1502;FM_MapFull;;2;FIXED_MAP;fsfw/src/fsfw/container/FixedMap.h +0x1503;FM_KeyDoesNotExist;;3;FIXED_MAP;fsfw/src/fsfw/container/FixedMap.h +0x1601;FMM_MapFull;;1;FIXED_MULTIMAP;fsfw/src/fsfw/container/FixedOrderedMultimap.h +0x1602;FMM_KeyDoesNotExist;;2;FIXED_MULTIMAP;fsfw/src/fsfw/container/FixedOrderedMultimap.h +0x37a1;SGP4_InvalidEccentricity;;161;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x37a2;SGP4_InvalidMeanMotion;;162;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x37a3;SGP4_InvalidPerturbationElements;;163;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x37a4;SGP4_InvalidSemiLatusRectum;;164;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x37a5;SGP4_InvalidEpochElements;;165;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x37a6;SGP4_SatelliteHasDecayed;;166;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x37b1;SGP4_TleTooOld;;177;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x37b2;SGP4_TleNotInitialized;;178;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x2b01;CCS_BcIsSetVrCommand;;1;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2b02;CCS_BcIsUnlockCommand;;2;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2bb0;CCS_BcIllegalCommand;;176;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2bb1;CCS_BoardReadingNotFinished;;177;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2bf0;CCS_NsPositiveW;;240;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2bf1;CCS_NsNegativeW;;241;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2bf2;CCS_NsLockout;;242;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2bf3;CCS_FarmInLockout;;243;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2bf4;CCS_FarmInWait;;244;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2be0;CCS_WrongSymbol;;224;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2be1;CCS_DoubleStart;;225;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2be2;CCS_StartSymbolMissed;;226;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2be3;CCS_EndWithoutStart;;227;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2be4;CCS_TooLarge;;228;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2be5;CCS_TooShort;;229;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2be6;CCS_WrongTfVersion;;230;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2be7;CCS_WrongSpacecraftId;;231;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2be8;CCS_NoValidFrameType;;232;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2be9;CCS_CrcFailed;;233;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2bea;CCS_VcNotFound;;234;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2beb;CCS_ForwardingFailed;;235;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2bec;CCS_ContentTooLarge;;236;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2bed;CCS_ResidualData;;237;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2bee;CCS_DataCorrupted;;238;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2bef;CCS_IllegalSegmentationFlag;;239;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2bd0;CCS_IllegalFlagCombination;;208;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2bd1;CCS_ShorterThanHeader;;209;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2bd2;CCS_TooShortBlockedPacket;;210;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2bd3;CCS_TooShortMapExtraction;;211;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x0801;DPS_InvalidParameterDefinition;;1;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h +0x0802;DPS_SetWasAlreadyRead;;2;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h +0x0803;DPS_CommitingWithoutReading;;3;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h +0x0804;DPS_DataSetUninitialised;;4;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h +0x0805;DPS_DataSetFull;;5;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h +0x0806;DPS_PoolVarNull;;6;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h +0x3ca0;PVA_InvalidReadWriteMode;;160;POOL_VARIABLE_IF;fsfw/src/fsfw/datapool/PoolVariableIF.h +0x3ca1;PVA_InvalidPoolEntry;;161;POOL_VARIABLE_IF;fsfw/src/fsfw/datapool/PoolVariableIF.h +0x3d00;HKM_QueueOrDestinationInvalid;;0;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3d01;HKM_WrongHkPacketType;;1;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3d02;HKM_ReportingStatusUnchanged;;2;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3d03;HKM_PeriodicHelperInvalid;;3;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3d04;HKM_PoolobjectNotFound;;4;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3d05;HKM_DatasetNotFound;;5;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3b00;LPIF_PoolEntryNotFound;;0;LOCAL_POOL_OWNER_IF;fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h +0x3b01;LPIF_PoolEntryTypeConflict;;1;LOCAL_POOL_OWNER_IF;fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h +0x1201;AB_NeedSecondStep;;1;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x1202;AB_NeedToReconfigure;;2;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x1203;AB_ModeFallback;;3;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x1204;AB_ChildNotCommandable;;4;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x1205;AB_NeedToChangeHealth;;5;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x12a1;AB_NotEnoughChildrenInCorrectState;;161;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x3301;DC_NoReplyReceived;;1;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x3302;DC_ProtocolError;;2;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x3303;DC_Nullpointer;;3;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x3304;DC_InvalidCookieType;;4;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x3305;DC_NotActive;;5;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x3306;DC_TooMuchData;;6;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x03a0;DHB_InvalidChannel;;160;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h +0x03b0;DHB_AperiodicReply;;176;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h +0x03b1;DHB_IgnoreReplyData;;177;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h +0x03b2;DHB_IgnoreFullPacket;;178;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h +0x03c0;DHB_NothingToSend;;192;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h +0x03c2;DHB_CommandMapError;;194;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h +0x03d0;DHB_NoSwitch;;208;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h +0x03e0;DHB_ChildTimeout;;224;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h +0x03e1;DHB_SwitchFailed;;225;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h +0x26a0;DHI_NoCommandData;;160;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x26a1;DHI_CommandNotSupported;;161;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x26a2;DHI_CommandAlreadySent;;162;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x26a3;DHI_CommandWasNotSent;;163;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x26a4;DHI_CantSwitchAddress;;164;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x26a5;DHI_WrongModeForCommand;;165;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x26a6;DHI_Timeout;;166;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x26a7;DHI_Busy;;167;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x26a8;DHI_NoReplyExpected;;168;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x26a9;DHI_NonOpTemperature;;169;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x26aa;DHI_CommandNotImplemented;;170;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x26b0;DHI_ChecksumError;;176;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x26b1;DHI_LengthMissmatch;;177;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x26b2;DHI_InvalidData;;178;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x26b3;DHI_ProtocolError;;179;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x26c0;DHI_DeviceDidNotExecute;;192;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x26c1;DHI_DeviceReportedError;;193;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x26c2;DHI_UnknownDeviceReply;;194;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x26c3;DHI_DeviceReplyInvalid;;195;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x26d0;DHI_InvalidCommandParameter;;208;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x26d1;DHI_InvalidNumberOrLengthOfParameters;;209;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x2401;EV_ListenerNotFound;;1;EVENT_MANAGER_IF;fsfw/src/fsfw/events/EventManagerIF.h +0x2500;FDI_YourFault;;0;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h +0x2501;FDI_MyFault;;1;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h +0x2502;FDI_ConfirmLater;;2;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h +0x2301;MT_TooDetailedRequest;;1;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h +0x2302;MT_TooGeneralRequest;;2;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h +0x2303;MT_NoMatch;;3;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h +0x2304;MT_Full;;4;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h +0x2305;MT_NewNodeCreated;;5;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h +0x2e01;ASC_TooLongForTargetType;;1;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h +0x2e02;ASC_InvalidCharacters;;2;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h +0x2e03;ASC_BufferTooSmall;;3;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h +0x3e01;DLEE_StreamTooShort;;1;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleEncoder.h +0x3e02;DLEE_DecodingError;;2;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleEncoder.h +0x1701;HHI_ObjectNotHealthy;;1;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h +0x1702;HHI_InvalidHealthState;;2;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h +0x1703;HHI_IsExternallyControlled;;3;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h +0x0f01;CM_UnknownCommand;;1;COMMAND_MESSAGE;fsfw/src/fsfw/ipc/CommandMessageIF.h +0x3901;MQI_Empty;;1;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h +0x3902;MQI_Full;No space left for more messages;2;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h +0x3903;MQI_NoReplyPartner;Returned if a reply method was called without partner;3;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h +0x3904;MQI_DestinationInvalid;Returned if the target destination is invalid.;4;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h +0x3801;MUX_NotEnoughResources;;1;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3802;MUX_InsufficientMemory;;2;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3803;MUX_NoPrivilege;;3;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3804;MUX_WrongAttributeSetting;;4;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3805;MUX_MutexAlreadyLocked;;5;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3806;MUX_MutexNotFound;;6;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3807;MUX_MutexMaxLocks;;7;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3808;MUX_CurrThreadAlreadyOwnsMutex;;8;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3809;MUX_CurrThreadDoesNotOwnMutex;;9;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x380a;MUX_MutexTimeout;;10;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x380b;MUX_MutexInvalidId;;11;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x380c;MUX_MutexDestroyedWhileWaiting;;12;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x4200;FILS_GenericFileError;;0;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4201;FILS_IsBusy;;1;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4202;FILS_InvalidParameters;;2;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4205;FILS_FileDoesNotExist;;5;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4206;FILS_FileAlreadyExists;;6;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4207;FILS_FileLocked;;7;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x420a;FILS_DirectoryDoesNotExist;;10;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x420b;FILS_DirectoryAlreadyExists;;11;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x420c;FILS_DirectoryNotEmpty;;12;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x420f;FILS_SequencePacketMissingWrite;;15;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4210;FILS_SequencePacketMissingRead;;16;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x0601;PP_DoItMyself;;1;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0602;PP_PointsToVariable;;2;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0603;PP_PointsToMemory;;3;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0604;PP_ActivityCompleted;;4;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0605;PP_PointsToVectorUint8;;5;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0606;PP_PointsToVectorUint16;;6;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0607;PP_PointsToVectorUint32;;7;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0608;PP_PointsToVectorFloat;;8;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06a0;PP_DumpNotSupported;;160;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06e0;PP_InvalidSize;;224;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06e1;PP_InvalidAddress;;225;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06e2;PP_InvalidContent;;226;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06e3;PP_UnalignedAccess;;227;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06e4;PP_WriteProtected;;228;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x13e0;MH_UnknownCmd;;224;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h +0x13e1;MH_InvalidAddress;;225;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h +0x13e2;MH_InvalidSize;;226;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h +0x13e3;MH_StateMismatch;;227;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h +0x0e01;HM_InvalidMode;;1;HAS_MODES_IF;fsfw/src/fsfw/modes/HasModesIF.h +0x0e02;HM_TransNotAllowed;;2;HAS_MODES_IF;fsfw/src/fsfw/modes/HasModesIF.h +0x0e03;HM_InTransition;;3;HAS_MODES_IF;fsfw/src/fsfw/modes/HasModesIF.h +0x0e04;HM_InvalidSubmode;;4;HAS_MODES_IF;fsfw/src/fsfw/modes/HasModesIF.h +0x3001;LIM_Unchecked;;1;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +0x3002;LIM_Invalid;;2;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +0x3003;LIM_Unselected;;3;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +0x3004;LIM_BelowLowLimit;;4;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +0x3005;LIM_AboveHighLimit;;5;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +0x3006;LIM_UnexpectedValue;;6;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +0x3007;LIM_OutOfRange;;7;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +0x30a0;LIM_FirstSample;;160;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +0x30e0;LIM_InvalidSize;;224;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +0x30e1;LIM_WrongType;;225;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +0x30e2;LIM_WrongPid;;226;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +0x30e3;LIM_WrongLimitId;;227;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +0x30ee;LIM_MonitorNotFound;;238;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +0x1a01;TRC_NotEnoughSensors;;1;TRIPLE_REDUNDACY_CHECK;fsfw/src/fsfw/monitoring/TriplexMonitor.h +0x1a02;TRC_LowestValueOol;;2;TRIPLE_REDUNDACY_CHECK;fsfw/src/fsfw/monitoring/TriplexMonitor.h +0x1a03;TRC_HighestValueOol;;3;TRIPLE_REDUNDACY_CHECK;fsfw/src/fsfw/monitoring/TriplexMonitor.h +0x1a04;TRC_BothValuesOol;;4;TRIPLE_REDUNDACY_CHECK;fsfw/src/fsfw/monitoring/TriplexMonitor.h +0x1a05;TRC_DuplexOol;;5;TRIPLE_REDUNDACY_CHECK;fsfw/src/fsfw/monitoring/TriplexMonitor.h +0x0201;OM_InsertionFailed;;1;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h +0x0202;OM_NotFound;;2;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h +0x0203;OM_ChildInitFailed;;3;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h +0x0204;OM_InternalErrReporterUninit;;4;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h +0x0200;OM_ConnBroken;;0;OBJECT_MANAGER_IF;fsfw/src/fsfw/osal/common/TcpTmTcServer.h +0x2901;IEC_NoConfigurationTable;;1;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2902;IEC_NoCpuTable;;2;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2903;IEC_InvalidWorkspaceAddress;;3;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2904;IEC_TooLittleWorkspace;;4;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2905;IEC_WorkspaceAllocation;;5;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2906;IEC_InterruptStackTooSmall;;6;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2907;IEC_ThreadExitted;;7;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2908;IEC_InconsistentMpInformation;;8;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2909;IEC_InvalidNode;;9;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x290a;IEC_NoMpci;;10;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x290b;IEC_BadPacket;;11;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x290c;IEC_OutOfPackets;;12;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x290d;IEC_OutOfGlobalObjects;;13;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x290e;IEC_OutOfProxies;;14;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x290f;IEC_InvalidGlobalId;;15;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2910;IEC_BadStackHook;;16;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2911;IEC_BadAttributes;;17;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2912;IEC_ImplementationKeyCreateInconsistency;;18;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2913;IEC_ImplementationBlockingOperationCancel;;19;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2914;IEC_MutexObtainFromBadState;;20;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2915;IEC_UnlimitedAndMaximumIs0;;21;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2d01;HPA_InvalidIdentifierId;;1;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h +0x2d02;HPA_InvalidDomainId;;2;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h +0x2d03;HPA_InvalidValue;;3;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h +0x2d05;HPA_ReadOnly;;5;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h +0x2c01;PAW_UnknownDatatype;;1;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2c02;PAW_DatatypeMissmatch;;2;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2c03;PAW_Readonly;;3;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2c04;PAW_TooBig;;4;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2c05;PAW_SourceNotSet;;5;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2c06;PAW_OutOfBounds;;6;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2c07;PAW_NotSet;;7;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2c08;PAW_ColumnOrRowsZero;;8;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2f01;POS_InPowerTransition;;1;POWER_SWITCHER;fsfw/src/fsfw/power/PowerSwitcher.h +0x2f02;POS_SwitchStateMismatch;;2;POWER_SWITCHER;fsfw/src/fsfw/power/PowerSwitcher.h +0x0501;PS_SwitchOn;;1;POWER_SWITCH_IF;fsfw/src/fsfw/power/PowerSwitchIF.h +0x0500;PS_SwitchOff;;0;POWER_SWITCH_IF;fsfw/src/fsfw/power/PowerSwitchIF.h +0x0502;PS_SwitchTimeout;;2;POWER_SWITCH_IF;fsfw/src/fsfw/power/PowerSwitchIF.h +0x0503;PS_FuseOn;;3;POWER_SWITCH_IF;fsfw/src/fsfw/power/PowerSwitchIF.h +0x0504;PS_FuseOff;;4;POWER_SWITCH_IF;fsfw/src/fsfw/power/PowerSwitchIF.h +0x4101;PUS11_InvalidTypeTimeWindow;;1;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h +0x4102;PUS11_TimeshiftingNotPossible;;2;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h +0x4103;PUS11_InvalidRelativeTime;;3;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h +0x04e1;RMP_CommandNoDescriptorsAvailable;;225;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04e2;RMP_CommandBufferFull;;226;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04e3;RMP_CommandChannelOutOfRange;;227;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04e6;RMP_CommandChannelDeactivated;;230;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04e7;RMP_CommandPortOutOfRange;;231;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04e8;RMP_CommandPortInUse;;232;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04e9;RMP_CommandNoChannel;;233;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04ea;RMP_NoHwCrc;;234;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04d0;RMP_ReplyNoReply;;208;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04d1;RMP_ReplyNotSent;;209;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04d2;RMP_ReplyNotYetSent;;210;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04d3;RMP_ReplyMissmatch;;211;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04d4;RMP_ReplyTimeout;;212;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04c0;RMP_ReplyInterfaceBusy;;192;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04c1;RMP_ReplyTransmissionError;;193;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04c2;RMP_ReplyInvalidData;;194;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04c3;RMP_ReplyNotSupported;;195;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04f0;RMP_LinkDown;;240;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04f1;RMP_SpwCredit;;241;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04f2;RMP_SpwEscape;;242;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04f3;RMP_SpwDisconnect;;243;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04f4;RMP_SpwParity;;244;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04f5;RMP_SpwWriteSync;;245;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04f6;RMP_SpwInvalidAddress;;246;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04f7;RMP_SpwEarlyEop;;247;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04f8;RMP_SpwDma;;248;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x04f9;RMP_SpwLinkError;;249;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x0400;RMP_ReplyOk;;0;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x0401;RMP_ReplyGeneralErrorCode;;1;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x0402;RMP_ReplyUnusedPacketTypeOrCommandCode;;2;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x0403;RMP_ReplyInvalidKey;;3;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x0404;RMP_ReplyInvalidDataCrc;;4;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x0405;RMP_ReplyEarlyEop;;5;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x0406;RMP_ReplyTooMuchData;;6;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x0407;RMP_ReplyEep;;7;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x0408;RMP_ReplyReserved;;8;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x0409;RMP_ReplyVerifyBufferOverrun;;9;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x040a;RMP_ReplyCommandNotImplementedOrNotAuthorised;;10;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x040b;RMP_ReplyRmwDataLengthError;;11;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x040c;RMP_ReplyInvalidTargetLogicalAddress;;12;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h +0x1401;SE_BufferTooShort;;1;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h +0x1402;SE_StreamTooShort;;2;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h +0x1403;SE_TooManyElements;;3;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h +0x2701;SM_DataTooLarge;;1;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x2702;SM_DataStorageFull;;2;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x2703;SM_IllegalStorageId;;3;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x2704;SM_DataDoesNotExist;;4;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x2705;SM_IllegalAddress;;5;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x2706;SM_PoolTooLarge;;6;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x0c02;MS_InvalidEntry;;2;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h +0x0c03;MS_TooManyElements;;3;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h +0x0c04;MS_CantStoreEmpty;;4;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h +0x0d01;SS_SequenceAlreadyExists;;1;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d02;SS_TableAlreadyExists;;2;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d03;SS_TableDoesNotExist;;3;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d04;SS_TableOrSequenceLengthInvalid;;4;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d05;SS_SequenceDoesNotExist;;5;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d06;SS_TableContainsInvalidObjectId;;6;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d07;SS_FallbackSequenceDoesNotExist;;7;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d08;SS_NoTargetTable;;8;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d09;SS_SequenceOrTableTooLong;;9;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d0b;SS_IsFallbackSequence;;11;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d0c;SS_AccessDenied;;12;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d0e;SS_TableInUse;;14;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0da1;SS_TargetTableNotReached;;161;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0da2;SS_TableCheckFailed;;162;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0b01;SB_ChildNotFound;;1;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h +0x0b02;SB_ChildInfoUpdated;;2;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h +0x0b03;SB_ChildDoesntHaveModes;;3;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h +0x0b04;SB_CouldNotInsertChild;;4;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h +0x0b05;SB_TableContainsInvalidObjectId;;5;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h +0x3a01;SPH_SemaphoreTimeout;;1;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h +0x3a02;SPH_SemaphoreNotOwned;;2;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h +0x3a03;SPH_SemaphoreInvalid;;3;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h +0x1c01;TCD_PacketLost;;1;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributor.h +0x1c02;TCD_DestinationNotFound;;2;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributor.h +0x1c03;TCD_ServiceIdAlreadyExists;;3;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributor.h +0x1b00;TCC_IllegalApid;;0;TC_PACKET_CHECK;fsfw/src/fsfw/tcdistribution/TcPacketCheckPUS.h +0x1b01;TCC_IncompletePacket;;1;TC_PACKET_CHECK;fsfw/src/fsfw/tcdistribution/TcPacketCheckPUS.h +0x1b02;TCC_IncorrectChecksum;;2;TC_PACKET_CHECK;fsfw/src/fsfw/tcdistribution/TcPacketCheckPUS.h +0x1b03;TCC_IllegalPacketType;;3;TC_PACKET_CHECK;fsfw/src/fsfw/tcdistribution/TcPacketCheckPUS.h +0x1b04;TCC_IllegalPacketSubtype;;4;TC_PACKET_CHECK;fsfw/src/fsfw/tcdistribution/TcPacketCheckPUS.h +0x1b05;TCC_IncorrectPrimaryHeader;;5;TC_PACKET_CHECK;fsfw/src/fsfw/tcdistribution/TcPacketCheckPUS.h +0x1b06;TCC_IncorrectSecondaryHeader;;6;TC_PACKET_CHECK;fsfw/src/fsfw/tcdistribution/TcPacketCheckPUS.h +0x2801;TC_InvalidTargetState;;1;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h +0x28f1;TC_AboveOperationalLimit;;241;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h +0x28f2;TC_BelowOperationalLimit;;242;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h +0x1000;TIM_UnsupportedTimeFormat;;0;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x1001;TIM_NotEnoughInformationForTargetFormat;;1;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x1002;TIM_LengthMismatch;;2;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x1003;TIM_InvalidTimeFormat;;3;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x1004;TIM_InvalidDayOfYear;;4;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x1005;TIM_TimeDoesNotFitFormat;;5;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x3601;TSI_BadTimestamp;;1;TIME_STAMPER_IF;fsfw/src/fsfw/timemanager/TimeStamperIF.h +0x2001;TMB_Busy;;1;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2002;TMB_Full;;2;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2003;TMB_Empty;;3;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2004;TMB_NullRequested;;4;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2005;TMB_TooLarge;;5;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2006;TMB_NotReady;;6;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2007;TMB_DumpError;;7;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2008;TMB_CrcError;;8;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2009;TMB_Timeout;;9;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x200a;TMB_IdlePacketFound;;10;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x200b;TMB_TelecommandFound;;11;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x200c;TMB_NoPusATm;;12;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x200d;TMB_TooSmall;;13;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x200e;TMB_BlockNotFound;;14;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x200f;TMB_InvalidRequest;;15;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2101;TMF_Busy;;1;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2102;TMF_LastPacketFound;;2;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2103;TMF_StopFetch;;3;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2104;TMF_Timeout;;4;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2105;TMF_TmChannelFull;;5;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2106;TMF_NotStored;;6;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2107;TMF_AllDeleted;;7;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2108;TMF_InvalidData;;8;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2109;TMF_NotReady;;9;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x1d01;PUS_ActivityStarted;;1;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h +0x1d02;PUS_InvalidSubservice;;2;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h +0x1d03;PUS_IllegalApplicationData;;3;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h +0x1d04;PUS_SendTmFailed;;4;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h +0x1d05;PUS_Timeout;;5;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h +0x1f01;CSB_ExecutionComplete;;1;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x1f02;CSB_NoStepMessage;;2;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x1f03;CSB_ObjectBusy;;3;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x1f04;CSB_Busy;;4;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x1f05;CSB_InvalidTc;;5;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x1f06;CSB_InvalidObject;;6;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x1f07;CSB_InvalidReply;;7;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x4b00;SPPA_NoPacketFound;;0;SPACE_PACKET_PARSER;fsfw/src/fsfw/tmtcservices/SpacePacketParser.h +0x4b01;SPPA_SplitPacket;;1;SPACE_PACKET_PARSER;fsfw/src/fsfw/tmtcservices/SpacePacketParser.h +0x68a0;FSHLP_SdNotMounted;SD card specified with path string not mounted;160;FILE_SYSTEM_HELPER;bsp_q7s/memory/FilesystemHelper.h +0x68a1;FSHLP_FileNotExists;Specified file does not exist on filesystem;161;FILE_SYSTEM_HELPER;bsp_q7s/memory/FilesystemHelper.h +0x7400;SCBU_KeyNotFound;;0;SCRATCH_BUFFER;bsp_q7s/memory/scratchApi.h +0x7300;SDMA_OpOngoing;;0;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h +0x7301;SDMA_AlreadyOn;;1;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h +0x7302;SDMA_AlreadyMounted;;2;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h +0x7303;SDMA_AlreadyOff;;3;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h +0x730a;SDMA_StatusFileNexists;;10;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h +0x730b;SDMA_StatusFileFormatInvalid;;11;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h +0x730c;SDMA_MountError;;12;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h +0x730d;SDMA_UnmountError;;13;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h +0x730e;SDMA_SystemCallError;;14;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h +0x730f;SDMA_PopenCallError;;15;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h diff --git a/generators/deps/fsfwgen b/generators/deps/fsfwgen new file mode 160000 index 00000000..a5dee6e4 --- /dev/null +++ b/generators/deps/fsfwgen @@ -0,0 +1 @@ +Subproject commit a5dee6e41749508a85842a931e6f1d210aee2031 diff --git a/generators/events/event_parser.py b/generators/events/event_parser.py index 9398ba98..487fbc6c 100644 --- a/generators/events/event_parser.py +++ b/generators/events/event_parser.py @@ -4,17 +4,19 @@ Event exporter. import datetime import time import os +from pathlib import Path from fsfwgen.events.event_parser import ( handle_csv_export, handle_cpp_export, SubsystemDefinitionParser, EventParser, + EventDictT, ) from fsfwgen.parserbase.file_list_parser import FileListParser from fsfwgen.utility.printer import PrettyPrinter from fsfwgen.utility.file_management import copy_file -from fsfwgen.core import get_console_logger +from fsfwgen.logging import get_console_logger from definitions import BspType, ROOT_DIR, OBSW_ROOT_DIR LOGGER = get_console_logger() @@ -31,24 +33,28 @@ MOVE_CSV_FILE = True PARSE_HOST_BSP = True # Store these files relative to the events folder -CPP_FILENAME = f"{os.path.dirname(os.path.realpath(__file__))}/translateEvents.cpp" -CPP_H_FILENAME = f"{os.path.dirname(os.path.realpath(__file__))}/translateEvents.h" +CPP_FILENAME = Path( + f"{os.path.dirname(os.path.realpath(__file__))}/translateEvents.cpp" +) +CPP_H_FILENAME = Path( + f"{os.path.dirname(os.path.realpath(__file__))}/translateEvents.h" +) BSP_SELECT = BspType.BSP_Q7S BSP_DIR_NAME = BSP_SELECT.value # Store this file in the root of the generators folder -CSV_FILENAME = f"{ROOT_DIR}/{BSP_SELECT.value}_events.csv" -CSV_COPY_DEST = f"{OBSW_ROOT_DIR}/tmtc/config/events.csv" +CSV_FILENAME = Path(f"{ROOT_DIR}/{BSP_SELECT.value}_events.csv") +CSV_COPY_DEST = Path(f"{OBSW_ROOT_DIR}/tmtc/config/events.csv") if BSP_SELECT == BspType.BSP_Q7S or BSP_SELECT == BspType.BSP_LINUX_BOARD: - FSFW_CONFIG_ROOT = f"{OBSW_ROOT_DIR}/linux/fsfwconfig" + FSFW_CONFIG_ROOT = Path(f"{OBSW_ROOT_DIR}/linux/fsfwconfig") else: - FSFW_CONFIG_ROOT = f"{OBSW_ROOT_DIR}/{BSP_DIR_NAME}/fsfwconfig" + FSFW_CONFIG_ROOT = Path(f"{OBSW_ROOT_DIR}/{BSP_DIR_NAME}/fsfwconfig") -CPP_COPY_DESTINATION = f"{FSFW_CONFIG_ROOT}/events/" +CPP_COPY_DESTINATION = Path(f"{FSFW_CONFIG_ROOT}/events/") FILE_SEPARATOR = ";" SUBSYSTEM_DEFINITION_DESTINATIONS = [ @@ -56,14 +62,21 @@ SUBSYSTEM_DEFINITION_DESTINATIONS = [ f"{OBSW_ROOT_DIR}/fsfw/src/fsfw/events/fwSubsystemIdRanges.h", f"{OBSW_ROOT_DIR}/common/config/commonSubsystemIds.h", ] +SUBSYSTEM_DEFS_DEST_AS_PATH = [Path(x) for x in SUBSYSTEM_DEFINITION_DESTINATIONS] + HEADER_DEFINITION_DESTINATIONS = [ f"{OBSW_ROOT_DIR}/mission/", f"{OBSW_ROOT_DIR}/fsfw/", f"{FSFW_CONFIG_ROOT}", f"{OBSW_ROOT_DIR}/test/", - f"{OBSW_ROOT_DIR}/bsp_q7s", + f"{OBSW_ROOT_DIR}/bsp_q7s/", f"{OBSW_ROOT_DIR}/linux/", ] +HEADER_DEFINITION_DESTINATIONS_AS_PATH = [ + Path(x) for x in HEADER_DEFINITION_DESTINATIONS +] + +LOGGER = get_console_logger() def parse_events( @@ -77,7 +90,6 @@ def parse_events( PrettyPrinter.pprint(event_list) # Delay for clean printout time.sleep(0.1) - # xml_test() if generate_csv: handle_csv_export( file_name=CSV_FILENAME, event_list=event_list, file_separator=FILE_SEPARATOR @@ -96,17 +108,19 @@ def parse_events( header_file_name=CPP_H_FILENAME, ) if COPY_CPP_FILE: - LOGGER.info(f"EventParser: Copying CPP translation file to {CPP_COPY_DESTINATION}") + LOGGER.info( + f"EventParser: Copying CPP translation file to {CPP_COPY_DESTINATION}" + ) copy_file(CPP_FILENAME, CPP_COPY_DESTINATION) copy_file(CPP_H_FILENAME, CPP_COPY_DESTINATION) -def generate_event_list() -> list: - subsystem_parser = SubsystemDefinitionParser(SUBSYSTEM_DEFINITION_DESTINATIONS) +def generate_event_list() -> EventDictT: + subsystem_parser = SubsystemDefinitionParser(SUBSYSTEM_DEFS_DEST_AS_PATH) subsystem_table = subsystem_parser.parse_files() LOGGER.info(f"Found {len(subsystem_table)} subsystem definitions.") PrettyPrinter.pprint(subsystem_table) - event_header_parser = FileListParser(HEADER_DEFINITION_DESTINATIONS) + event_header_parser = FileListParser(HEADER_DEFINITION_DESTINATIONS_AS_PATH) event_headers = event_header_parser.parse_header_files( True, "Parsing event header file list:\n", True ) @@ -116,6 +130,6 @@ def generate_event_list() -> list: event_parser.obsw_root_path = OBSW_ROOT_DIR event_parser.set_moving_window_mode(moving_window_size=7) event_table = event_parser.parse_files() - event_list = sorted(event_table.items()) - LOGGER.info(f"Found {len(event_list)} entries") - return event_list + events_sorted = dict(sorted(event_table.items())) + LOGGER.info(f"Found {len(events_sorted)} entries") + return events_sorted diff --git a/generators/events/translateEvents.cpp b/generators/events/translateEvents.cpp index 1a155186..7f9cfc78 100644 --- a/generators/events/translateEvents.cpp +++ b/generators/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 187 translations. + * @brief Auto-generated event translation file. Contains 209 translations. * @details - * Generated on: 2022-05-03 16:32:00 + * Generated on: 2022-06-27 09:14:37 */ #include "translateEvents.h" @@ -82,6 +82,7 @@ const char *BIT_LOCK_LOST_STRING = "BIT_LOCK_LOST"; const char *FRAME_PROCESSING_FAILED_STRING = "FRAME_PROCESSING_FAILED"; const char *CLOCK_SET_STRING = "CLOCK_SET"; const char *CLOCK_SET_FAILURE_STRING = "CLOCK_SET_FAILURE"; +const char *TC_DELETION_FAILED_STRING = "TC_DELETION_FAILED"; const char *TEST_STRING = "TEST"; const char *CHANGE_OF_SETUP_PARAMETER_STRING = "CHANGE_OF_SETUP_PARAMETER"; const char *SWITCH_CMD_SENT_STRING = "SWITCH_CMD_SENT"; @@ -90,9 +91,12 @@ const char *SWITCHING_Q7S_DENIED_STRING = "SWITCHING_Q7S_DENIED"; const char *FDIR_REACTION_IGNORED_STRING = "FDIR_REACTION_IGNORED"; const char *GPIO_PULL_HIGH_FAILED_STRING = "GPIO_PULL_HIGH_FAILED"; const char *GPIO_PULL_LOW_FAILED_STRING = "GPIO_PULL_LOW_FAILED"; +const char *HEATER_WENT_ON_STRING = "HEATER_WENT_ON"; +const char *HEATER_WENT_OFF_STRING = "HEATER_WENT_OFF"; const char *SWITCH_ALREADY_ON_STRING = "SWITCH_ALREADY_ON"; const char *SWITCH_ALREADY_OFF_STRING = "SWITCH_ALREADY_OFF"; const char *MAIN_SWITCH_TIMEOUT_STRING = "MAIN_SWITCH_TIMEOUT"; +const char *FAULTY_HEATER_WAS_ON_STRING = "FAULTY_HEATER_WAS_ON"; const char *MAIN_SWITCH_ON_TIMEOUT_STRING = "MAIN_SWITCH_ON_TIMEOUT"; const char *MAIN_SWITCH_OFF_TIMEOUT_STRING = "MAIN_SWITCH_OFF_TIMEOUT"; const char *DEPLOYMENT_FAILED_STRING = "DEPLOYMENT_FAILED"; @@ -102,7 +106,7 @@ const char *MEMORY_READ_RPT_CRC_FAILURE_STRING = "MEMORY_READ_RPT_CRC_FAILURE"; const char *ACK_FAILURE_STRING = "ACK_FAILURE"; const char *EXE_FAILURE_STRING = "EXE_FAILURE"; const char *MPSOC_HANDLER_CRC_FAILURE_STRING = "MPSOC_HANDLER_CRC_FAILURE"; -const char *MPSOC_HANDLER_SEQ_CNT_MISMATCH_STRING = "MPSOC_HANDLER_SEQ_CNT_MISMATCH"; +const char *MPSOC_HANDLER_SEQUENCE_COUNT_MISMATCH_STRING = "MPSOC_HANDLER_SEQUENCE_COUNT_MISMATCH"; const char *MPSOC_SHUTDOWN_FAILED_STRING = "MPSOC_SHUTDOWN_FAILED"; const char *SELF_TEST_I2C_FAILURE_STRING = "SELF_TEST_I2C_FAILURE"; const char *SELF_TEST_SPI_FAILURE_STRING = "SELF_TEST_SPI_FAILURE"; @@ -113,20 +117,16 @@ const char *SELF_TEST_MTM_RANGE_FAILURE_STRING = "SELF_TEST_MTM_RANGE_FAILURE"; const char *SELF_TEST_COIL_CURRENT_FAILURE_STRING = "SELF_TEST_COIL_CURRENT_FAILURE"; const char *INVALID_ERROR_BYTE_STRING = "INVALID_ERROR_BYTE"; const char *ERROR_STATE_STRING = "ERROR_STATE"; +const char *RESET_OCCURED_STRING = "RESET_OCCURED"; const char *BOOTING_FIRMWARE_FAILED_STRING = "BOOTING_FIRMWARE_FAILED"; const char *BOOTING_BOOTLOADER_FAILED_STRING = "BOOTING_BOOTLOADER_FAILED"; const char *SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING = "SUPV_MEMORY_READ_RPT_CRC_FAILURE"; const char *SUPV_ACK_FAILURE_STRING = "SUPV_ACK_FAILURE"; const char *SUPV_EXE_FAILURE_STRING = "SUPV_EXE_FAILURE"; const char *SUPV_CRC_FAILURE_EVENT_STRING = "SUPV_CRC_FAILURE_EVENT"; +const char *SUPV_MPSOC_SHUWDOWN_BUILD_FAILED_STRING = "SUPV_MPSOC_SHUWDOWN_BUILD_FAILED"; const char *SANITIZATION_FAILED_STRING = "SANITIZATION_FAILED"; const char *MOUNTED_SD_CARD_STRING = "MOUNTED_SD_CARD"; -const char *UPDATE_FILE_NOT_EXISTS_STRING = "UPDATE_FILE_NOT_EXISTS"; -const char *ACTION_COMMANDING_FAILED_STRING = "ACTION_COMMANDING_FAILED"; -const char *UPDATE_AVAILABLE_FAILED_STRING = "UPDATE_AVAILABLE_FAILED"; -const char *UPDATE_TRANSFER_FAILED_STRING = "UPDATE_TRANSFER_FAILED"; -const char *UPDATE_VERIFY_FAILED_STRING = "UPDATE_VERIFY_FAILED"; -const char *UPDATE_FINISHED_STRING = "UPDATE_FINISHED"; const char *SEND_MRAM_DUMP_FAILED_STRING = "SEND_MRAM_DUMP_FAILED"; const char *MRAM_DUMP_FAILED_STRING = "MRAM_DUMP_FAILED"; const char *MRAM_DUMP_FINISHED_STRING = "MRAM_DUMP_FINISHED"; @@ -134,6 +134,8 @@ const char *INVALID_TC_FRAME_STRING = "INVALID_TC_FRAME"; const char *INVALID_FAR_STRING = "INVALID_FAR"; const char *CARRIER_LOCK_STRING = "CARRIER_LOCK"; const char *BIT_LOCK_PDEC_STRING = "BIT_LOCK_PDEC"; +const char *LOST_CARRIER_LOCK_PDEC_STRING = "LOST_CARRIER_LOCK_PDEC"; +const char *LOST_BIT_LOCK_PDEC_STRING = "LOST_BIT_LOCK_PDEC"; const char *IMAGE_UPLOAD_FAILED_STRING = "IMAGE_UPLOAD_FAILED"; const char *IMAGE_DOWNLOAD_FAILED_STRING = "IMAGE_DOWNLOAD_FAILED"; const char *IMAGE_UPLOAD_SUCCESSFUL_STRING = "IMAGE_UPLOAD_SUCCESSFUL"; @@ -153,15 +155,15 @@ const char *STR_HELPER_SENDING_PACKET_FAILED_STRING = "STR_HELPER_SENDING_PACKET const char *STR_HELPER_REQUESTING_MSG_FAILED_STRING = "STR_HELPER_REQUESTING_MSG_FAILED"; const char *MPSOC_FLASH_WRITE_FAILED_STRING = "MPSOC_FLASH_WRITE_FAILED"; const char *MPSOC_FLASH_WRITE_SUCCESSFUL_STRING = "MPSOC_FLASH_WRITE_SUCCESSFUL"; -const char *SENDING_COMMAND_FAILED_STRING = "SENDING_COMMAND_FAILED"; +const char *MPSOC_SENDING_COMMAND_FAILED_STRING = "MPSOC_SENDING_COMMAND_FAILED"; const char *MPSOC_HELPER_REQUESTING_REPLY_FAILED_STRING = "MPSOC_HELPER_REQUESTING_REPLY_FAILED"; const char *MPSOC_HELPER_READING_REPLY_FAILED_STRING = "MPSOC_HELPER_READING_REPLY_FAILED"; -const char *MISSING_ACK_STRING = "MISSING_ACK"; -const char *MISSING_EXE_STRING = "MISSING_EXE"; -const char *ACK_FAILURE_REPORT_STRING = "ACK_FAILURE_REPORT"; -const char *EXE_FAILURE_REPORT_STRING = "EXE_FAILURE_REPORT"; -const char *ACK_INVALID_APID_STRING = "ACK_INVALID_APID"; -const char *EXE_INVALID_APID_STRING = "EXE_INVALID_APID"; +const char *MPSOC_MISSING_ACK_STRING = "MPSOC_MISSING_ACK"; +const char *MPSOC_MISSING_EXE_STRING = "MPSOC_MISSING_EXE"; +const char *MPSOC_ACK_FAILURE_REPORT_STRING = "MPSOC_ACK_FAILURE_REPORT"; +const char *MPSOC_EXE_FAILURE_REPORT_STRING = "MPSOC_EXE_FAILURE_REPORT"; +const char *MPSOC_ACK_INVALID_APID_STRING = "MPSOC_ACK_INVALID_APID"; +const char *MPSOC_EXE_INVALID_APID_STRING = "MPSOC_EXE_INVALID_APID"; const char *MPSOC_HELPER_SEQ_CNT_MISMATCH_STRING = "MPSOC_HELPER_SEQ_CNT_MISMATCH"; const char *TRANSITION_BACK_TO_OFF_STRING = "TRANSITION_BACK_TO_OFF"; const char *NEG_V_OUT_OF_BOUNDS_STRING = "NEG_V_OUT_OF_BOUNDS"; @@ -184,6 +186,26 @@ const char *GPS_FIX_CHANGE_STRING = "GPS_FIX_CHANGE"; const char *P60_BOOT_COUNT_STRING = "P60_BOOT_COUNT"; const char *BATT_MODE_STRING = "BATT_MODE"; const char *BATT_MODE_CHANGED_STRING = "BATT_MODE_CHANGED"; +const char *SUPV_UPDATE_FAILED_STRING = "SUPV_UPDATE_FAILED"; +const char *SUPV_UPDATE_SUCCESSFUL_STRING = "SUPV_UPDATE_SUCCESSFUL"; +const char *SUPV_CONTINUE_UPDATE_FAILED_STRING = "SUPV_CONTINUE_UPDATE_FAILED"; +const char *SUPV_CONTINUE_UPDATE_SUCCESSFUL_STRING = "SUPV_CONTINUE_UPDATE_SUCCESSFUL"; +const char *TERMINATED_UPDATE_PROCEDURE_STRING = "TERMINATED_UPDATE_PROCEDURE"; +const char *SUPV_EVENT_BUFFER_REQUEST_SUCCESSFUL_STRING = "SUPV_EVENT_BUFFER_REQUEST_SUCCESSFUL"; +const char *SUPV_EVENT_BUFFER_REQUEST_FAILED_STRING = "SUPV_EVENT_BUFFER_REQUEST_FAILED"; +const char *SUPV_EVENT_BUFFER_REQUEST_TERMINATED_STRING = "SUPV_EVENT_BUFFER_REQUEST_TERMINATED"; +const char *SUPV_SENDING_COMMAND_FAILED_STRING = "SUPV_SENDING_COMMAND_FAILED"; +const char *SUPV_HELPER_REQUESTING_REPLY_FAILED_STRING = "SUPV_HELPER_REQUESTING_REPLY_FAILED"; +const char *SUPV_HELPER_READING_REPLY_FAILED_STRING = "SUPV_HELPER_READING_REPLY_FAILED"; +const char *SUPV_MISSING_ACK_STRING = "SUPV_MISSING_ACK"; +const char *SUPV_MISSING_EXE_STRING = "SUPV_MISSING_EXE"; +const char *SUPV_ACK_FAILURE_REPORT_STRING = "SUPV_ACK_FAILURE_REPORT"; +const char *SUPV_EXE_FAILURE_REPORT_STRING = "SUPV_EXE_FAILURE_REPORT"; +const char *SUPV_ACK_INVALID_APID_STRING = "SUPV_ACK_INVALID_APID"; +const char *SUPV_EXE_INVALID_APID_STRING = "SUPV_EXE_INVALID_APID"; +const char *ACK_RECEPTION_FAILURE_STRING = "ACK_RECEPTION_FAILURE"; +const char *EXE_RECEPTION_FAILURE_STRING = "EXE_RECEPTION_FAILURE"; +const char *WRITE_MEMORY_FAILED_STRING = "WRITE_MEMORY_FAILED"; const char *ALLOC_FAILURE_STRING = "ALLOC_FAILURE"; const char *REBOOT_SW_STRING = "REBOOT_SW"; const char *REBOOT_MECHANISM_TRIGGERED_STRING = "REBOOT_MECHANISM_TRIGGERED"; @@ -345,6 +367,8 @@ const char *translateEvents(Event event) { return CLOCK_SET_STRING; case (8901): return CLOCK_SET_FAILURE_STRING; + case (9100): + return TC_DELETION_FAILED_STRING; case (9700): return TEST_STRING; case (10600): @@ -362,11 +386,17 @@ const char *translateEvents(Event event) { case (11401): return GPIO_PULL_LOW_FAILED_STRING; case (11402): - return SWITCH_ALREADY_ON_STRING; + return HEATER_WENT_ON_STRING; case (11403): - return SWITCH_ALREADY_OFF_STRING; + return HEATER_WENT_OFF_STRING; case (11404): + return SWITCH_ALREADY_ON_STRING; + case (11405): + return SWITCH_ALREADY_OFF_STRING; + case (11406): return MAIN_SWITCH_TIMEOUT_STRING; + case (11407): + return FAULTY_HEATER_WAS_ON_STRING; case (11500): return MAIN_SWITCH_ON_TIMEOUT_STRING; case (11501): @@ -386,7 +416,7 @@ const char *translateEvents(Event event) { case (11604): return MPSOC_HANDLER_CRC_FAILURE_STRING; case (11605): - return MPSOC_HANDLER_SEQ_CNT_MISMATCH_STRING; + return MPSOC_HANDLER_SEQUENCE_COUNT_MISMATCH_STRING; case (11606): return MPSOC_SHUTDOWN_FAILED_STRING; case (11701): @@ -407,6 +437,8 @@ const char *translateEvents(Event event) { return INVALID_ERROR_BYTE_STRING; case (11801): return ERROR_STATE_STRING; + case (11802): + return RESET_OCCURED_STRING; case (11901): return BOOTING_FIRMWARE_FAILED_STRING; case (11902): @@ -419,22 +451,12 @@ const char *translateEvents(Event event) { return SUPV_EXE_FAILURE_STRING; case (12004): return SUPV_CRC_FAILURE_EVENT_STRING; + case (12005): + return SUPV_MPSOC_SHUWDOWN_BUILD_FAILED_STRING; case (12100): return SANITIZATION_FAILED_STRING; case (12101): return MOUNTED_SD_CARD_STRING; - case (12200): - return UPDATE_FILE_NOT_EXISTS_STRING; - case (12201): - return ACTION_COMMANDING_FAILED_STRING; - case (12202): - return UPDATE_AVAILABLE_FAILED_STRING; - case (12203): - return UPDATE_TRANSFER_FAILED_STRING; - case (12204): - return UPDATE_VERIFY_FAILED_STRING; - case (12205): - return UPDATE_FINISHED_STRING; case (12300): return SEND_MRAM_DUMP_FAILED_STRING; case (12301): @@ -449,6 +471,10 @@ const char *translateEvents(Event event) { return CARRIER_LOCK_STRING; case (12404): return BIT_LOCK_PDEC_STRING; + case (12405): + return LOST_CARRIER_LOCK_PDEC_STRING; + case (12406): + return LOST_BIT_LOCK_PDEC_STRING; case (12500): return IMAGE_UPLOAD_FAILED_STRING; case (12501): @@ -488,23 +514,23 @@ const char *translateEvents(Event event) { case (12601): return MPSOC_FLASH_WRITE_SUCCESSFUL_STRING; case (12602): - return SENDING_COMMAND_FAILED_STRING; + return MPSOC_SENDING_COMMAND_FAILED_STRING; case (12603): return MPSOC_HELPER_REQUESTING_REPLY_FAILED_STRING; case (12604): return MPSOC_HELPER_READING_REPLY_FAILED_STRING; case (12605): - return MISSING_ACK_STRING; + return MPSOC_MISSING_ACK_STRING; case (12606): - return MISSING_EXE_STRING; + return MPSOC_MISSING_EXE_STRING; case (12607): - return ACK_FAILURE_REPORT_STRING; + return MPSOC_ACK_FAILURE_REPORT_STRING; case (12608): - return EXE_FAILURE_REPORT_STRING; + return MPSOC_EXE_FAILURE_REPORT_STRING; case (12609): - return ACK_INVALID_APID_STRING; + return MPSOC_ACK_INVALID_APID_STRING; case (12610): - return EXE_INVALID_APID_STRING; + return MPSOC_EXE_INVALID_APID_STRING; case (12611): return MPSOC_HELPER_SEQ_CNT_MISMATCH_STRING; case (12700): @@ -550,12 +576,52 @@ const char *translateEvents(Event event) { case (13202): return BATT_MODE_CHANGED_STRING; case (13600): - return ALLOC_FAILURE_STRING; + return SUPV_UPDATE_FAILED_STRING; case (13601): - return REBOOT_SW_STRING; + return SUPV_UPDATE_SUCCESSFUL_STRING; case (13602): - return REBOOT_MECHANISM_TRIGGERED_STRING; + return SUPV_CONTINUE_UPDATE_FAILED_STRING; case (13603): + return SUPV_CONTINUE_UPDATE_SUCCESSFUL_STRING; + case (13604): + return TERMINATED_UPDATE_PROCEDURE_STRING; + case (13605): + return SUPV_EVENT_BUFFER_REQUEST_SUCCESSFUL_STRING; + case (13606): + return SUPV_EVENT_BUFFER_REQUEST_FAILED_STRING; + case (13607): + return SUPV_EVENT_BUFFER_REQUEST_TERMINATED_STRING; + case (13608): + return SUPV_SENDING_COMMAND_FAILED_STRING; + case (13609): + return SUPV_HELPER_REQUESTING_REPLY_FAILED_STRING; + case (13610): + return SUPV_HELPER_READING_REPLY_FAILED_STRING; + case (13611): + return SUPV_MISSING_ACK_STRING; + case (13612): + return SUPV_MISSING_EXE_STRING; + case (13613): + return SUPV_ACK_FAILURE_REPORT_STRING; + case (13614): + return SUPV_EXE_FAILURE_REPORT_STRING; + case (13615): + return SUPV_ACK_INVALID_APID_STRING; + case (13616): + return SUPV_EXE_INVALID_APID_STRING; + case (13617): + return ACK_RECEPTION_FAILURE_STRING; + case (13618): + return EXE_RECEPTION_FAILURE_STRING; + case (13619): + return WRITE_MEMORY_FAILED_STRING; + case (13700): + return ALLOC_FAILURE_STRING; + case (13701): + return REBOOT_SW_STRING; + case (13702): + return REBOOT_MECHANISM_TRIGGERED_STRING; + case (13703): return REBOOT_HW_STRING; default: return "UNKNOWN_EVENT"; diff --git a/generators/fsfwgen b/generators/fsfwgen deleted file mode 160000 index 169ad98c..00000000 --- a/generators/fsfwgen +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 169ad98cdeebe3ccfd1b78938934496a20b6a294 diff --git a/generators/gen.py b/generators/gen.py index f79e7226..5ae9f071 100755 --- a/generators/gen.py +++ b/generators/gen.py @@ -7,10 +7,8 @@ from returnvalues.returnvalues_parser import parse_returnvalues from fsfwgen.core import ( return_generic_args_parser, init_printout, - get_console_logger, - ParserTypes, ) - +from fsfwgen.logging import get_console_logger LOGGER = get_console_logger() @@ -20,7 +18,7 @@ def main(): parser = return_generic_args_parser() args = parser.parse_args() if args.type == "objects": - LOGGER.info(f"Generating objects data..") + LOGGER.info(f"Generating objects data") time.sleep(0.05) parse_objects() elif args.type == "events": diff --git a/generators/objects/objects.py b/generators/objects/objects.py index fa174bc1..80eb106a 100644 --- a/generators/objects/objects.py +++ b/generators/objects/objects.py @@ -3,8 +3,9 @@ Object exporter. """ import datetime import os +from pathlib import Path -from fsfwgen.core import get_console_logger +from fsfwgen.logging import get_console_logger from fsfwgen.objects.objects import ( sql_object_exporter, ObjectDefinitionParser, @@ -46,11 +47,11 @@ CSV_COPY_DEST = f"{OBSW_ROOT_DIR}/tmtc/config/objects.csv" FILE_SEPARATOR = ";" -OBJECTS_PATH = f"{FSFW_CONFIG_ROOT}/objects/systemObjectList.h" -FRAMEWORK_OBJECT_PATH = ( +OBJECTS_PATH = Path(f"{FSFW_CONFIG_ROOT}/objects/systemObjectList.h") +FRAMEWORK_OBJECT_PATH = Path( f"{OBSW_ROOT_DIR}/fsfw/src/fsfw/objectmanager/frameworkObjects.h" ) -COMMON_OBJECTS_PATH = f"{OBSW_ROOT_DIR}/common/config/commonObjects.h" +COMMON_OBJECTS_PATH = Path(f"{OBSW_ROOT_DIR}/common/config/commonObjects.h") OBJECTS_DEFINITIONS = [OBJECTS_PATH, FRAMEWORK_OBJECT_PATH, COMMON_OBJECTS_PATH] SQL_DELETE_OBJECTS_CMD = """ diff --git a/generators/objects/translateObjects.cpp b/generators/objects/translateObjects.cpp index 62e0d583..2b6dc330 100644 --- a/generators/objects/translateObjects.cpp +++ b/generators/objects/translateObjects.cpp @@ -1,8 +1,8 @@ /** * @brief Auto-generated object translation file. * @details - * Contains 117 translations. - * Generated on: 2022-05-03 16:32:00 + * Contains 132 translations. + * Generated on: 2022-06-27 09:14:34 */ #include "translateObjects.h" @@ -12,18 +12,18 @@ const char *ACS_CONTROLLER_STRING = "ACS_CONTROLLER"; const char *THERMAL_CONTROLLER_STRING = "THERMAL_CONTROLLER"; const char *MGM_0_LIS3_HANDLER_STRING = "MGM_0_LIS3_HANDLER"; const char *GYRO_0_ADIS_HANDLER_STRING = "GYRO_0_ADIS_HANDLER"; -const char *SUS_0_STRING = "SUS_0"; -const char *SUS_1_STRING = "SUS_1"; -const char *SUS_2_STRING = "SUS_2"; -const char *SUS_3_STRING = "SUS_3"; -const char *SUS_4_STRING = "SUS_4"; -const char *SUS_5_STRING = "SUS_5"; -const char *SUS_6_STRING = "SUS_6"; -const char *SUS_7_STRING = "SUS_7"; -const char *SUS_8_STRING = "SUS_8"; -const char *SUS_9_STRING = "SUS_9"; -const char *SUS_10_STRING = "SUS_10"; -const char *SUS_11_STRING = "SUS_11"; +const char *SUS_0_N_LOC_XFYFZM_PT_XF_STRING = "SUS_0_N_LOC_XFYFZM_PT_XF"; +const char *SUS_1_N_LOC_XBYFZM_PT_XB_STRING = "SUS_1_N_LOC_XBYFZM_PT_XB"; +const char *SUS_2_N_LOC_XFYBZB_PT_YB_STRING = "SUS_2_N_LOC_XFYBZB_PT_YB"; +const char *SUS_3_N_LOC_XFYBZF_PT_YF_STRING = "SUS_3_N_LOC_XFYBZF_PT_YF"; +const char *SUS_4_N_LOC_XMYFZF_PT_ZF_STRING = "SUS_4_N_LOC_XMYFZF_PT_ZF"; +const char *SUS_5_N_LOC_XFYMZB_PT_ZB_STRING = "SUS_5_N_LOC_XFYMZB_PT_ZB"; +const char *SUS_6_R_LOC_XFYBZM_PT_XF_STRING = "SUS_6_R_LOC_XFYBZM_PT_XF"; +const char *SUS_7_R_LOC_XBYBZM_PT_XB_STRING = "SUS_7_R_LOC_XBYBZM_PT_XB"; +const char *SUS_8_R_LOC_XBYBZB_PT_YB_STRING = "SUS_8_R_LOC_XBYBZB_PT_YB"; +const char *SUS_9_R_LOC_XBYBZB_PT_YF_STRING = "SUS_9_R_LOC_XBYBZB_PT_YF"; +const char *SUS_10_N_LOC_XMYBZF_PT_ZF_STRING = "SUS_10_N_LOC_XMYBZF_PT_ZF"; +const char *SUS_11_R_LOC_XBYMZB_PT_ZB_STRING = "SUS_11_R_LOC_XBYMZB_PT_ZB"; const char *RW1_STRING = "RW1"; const char *MGM_1_RM3100_HANDLER_STRING = "MGM_1_RM3100_HANDLER"; const char *GYRO_1_L3G_HANDLER_STRING = "GYRO_1_L3G_HANDLER"; @@ -49,6 +49,8 @@ const char *PLOC_UPDATER_STRING = "PLOC_UPDATER"; const char *PLOC_MEMORY_DUMPER_STRING = "PLOC_MEMORY_DUMPER"; const char *STR_HELPER_STRING = "STR_HELPER"; const char *PLOC_MPSOC_HELPER_STRING = "PLOC_MPSOC_HELPER"; +const char *AXI_PTME_CONFIG_STRING = "AXI_PTME_CONFIG"; +const char *PTME_CONFIG_STRING = "PTME_CONFIG"; const char *PLOC_MPSOC_HANDLER_STRING = "PLOC_MPSOC_HANDLER"; const char *PLOC_SUPERVISOR_HANDLER_STRING = "PLOC_SUPERVISOR_HANDLER"; const char *PLOC_SUPERVISOR_HELPER_STRING = "PLOC_SUPERVISOR_HELPER"; @@ -56,26 +58,28 @@ const char *SOLAR_ARRAY_DEPL_HANDLER_STRING = "SOLAR_ARRAY_DEPL_HANDLER"; const char *HEATER_HANDLER_STRING = "HEATER_HANDLER"; const char *TMP1075_HANDLER_1_STRING = "TMP1075_HANDLER_1"; const char *TMP1075_HANDLER_2_STRING = "TMP1075_HANDLER_2"; -const char *RTD_IC_3_STRING = "RTD_IC_3"; -const char *RTD_IC_4_STRING = "RTD_IC_4"; -const char *RTD_IC_5_STRING = "RTD_IC_5"; -const char *RTD_IC_6_STRING = "RTD_IC_6"; -const char *RTD_IC_7_STRING = "RTD_IC_7"; -const char *RTD_IC_8_STRING = "RTD_IC_8"; -const char *RTD_IC_9_STRING = "RTD_IC_9"; -const char *RTD_IC_10_STRING = "RTD_IC_10"; -const char *RTD_IC_11_STRING = "RTD_IC_11"; -const char *RTD_IC_12_STRING = "RTD_IC_12"; -const char *RTD_IC_13_STRING = "RTD_IC_13"; -const char *RTD_IC_14_STRING = "RTD_IC_14"; -const char *RTD_IC_15_STRING = "RTD_IC_15"; -const char *RTD_IC_16_STRING = "RTD_IC_16"; -const char *RTD_IC_17_STRING = "RTD_IC_17"; -const char *RTD_IC_18_STRING = "RTD_IC_18"; +const char *RTD_0_IC3_PLOC_HEATSPREADER_STRING = "RTD_0_IC3_PLOC_HEATSPREADER"; +const char *RTD_1_IC4_PLOC_MISSIONBOARD_STRING = "RTD_1_IC4_PLOC_MISSIONBOARD"; +const char *RTD_2_IC5_4K_CAMERA_STRING = "RTD_2_IC5_4K_CAMERA"; +const char *RTD_3_IC6_DAC_HEATSPREADER_STRING = "RTD_3_IC6_DAC_HEATSPREADER"; +const char *RTD_4_IC7_STARTRACKER_STRING = "RTD_4_IC7_STARTRACKER"; +const char *RTD_5_IC8_RW1_MX_MY_STRING = "RTD_5_IC8_RW1_MX_MY"; +const char *RTD_6_IC9_DRO_STRING = "RTD_6_IC9_DRO"; +const char *RTD_7_IC10_SCEX_STRING = "RTD_7_IC10_SCEX"; +const char *RTD_8_IC11_X8_STRING = "RTD_8_IC11_X8"; +const char *RTD_9_IC12_HPA_STRING = "RTD_9_IC12_HPA"; +const char *RTD_10_IC13_PL_TX_STRING = "RTD_10_IC13_PL_TX"; +const char *RTD_11_IC14_MPA_STRING = "RTD_11_IC14_MPA"; +const char *RTD_12_IC15_ACU_STRING = "RTD_12_IC15_ACU"; +const char *RTD_13_IC16_PLPCDU_HEATSPREADER_STRING = "RTD_13_IC16_PLPCDU_HEATSPREADER"; +const char *RTD_14_IC17_TCS_BOARD_STRING = "RTD_14_IC17_TCS_BOARD"; +const char *RTD_15_IC18_IMTQ_STRING = "RTD_15_IC18_IMTQ"; const char *SYRLINKS_HK_HANDLER_STRING = "SYRLINKS_HK_HANDLER"; const char *ARDUINO_COM_IF_STRING = "ARDUINO_COM_IF"; const char *GPIO_IF_STRING = "GPIO_IF"; -const char *SPI_COM_IF_STRING = "SPI_COM_IF"; +const char *SPI_MAIN_COM_IF_STRING = "SPI_MAIN_COM_IF"; +const char *SPI_RW_COM_IF_STRING = "SPI_RW_COM_IF"; +const char *SPI_RTD_COM_IF_STRING = "SPI_RTD_COM_IF"; const char *UART_COM_IF_STRING = "UART_COM_IF"; const char *I2C_COM_IF_STRING = "I2C_COM_IF"; const char *CSP_COM_IF_STRING = "CSP_COM_IF"; @@ -96,6 +100,7 @@ const char *PUS_SERVICE_3_HOUSEKEEPING_STRING = "PUS_SERVICE_3_HOUSEKEEPING"; const char *PUS_SERVICE_5_EVENT_REPORTING_STRING = "PUS_SERVICE_5_EVENT_REPORTING"; const char *PUS_SERVICE_8_FUNCTION_MGMT_STRING = "PUS_SERVICE_8_FUNCTION_MGMT"; const char *PUS_SERVICE_9_TIME_MGMT_STRING = "PUS_SERVICE_9_TIME_MGMT"; +const char *PUS_SERVICE_11_TC_SCHEDULER_STRING = "PUS_SERVICE_11_TC_SCHEDULER"; const char *PUS_SERVICE_17_TEST_STRING = "PUS_SERVICE_17_TEST"; const char *PUS_SERVICE_20_PARAMETERS_STRING = "PUS_SERVICE_20_PARAMETERS"; const char *PUS_SERVICE_200_MODE_MGMT_STRING = "PUS_SERVICE_200_MODE_MGMT"; @@ -113,13 +118,23 @@ const char *FSFW_OBJECTS_END_STRING = "FSFW_OBJECTS_END"; const char *SPI_TEST_STRING = "SPI_TEST"; const char *UART_TEST_STRING = "UART_TEST"; const char *I2C_TEST_STRING = "I2C_TEST"; +const char *DUMMY_COM_IF_STRING = "DUMMY_COM_IF"; const char *DUMMY_HANDLER_STRING = "DUMMY_HANDLER"; const char *DUMMY_INTERFACE_STRING = "DUMMY_INTERFACE"; const char *LIBGPIOD_TEST_STRING = "LIBGPIOD_TEST"; const char *TEST_TASK_STRING = "TEST_TASK"; +const char *HEATER_0_PLOC_PROC_BRD_STRING = "HEATER_0_PLOC_PROC_BRD"; +const char *HEATER_1_PCDU_BRD_STRING = "HEATER_1_PCDU_BRD"; +const char *HEATER_2_ACS_BRD_STRING = "HEATER_2_ACS_BRD"; +const char *HEATER_3_OBC_BRD_STRING = "HEATER_3_OBC_BRD"; +const char *HEATER_4_CAMERA_STRING = "HEATER_4_CAMERA"; +const char *HEATER_5_STR_STRING = "HEATER_5_STR"; +const char *HEATER_6_DRO_STRING = "HEATER_6_DRO"; +const char *HEATER_7_HPA_STRING = "HEATER_7_HPA"; const char *ACS_BOARD_ASS_STRING = "ACS_BOARD_ASS"; const char *SUS_BOARD_ASS_STRING = "SUS_BOARD_ASS"; const char *TCS_BOARD_ASS_STRING = "TCS_BOARD_ASS"; +const char *RW_ASS_STRING = "RW_ASS"; const char *TM_FUNNEL_STRING = "TM_FUNNEL"; const char *CCSDS_IP_CORE_BRIDGE_STRING = "CCSDS_IP_CORE_BRIDGE"; const char *NO_OBJECT_STRING = "NO_OBJECT"; @@ -139,29 +154,29 @@ const char *translateObject(object_id_t object) { case 0x44120010: return GYRO_0_ADIS_HANDLER_STRING; case 0x44120032: - return SUS_0_STRING; + return SUS_0_N_LOC_XFYFZM_PT_XF_STRING; case 0x44120033: - return SUS_1_STRING; + return SUS_1_N_LOC_XBYFZM_PT_XB_STRING; case 0x44120034: - return SUS_2_STRING; + return SUS_2_N_LOC_XFYBZB_PT_YB_STRING; case 0x44120035: - return SUS_3_STRING; + return SUS_3_N_LOC_XFYBZF_PT_YF_STRING; case 0x44120036: - return SUS_4_STRING; + return SUS_4_N_LOC_XMYFZF_PT_ZF_STRING; case 0x44120037: - return SUS_5_STRING; + return SUS_5_N_LOC_XFYMZB_PT_ZB_STRING; case 0x44120038: - return SUS_6_STRING; + return SUS_6_R_LOC_XFYBZM_PT_XF_STRING; case 0x44120039: - return SUS_7_STRING; + return SUS_7_R_LOC_XBYBZM_PT_XB_STRING; case 0x44120040: - return SUS_8_STRING; + return SUS_8_R_LOC_XBYBZB_PT_YB_STRING; case 0x44120041: - return SUS_9_STRING; + return SUS_9_R_LOC_XBYBZB_PT_YF_STRING; case 0x44120042: - return SUS_10_STRING; + return SUS_10_N_LOC_XMYBZF_PT_ZF_STRING; case 0x44120043: - return SUS_11_STRING; + return SUS_11_R_LOC_XBYMZB_PT_ZB_STRING; case 0x44120047: return RW1_STRING; case 0x44120107: @@ -212,6 +227,10 @@ const char *translateObject(object_id_t object) { return STR_HELPER_STRING; case 0x44330003: return PLOC_MPSOC_HELPER_STRING; + case 0x44330004: + return AXI_PTME_CONFIG_STRING; + case 0x44330005: + return PTME_CONFIG_STRING; case 0x44330015: return PLOC_MPSOC_HANDLER_STRING; case 0x44330016: @@ -227,37 +246,37 @@ const char *translateObject(object_id_t object) { case 0x44420005: return TMP1075_HANDLER_2_STRING; case 0x44420016: - return RTD_IC_3_STRING; + return RTD_0_IC3_PLOC_HEATSPREADER_STRING; case 0x44420017: - return RTD_IC_4_STRING; + return RTD_1_IC4_PLOC_MISSIONBOARD_STRING; case 0x44420018: - return RTD_IC_5_STRING; + return RTD_2_IC5_4K_CAMERA_STRING; case 0x44420019: - return RTD_IC_6_STRING; + return RTD_3_IC6_DAC_HEATSPREADER_STRING; case 0x44420020: - return RTD_IC_7_STRING; + return RTD_4_IC7_STARTRACKER_STRING; case 0x44420021: - return RTD_IC_8_STRING; + return RTD_5_IC8_RW1_MX_MY_STRING; case 0x44420022: - return RTD_IC_9_STRING; + return RTD_6_IC9_DRO_STRING; case 0x44420023: - return RTD_IC_10_STRING; + return RTD_7_IC10_SCEX_STRING; case 0x44420024: - return RTD_IC_11_STRING; + return RTD_8_IC11_X8_STRING; case 0x44420025: - return RTD_IC_12_STRING; + return RTD_9_IC12_HPA_STRING; case 0x44420026: - return RTD_IC_13_STRING; + return RTD_10_IC13_PL_TX_STRING; case 0x44420027: - return RTD_IC_14_STRING; + return RTD_11_IC14_MPA_STRING; case 0x44420028: - return RTD_IC_15_STRING; + return RTD_12_IC15_ACU_STRING; case 0x44420029: - return RTD_IC_16_STRING; + return RTD_13_IC16_PLPCDU_HEATSPREADER_STRING; case 0x44420030: - return RTD_IC_17_STRING; + return RTD_14_IC17_TCS_BOARD_STRING; case 0x44420031: - return RTD_IC_18_STRING; + return RTD_15_IC18_IMTQ_STRING; case 0x445300A3: return SYRLINKS_HK_HANDLER_STRING; case 0x49000000: @@ -265,7 +284,11 @@ const char *translateObject(object_id_t object) { case 0x49010005: return GPIO_IF_STRING; case 0x49020004: - return SPI_COM_IF_STRING; + return SPI_MAIN_COM_IF_STRING; + case 0x49020005: + return SPI_RW_COM_IF_STRING; + case 0x49020006: + return SPI_RTD_COM_IF_STRING; case 0x49030003: return UART_COM_IF_STRING; case 0x49040002: @@ -306,6 +329,8 @@ const char *translateObject(object_id_t object) { return PUS_SERVICE_8_FUNCTION_MGMT_STRING; case 0x53000009: return PUS_SERVICE_9_TIME_MGMT_STRING; + case 0x53000011: + return PUS_SERVICE_11_TC_SCHEDULER_STRING; case 0x53000017: return PUS_SERVICE_17_TEST_STRING; case 0x53000020: @@ -340,6 +365,8 @@ const char *translateObject(object_id_t object) { return UART_TEST_STRING; case 0x54000030: return I2C_TEST_STRING; + case 0x54000040: + return DUMMY_COM_IF_STRING; case 0x5400AFFE: return DUMMY_HANDLER_STRING; case 0x5400CAFE: @@ -348,12 +375,30 @@ const char *translateObject(object_id_t object) { return LIBGPIOD_TEST_STRING; case 0x54694269: return TEST_TASK_STRING; + case 0x60000000: + return HEATER_0_PLOC_PROC_BRD_STRING; + case 0x60000001: + return HEATER_1_PCDU_BRD_STRING; + case 0x60000002: + return HEATER_2_ACS_BRD_STRING; + case 0x60000003: + return HEATER_3_OBC_BRD_STRING; + case 0x60000004: + return HEATER_4_CAMERA_STRING; + case 0x60000005: + return HEATER_5_STR_STRING; + case 0x60000006: + return HEATER_6_DRO_STRING; + case 0x60000007: + return HEATER_7_HPA_STRING; case 0x73000001: return ACS_BOARD_ASS_STRING; case 0x73000002: return SUS_BOARD_ASS_STRING; case 0x73000003: return TCS_BOARD_ASS_STRING; + case 0x73000004: + return RW_ASS_STRING; case 0x73000100: return TM_FUNNEL_STRING; case 0x73500000: diff --git a/generators/returnvalues/returnvalues_parser.py b/generators/returnvalues/returnvalues_parser.py index 5bcf3bc2..4cacd529 100644 --- a/generators/returnvalues/returnvalues_parser.py +++ b/generators/returnvalues/returnvalues_parser.py @@ -3,10 +3,16 @@ """Part of the MIB export tools for the EIVE project by. Returnvalue exporter. """ -from fsfwgen.core import get_console_logger +from pathlib import Path + +from fsfwgen.logging import get_console_logger from fsfwgen.utility.file_management import copy_file from fsfwgen.parserbase.file_list_parser import FileListParser -from fsfwgen.returnvalues.returnvalues_parser import InterfaceParser, ReturnValueParser +from fsfwgen.returnvalues.returnvalues_parser import ( + InterfaceParser, + ReturnValueParser, + RetvalDictT, +) from fsfwgen.utility.sql_writer import SqlWriter from fsfwgen.utility.printer import PrettyPrinter @@ -24,8 +30,8 @@ MAX_STRING_LENGTH = 32 BSP_SELECT = BspType.BSP_Q7S BSP_DIR_NAME = BSP_SELECT.value -CSV_RETVAL_FILENAME = f"{ROOT_DIR}/{BSP_SELECT.value}_returnvalues.csv" -CSV_COPY_DEST = f"{OBSW_ROOT_DIR}/tmtc/config/returnvalues.csv" +CSV_RETVAL_FILENAME = Path(f"{ROOT_DIR}/{BSP_SELECT.value}_returnvalues.csv") +CSV_COPY_DEST = Path(f"{OBSW_ROOT_DIR}/tmtc/config/returnvalues.csv") ADD_LINUX_FOLDER = False if BSP_SELECT == BspType.BSP_Q7S or BSP_SELECT == BspType.BSP_LINUX_BOARD: @@ -45,6 +51,7 @@ RETURNVALUE_SOURCES = [ f"{OBSW_ROOT_DIR}/fsfw/", f"{BSP_PATH}", ] +RETVAL_SRCS_AS_PATH = [Path(x) for x in RETURNVALUE_SOURCES] if ADD_LINUX_FOLDER: RETURNVALUE_SOURCES.append(f"{OBSW_ROOT_DIR}/linux") @@ -73,7 +80,7 @@ VALUES(?,?,?,?,?) def parse_returnvalues(): returnvalue_table = generate_returnvalue_table() if EXPORT_TO_FILE: - ReturnValueParser.export_to_file( + ReturnValueParser.export_to_csv( CSV_RETVAL_FILENAME, returnvalue_table, FILE_SEPARATOR ) if COPY_CSV_FILE: @@ -95,7 +102,7 @@ def generate_returnvalue_table(): file_list=INTERFACE_DEFINITION_FILES, print_table=PRINT_TABLES ) interfaces = interface_parser.parse_files() - header_parser = FileListParser(RETURNVALUE_SOURCES) + header_parser = FileListParser(RETVAL_SRCS_AS_PATH) header_list = header_parser.parse_header_files(True, "Parsing header file list: ") returnvalue_parser = ReturnValueParser(interfaces, header_list, PRINT_TABLES) returnvalue_parser.obsw_root_path = OBSW_ROOT_DIR @@ -105,13 +112,19 @@ def generate_returnvalue_table(): return returnvalue_table -def sql_retval_exporter(returnvalue_table, db_filename: str): +def sql_retval_exporter(returnvalue_table: RetvalDictT, db_filename: str): sql_writer = SqlWriter(db_filename=db_filename) sql_writer.open(SQL_CREATE_RETURNVALUES_CMD) for entry in returnvalue_table.items(): sql_writer.write_entries( SQL_INSERT_RETURNVALUES_CMD, - (entry[0], entry[1][2], entry[1][4], entry[1][3], entry[1][1]), + ( + entry[0], + entry[1].name, + entry[1].description, + entry[1].unique_id, + entry[1].subsystem_name, + ), ) sql_writer.commit() sql_writer.close() diff --git a/linux/CMakeLists.txt b/linux/CMakeLists.txt index c183ea60..e1d80966 100644 --- a/linux/CMakeLists.txt +++ b/linux/CMakeLists.txt @@ -6,6 +6,4 @@ add_subdirectory(devices) add_subdirectory(fsfwconfig) add_subdirectory(obc) -target_sources(${OBSW_NAME} PUBLIC - ObjectFactory.cpp -) \ No newline at end of file +target_sources(${OBSW_NAME} PUBLIC ObjectFactory.cpp) diff --git a/linux/ObjectFactory.cpp b/linux/ObjectFactory.cpp index 23311229..e8ba7947 100644 --- a/linux/ObjectFactory.cpp +++ b/linux/ObjectFactory.cpp @@ -7,6 +7,9 @@ #include #include #include +#include +#include +#include #include #include #include @@ -62,93 +65,104 @@ void ObjectFactory::createSunSensorComponents(GpioIF* gpioComIF, SpiComIF* spiCo &gpioCallbacks::spiCsDecoderCallback, gpioComIF); gpioCookieSus->addGpio(gpioIds::CS_SUS_11, susgpio); - gpioComIF->addGpios(gpioCookieSus); + gpioChecker(gpioComIF->addGpios(gpioCookieSus), "Sun Sensors"); #if OBSW_ADD_SUN_SENSORS == 1 SusFdir* fdir = nullptr; std::array susHandlers = {}; - SpiCookie* spiCookie = - new SpiCookie(addresses::SUS_0, gpioIds::CS_SUS_0, spiDev, SUS::MAX_CMD_SIZE, - spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); - susHandlers[0] = new SusHandler(objects::SUS_0, 0, objects::SPI_COM_IF, spiCookie); - fdir = new SusFdir(objects::SUS_0); + SpiCookie* spiCookie = new SpiCookie(addresses::SUS_0, gpioIds::CS_SUS_0, SUS::MAX_CMD_SIZE, + spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); + susHandlers[0] = + new SusHandler(objects::SUS_0_N_LOC_XFYFZM_PT_XF, 0, objects::SPI_MAIN_COM_IF, spiCookie); + fdir = new SusFdir(objects::SUS_0_N_LOC_XFYFZM_PT_XF); susHandlers[0]->setParent(objects::SUS_BOARD_ASS); susHandlers[0]->setCustomFdir(fdir); - spiCookie = new SpiCookie(addresses::SUS_1, gpioIds::CS_SUS_1, spiDev, SUS::MAX_CMD_SIZE, + spiCookie = new SpiCookie(addresses::SUS_1, gpioIds::CS_SUS_1, SUS::MAX_CMD_SIZE, spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); - susHandlers[1] = new SusHandler(objects::SUS_1, 1, objects::SPI_COM_IF, spiCookie); - fdir = new SusFdir(objects::SUS_1); + susHandlers[1] = + new SusHandler(objects::SUS_1_N_LOC_XBYFZM_PT_XB, 1, objects::SPI_MAIN_COM_IF, spiCookie); + fdir = new SusFdir(objects::SUS_1_N_LOC_XBYFZM_PT_XB); susHandlers[1]->setParent(objects::SUS_BOARD_ASS); susHandlers[1]->setCustomFdir(fdir); - spiCookie = new SpiCookie(addresses::SUS_2, gpioIds::CS_SUS_2, spiDev, SUS::MAX_CMD_SIZE, + spiCookie = new SpiCookie(addresses::SUS_2, gpioIds::CS_SUS_2, SUS::MAX_CMD_SIZE, spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); - susHandlers[2] = new SusHandler(objects::SUS_2, 2, objects::SPI_COM_IF, spiCookie); - fdir = new SusFdir(objects::SUS_2); + susHandlers[2] = + new SusHandler(objects::SUS_2_N_LOC_XFYBZB_PT_YB, 2, objects::SPI_MAIN_COM_IF, spiCookie); + fdir = new SusFdir(objects::SUS_2_N_LOC_XFYBZB_PT_YB); susHandlers[2]->setParent(objects::SUS_BOARD_ASS); susHandlers[2]->setCustomFdir(fdir); - spiCookie = new SpiCookie(addresses::SUS_3, gpioIds::CS_SUS_3, spiDev, SUS::MAX_CMD_SIZE, + spiCookie = new SpiCookie(addresses::SUS_3, gpioIds::CS_SUS_3, SUS::MAX_CMD_SIZE, spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); - susHandlers[3] = new SusHandler(objects::SUS_3, 3, objects::SPI_COM_IF, spiCookie); - fdir = new SusFdir(objects::SUS_3); + susHandlers[3] = + new SusHandler(objects::SUS_3_N_LOC_XFYBZF_PT_YF, 3, objects::SPI_MAIN_COM_IF, spiCookie); + fdir = new SusFdir(objects::SUS_3_N_LOC_XFYBZF_PT_YF); susHandlers[3]->setParent(objects::SUS_BOARD_ASS); susHandlers[3]->setCustomFdir(fdir); - spiCookie = new SpiCookie(addresses::SUS_4, gpioIds::CS_SUS_4, spiDev, SUS::MAX_CMD_SIZE, + spiCookie = new SpiCookie(addresses::SUS_4, gpioIds::CS_SUS_4, SUS::MAX_CMD_SIZE, spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); - susHandlers[4] = new SusHandler(objects::SUS_4, 4, objects::SPI_COM_IF, spiCookie); - fdir = new SusFdir(objects::SUS_4); + susHandlers[4] = + new SusHandler(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, 4, objects::SPI_MAIN_COM_IF, spiCookie); + fdir = new SusFdir(objects::SUS_4_N_LOC_XMYFZF_PT_ZF); susHandlers[4]->setParent(objects::SUS_BOARD_ASS); susHandlers[4]->setCustomFdir(fdir); - spiCookie = new SpiCookie(addresses::SUS_5, gpioIds::CS_SUS_5, spiDev, SUS::MAX_CMD_SIZE, + spiCookie = new SpiCookie(addresses::SUS_5, gpioIds::CS_SUS_5, SUS::MAX_CMD_SIZE, spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); - susHandlers[5] = new SusHandler(objects::SUS_5, 5, objects::SPI_COM_IF, spiCookie); - fdir = new SusFdir(objects::SUS_5); + susHandlers[5] = + new SusHandler(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, 5, objects::SPI_MAIN_COM_IF, spiCookie); + fdir = new SusFdir(objects::SUS_5_N_LOC_XFYMZB_PT_ZB); susHandlers[5]->setParent(objects::SUS_BOARD_ASS); susHandlers[5]->setCustomFdir(fdir); - spiCookie = new SpiCookie(addresses::SUS_6, gpioIds::CS_SUS_6, spiDev, SUS::MAX_CMD_SIZE, + spiCookie = new SpiCookie(addresses::SUS_6, gpioIds::CS_SUS_6, SUS::MAX_CMD_SIZE, spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); - susHandlers[6] = new SusHandler(objects::SUS_6, 6, objects::SPI_COM_IF, spiCookie); - fdir = new SusFdir(objects::SUS_6); + susHandlers[6] = + new SusHandler(objects::SUS_6_R_LOC_XFYBZM_PT_XF, 6, objects::SPI_MAIN_COM_IF, spiCookie); + fdir = new SusFdir(objects::SUS_6_R_LOC_XFYBZM_PT_XF); susHandlers[6]->setParent(objects::SUS_BOARD_ASS); susHandlers[6]->setCustomFdir(fdir); - spiCookie = new SpiCookie(addresses::SUS_7, gpioIds::CS_SUS_7, spiDev, SUS::MAX_CMD_SIZE, + spiCookie = new SpiCookie(addresses::SUS_7, gpioIds::CS_SUS_7, SUS::MAX_CMD_SIZE, spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); - susHandlers[7] = new SusHandler(objects::SUS_7, 7, objects::SPI_COM_IF, spiCookie); - fdir = new SusFdir(objects::SUS_7); + susHandlers[7] = + new SusHandler(objects::SUS_7_R_LOC_XBYBZM_PT_XB, 7, objects::SPI_MAIN_COM_IF, spiCookie); + fdir = new SusFdir(objects::SUS_7_R_LOC_XBYBZM_PT_XB); susHandlers[7]->setParent(objects::SUS_BOARD_ASS); susHandlers[7]->setCustomFdir(fdir); - spiCookie = new SpiCookie(addresses::SUS_8, gpioIds::CS_SUS_8, spiDev, SUS::MAX_CMD_SIZE, + spiCookie = new SpiCookie(addresses::SUS_8, gpioIds::CS_SUS_8, SUS::MAX_CMD_SIZE, spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); - susHandlers[8] = new SusHandler(objects::SUS_8, 8, objects::SPI_COM_IF, spiCookie); - fdir = new SusFdir(objects::SUS_8); + susHandlers[8] = + new SusHandler(objects::SUS_8_R_LOC_XBYBZB_PT_YB, 8, objects::SPI_MAIN_COM_IF, spiCookie); + fdir = new SusFdir(objects::SUS_8_R_LOC_XBYBZB_PT_YB); susHandlers[8]->setParent(objects::SUS_BOARD_ASS); susHandlers[8]->setCustomFdir(fdir); - spiCookie = new SpiCookie(addresses::SUS_9, gpioIds::CS_SUS_9, spiDev, SUS::MAX_CMD_SIZE, + spiCookie = new SpiCookie(addresses::SUS_9, gpioIds::CS_SUS_9, SUS::MAX_CMD_SIZE, spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); - susHandlers[9] = new SusHandler(objects::SUS_9, 9, objects::SPI_COM_IF, spiCookie); - fdir = new SusFdir(objects::SUS_9); + susHandlers[9] = + new SusHandler(objects::SUS_9_R_LOC_XBYBZB_PT_YF, 9, objects::SPI_MAIN_COM_IF, spiCookie); + fdir = new SusFdir(objects::SUS_9_R_LOC_XBYBZB_PT_YF); susHandlers[9]->setParent(objects::SUS_BOARD_ASS); susHandlers[9]->setCustomFdir(fdir); - spiCookie = new SpiCookie(addresses::SUS_10, gpioIds::CS_SUS_10, spiDev, SUS::MAX_CMD_SIZE, + spiCookie = new SpiCookie(addresses::SUS_10, gpioIds::CS_SUS_10, SUS::MAX_CMD_SIZE, spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); - susHandlers[10] = new SusHandler(objects::SUS_10, 10, objects::SPI_COM_IF, spiCookie); - fdir = new SusFdir(objects::SUS_10); + susHandlers[10] = + new SusHandler(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, 10, objects::SPI_MAIN_COM_IF, spiCookie); + fdir = new SusFdir(objects::SUS_10_N_LOC_XMYBZF_PT_ZF); susHandlers[10]->setParent(objects::SUS_BOARD_ASS); susHandlers[10]->setCustomFdir(fdir); - spiCookie = new SpiCookie(addresses::SUS_11, gpioIds::CS_SUS_11, spiDev, SUS::MAX_CMD_SIZE, + spiCookie = new SpiCookie(addresses::SUS_11, gpioIds::CS_SUS_11, SUS::MAX_CMD_SIZE, spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); - susHandlers[11] = new SusHandler(objects::SUS_11, 11, objects::SPI_COM_IF, spiCookie); - fdir = new SusFdir(objects::SUS_11); + susHandlers[11] = + new SusHandler(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, 11, objects::SPI_MAIN_COM_IF, spiCookie); + fdir = new SusFdir(objects::SUS_11_R_LOC_XBYMZB_PT_ZB); susHandlers[11]->setParent(objects::SUS_BOARD_ASS); susHandlers[11]->setCustomFdir(fdir); @@ -163,10 +177,13 @@ void ObjectFactory::createSunSensorComponents(GpioIF* gpioComIF, SpiComIF* spiCo #endif } } - std::array susIds = {objects::SUS_0, objects::SUS_1, objects::SUS_2, - objects::SUS_3, objects::SUS_4, objects::SUS_5, - objects::SUS_6, objects::SUS_7, objects::SUS_8, - objects::SUS_9, objects::SUS_10, objects::SUS_11}; + std::array susIds = { + objects::SUS_0_N_LOC_XFYFZM_PT_XF, objects::SUS_1_N_LOC_XBYFZM_PT_XB, + objects::SUS_2_N_LOC_XFYBZB_PT_YB, objects::SUS_3_N_LOC_XFYBZF_PT_YF, + objects::SUS_4_N_LOC_XMYFZF_PT_ZF, objects::SUS_5_N_LOC_XFYMZB_PT_ZB, + objects::SUS_6_R_LOC_XFYBZM_PT_XF, objects::SUS_7_R_LOC_XBYBZM_PT_XB, + objects::SUS_8_R_LOC_XBYBZB_PT_YB, objects::SUS_9_R_LOC_XBYBZB_PT_YF, + objects::SUS_10_N_LOC_XMYBZF_PT_ZF, objects::SUS_11_R_LOC_XBYMZB_PT_ZB}; SusAssHelper susAssHelper = SusAssHelper(susIds); auto susAss = new SusAssembly(objects::SUS_BOARD_ASS, objects::NO_OBJECT, pwrSwitcher, susAssHelper); @@ -175,7 +192,7 @@ void ObjectFactory::createSunSensorComponents(GpioIF* gpioComIF, SpiComIF* spiCo } void ObjectFactory::createRtdComponents(std::string spiDev, GpioIF* gpioComIF, - PowerSwitchIF* pwrSwitcher) { + PowerSwitchIF* pwrSwitcher, SpiComIF* comIF) { using namespace gpio; GpioCookie* rtdGpioCookie = new GpioCookie; @@ -228,11 +245,11 @@ void ObjectFactory::createRtdComponents(std::string spiDev, GpioIF* gpioComIF, &gpioCallbacks::spiCsDecoderCallback, gpioComIF); rtdGpioCookie->addGpio(gpioIds::RTD_IC_18, gpioRtdIc15); - gpioComIF->addGpios(rtdGpioCookie); + gpioChecker(gpioComIF->addGpios(rtdGpioCookie), "RTDs"); #if OBSW_ADD_RTD_DEVICES == 1 - static constexpr uint8_t NUMBER_RTDS = 16; - std::array, NUMBER_RTDS> cookieArgs = {{ + using namespace EiveMax31855; + std::array, NUM_RTDS> cookieArgs = {{ {addresses::RTD_IC_3, gpioIds::RTD_IC_3}, {addresses::RTD_IC_4, gpioIds::RTD_IC_4}, {addresses::RTD_IC_5, gpioIds::RTD_IC_5}, @@ -250,40 +267,65 @@ void ObjectFactory::createRtdComponents(std::string spiDev, GpioIF* gpioComIF, {addresses::RTD_IC_17, gpioIds::RTD_IC_17}, {addresses::RTD_IC_18, gpioIds::RTD_IC_18}, }}; - std::array rtdIds = { - objects::RTD_IC_3, objects::RTD_IC_4, objects::RTD_IC_5, objects::RTD_IC_6, - objects::RTD_IC_7, objects::RTD_IC_8, objects::RTD_IC_9, objects::RTD_IC_10, - objects::RTD_IC_11, objects::RTD_IC_12, objects::RTD_IC_13, objects::RTD_IC_14, - objects::RTD_IC_15, objects::RTD_IC_16, objects::RTD_IC_17, objects::RTD_IC_18}; - std::array rtdCookies = {}; - std::array rtds = {}; + // HSPD: Heatspreader + std::array, NUM_RTDS> rtdInfos = {{ + {objects::RTD_0_IC3_PLOC_HEATSPREADER, "RTD_0_PLOC_HSPD"}, + {objects::RTD_1_IC4_PLOC_MISSIONBOARD, "RTD_1_PLOC_MISSIONBRD"}, + {objects::RTD_2_IC5_4K_CAMERA, "RTD_2_4K_CAMERA"}, + {objects::RTD_3_IC6_DAC_HEATSPREADER, "RTD_3_DAC_HSPD"}, + {objects::RTD_4_IC7_STARTRACKER, "RTD_4_STARTRACKER"}, + {objects::RTD_5_IC8_RW1_MX_MY, "RTD_5_RW1_MX_MY"}, + {objects::RTD_6_IC9_DRO, "RTD_6_DRO"}, + {objects::RTD_7_IC10_SCEX, "RTD_7_SCEX"}, + {objects::RTD_8_IC11_X8, "RTD_8_X8"}, + {objects::RTD_9_IC12_HPA, "RTD_9_HPA"}, + {objects::RTD_10_IC13_PL_TX, "RTD_10_PL_TX,"}, + {objects::RTD_11_IC14_MPA, "RTD_11_MPA"}, + {objects::RTD_12_IC15_ACU, "RTD_12_ACU"}, + {objects::RTD_13_IC16_PLPCDU_HEATSPREADER, "RTD_13_PLPCDU_HSPD"}, + {objects::RTD_14_IC17_TCS_BOARD, "RTD_14_TCS_BOARD"}, + {objects::RTD_15_IC18_IMTQ, "RTD_15_IMTQ"}, + }}; + std::array rtdCookies = {}; + std::array rtds = {}; RtdFdir* rtdFdir = nullptr; - for (uint8_t idx = 0; idx < NUMBER_RTDS; idx++) { - rtdCookies[idx] = - new SpiCookie(cookieArgs[idx].first, cookieArgs[idx].second, spiDev, - Max31865Definitions::MAX_REPLY_SIZE, spi::RTD_MODE, spi::RTD_SPEED); - rtds[idx] = new Max31865PT1000Handler(rtdIds[idx], objects::SPI_COM_IF, rtdCookies[idx]); + // Create special low level reader communication interface + new Max31865RtdReader(objects::SPI_RTD_COM_IF, comIF, gpioComIF); + for (uint8_t idx = 0; idx < NUM_RTDS; idx++) { + rtdCookies[idx] = new SpiCookie(cookieArgs[idx].first, cookieArgs[idx].second, + MAX31865::MAX_REPLY_SIZE, spi::RTD_MODE, spi::RTD_SPEED); + rtdCookies[idx]->setMutexParams(MutexIF::TimeoutType::WAITING, spi::RTD_CS_TIMEOUT); + Max31865ReaderCookie* rtdLowLevelCookie = + new Max31865ReaderCookie(rtdInfos[idx].first, idx, rtdInfos[idx].second, rtdCookies[idx]); + rtds[idx] = + new Max31865EiveHandler(rtdInfos[idx].first, objects::SPI_RTD_COM_IF, rtdLowLevelCookie); + rtds[idx]->setDeviceInfo(idx, rtdInfos[idx].second); rtds[idx]->setParent(objects::TCS_BOARD_ASS); - rtdFdir = new RtdFdir(rtdIds[idx]); + rtdFdir = new RtdFdir(rtdInfos[idx].first); rtds[idx]->setCustomFdir(rtdFdir); - rtds[idx]->setDeviceIdx(idx + 3); #if OBSW_DEBUG_RTD == 1 - rtds[idx]->setDebugMode(true); + rtds[idx]->setDebugMode(true, 5); +#endif +#if OBSW_TEST_RTD == 1 + rtds[idx]->setInstantNormal(true); + rtds[idx]->setStartUpImmediately(); #endif } -#if OBSW_TEST_RTD == 1 - for (auto& rtd : rtds) { - if (rtd != nullptr) { - rtd->setStartUpImmediately(); - rtd->setInstantNormal(true); - } - } -#endif // OBSW_TEST_RTD == 1 - TcsBoardHelper helper(rtdIds); + TcsBoardHelper helper(rtdInfos); TcsBoardAssembly* tcsBoardAss = new TcsBoardAssembly(objects::TCS_BOARD_ASS, objects::NO_OBJECT, pwrSwitcher, pcdu::Switches::PDU1_CH0_TCS_BOARD_3V3, helper); static_cast(tcsBoardAss); #endif // OBSW_ADD_RTD_DEVICES == 1 } + +void ObjectFactory::createThermalController() { + new ThermalController(objects::THERMAL_CONTROLLER, objects::NO_OBJECT); +} + +void ObjectFactory::gpioChecker(ReturnValue_t result, std::string output) { + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "ObjectFactory: Adding GPIOs failed for " << output << std::endl; + } +} diff --git a/linux/ObjectFactory.h b/linux/ObjectFactory.h index d918115f..668917e7 100644 --- a/linux/ObjectFactory.h +++ b/linux/ObjectFactory.h @@ -1,5 +1,8 @@ #pragma once +#include +#include + #include class GpioIF; @@ -10,6 +13,11 @@ namespace ObjectFactory { void createSunSensorComponents(GpioIF* gpioComIF, SpiComIF* spiComIF, PowerSwitchIF* pwrSwitcher, std::string spiDev); -void createRtdComponents(std::string spiDev, GpioIF* gpioComIF, PowerSwitchIF* pwrSwitcher); +void createRtdComponents(std::string spiDev, GpioIF* gpioComIF, PowerSwitchIF* pwrSwitcher, + SpiComIF* comIF); + +void gpioChecker(ReturnValue_t result, std::string output); + +void createThermalController(); } // namespace ObjectFactory diff --git a/linux/boardtest/CMakeLists.txt b/linux/boardtest/CMakeLists.txt index 1fa4b290..0ec55120 100644 --- a/linux/boardtest/CMakeLists.txt +++ b/linux/boardtest/CMakeLists.txt @@ -1,10 +1,2 @@ -target_sources(${OBSW_NAME} PRIVATE - LibgpiodTest.cpp - I2cTestClass.cpp - SpiTestClass.cpp - UartTestClass.cpp -) - - - - +target_sources(${OBSW_NAME} PRIVATE LibgpiodTest.cpp I2cTestClass.cpp + SpiTestClass.cpp UartTestClass.cpp) diff --git a/linux/boardtest/LibgpiodTest.cpp b/linux/boardtest/LibgpiodTest.cpp index 1c8fec5e..66e26e3b 100644 --- a/linux/boardtest/LibgpiodTest.cpp +++ b/linux/boardtest/LibgpiodTest.cpp @@ -29,8 +29,8 @@ ReturnValue_t LibgpiodTest::performPeriodicAction() { sif::warning << "LibgpiodTest::performPeriodicAction: Failed to read gpio " << std::endl; return RETURN_FAILED; } else { - sif::debug << "LibgpiodTest::performPeriodicAction: MIO 0 state = " << - static_cast(gpioState) << std::endl; + sif::debug << "LibgpiodTest::performPeriodicAction: MIO 0 state = " + << static_cast(gpioState) << std::endl; } break; } diff --git a/linux/callbacks/CMakeLists.txt b/linux/callbacks/CMakeLists.txt index 89bb24bb..49a71c15 100644 --- a/linux/callbacks/CMakeLists.txt +++ b/linux/callbacks/CMakeLists.txt @@ -1,3 +1 @@ -target_sources(${OBSW_NAME} PRIVATE - gpioCallbacks.cpp -) +target_sources(${OBSW_NAME} PRIVATE gpioCallbacks.cpp) diff --git a/linux/csp/CMakeLists.txt b/linux/csp/CMakeLists.txt index f1ebb028..71906a69 100644 --- a/linux/csp/CMakeLists.txt +++ b/linux/csp/CMakeLists.txt @@ -1,8 +1 @@ -target_sources(${OBSW_NAME} PUBLIC - CspComIF.cpp - CspCookie.cpp -) - - - - +target_sources(${OBSW_NAME} PUBLIC CspComIF.cpp CspCookie.cpp) diff --git a/linux/devices/CMakeLists.txt b/linux/devices/CMakeLists.txt index 00d407e8..b68d1c4e 100644 --- a/linux/devices/CMakeLists.txt +++ b/linux/devices/CMakeLists.txt @@ -1,8 +1,8 @@ if(EIVE_BUILD_GPSD_GPS_HANDLER) - target_sources(${OBSW_NAME} PRIVATE - GPSHyperionLinuxController.cpp - ) + target_sources(${OBSW_NAME} PRIVATE GPSHyperionLinuxController.cpp) endif() +target_sources(${OBSW_NAME} PRIVATE Max31865RtdLowlevelHandler.cpp) + add_subdirectory(ploc) add_subdirectory(startracker) diff --git a/linux/devices/GPSHyperionLinuxController.cpp b/linux/devices/GPSHyperionLinuxController.cpp index dee3c9af..5d97554a 100644 --- a/linux/devices/GPSHyperionLinuxController.cpp +++ b/linux/devices/GPSHyperionLinuxController.cpp @@ -57,12 +57,12 @@ ReturnValue_t GPSHyperionLinuxController::executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, const uint8_t *data, size_t size) { switch (actionId) { - case (GpsHyperion::TRIGGER_RESET_PIN): { + case (GpsHyperion::TRIGGER_RESET_PIN_GNSS): { if (resetCallback != nullptr) { PoolReadGuard pg(&gpsSet); // Set HK entries invalid gpsSet.setValidity(false, true); - resetCallback(resetCallbackArgs); + resetCallback(data, size, resetCallbackArgs); return HasActionsIF::EXECUTION_FINISHED; } return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED; diff --git a/linux/devices/GPSHyperionLinuxController.h b/linux/devices/GPSHyperionLinuxController.h index 94e82023..35ce0a63 100644 --- a/linux/devices/GPSHyperionLinuxController.h +++ b/linux/devices/GPSHyperionLinuxController.h @@ -30,7 +30,7 @@ class GPSHyperionLinuxController : public ExtendedControllerBase { bool debugHyperionGps = false); virtual ~GPSHyperionLinuxController(); - using gpioResetFunction_t = ReturnValue_t (*)(void* args); + using gpioResetFunction_t = ReturnValue_t (*)(const uint8_t* actionData, size_t len, void* args); void setResetPinTriggerFunction(gpioResetFunction_t resetCallback, void* args); ReturnValue_t handleCommandMessage(CommandMessage* message) override; diff --git a/linux/devices/Max31865RtdLowlevelHandler.cpp b/linux/devices/Max31865RtdLowlevelHandler.cpp new file mode 100644 index 00000000..ea038c8b --- /dev/null +++ b/linux/devices/Max31865RtdLowlevelHandler.cpp @@ -0,0 +1,465 @@ +#include "Max31865RtdLowlevelHandler.h" + +#include +#include +#include + +#define OBSW_RTD_AUTO_MODE 1 + +#if OBSW_RTD_AUTO_MODE == 1 +static constexpr uint8_t BASE_CFG = (MAX31865::Bias::ON << MAX31865::CfgBitPos::BIAS_SEL) | + (MAX31865::Wires::FOUR_WIRE << MAX31865::CfgBitPos::WIRE_SEL) | + (MAX31865::ConvMode::AUTO << MAX31865::CfgBitPos::CONV_MODE); +#else +static constexpr uint8_t BASE_CFG = + (MAX31865::Bias::OFF << MAX31865::CfgBitPos::BIAS_SEL) | + (MAX31865::Wires::FOUR_WIRE << MAX31865::CfgBitPos::WIRE_SEL) | + (MAX31865::ConvMode::NORM_OFF << MAX31865::CfgBitPos::CONV_MODE); +#endif + +Max31865RtdReader::Max31865RtdReader(object_id_t objectId, SpiComIF* lowLevelComIF, GpioIF* gpioIF) + : SystemObject(objectId), rtds(EiveMax31855::NUM_RTDS), comIF(lowLevelComIF), gpioIF(gpioIF) { + readerMutex = MutexFactory::instance()->createMutex(); +} + +ReturnValue_t Max31865RtdReader::performOperation(uint8_t operationCode) { + using namespace MAX31865; + ReturnValue_t result = RETURN_OK; + static_cast(result); + // Stopwatch watch; + if (periodicInitHandling()) { +#if OBSW_RTD_AUTO_MODE == 0 + // 10 ms delay for VBIAS startup + TaskFactory::delayTask(10); +#endif + } else { + // No devices usable (e.g. TCS board off) + return RETURN_OK; + } + +#if OBSW_RTD_AUTO_MODE == 0 + result = periodicReadReqHandling(); + if (result != RETURN_OK) { + return result; + } + // After requesting, 65 milliseconds delay required + TaskFactory::delayTask(65); +#endif + + return periodicReadHandling(); +} + +bool Max31865RtdReader::rtdIsActive(uint8_t idx) { + if (rtds[idx]->on and rtds[idx]->active and rtds[idx]->configured) { + return true; + } + return false; +} + +bool Max31865RtdReader::periodicInitHandling() { + using namespace MAX31865; + MutexGuard mg(readerMutex); + ReturnValue_t result = RETURN_OK; + if (mg.getLockResult() != RETURN_OK) { + sif::warning << "Max31865RtdReader::periodicInitHandling: Mutex lock failed" << std::endl; + return false; + } + + for (auto& rtd : rtds) { + if (rtd == nullptr) { + continue; + } + if ((rtd->on or rtd->active) and not rtd->configured and rtd->cd.hasTimedOut()) { + ManualCsLockWrapper mg(csLock, gpioIF, rtd->spiCookie, csTimeoutType, csTimeoutMs); + if (mg.lockResult != RETURN_OK or mg.gpioResult != RETURN_OK) { + sif::error << "Max31865RtdReader::periodicInitHandling: Manual CS lock failed" << std::endl; + break; + } + result = writeCfgReg(rtd->spiCookie, BASE_CFG); + if (result != HasReturnvaluesIF::RETURN_OK) { + handleSpiError(rtd, result, "writeCfgReg"); + } + if (rtd->writeLowThreshold) { + result = writeLowThreshold(rtd->spiCookie, rtd->lowThreshold); + if (result != HasReturnvaluesIF::RETURN_OK) { + handleSpiError(rtd, result, "writeLowThreshold"); + } + } + if (rtd->writeHighThreshold) { + result = writeHighThreshold(rtd->spiCookie, rtd->highThreshold); + if (result != HasReturnvaluesIF::RETURN_OK) { + handleSpiError(rtd, result, "writeHighThreshold"); + } + } + result = clearFaultStatus(rtd->spiCookie); + if (result != HasReturnvaluesIF::RETURN_OK) { + handleSpiError(rtd, result, "clearFaultStatus"); + } + rtd->configured = true; + rtd->db.configured = true; + if (rtd->active) { + rtd->db.active = true; + } + } + if (rtd->active and rtd->configured and not rtd->db.active) { + rtd->db.active = true; + } + } + bool someRtdUsable = false; + for (auto& rtd : rtds) { + if (rtd == nullptr) { + continue; + } + if (rtdIsActive(rtd->idx)) { +#if OBSW_RTD_AUTO_MODE == 0 + result = writeBiasSel(Bias::ON, rtd->spiCookie, BASE_CFG); +#endif + someRtdUsable = true; + } + } + return someRtdUsable; +} + +ReturnValue_t Max31865RtdReader::periodicReadReqHandling() { + using namespace MAX31865; + MutexGuard mg(readerMutex); + if (mg.getLockResult() != RETURN_OK) { + sif::warning << "Max31865RtdReader::periodicReadReqHandling: Mutex lock failed" << std::endl; + return RETURN_FAILED; + } + // Now request one shot config for all active RTDs + for (auto& rtd : rtds) { + if (rtd == nullptr) { + continue; + } + if (rtdIsActive(rtd->idx)) { + ReturnValue_t result = writeCfgReg(rtd->spiCookie, BASE_CFG | (1 << CfgBitPos::ONE_SHOT)); + if (result != RETURN_OK) { + handleSpiError(rtd, result, "writeCfgReg"); + // Release mutex ASAP + return RETURN_FAILED; + } + } + } + return RETURN_OK; +} + +ReturnValue_t Max31865RtdReader::periodicReadHandling() { + using namespace MAX31865; + auto result = RETURN_OK; + MutexGuard mg(readerMutex); + if (mg.getLockResult() != RETURN_OK) { + sif::warning << "Max31865RtdReader::periodicReadReqHandling: Mutex lock failed" << std::endl; + return RETURN_FAILED; + } + // Now read the RTD values + for (auto& rtd : rtds) { + if (rtd == nullptr) { + continue; + } + if (rtdIsActive(rtd->idx)) { + uint16_t rtdVal = 0; + bool faultBitSet = false; + result = readRtdVal(rtd->spiCookie, rtdVal, faultBitSet); + if (result != RETURN_OK) { + handleSpiError(rtd, result, "readRtdVal"); + return RETURN_FAILED; + } + if (faultBitSet) { + rtd->db.faultBitSet = faultBitSet; + } + rtd->db.adcCode = rtdVal; + } + } +#if OBSW_RTD_AUTO_MODE == 0 + for (auto& rtd : rtds) { + if (rtd == nullptr) { + continue; + } + // Even if a device was made inactive, turn off the bias here. If it was turned off, not + // necessary anymore.. + if (rtd->on) { + result = writeBiasSel(Bias::OFF, rtd->spiCookie, BASE_CFG); + } + } +#endif + return RETURN_OK; +} + +ReturnValue_t Max31865RtdReader::initializeInterface(CookieIF* cookie) { + if (cookie == nullptr) { + throw std::invalid_argument("Invalid MAX31865 Reader Cookie"); + } + auto* rtdCookie = dynamic_cast(cookie); + ReturnValue_t result = comIF->initializeInterface(rtdCookie->spiCookie); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (rtdCookie->idx > EiveMax31855::NUM_RTDS) { + throw std::invalid_argument("Invalid RTD index"); + } + rtds[rtdCookie->idx] = rtdCookie; + MutexGuard mg(readerMutex); + if (dbLen == 0) { + dbLen = rtdCookie->db.getSerializedSize(); + } + return RETURN_OK; +} + +ReturnValue_t Max31865RtdReader::sendMessage(CookieIF* cookie, const uint8_t* sendData, + size_t sendLen) { + if (cookie == nullptr) { + return RETURN_FAILED; + } + // Empty command.. don't fail for now + if (sendLen < 1) { + return RETURN_OK; + } + MutexGuard mg(readerMutex); + if (mg.getLockResult() != RETURN_OK) { + sif::warning << "Max31865RtdReader::sendMessage: Mutex lock failed" << std::endl; + return RETURN_FAILED; + } + auto* rtdCookie = dynamic_cast(cookie); + uint8_t cmdRaw = sendData[0]; + if (cmdRaw > EiveMax31855::RtdCommands::NUM_CMDS) { + sif::warning << "Max31865RtdReader::sendMessage: Invalid command" << std::endl; + return RETURN_FAILED; + } + + auto thresholdHandler = [](Max31865ReaderCookie* rtdCookie, const uint8_t* sendData) { + rtdCookie->lowThreshold = (sendData[1] << 8) | sendData[2]; + rtdCookie->highThreshold = (sendData[3] << 8) | sendData[4]; + rtdCookie->writeLowThreshold = true; + rtdCookie->writeHighThreshold = true; + }; + + auto cmd = static_cast(sendData[0]); + switch (cmd) { + case (EiveMax31855::RtdCommands::ON): { + if (not rtdCookie->on) { + rtdCookie->cd.setTimeout(MAX31865::WARMUP_MS); + rtdCookie->cd.resetTimer(); + rtdCookie->on = true; + rtdCookie->active = false; + rtdCookie->configured = false; + if (sendLen == 5) { + thresholdHandler(rtdCookie, sendData); + } + } + break; + } + case (EiveMax31855::RtdCommands::ACTIVE): { + if (not rtdCookie->on) { + rtdCookie->cd.setTimeout(MAX31865::WARMUP_MS); + rtdCookie->cd.resetTimer(); + rtdCookie->on = true; + rtdCookie->active = true; + rtdCookie->configured = false; + } else { + rtdCookie->active = true; + } + if (sendLen == 5) { + thresholdHandler(rtdCookie, sendData); + } + break; + } + case (EiveMax31855::RtdCommands::OFF): { + rtdCookie->on = false; + rtdCookie->active = false; + rtdCookie->configured = false; + break; + } + case (EiveMax31855::RtdCommands::HIGH_TRESHOLD): { + if (sendLen == 3) { + rtdCookie->highThreshold = (sendData[1] << 8) | sendData[2]; + rtdCookie->writeHighThreshold = true; + } else { + return RETURN_FAILED; + } + break; + } + case (EiveMax31855::RtdCommands::LOW_THRESHOLD): { + if (sendLen == 3) { + rtdCookie->lowThreshold = (sendData[1] << 8) | sendData[2]; + rtdCookie->writeLowThreshold = true; + } else { + return RETURN_FAILED; + } + break; + } + case (EiveMax31855::RtdCommands::CFG): + default: { + // TODO: Only implement if needed + break; + } + } + return RETURN_OK; +} + +ReturnValue_t Max31865RtdReader::getSendSuccess(CookieIF* cookie) { return RETURN_OK; } + +ReturnValue_t Max31865RtdReader::requestReceiveMessage(CookieIF* cookie, size_t requestLen) { + return RETURN_OK; +} + +ReturnValue_t Max31865RtdReader::readReceivedMessage(CookieIF* cookie, uint8_t** buffer, + size_t* size) { + MutexGuard mg(readerMutex); + if (mg.getLockResult() != RETURN_OK) { + // TODO: Emit warning + return RETURN_FAILED; + } + auto* rtdCookie = dynamic_cast(cookie); + uint8_t* exchangePtr = rtdCookie->exchangeBuf.data(); + size_t serLen = 0; + auto result = rtdCookie->db.serialize(&exchangePtr, &serLen, rtdCookie->exchangeBuf.size(), + SerializeIF::Endianness::MACHINE); + if (result != RETURN_OK) { + // TODO: Emit warning + return RETURN_FAILED; + } + *buffer = reinterpret_cast(rtdCookie->exchangeBuf.data()); + *size = serLen; + return RETURN_OK; +} + +ReturnValue_t Max31865RtdReader::writeCfgReg(SpiCookie* cookie, uint8_t cfg) { + using namespace MAX31865; + return writeNToReg(cookie, CONFIG, 1, &cfg, nullptr); +} + +ReturnValue_t Max31865RtdReader::writeBiasSel(MAX31865::Bias bias, SpiCookie* cookie, + uint8_t baseCfg) { + using namespace MAX31865; + if (bias == MAX31865::Bias::OFF) { + baseCfg &= ~(1 << CfgBitPos::BIAS_SEL); + } else { + baseCfg |= (1 << CfgBitPos::BIAS_SEL); + } + return writeCfgReg(cookie, baseCfg); +} + +ReturnValue_t Max31865RtdReader::clearFaultStatus(SpiCookie* cookie) { + using namespace MAX31865; + // Read back the current configuration to avoid overwriting it when clearing te fault status + uint8_t currentCfg = 0; + auto result = readCfgReg(cookie, currentCfg); + if (result != RETURN_OK) { + return result; + } + // Clear bytes 5, 3 and 2 which need to be 0 + currentCfg &= ~0x2C; + currentCfg |= (1 << CfgBitPos::FAULT_STATUS_CLEAR); + return writeCfgReg(cookie, currentCfg); +} + +ReturnValue_t Max31865RtdReader::readCfgReg(SpiCookie* cookie, uint8_t& cfg) { + using namespace MAX31865; + uint8_t* replyPtr = nullptr; + auto result = readNFromReg(cookie, CONFIG, 1, &replyPtr); + if (result == RETURN_OK) { + cfg = replyPtr[0]; + } + return result; +} + +ReturnValue_t Max31865RtdReader::writeLowThreshold(SpiCookie* cookie, uint16_t val) { + using namespace MAX31865; + uint8_t cmd[2] = {static_cast((val >> 8) & 0xff), static_cast(val & 0xff)}; + return writeNToReg(cookie, LOW_THRESHOLD, 2, cmd, nullptr); +} + +ReturnValue_t Max31865RtdReader::writeHighThreshold(SpiCookie* cookie, uint16_t val) { + using namespace MAX31865; + uint8_t cmd[2] = {static_cast((val >> 8) & 0xff), static_cast(val & 0xff)}; + return writeNToReg(cookie, HIGH_THRESHOLD, 2, cmd, nullptr); +} + +ReturnValue_t Max31865RtdReader::readLowThreshold(SpiCookie* cookie, uint16_t& lowThreshold) { + using namespace MAX31865; + uint8_t* replyPtr = nullptr; + auto result = readNFromReg(cookie, LOW_THRESHOLD, 2, &replyPtr); + if (result == RETURN_OK) { + lowThreshold = (replyPtr[0] << 8) | replyPtr[1]; + } + return result; +} + +ReturnValue_t Max31865RtdReader::readHighThreshold(SpiCookie* cookie, uint16_t& highThreshold) { + using namespace MAX31865; + uint8_t* replyPtr = nullptr; + auto result = readNFromReg(cookie, HIGH_THRESHOLD, 2, &replyPtr); + if (result == RETURN_OK) { + highThreshold = (replyPtr[0] << 8) | replyPtr[1]; + } + return result; +} + +ReturnValue_t Max31865RtdReader::writeNToReg(SpiCookie* cookie, uint8_t reg, size_t n, uint8_t* cmd, + uint8_t** reply) { + using namespace MAX31865; + if (n > cmdBuf.size() - 1) { + return HasReturnvaluesIF::RETURN_FAILED; + } + cmdBuf[0] = reg | WRITE_BIT; + for (size_t idx = 0; idx < n; idx++) { + cmdBuf[idx + 1] = cmd[idx]; + } + return comIF->sendMessage(cookie, cmdBuf.data(), n + 1); +} + +ReturnValue_t Max31865RtdReader::readRtdVal(SpiCookie* cookie, uint16_t& val, bool& faultBitSet) { + using namespace MAX31865; + uint8_t* replyPtr = nullptr; + auto result = readNFromReg(cookie, RTD, 2, &replyPtr); + if (result != RETURN_OK) { + return result; + } + if (replyPtr[1] & 0b0000'0001) { + faultBitSet = true; + } + // Shift 1 to the right to remove fault bit + val = ((replyPtr[0] << 8) | replyPtr[1]) >> 1; + return result; +} + +ReturnValue_t Max31865RtdReader::readNFromReg(SpiCookie* cookie, uint8_t reg, size_t n, + uint8_t** reply) { + using namespace MAX31865; + if (n > 4) { + return HasReturnvaluesIF::RETURN_FAILED; + } + // Clear write bit in any case + reg &= ~WRITE_BIT; + cmdBuf[0] = reg; + std::memset(cmdBuf.data() + 1, 0, n); + ReturnValue_t result = comIF->sendMessage(cookie, cmdBuf.data(), n + 1); + if (result != RETURN_OK) { + return RETURN_FAILED; + } + + size_t dummyLen = 0; + uint8_t* replyPtr = nullptr; + result = comIF->readReceivedMessage(cookie, &replyPtr, &dummyLen); + if (result != RETURN_OK) { + return result; + } + if (reply != nullptr) { + *reply = replyPtr + 1; + } + return RETURN_OK; +} + +ReturnValue_t Max31865RtdReader::handleSpiError(Max31865ReaderCookie* cookie, ReturnValue_t result, + const char* ctx) { + cookie->db.spiErrorCount.value += 1; + sif::warning << "Max31865RtdReader::handleSpiError: " << ctx << " | Failed with result " << result + << std::endl; + return result; +} + +ReturnValue_t Max31865RtdReader::initialize() { + csLock = comIF->getCsMutex(); + return SystemObject::initialize(); +} diff --git a/linux/devices/Max31865RtdLowlevelHandler.h b/linux/devices/Max31865RtdLowlevelHandler.h new file mode 100644 index 00000000..d3845bd5 --- /dev/null +++ b/linux/devices/Max31865RtdLowlevelHandler.h @@ -0,0 +1,87 @@ +#ifndef LINUX_DEVICES_MAX31865RTDREADER_H_ +#define LINUX_DEVICES_MAX31865RTDREADER_H_ + +#include +#include +#include +#include + +#include "fsfw/devicehandlers/DeviceCommunicationIF.h" +#include "mission/devices/devicedefinitions/Max31865Definitions.h" + +struct Max31865ReaderCookie : public CookieIF { + Max31865ReaderCookie(){}; + Max31865ReaderCookie(object_id_t handlerId_, uint8_t idx_, const std::string& locString_, + SpiCookie* spiCookie_) + : idx(idx_), handlerId(handlerId_), locString(locString_), spiCookie(spiCookie_) {} + + uint8_t idx = 0; + object_id_t handlerId = objects::NO_OBJECT; + + std::string locString = ""; + std::array exchangeBuf{}; + Countdown cd = Countdown(MAX31865::WARMUP_MS); + + bool on = false; + bool configured = false; + bool active = false; + bool writeLowThreshold = false; + bool writeHighThreshold = false; + uint16_t lowThreshold = 0; + uint16_t highThreshold = 0; + SpiCookie* spiCookie = nullptr; + + // Exchange data buffer struct + EiveMax31855::ReadOutStruct db; +}; + +class Max31865RtdReader : public SystemObject, + public ExecutableObjectIF, + public DeviceCommunicationIF { + public: + Max31865RtdReader(object_id_t objectId, SpiComIF* lowLevelComIF, GpioIF* gpioIF); + + ReturnValue_t performOperation(uint8_t operationCode) override; + ReturnValue_t initialize() override; + + private: + std::vector rtds; + std::array cmdBuf = {}; + size_t dbLen = 0; + MutexIF* readerMutex; + + SpiComIF* comIF; + GpioIF* gpioIF; + MutexIF::TimeoutType csTimeoutType = MutexIF::TimeoutType::BLOCKING; + uint32_t csTimeoutMs = 0; + MutexIF* csLock = nullptr; + + bool periodicInitHandling(); + ReturnValue_t periodicReadReqHandling(); + ReturnValue_t periodicReadHandling(); + + bool rtdIsActive(uint8_t idx); + ReturnValue_t writeCfgReg(SpiCookie* cookie, uint8_t cfg); + ReturnValue_t writeBiasSel(MAX31865::Bias bias, SpiCookie* cookie, uint8_t baseCfg); + ReturnValue_t readCfgReg(SpiCookie* cookie, uint8_t& cfg); + ReturnValue_t readRtdVal(SpiCookie* cookie, uint16_t& val, bool& faultBitSet); + ReturnValue_t writeLowThreshold(SpiCookie* cookie, uint16_t val); + ReturnValue_t writeHighThreshold(SpiCookie* cookie, uint16_t val); + ReturnValue_t readLowThreshold(SpiCookie* cookie, uint16_t& val); + ReturnValue_t readHighThreshold(SpiCookie* cookie, uint16_t& val); + ReturnValue_t clearFaultStatus(SpiCookie* cookie); + + ReturnValue_t readNFromReg(SpiCookie* cookie, uint8_t reg, size_t n, uint8_t** reply); + ReturnValue_t writeNToReg(SpiCookie* cookie, uint8_t reg, size_t n, uint8_t* cmd, + uint8_t** reply); + + ReturnValue_t initializeInterface(CookieIF* cookie) override; + ReturnValue_t sendMessage(CookieIF* cookie, const uint8_t* sendData, size_t sendLen) override; + ReturnValue_t getSendSuccess(CookieIF* cookie) override; + ReturnValue_t requestReceiveMessage(CookieIF* cookie, size_t requestLen) override; + ReturnValue_t readReceivedMessage(CookieIF* cookie, uint8_t** buffer, size_t* size) override; + + ReturnValue_t handleSpiError(Max31865ReaderCookie* cookie, ReturnValue_t result, const char* ctx); +}; + +#endif /* LINUX_DEVICES_MAX31865RTDREADER_H_ */ diff --git a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h index 23389208..d64bb863 100644 --- a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h +++ b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h @@ -29,6 +29,8 @@ static const DeviceCommandId_t TC_MODE_REPLAY = 16; static const DeviceCommandId_t TC_CAM_CMD_SEND = 17; static const DeviceCommandId_t TC_MODE_IDLE = 18; static const DeviceCommandId_t TM_CAM_CMD_RPT = 19; +static const DeviceCommandId_t SET_UART_TX_TRISTATE = 20; +static const DeviceCommandId_t RELEASE_UART_TX = 21; // Will reset the sequence count of the OBSW static const DeviceCommandId_t OBSW_RESET_SEQ_COUNT = 50; @@ -98,6 +100,33 @@ static const uint16_t TC_WRITE_SEQ_EXECUTION_DELAY = 80; // Requires approx. 2 seconds for execution. 8 => 4 seconds static const uint16_t TC_DOWNLINK_PWR_ON_EXECUTION_DELAY = 8; +namespace status_code { +static const uint16_t UNKNOWN_APID = 0x5DD; +static const uint16_t INCORRECT_LENGTH = 0x5DE; +static const uint16_t INCORRECT_CRC = 0x5DF; +static const uint16_t INCORRECT_PKT_SEQ_CNT = 0x5E0; +static const uint16_t TC_NOT_ALLOWED_IN_MODE = 0x5E1; +static const uint16_t TC_EXEUTION_DISABLED = 0x5E2; +static const uint16_t FLASH_MOUNT_FAILED = 0x5E3; +static const uint16_t FLASH_FILE_ALREADY_CLOSED = 0x5E4; +static const uint16_t FLASH_FILE_OPEN_FAILED = 0x5E5; +static const uint16_t FLASH_FILE_ALREDY_OPEN = 0x5E6; +static const uint16_t FLASH_FILE_NOT_OPEN = 0x5E7; +static const uint16_t FLASH_UNMOUNT_FAILED = 0x5E8; +static const uint16_t HEAP_ALLOCATION_FAILED = 0x5E9; +static const uint16_t INVALID_PARAMETER = 0x5EA; +static const uint16_t NOT_INITIALIZED = 0x5EB; +static const uint16_t REBOOT_IMMINENT = 0x5EC; +static const uint16_t CORRUPT_DATA = 0x5ED; +static const uint16_t FLASH_CORRECTABLE_MISMATCH = 0x5EE; +static const uint16_t FLASH_UNCORRECTABLE_MISMATCH = 0x5EF; +static const uint16_t RESERVED_0 = 0x5F0; +static const uint16_t RESERVED_1 = 0x5F1; +static const uint16_t RESERVED_2 = 0x5F2; +static const uint16_t RESERVED_3 = 0x5F3; +static const uint16_t RESERVED_4 = 0x5F4; +} // namespace status_code + /** * @brief Abstract base class for TC space packet of MPSoC. */ @@ -576,6 +605,9 @@ class TcReplayWriteSeq : public TcBase { } }; +/** + * @brief Helps to extract the fields of the flash write command from the PUS packet. + */ class FlashWritePusCmd : public MPSoCReturnValuesIF { public: FlashWritePusCmd(){}; @@ -651,9 +683,13 @@ class TcCamcmdSend : public TcBase { if (commandDataLen > MAX_DATA_LENGTH) { return INVALID_LENGTH; } - std::memcpy(this->getPacketData(), commandData, commandDataLen); - *(this->getPacketData() + commandDataLen) = CARRIAGE_RETURN; - uint16_t trueLength = commandDataLen + sizeof(CARRIAGE_RETURN) + CRC_SIZE; + uint16_t dataLen = static_cast(commandDataLen + sizeof(CARRIAGE_RETURN)); + size_t size = sizeof(dataLen); + SerializeAdapter::serialize(&dataLen, this->getPacketData(), &size, sizeof(dataLen), + SerializeIF::Endianness::BIG); + std::memcpy(this->getPacketData() + sizeof(dataLen), commandData, commandDataLen); + *(this->getPacketData() + sizeof(dataLen) + commandDataLen) = CARRIAGE_RETURN; + uint16_t trueLength = sizeof(dataLen) + commandDataLen + sizeof(CARRIAGE_RETURN) + CRC_SIZE; this->setPacketDataLength(trueLength - 1); return HasReturnvaluesIF::RETURN_OK; } diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 58166e98..462ee632 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -8,12 +8,13 @@ #include #include +#include "linux/devices/devicedefinitions/SupvReturnValuesIF.h" + namespace supv { /** Command IDs */ static const DeviceCommandId_t NONE = 0; static const DeviceCommandId_t GET_HK_REPORT = 1; -static const DeviceCommandId_t RESTART_MPSOC = 2; static const DeviceCommandId_t START_MPSOC = 3; static const DeviceCommandId_t SHUTDOWN_MPSOC = 4; static const DeviceCommandId_t SEL_MPSOC_BOOT_IMAGE = 5; @@ -23,52 +24,57 @@ static const DeviceCommandId_t RESET_MPSOC = 8; static const DeviceCommandId_t SET_TIME_REF = 9; static const DeviceCommandId_t DISABLE_PERIOIC_HK_TRANSMISSION = 10; static const DeviceCommandId_t GET_BOOT_STATUS_REPORT = 11; -/** Notifies the supervisor that a new update is available for the MPSoC */ -static const DeviceCommandId_t UPDATE_AVAILABLE = 12; -static const DeviceCommandId_t WATCHDOGS_ENABLE = 13; -static const DeviceCommandId_t WATCHDOGS_CONFIG_TIMEOUT = 14; static const DeviceCommandId_t ENABLE_LATCHUP_ALERT = 15; static const DeviceCommandId_t DISABLE_LATCHUP_ALERT = 16; -static const DeviceCommandId_t AUTO_CALIBRATE_ALERT = 17; static const DeviceCommandId_t SET_ALERT_LIMIT = 18; -static const DeviceCommandId_t SET_ALERT_IRQ_FILTER = 19; -static const DeviceCommandId_t SET_ADC_SWEEP_PERIOD = 20; static const DeviceCommandId_t SET_ADC_ENABLED_CHANNELS = 21; static const DeviceCommandId_t SET_ADC_WINDOW_AND_STRIDE = 22; static const DeviceCommandId_t SET_ADC_THRESHOLD = 23; static const DeviceCommandId_t GET_LATCHUP_STATUS_REPORT = 24; static const DeviceCommandId_t COPY_ADC_DATA_TO_MRAM = 25; -static const DeviceCommandId_t ENABLE_NVMS = 26; -static const DeviceCommandId_t SELECT_NVM = 27; static const DeviceCommandId_t RUN_AUTO_EM_TESTS = 28; static const DeviceCommandId_t WIPE_MRAM = 29; static const DeviceCommandId_t FIRST_MRAM_DUMP = 30; -static const DeviceCommandId_t SET_DBG_VERBOSITY = 31; -static const DeviceCommandId_t CAN_LOOPBACK_TEST = 32; -static const DeviceCommandId_t PRINT_CPU_STATS = 33; static const DeviceCommandId_t SET_GPIO = 34; static const DeviceCommandId_t READ_GPIO = 35; static const DeviceCommandId_t RESTART_SUPERVISOR = 36; static const DeviceCommandId_t FACTORY_RESET_CLEAR_ALL = 37; -static const DeviceCommandId_t REQUEST_LOGGING_DATA = 38; -static const DeviceCommandId_t UPDATE_IMAGE_DATA = 39; +static const DeviceCommandId_t LOGGING_REQUEST_COUNTERS = 38; static const DeviceCommandId_t FACTORY_RESET_CLEAR_MIRROR = 40; static const DeviceCommandId_t FACTORY_RESET_CLEAR_CIRCULAR = 41; -static const DeviceCommandId_t UPDATE_VERIFY = 42; static const DeviceCommandId_t CONSECUTIVE_MRAM_DUMP = 43; +static const DeviceCommandId_t START_MPSOC_QUIET = 45; +static const DeviceCommandId_t SET_SHUTDOWN_TIMEOUT = 46; +static const DeviceCommandId_t FACTORY_FLASH = 47; +static const DeviceCommandId_t PERFORM_UPDATE = 48; +static const DeviceCommandId_t TERMINATE_SUPV_HELPER = 49; +static const DeviceCommandId_t ENABLE_AUTO_TM = 50; +static const DeviceCommandId_t DISABLE_AUTO_TM = 51; +static const DeviceCommandId_t LOGGING_REQUEST_EVENT_BUFFERS = 54; +static const DeviceCommandId_t LOGGING_CLEAR_COUNTERS = 55; +static const DeviceCommandId_t LOGGING_SET_TOPIC = 56; +static const DeviceCommandId_t REQUEST_ADC_REPORT = 57; +static const DeviceCommandId_t RESET_PL = 58; +static const DeviceCommandId_t ENABLE_NVMS = 59; +static const DeviceCommandId_t CONTINUE_UPDATE = 60; /** Reply IDs */ -static const DeviceCommandId_t ACK_REPORT = 50; -static const DeviceCommandId_t EXE_REPORT = 51; -static const DeviceCommandId_t HK_REPORT = 52; -static const DeviceCommandId_t BOOT_STATUS_REPORT = 53; -static const DeviceCommandId_t LATCHUP_REPORT = 54; +static const DeviceCommandId_t ACK_REPORT = 100; +static const DeviceCommandId_t EXE_REPORT = 101; +static const DeviceCommandId_t HK_REPORT = 102; +static const DeviceCommandId_t BOOT_STATUS_REPORT = 103; +static const DeviceCommandId_t LATCHUP_REPORT = 104; +static const DeviceCommandId_t LOGGING_REPORT = 105; +static const DeviceCommandId_t ADC_REPORT = 106; +// Size of complete space packet (6 byte header + size of data + 2 byte CRC) static const uint16_t SIZE_ACK_REPORT = 14; static const uint16_t SIZE_EXE_REPORT = 14; -static const uint16_t SIZE_HK_REPORT = 48; -static const uint16_t SIZE_BOOT_STATUS_REPORT = 22; -static const uint16_t SIZE_LATCHUP_STATUS_REPORT = 55; +static const uint16_t SIZE_HK_REPORT = 52; +static const uint16_t SIZE_BOOT_STATUS_REPORT = 24; +static const uint16_t SIZE_LATCHUP_STATUS_REPORT = 31; +static const uint16_t SIZE_LOGGING_REPORT = 73; +static const uint16_t SIZE_ADC_REPORT = 72; /** * SpacePacket apids of telemetry packets @@ -80,7 +86,7 @@ static const uint16_t APID_EXE_FAILURE = 0x203; static const uint16_t APID_HK_REPORT = 0x204; static const uint16_t APID_BOOT_STATUS_REPORT = 0x205; static const uint16_t APID_UPDATE_STATUS_REPORT = 0x206; -static const uint16_t APID_WDG_STATUS_REPORT = 0x207; +static const uint16_t APID_ADC_REPORT = 0x207; static const uint16_t APID_LATCHUP_STATUS_REPORT = 0x208; static const uint16_t APID_SOC_SYSMON = 0x209; static const uint16_t APID_MRAM_DUMP_TM = 0x20A; @@ -91,40 +97,37 @@ static const uint16_t APID_DATA_LOGGER_DATA = 0x20D; /** * APIDs of telecommand packets */ -static const uint16_t APID_RESTART_MPSOC = 0xA0; static const uint16_t APID_START_MPSOC = 0xA1; static const uint16_t APID_SHUTWOWN_MPSOC = 0xA2; static const uint16_t APID_SEL_MPSOC_BOOT_IMAGE = 0xA3; static const uint16_t APID_SET_BOOT_TIMEOUT = 0xA4; static const uint16_t APID_SET_MAX_RESTART_TRIES = 0xA5; static const uint16_t APID_RESET_MPSOC = 0xA6; +static const uint16_t APID_RESET_PL = 0xA7; static const uint16_t APID_GET_BOOT_STATUS_RPT = 0xA8; -static const uint16_t APID_UPDATE_AVAILABLE = 0xB0; -static const uint16_t APID_UPDATE_IMAGE_DATA = 0xB1; -static const uint16_t APID_UPDATE_VERIFY = 0xB2; -static const uint16_t APID_WTD_ENABLE = 0xC0; -static const uint16_t APID_WTD_CONFIG_TIMEOUT = 0xC1; +static const uint16_t APID_PREPARE_UPDATE = 0xA9; +static const uint16_t APID_START_MPSOC_QUIET = 0xAA; +static const uint16_t APID_SET_SHUTDOWN_TIMEOUT = 0xAB; +static const uint16_t APID_FACTORY_FLASH = 0xAC; +static const uint16_t APID_ERASE_MEMORY = 0xB0; +static const uint16_t APID_WRITE_MEMORY = 0xB1; +static const uint16_t APID_CHECK_MEMORY = 0xB2; static const uint16_t APID_SET_TIME_REF = 0xC2; static const uint16_t APID_DISABLE_HK = 0xC3; +static const uint16_t APID_AUTO_TM = 0xC5; static const uint16_t APID_ENABLE_LATCHUP_ALERT = 0xD0; static const uint16_t APID_DISABLE_LATCHUP_ALERT = 0xD1; -static const uint16_t APID_AUTO_CALIBRATE_ALERT = 0xD2; static const uint16_t APID_SET_ALERT_LIMIT = 0xD3; -static const uint16_t APID_SET_ALERT_IRQ_FILTER = 0xD4; -static const uint16_t APID_SET_ADC_SWEEP_PERIOD = 0xD5; -static const uint16_t APID_SET_ADC_ENABLED_CHANNELS = 0xD6; -static const uint16_t APID_SET_ADC_WINDOW_AND_STRIDE = 0xD7; -static const uint16_t APID_SET_ADC_THRESHOLD = 0xD8; +static const uint16_t APID_SET_ADC_ENABLED_CHANNELS = 0xE1; +static const uint16_t APID_SET_ADC_WINDOW_AND_STRIDE = 0xE2; +static const uint16_t APID_SET_ADC_THRESHOLD = 0xE3; static const uint16_t APID_GET_LATCHUP_STATUS_REPORT = 0xD9; static const uint16_t APID_COPY_ADC_DATA_TO_MRAM = 0xDA; +static const uint16_t APID_REQUEST_ADC_REPORT = 0xDB; static const uint16_t APID_ENABLE_NVMS = 0xF0; -static const uint16_t APID_SELECT_NVM = 0xF1; static const uint16_t APID_RUN_AUTO_EM_TESTS = 0xF2; static const uint16_t APID_WIPE_MRAM = 0xF3; static const uint16_t APID_DUMP_MRAM = 0xF4; -static const uint16_t APID_SET_DBG_VERBOSITY = 0xF5; -static const uint16_t APID_CAN_LOOPBACK_TEST = 0xF6; -static const uint16_t APID_PRINT_CPU_STATS = 0xF8; static const uint16_t APID_SET_GPIO = 0xF9; static const uint16_t APID_READ_GPIO = 0xFA; static const uint16_t APID_RESTART_SUPERVISOR = 0xFB; @@ -164,7 +167,7 @@ enum PoolIds : lp_id_t { NUM_TMS, TEMP_PS, TEMP_PL, - SOC_STATE, + HK_SOC_STATE, NVM0_1_STATE, NVM3_STATE, MISSION_IO_STATE, @@ -174,14 +177,16 @@ enum PoolIds : lp_id_t { UPTIME, CPULOAD, AVAILABLEHEAP, - BOOT_SIGNAL, - RESET_COUNTER, + BR_SOC_STATE, + POWER_CYCLES, BOOT_AFTER_MS, BOOT_TIMEOUT_MS, ACTIVE_NVM, BP0_STATE, BP1_STATE, BP2_STATE, + BOOT_STATE, + BOOT_CYCLES, LATCHUP_ID, CNT0, @@ -198,22 +203,81 @@ enum PoolIds : lp_id_t { LATCHUP_RPT_TIME_MON, LATCHUP_RPT_TIME_YEAR, LATCHUP_RPT_TIME_MSEC, - LATCHUP_RPT_TIME_USEC, - LATCHUP_RPT_TIME_IS_SET, + LATCHUP_RPT_IS_SET, + + LATCHUP_HAPPENED_CNT_0, + LATCHUP_HAPPENED_CNT_1, + LATCHUP_HAPPENED_CNT_2, + LATCHUP_HAPPENED_CNT_3, + LATCHUP_HAPPENED_CNT_4, + LATCHUP_HAPPENED_CNT_5, + LATCHUP_HAPPENED_CNT_6, + ADC_DEVIATION_TRIGGERS_CNT, + TC_RECEIVED_CNT, + TM_AVAILABLE_CNT, + SUPERVISOR_BOOTS, + MPSOC_BOOTS, + MPSOC_BOOT_FAILED_ATTEMPTS, + MPSOC_POWER_UP, + MPSOC_UPDATES, + LAST_RECVD_TC, + + ADC_RAW_0, + ADC_RAW_1, + ADC_RAW_2, + ADC_RAW_3, + ADC_RAW_4, + ADC_RAW_5, + ADC_RAW_6, + ADC_RAW_7, + ADC_RAW_8, + ADC_RAW_9, + ADC_RAW_10, + ADC_RAW_11, + ADC_RAW_12, + ADC_RAW_13, + ADC_RAW_14, + ADC_RAW_15, + ADC_ENG_0, + ADC_ENG_1, + ADC_ENG_2, + ADC_ENG_3, + ADC_ENG_4, + ADC_ENG_5, + ADC_ENG_6, + ADC_ENG_7, + ADC_ENG_8, + ADC_ENG_9, + ADC_ENG_10, + ADC_ENG_11, + ADC_ENG_12, + ADC_ENG_13, + ADC_ENG_14, + ADC_ENG_15 }; static const uint8_t HK_SET_ENTRIES = 13; -static const uint8_t BOOT_REPORT_SET_ENTRIES = 8; +static const uint8_t BOOT_REPORT_SET_ENTRIES = 10; static const uint8_t LATCHUP_RPT_SET_ENTRIES = 16; +static const uint8_t LOGGING_RPT_SET_ENTRIES = 16; +static const uint8_t ADC_RPT_SET_ENTRIES = 32; static const uint32_t HK_SET_ID = HK_REPORT; static const uint32_t BOOT_REPORT_SET_ID = BOOT_STATUS_REPORT; static const uint32_t LATCHUP_RPT_ID = LATCHUP_REPORT; +static const uint32_t LOGGING_RPT_ID = LOGGING_REPORT; +static const uint32_t ADC_REPORT_SET_ID = ADC_REPORT; + +namespace recv_timeout { +// Erase memory can require up to 60 seconds for execution +static const uint32_t ERASE_MEMORY = 60000; +static const uint32_t UPDATE_STATUS_REPORT = 70000; +} // namespace recv_timeout /** - * @brief With this class a space packet can be created which does not contain any data. + * @brief This class creates a space packet containing only the header data and the CRC. */ -class EmptyPacket : public SpacePacket { +class ApidOnlyPacket : public SpacePacket { public: /** * @brief Constructor @@ -222,7 +286,7 @@ class EmptyPacket : public SpacePacket { * * @note Sequence count of empty packet is always 1. */ - EmptyPacket(uint16_t apid) : SpacePacket(LENGTH_EMPTY_TC - 1, true, apid, 1) { calcCrc(); } + ApidOnlyPacket(uint16_t apid) : SpacePacket(LENGTH_EMPTY_TC - 1, true, apid, 1) { calcCrc(); } private: /** @@ -246,6 +310,9 @@ class EmptyPacket : public SpacePacket { */ class MPSoCBootSelect : public SpacePacket { public: + static const uint8_t NVM0 = 0; + static const uint8_t NVM1 = 1; + /** * @brief Constructor * @@ -253,8 +320,10 @@ class MPSoCBootSelect : public SpacePacket { * @param bp0 Partition pin 0 * @param bp1 Partition pin 1 * @param bp2 Partition pin 2 + * + * @note Selection of partitions is currently not supported. */ - MPSoCBootSelect(uint8_t mem, uint8_t bp0, uint8_t bp1, uint8_t bp2) + MPSoCBootSelect(uint8_t mem = 0, uint8_t bp0 = 0, uint8_t bp1 = 0, uint8_t bp2 = 0) : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SEL_MPSOC_BOOT_IMAGE, DEFAULT_SEQUENCE_COUNT), mem(mem), bp0(bp0), @@ -296,6 +365,50 @@ class MPSoCBootSelect : public SpacePacket { } }; +/** + * @brief This class creates the command to enable or disable the NVMs connected to the + * supervisor. + */ +class EnableNvms : public SpacePacket { + public: + /** + * @brief Constructor + * + * @param mem The memory to boot from: NVM0 (0), NVM1 (1) + * @param bp0 Partition pin 0 + * @param bp1 Partition pin 1 + * @param bp2 Partition pin 2 + */ + EnableNvms(uint8_t nvm01, uint8_t nvm3) + : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_ENABLE_NVMS, DEFAULT_SEQUENCE_COUNT), + nvm01(nvm01), + nvm3(nvm3) { + initPacket(); + } + + private: + static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; + static const uint8_t DATA_FIELD_LENGTH = 4; + static const uint8_t CRC_OFFSET = 2; + uint8_t nvm01 = 0; + uint8_t nvm3 = 0; + + void initPacket() { + *(this->localData.fields.buffer) = nvm01; + *(this->localData.fields.buffer + 1) = nvm3; + + /* Calculate crc */ + uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, + sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); + + /* Add crc to packet data field of space packet */ + size_t serializedSize = 0; + uint8_t* crcPos = this->localData.fields.buffer + CRC_OFFSET; + SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), + SerializeIF::Endianness::BIG); + } +}; + /** * @brief This class generates the space packet to update the time of the PLOC supervisor. */ @@ -307,43 +420,46 @@ class SetTimeRef : public SpacePacket { } private: - static const uint16_t DATA_FIELD_LENGTH = 34; + static const uint16_t DATA_FIELD_LENGTH = 10; static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; + static const uint16_t SYNC = 0x8000; void initPacket(Clock::TimeOfDay_t* time) { size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&time->second, &data_field_ptr, &serializedSize, - sizeof(time->second), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&time->minute, &data_field_ptr, &serializedSize, - sizeof(time->minute), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&time->hour, &data_field_ptr, &serializedSize, - sizeof(time->hour), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&time->day, &data_field_ptr, &serializedSize, - sizeof(time->day), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&time->month, &data_field_ptr, &serializedSize, - sizeof(time->month), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&time->year, &data_field_ptr, &serializedSize, - sizeof(time->year), SerializeIF::Endianness::BIG); - serializedSize = 0; - uint32_t milliseconds = time->usecond / 1000; - SerializeAdapter::serialize(&milliseconds, &data_field_ptr, &serializedSize, + uint8_t* dataFieldPtr = this->localData.fields.buffer; + uint16_t milliseconds = static_cast(time->usecond / 1000) | SYNC; + SerializeAdapter::serialize(&milliseconds, &dataFieldPtr, &serializedSize, sizeof(milliseconds), SerializeIF::Endianness::BIG); + uint8_t second = static_cast(time->second); serializedSize = 0; - uint32_t isSet = 0xFFFFFFFF; - SerializeAdapter::serialize(&isSet, &data_field_ptr, &serializedSize, sizeof(isSet), - SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(&second, &dataFieldPtr, &serializedSize, + sizeof(time->second), SerializeIF::Endianness::BIG); + uint8_t minute = static_cast(time->minute); + serializedSize = 0; + SerializeAdapter::serialize(&minute, &dataFieldPtr, &serializedSize, + sizeof(time->minute), SerializeIF::Endianness::BIG); + uint8_t hour = static_cast(time->hour); + serializedSize = 0; + SerializeAdapter::serialize(&hour, &dataFieldPtr, &serializedSize, sizeof(time->hour), + SerializeIF::Endianness::BIG); + uint8_t day = static_cast(time->day); + serializedSize = 0; + SerializeAdapter::serialize(&day, &dataFieldPtr, &serializedSize, sizeof(time->day), + SerializeIF::Endianness::BIG); + uint8_t month = static_cast(time->month); + serializedSize = 0; + SerializeAdapter::serialize(&month, &dataFieldPtr, &serializedSize, + sizeof(time->month), SerializeIF::Endianness::BIG); + uint8_t year = static_cast(time->year - 1900); + serializedSize = 0; + SerializeAdapter::serialize(&year, &dataFieldPtr, &serializedSize, sizeof(time->year), + SerializeIF::Endianness::BIG); serializedSize = 0; /* Calculate crc */ uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - SerializeAdapter::serialize(&crc, &data_field_ptr, &serializedSize, sizeof(crc), + SerializeAdapter::serialize(&crc, &dataFieldPtr, &serializedSize, sizeof(crc), SerializeIF::Endianness::BIG); } }; @@ -371,15 +487,15 @@ class SetBootTimeout : public SpacePacket { void initPacket() { size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&timeout, &data_field_ptr, &serializedSize, - sizeof(timeout), SerializeIF::Endianness::BIG); + uint8_t* dataFieldPtr = this->localData.fields.buffer; + SerializeAdapter::serialize(&timeout, &dataFieldPtr, &serializedSize, sizeof(timeout), + SerializeIF::Endianness::BIG); /* Calculate crc */ uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); /* Add crc to packet data field of space packet */ serializedSize = 0; - SerializeAdapter::serialize(&crc, &data_field_ptr, &serializedSize, sizeof(crc), + SerializeAdapter::serialize(&crc, &dataFieldPtr, &serializedSize, sizeof(crc), SerializeIF::Endianness::BIG); } }; @@ -407,81 +523,17 @@ class SetRestartTries : public SpacePacket { static const uint16_t DATA_FIELD_LENGTH = 3; void initPacket() { - uint8_t* data_field_ptr = this->localData.fields.buffer; - *data_field_ptr = restartTries; + uint8_t* dataFieldPtr = this->localData.fields.buffer; + *dataFieldPtr = restartTries; uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); size_t serializedSize = 0; - uint8_t* crcPtr = data_field_ptr + 1; + uint8_t* crcPtr = dataFieldPtr + 1; SerializeAdapter::serialize(&crc, &crcPtr, &serializedSize, sizeof(crc), SerializeIF::Endianness::BIG); } }; -/** - * @brief This class packages the command to notify the supervisor that a new update for the - * MPSoC is available. - */ -class UpdateAvailable : public SpacePacket { - public: - /** - * @brief Constructor - * - * @param imageSelect - * @param imagePartition - * @param imageSize - * @param imageCrc - * @param numberOfPackets - */ - UpdateAvailable(uint8_t imageSelect, uint8_t imagePartition, uint32_t imageSize, - uint32_t imageCrc, uint32_t numberOfPackets) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_UPDATE_AVAILABLE, DEFAULT_SEQUENCE_COUNT), - imageSelect(imageSelect), - imagePartition(imagePartition), - imageSize(imageSize), - imageCrc(imageCrc), - numberOfPackets(numberOfPackets) { - initPacket(); - } - - private: - static const uint16_t DATA_FIELD_LENGTH = 16; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - - uint8_t imageSelect = 0; - uint8_t imagePartition = 0; - uint32_t imageSize = 0; - uint32_t imageCrc = 0; - uint32_t numberOfPackets = 0; - - void initPacket() { - size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&imageSelect, &data_field_ptr, &serializedSize, - sizeof(imageSelect), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&imagePartition, &data_field_ptr, &serializedSize, - sizeof(imagePartition), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&imageSize, &data_field_ptr, &serializedSize, - sizeof(imageSize), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&imageCrc, &data_field_ptr, &serializedSize, - sizeof(imageCrc), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&numberOfPackets, &data_field_ptr, &serializedSize, - sizeof(numberOfPackets), SerializeIF::Endianness::BIG); - serializedSize = 0; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - uint8_t* crcPos = this->localData.fields.buffer + CRC_OFFSET; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); - } -}; - /** * @brief With this class the space packet can be generated to disable to periodic transmission * of housekeeping data. Normally, this will be disabled by default. However, adding this @@ -503,112 +555,17 @@ class DisablePeriodicHkTransmission : public SpacePacket { static const uint16_t DATA_FIELD_LENGTH = 3; void initPacket() { - uint8_t* data_field_ptr = this->localData.fields.buffer; - *data_field_ptr = disableHk; + uint8_t* dataFieldPtr = this->localData.fields.buffer; + *dataFieldPtr = disableHk; uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); size_t serializedSize = 0; - uint8_t* crcPtr = data_field_ptr + 1; + uint8_t* crcPtr = dataFieldPtr + 1; SerializeAdapter::serialize(&crc, &crcPtr, &serializedSize, sizeof(crc), SerializeIF::Endianness::BIG); } }; -/** - * @brief This class packages the command to enable the watchdogs of the PLOC. - */ -class WatchdogsEnable : public SpacePacket { - public: - /** - * @brief Constructor - * - * @param watchdogPs Enables processing system watchdog - * @param watchdogPl Enables programmable logic wathdog - * @param watchdogInt - */ - WatchdogsEnable(uint8_t watchdogPs, uint8_t watchdogPl, uint8_t watchdogInt) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_WTD_ENABLE, DEFAULT_SEQUENCE_COUNT), - watchdogPs(watchdogPs), - watchdogPl(watchdogPl), - watchdogInt(watchdogInt) { - initPacket(); - } - - private: - static const uint16_t DATA_FIELD_LENGTH = 5; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - - uint8_t watchdogPs = 0; - uint8_t watchdogPl = 0; - uint8_t watchdogInt = 0; - - void initPacket() { - size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&watchdogPs, &data_field_ptr, &serializedSize, - sizeof(watchdogPs), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&watchdogPl, &data_field_ptr, &serializedSize, - sizeof(watchdogPl), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&watchdogInt, &data_field_ptr, &serializedSize, - sizeof(watchdogInt), SerializeIF::Endianness::BIG); - serializedSize = 0; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - uint8_t* crcPos = this->localData.fields.buffer + CRC_OFFSET; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); - } -}; - -/** - * @brief This class packages the command to set the timeout of one of the three watchdogs (PS, - * PL, INT) - */ -class WatchdogsConfigTimeout : public SpacePacket { - public: - /** - * @brief Constructor - * - * @param watchdogPs Selects the watchdog to configure (0 - PS, 1 - PL, 2 - INT) - * @param timeout The timeout to set - */ - WatchdogsConfigTimeout(uint8_t watchdog, uint32_t timeout) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_WTD_CONFIG_TIMEOUT, DEFAULT_SEQUENCE_COUNT), - watchdog(watchdog), - timeout(timeout) { - initPacket(); - } - - private: - static const uint16_t DATA_FIELD_LENGTH = 7; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - - uint8_t watchdog = 0; - uint32_t timeout = 0; - - void initPacket() { - size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&watchdog, &data_field_ptr, &serializedSize, - sizeof(watchdog), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&timeout, &data_field_ptr, &serializedSize, - sizeof(timeout), SerializeIF::Endianness::BIG); - serializedSize = 0; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - uint8_t* crcPos = this->localData.fields.buffer + CRC_OFFSET; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); - } -}; - /** * @brief This class packages the command to enable of disable the latchup alert. * @@ -656,51 +613,6 @@ class LatchupAlert : public SpacePacket { } }; -/** - * @brief This class packages the command to calibrate a certain latchup alert. - */ -class AutoCalibrateAlert : public SpacePacket { - public: - /** - * @brief Constructor - * - * @param latchupId Identifies the latchup alert to calibrate (0 - 0.85V, 1 - 1.8V, 2 - MISC, - * 3 - 3.3V, 4 - NVM_4XO, 5 - MISSION, 6 - SAFECOTS) - * @param mg - */ - AutoCalibrateAlert(uint8_t latchupId, uint32_t mg) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_AUTO_CALIBRATE_ALERT, DEFAULT_SEQUENCE_COUNT), - latchupId(latchupId), - mg(mg) { - initPacket(); - } - - private: - static const uint16_t DATA_FIELD_LENGTH = 7; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - - uint8_t latchupId = 0; - uint32_t mg = 0; - - void initPacket() { - size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&latchupId, &data_field_ptr, &serializedSize, - sizeof(latchupId), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&mg, &data_field_ptr, &serializedSize, sizeof(mg), - SerializeIF::Endianness::BIG); - serializedSize = 0; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - uint8_t* crcPos = this->localData.fields.buffer + CRC_OFFSET; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); - } -}; - class SetAlertlimit : public SpacePacket { public: /** @@ -728,11 +640,11 @@ class SetAlertlimit : public SpacePacket { void initPacket() { size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&latchupId, &data_field_ptr, &serializedSize, + uint8_t* dataFieldPtr = this->localData.fields.buffer; + SerializeAdapter::serialize(&latchupId, &dataFieldPtr, &serializedSize, sizeof(latchupId), SerializeIF::Endianness::BIG); serializedSize = 0; - SerializeAdapter::serialize(&dutycycle, &data_field_ptr, &serializedSize, + SerializeAdapter::serialize(&dutycycle, &dataFieldPtr, &serializedSize, sizeof(dutycycle), SerializeIF::Endianness::BIG); serializedSize = 0; uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, @@ -743,91 +655,6 @@ class SetAlertlimit : public SpacePacket { } }; -class SetAlertIrqFilter : public SpacePacket { - public: - /** - * @brief Constructor - * - * @param latchupId Identifies the latchup alert to calibrate (0 - 0.85V, 1 - 1.8V, 2 - MISC, - * 3 - 3.3V, 4 - NVM_4XO, 5 - MISSION, 6 - SAFECOTS) - * @param tp - * @param div - */ - SetAlertIrqFilter(uint8_t latchupId, uint8_t tp, uint8_t div) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_ALERT_IRQ_FILTER, DEFAULT_SEQUENCE_COUNT), - tp(tp), - div(div) { - initPacket(); - } - - private: - static const uint16_t DATA_FIELD_LENGTH = 5; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - - uint8_t latchupId = 0; - uint8_t tp = 0; - uint8_t div = 0; - - void initPacket() { - size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&latchupId, &data_field_ptr, &serializedSize, - sizeof(latchupId), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&tp, &data_field_ptr, &serializedSize, sizeof(tp), - SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&div, &data_field_ptr, &serializedSize, sizeof(div), - SerializeIF::Endianness::BIG); - serializedSize = 0; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - uint8_t* crcPos = this->localData.fields.buffer + CRC_OFFSET; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); - } -}; - -/** - * @brief This class packages the space packet to set the sweep period of the ADC. - */ -class SetAdcSweepPeriod : public SpacePacket { - public: - /** - * @brief Constructor - * - * @param sweepPeriod Sweep period in us. minimum is 21 us - */ - SetAdcSweepPeriod(uint32_t sweepPeriod) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_ADC_SWEEP_PERIOD, DEFAULT_SEQUENCE_COUNT), - sweepPeriod(sweepPeriod) { - initPacket(); - } - - private: - static const uint16_t DATA_FIELD_LENGTH = 6; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - - uint32_t sweepPeriod = 0; - - void initPacket() { - size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&sweepPeriod, &data_field_ptr, &serializedSize, - sizeof(sweepPeriod), SerializeIF::Endianness::BIG); - serializedSize = 0; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - uint8_t* crcPos = this->localData.fields.buffer + CRC_OFFSET; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); - } -}; - /** * @brief This class packages the space packet to enable or disable ADC channels. */ @@ -855,8 +682,8 @@ class SetAdcEnabledChannels : public SpacePacket { void initPacket() { size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&ch, &data_field_ptr, &serializedSize, sizeof(ch), + uint8_t* dataFieldPtr = this->localData.fields.buffer; + SerializeAdapter::serialize(&ch, &dataFieldPtr, &serializedSize, sizeof(ch), SerializeIF::Endianness::BIG); serializedSize = 0; uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, @@ -898,11 +725,11 @@ class SetAdcWindowAndStride : public SpacePacket { void initPacket() { size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&windowSize, &data_field_ptr, &serializedSize, + uint8_t* dataFieldPtr = this->localData.fields.buffer; + SerializeAdapter::serialize(&windowSize, &dataFieldPtr, &serializedSize, sizeof(windowSize), SerializeIF::Endianness::BIG); serializedSize = 0; - SerializeAdapter::serialize(&stridingStepSize, &data_field_ptr, &serializedSize, + SerializeAdapter::serialize(&stridingStepSize, &dataFieldPtr, &serializedSize, sizeof(stridingStepSize), SerializeIF::Endianness::BIG); serializedSize = 0; uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, @@ -939,8 +766,8 @@ class SetAdcThreshold : public SpacePacket { void initPacket() { size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&threshold, &data_field_ptr, &serializedSize, + uint8_t* dataFieldPtr = this->localData.fields.buffer; + SerializeAdapter::serialize(&threshold, &dataFieldPtr, &serializedSize, sizeof(threshold), SerializeIF::Endianness::BIG); serializedSize = 0; uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, @@ -951,88 +778,6 @@ class SetAdcThreshold : public SpacePacket { } }; -/** - * @brief This class packages the space packet to select between NVM 0 and NVM 1. - */ -class SelectNvm : public SpacePacket { - public: - /** - * @brief Constructor - * - * @param mem 0 - select NVM0, 1 - select NVM1. - */ - SelectNvm(uint8_t mem) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SELECT_NVM, DEFAULT_SEQUENCE_COUNT), - mem(mem) { - initPacket(); - } - - private: - static const uint16_t DATA_FIELD_LENGTH = 3; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - - uint8_t mem = 0; - - void initPacket() { - size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&mem, &data_field_ptr, &serializedSize, sizeof(mem), - SerializeIF::Endianness::BIG); - serializedSize = 0; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - uint8_t* crcPos = this->localData.fields.buffer + CRC_OFFSET; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); - } -}; - -/** - * @brief This class packages the space packet to power the NVMs on or off. - */ -class EnableNvms : public SpacePacket { - public: - /** - * @brief Constructor - * - * @param n01 Set to one to power NVM0 and NVM1 on. 0 powers off memory. - * @param n3 Set to one to power NVM3 on. 0 powers off the memory. - */ - EnableNvms(uint8_t n01, uint8_t n3) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_ENABLE_NVMS, DEFAULT_SEQUENCE_COUNT), - n01(n01), - n3(n3) { - initPacket(); - } - - private: - static const uint16_t DATA_FIELD_LENGTH = 4; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - - uint8_t n01 = 0; - uint8_t n3 = 0; - - void initPacket() { - size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&n01, &data_field_ptr, &serializedSize, sizeof(n01), - SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&n3, &data_field_ptr, &serializedSize, sizeof(n3), - SerializeIF::Endianness::BIG); - serializedSize = 0; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - uint8_t* crcPos = this->localData.fields.buffer + CRC_OFFSET; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); - } -}; - /** * @brief This class packages the space packet to run auto EM tests. */ @@ -1059,86 +804,8 @@ class RunAutoEmTests : public SpacePacket { void initPacket() { size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&test, &data_field_ptr, &serializedSize, sizeof(test), - SerializeIF::Endianness::BIG); - serializedSize = 0; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - uint8_t* crcPos = this->localData.fields.buffer + CRC_OFFSET; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); - } -}; - -/** - * @brief This class packages the space packet causing the supervisor to print the CPU load to - * the debug output. - */ -class PrintCpuStats : public SpacePacket { - public: - /** - * @brief Constructor - * - * @param en Print is enabled if en != 0 - */ - PrintCpuStats(uint8_t en) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_PRINT_CPU_STATS, DEFAULT_SEQUENCE_COUNT), - en(en) { - initPacket(); - } - - private: - static const uint16_t DATA_FIELD_LENGTH = 3; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - - uint8_t en = 0; - - void initPacket() { - size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&en, &data_field_ptr, &serializedSize, sizeof(en), - SerializeIF::Endianness::BIG); - serializedSize = 0; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - uint8_t* crcPos = this->localData.fields.buffer + CRC_OFFSET; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); - } -}; - -/** - * @brief This class packages the space packet to set the print verbosity in the supervisor - * software. - */ -class SetDbgVerbosity : public SpacePacket { - public: - /** - * @brief Constructor - * - * @param vb 0: None, 1: Error, 2: Warn, 3: Info - */ - SetDbgVerbosity(uint8_t vb) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_DBG_VERBOSITY, DEFAULT_SEQUENCE_COUNT), - vb(vb) { - initPacket(); - } - - private: - static const uint16_t DATA_FIELD_LENGTH = 3; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - - uint8_t vb = 0; - - void initPacket() { - size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&vb, &data_field_ptr, &serializedSize, sizeof(vb), + uint8_t* dataFieldPtr = this->localData.fields.buffer; + SerializeAdapter::serialize(&test, &dataFieldPtr, &serializedSize, sizeof(test), SerializeIF::Endianness::BIG); serializedSize = 0; uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, @@ -1196,8 +863,8 @@ class MramCmd : public SpacePacket { concatBuffer[3] = static_cast(stop >> 16); concatBuffer[4] = static_cast(stop >> 8); concatBuffer[5] = static_cast(stop); - uint8_t* data_field_ptr = this->localData.fields.buffer; - std::memcpy(data_field_ptr, concatBuffer, sizeof(concatBuffer)); + uint8_t* dataFieldPtr = this->localData.fields.buffer; + std::memcpy(dataFieldPtr, concatBuffer, sizeof(concatBuffer)); size_t serializedSize = 0; uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); @@ -1240,14 +907,14 @@ class SetGpio : public SpacePacket { void initPacket() { size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&port, &data_field_ptr, &serializedSize, sizeof(port), + uint8_t* dataFieldPtr = this->localData.fields.buffer; + SerializeAdapter::serialize(&port, &dataFieldPtr, &serializedSize, sizeof(port), SerializeIF::Endianness::BIG); serializedSize = 0; - SerializeAdapter::serialize(&pin, &data_field_ptr, &serializedSize, sizeof(pin), + SerializeAdapter::serialize(&pin, &dataFieldPtr, &serializedSize, sizeof(pin), SerializeIF::Endianness::BIG); serializedSize = 0; - SerializeAdapter::serialize(&val, &data_field_ptr, &serializedSize, sizeof(val), + SerializeAdapter::serialize(&val, &dataFieldPtr, &serializedSize, sizeof(val), SerializeIF::Endianness::BIG); serializedSize = 0; uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, @@ -1288,11 +955,11 @@ class ReadGpio : public SpacePacket { void initPacket() { size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&port, &data_field_ptr, &serializedSize, sizeof(port), + uint8_t* dataFieldPtr = this->localData.fields.buffer; + SerializeAdapter::serialize(&port, &dataFieldPtr, &serializedSize, sizeof(port), SerializeIF::Endianness::BIG); serializedSize = 0; - SerializeAdapter::serialize(&pin, &data_field_ptr, &serializedSize, sizeof(pin), + SerializeAdapter::serialize(&pin, &dataFieldPtr, &serializedSize, sizeof(pin), SerializeIF::Endianness::BIG); serializedSize = 0; uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, @@ -1333,16 +1000,16 @@ class FactoryReset : public SpacePacket { Op op = Op::CLEAR_ALL; void initPacket() { - uint8_t* data_field_ptr = this->localData.fields.buffer; + uint8_t* dataFieldPtr = this->localData.fields.buffer; switch (op) { case Op::MIRROR_ENTRIES: - *data_field_ptr = 1; + *dataFieldPtr = 1; packetLen = 2; crcOffset = 1; break; case Op::CIRCULAR_ENTRIES: - *data_field_ptr = 2; + *dataFieldPtr = 2; packetLen = 2; crcOffset = 1; break; @@ -1361,7 +1028,12 @@ class FactoryReset : public SpacePacket { class SupvTcSpacePacket : public SpacePacket { public: - SupvTcSpacePacket(size_t payloadDataLen, uint16_t apid) + /** + * @brief Constructor + * + * @param payloadDataLen Length of data field without CRC + */ + SupvTcSpacePacket(uint16_t payloadDataLen, uint16_t apid) : SpacePacket(payloadDataLen + 1, true, apid, DEFAULT_SEQUENCE_COUNT), payloadDataLen(payloadDataLen) {} @@ -1382,79 +1054,644 @@ class SupvTcSpacePacket : public SpacePacket { size_t payloadDataLen = 0; }; -/** - * @brief This class can be used to package the update available or update verify command. - */ -class UpdateInfo : public SupvTcSpacePacket { +class SetShutdownTimeout : public SupvTcSpacePacket { public: - /** - * @brief Constructor - * - * @param apid Packet can be used to generate the update available and the update verify - * packet. Thus the APID must be specified here. - * @param image The image to update on a NVM (A - 0, B - 1) - * @param partition The partition to update. uboot - 1, bitstream - 2, linux - 3, - * application - 4 - * @param imageSize The size of the update image - * param numPackets The number of space packets required to transfer all data. - */ - UpdateInfo(uint16_t apid, uint8_t image, uint8_t partition, uint32_t imageSize, uint32_t imageCrc, - uint32_t numPackets) - : SupvTcSpacePacket(PAYLOAD_LENGTH, apid), - image(image), - partition(partition), - imageSize(imageSize), - imageCrc(imageCrc), - numPackets(numPackets) { + SetShutdownTimeout(uint32_t timeout) + : SupvTcSpacePacket(PACKET_LEN, APID_SET_SHUTDOWN_TIMEOUT), timeout(timeout) { initPacket(); makeCrc(); } private: - static const uint16_t PAYLOAD_LENGTH = 14; // length without CRC field + static const uint16_t PACKET_LEN = 4; // uint32_t timeout - uint8_t image = 0; - uint8_t partition = 0; - uint32_t imageSize = 0; - uint32_t imageCrc = 0; - uint32_t numPackets = 0; + uint32_t timeout = 0; + + void initPacket() { + uint8_t* dataFieldPtr = this->localData.fields.buffer; + size_t serializedSize = 0; + SerializeAdapter::serialize(&timeout, dataFieldPtr, &serializedSize, sizeof(timeout), + SerializeIF::Endianness::BIG); + } +}; + +/** + * @brief Command to request CRC over memory region of the supervisor. + */ +class CheckMemory : public SupvTcSpacePacket { + public: + /** + * @brief Constructor + * + * @param memoryId + * @param startAddress Start address of CRC calculation + * @param length Length in bytes of memory region + */ + CheckMemory(uint8_t memoryId, uint32_t startAddress, uint32_t length) + : SupvTcSpacePacket(PAYLOAD_LENGTH, APID_CHECK_MEMORY), + memoryId(memoryId), + startAddress(startAddress), + length(length) { + initPacket(); + makeCrc(); + } + + private: + static const uint16_t PAYLOAD_LENGTH = 10; // length without CRC field + + uint8_t memoryId = 0; + uint8_t n = 1; + uint32_t startAddress = 0; + uint32_t length = 0; void initPacket() { size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&image, &data_field_ptr, &serializedSize, sizeof(image), + uint8_t* dataFieldPtr = this->localData.fields.buffer; + SerializeAdapter::serialize(&memoryId, &dataFieldPtr, &serializedSize, + sizeof(memoryId), SerializeIF::Endianness::BIG); + serializedSize = 0; + SerializeAdapter::serialize(&n, &dataFieldPtr, &serializedSize, sizeof(n), SerializeIF::Endianness::BIG); serializedSize = 0; - SerializeAdapter::serialize(&partition, &data_field_ptr, &serializedSize, - sizeof(partition), SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(&startAddress, &dataFieldPtr, &serializedSize, + sizeof(startAddress), SerializeIF::Endianness::BIG); serializedSize = 0; - SerializeAdapter::serialize(&imageSize, &data_field_ptr, &serializedSize, - sizeof(imageSize), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&imageCrc, &data_field_ptr, &serializedSize, - sizeof(imageCrc), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&numPackets, &data_field_ptr, &serializedSize, - sizeof(numPackets), SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(&length, &dataFieldPtr, &serializedSize, sizeof(length), + SerializeIF::Endianness::BIG); } }; /** * @brief This class packages the space packet transporting a part of an MPSoC update. */ -class UpdatePacket : public SupvTcSpacePacket { +class WriteMemory : public SupvTcSpacePacket { public: /** * @brief Constructor * - * @param payloadLength Update data length (data field length without CRC) + * @param seqFlags Sequence flags + * @param sequenceCount Sequence count (first update packet expects 1 as sequence count) + * @param updateData Pointer to buffer containing update data */ - UpdatePacket(uint16_t payloadLength) : SupvTcSpacePacket(payloadLength, APID_UPDATE_IMAGE_DATA) {} + WriteMemory(SequenceFlags seqFlags, uint16_t sequenceCount, uint8_t memoryId, + uint32_t startAddress, uint16_t length, uint8_t* updateData) + : SupvTcSpacePacket(META_DATA_LENGTH + length, APID_WRITE_MEMORY), + memoryId(memoryId), + startAddress(startAddress), + length(length) { + if (this->length > CHUNK_MAX) { + sif::error << "WriteMemory::WriteMemory: Invalid length" << std::endl; + } + initPacket(updateData); + this->setSequenceFlags(static_cast(seqFlags)); + this->setPacketSequenceCount(sequenceCount); + makeCrc(); + } + + // Although the space packet has space left for 1010 bytes of data to supervisor can only process + // update packets with a maximum of 512 bytes. + static const uint16_t CHUNK_MAX = 512; + + private: + static const uint16_t META_DATA_LENGTH = 8; + + uint8_t memoryId = 0; + uint8_t n = 1; + uint32_t startAddress = 0; + uint16_t length = 0; + + void initPacket(uint8_t* updateData) { + size_t serializedSize = 0; + uint8_t* dataFieldPtr = this->localData.fields.buffer; + SerializeAdapter::serialize(&memoryId, &dataFieldPtr, &serializedSize, + sizeof(memoryId), SerializeIF::Endianness::BIG); + serializedSize = 0; + SerializeAdapter::serialize(&n, &dataFieldPtr, &serializedSize, sizeof(n), + SerializeIF::Endianness::BIG); + serializedSize = 0; + SerializeAdapter::serialize(&startAddress, &dataFieldPtr, &serializedSize, + sizeof(startAddress), SerializeIF::Endianness::BIG); + serializedSize = 0; + SerializeAdapter::serialize(&length, &dataFieldPtr, &serializedSize, sizeof(length), + SerializeIF::Endianness::BIG); + std::memcpy(dataFieldPtr, updateData, length); + if (length % 2 != 0) { + this->setPacketDataLength(length + sizeof(CCSDSPrimaryHeader) + CRC_SIZE - 1); + // The data field must be two bytes aligned. Thus, in case the number of bytes to write is odd + // a value of zero is added here + *(dataFieldPtr + length + 1) = 0; + } + } +}; + +/** + * @brief This class can be used to package the update available or update verify command. + */ +class EraseMemory : public SupvTcSpacePacket { + public: + EraseMemory(uint8_t memoryId, uint32_t startAddress, uint32_t length) + : SupvTcSpacePacket(PAYLOAD_LENGTH, APID_ERASE_MEMORY), + memoryId(memoryId), + startAddress(startAddress), + length(length) { + initPacket(); + makeCrc(); + } + + private: + static const uint16_t PAYLOAD_LENGTH = 10; // length without CRC field + + uint8_t memoryId = 0; + uint8_t n = 1; + uint32_t startAddress = 0; + uint32_t length = 0; + + void initPacket() { + size_t serializedSize = 0; + uint8_t* dataFieldPtr = this->localData.fields.buffer; + SerializeAdapter::serialize(&memoryId, &dataFieldPtr, &serializedSize, + sizeof(memoryId), SerializeIF::Endianness::BIG); + serializedSize = 0; + SerializeAdapter::serialize(&n, &dataFieldPtr, &serializedSize, sizeof(n), + SerializeIF::Endianness::BIG); + serializedSize = 0; + SerializeAdapter::serialize(&startAddress, &dataFieldPtr, &serializedSize, + sizeof(startAddress), SerializeIF::Endianness::BIG); + serializedSize = 0; + SerializeAdapter::serialize(&length, &dataFieldPtr, &serializedSize, sizeof(length), + SerializeIF::Endianness::BIG); + } +}; + +/** + * @brief This class creates the space packet to enable the auto TM generation + */ +class EnableAutoTm : public SupvTcSpacePacket { + public: + EnableAutoTm() : SupvTcSpacePacket(PAYLOAD_LENGTH, APID_AUTO_TM) { + *(this->localData.fields.buffer) = ENABLE; + makeCrc(); + } + + private: + static const uint16_t PAYLOAD_LENGTH = 1; // length without CRC field + static const uint8_t ENABLE = 1; +}; + +/** + * @brief This class creates the space packet to disable the auto TM generation + */ +class DisableAutoTm : public SupvTcSpacePacket { + public: + DisableAutoTm() : SupvTcSpacePacket(PAYLOAD_LENGTH, APID_AUTO_TM) { + *(this->localData.fields.buffer) = DISABLE; + makeCrc(); + } + + private: + static const uint16_t PAYLOAD_LENGTH = 1; // length without CRC field + static const uint8_t DISABLE = 0; +}; + +/** + * @brief This class creates the space packet to request the logging data from the supervisor + */ +class RequestLoggingData : public SupvTcSpacePacket { + public: + enum class Sa : uint8_t { + REQUEST_COUNTERS = 1, + REQUEST_EVENT_BUFFERS = 2, + CLEAR_COUNTERS = 3, + SET_LOGGING_TOPIC = 4 + }; + + RequestLoggingData(Sa sa, uint8_t tpc = 0) + : SupvTcSpacePacket(PAYLOAD_LENGTH, APID_REQUEST_LOGGING_DATA) { + *(this->localData.fields.buffer) = static_cast(sa); + *(this->localData.fields.buffer + TPC_OFFSET) = tpc; + makeCrc(); + } + + private: + static const uint16_t PAYLOAD_LENGTH = 2; // length without CRC field + static const uint8_t TPC_OFFSET = 1; +}; + +/** + * @brief Class for handling tm replies of the supervisor. + */ +class TmPacket : public SpacePacket { + public: + /** + * @brief Constructor creates idle packet and sets length field to maximum allowed size. + */ + TmPacket() : SpacePacket(PACKET_MAX_SIZE) {} /** - * @brief Returns the pointer to the beginning of the data field. + * @brief Returns the payload data length (data field length without CRC) */ - uint8_t* getDataFieldPointer() { return this->localData.fields.buffer; } + uint16_t getPayloadDataLength() { return this->getPacketDataLength() - 1; } + + ReturnValue_t checkCrc() { + uint8_t* crcPtr = this->getPacketData() + this->getPayloadDataLength(); + uint16_t receivedCrc = *(crcPtr) << 8 | *(crcPtr + 1); + uint16_t recalculatedCrc = + CRC::crc16ccitt(this->localData.byteStream, this->getFullSize() - CRC_SIZE); + if (recalculatedCrc != receivedCrc) { + return SupvReturnValuesIF::CRC_FAILURE; + } + return HasReturnvaluesIF::RETURN_OK; + } +}; + +class VerificationReport : public TmPacket { + public: + VerificationReport() : TmPacket() {} + + /** + * @brief Gets the APID of command which caused the transmission of this verification report. + */ + uint16_t getRefApid() { + uint16_t refApid = 0; + size_t size = 0; + uint8_t* refApidPtr = this->getPacketData(); + ReturnValue_t result = + SerializeAdapter::deSerialize(&refApid, refApidPtr, &size, SerializeIF::Endianness::BIG); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::debug << "ExecutionReport: Failed to deserialize reference APID field" << std::endl; + return result; + } + return refApid; + } + + uint16_t getStatusCode() { + uint16_t statusCode = 0; + size_t size = 0; + uint8_t* statusCodePtr = this->getPacketData() + OFFSET_STATUS_CODE; + ReturnValue_t result = SerializeAdapter::deSerialize(&statusCode, statusCodePtr, &size, + SerializeIF::Endianness::BIG); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::debug << "ExecutionReport: Failed to deserialize status code field" << std::endl; + return result; + } + return statusCode; + } + + virtual ReturnValue_t checkApid() { return HasReturnvaluesIF::RETURN_FAILED; } + + private: + static const uint8_t OFFSET_STATUS_CODE = 4; +}; + +class AcknowledgmentReport : public VerificationReport { + public: + AcknowledgmentReport() : VerificationReport() {} + + ReturnValue_t checkApid() { + uint16_t apid = this->getAPID(); + if (apid == APID_ACK_SUCCESS) { + return HasReturnvaluesIF::RETURN_OK; + } else if (apid == APID_ACK_FAILURE) { + printStatusInformation(); + return SupvReturnValuesIF::RECEIVED_ACK_FAILURE; + } else { + sif::warning << "AcknowledgmentReport::checkApid: Invalid apid: 0x" << std::hex << apid + << std::endl; + return SupvReturnValuesIF::INVALID_APID; + } + } + + void printStatusInformation() { + StatusCode statusCode = static_cast(getStatusCode()); + switch (statusCode) { + case StatusCode::OK: { + sif::warning << "Supervisor acknowledgment report status: Ok" << std::endl; + break; + } + case StatusCode::BAD_PARAM: { + sif::warning << "Supervisor acknowledgment report status: Bad param" << std::endl; + break; + } + case StatusCode::TIMEOUT: { + sif::warning << "Supervisor acknowledgment report status: Timeout" << std::endl; + break; + } + case StatusCode::RX_ERROR: { + sif::warning << "Supervisor acknowledgment report status: RX error" << std::endl; + break; + } + case StatusCode::TX_ERROR: { + sif::warning << "Supervisor acknowledgment report status: TX error" << std::endl; + break; + } + case StatusCode::HEADER_EMPTY: { + sif::warning << "Supervisor acknowledgment report status: Header empty" << std::endl; + break; + } + case StatusCode::DEFAULT_NAK: { + sif::warning << "Supervisor acknowledgment report status: Default code for nak" + << std::endl; + break; + } + case StatusCode::ROUTE_PACKET: { + sif::warning << "Supervisor acknowledgment report status: Route packet error" << std::endl; + break; + } + default: + sif::warning << "AcknowledgmentReport::printStatusInformation: Invalid status code: 0x" + << std::hex << static_cast(statusCode) << std::endl; + break; + } + } + + private: + enum class StatusCode : uint16_t { + OK = 0x0, + BAD_PARAM = 0x1, + TIMEOUT = 0x2, + RX_ERROR = 0x3, + TX_ERROR = 0x4, + HEADER_EMPTY = 0x5, + DEFAULT_NAK = 0x6, + ROUTE_PACKET = 0x7 + }; +}; + +class ExecutionReport : public VerificationReport { + public: + ExecutionReport() : VerificationReport() {} + + ReturnValue_t checkApid() { + uint16_t apid = this->getAPID(); + if (apid == APID_EXE_SUCCESS) { + return HasReturnvaluesIF::RETURN_OK; + } else if (apid == APID_EXE_FAILURE) { + printStatusInformation(); + return SupvReturnValuesIF::RECEIVED_EXE_FAILURE; + } else { + sif::warning << "ExecutionReport::checkApid: Invalid apid: 0x" << std::hex << apid + << std::endl; + return SupvReturnValuesIF::INVALID_APID; + } + } + + private: + static constexpr char STATUS_PRINTOUT_PREFIX[] = "Supervisor execution failure report status: "; + + enum class StatusCode : uint16_t { + OK = 0x0, + INIT_ERROR = 0x1, + BAD_PARAM = 0x2, + NOT_INITIALIZED = 0x3, + BAD_PERIPH_ID = 0x4, + TIMEOUT = 0x5, + RX_ERROR = 0x6, + TX_ERROR = 0x7, + BUF_EMPTY = 0x8, + BUF_FULL = 0x9, + NAK = 0xA, + ARB_LOST = 0xB, + BUSY = 0xC, + NOT_IMPLEMENTED = 0xD, + ALIGNEMENT_ERROR = 0xE, + PERIPH_ERR = 0xF, + FAILED_LATCH = 0x10, + GPIO_HIGH = 0x11, + GPIO_LOW = 0x12, + TEST_PASSED = 0x13, + TEST_FAILED = 0x14, + NOTHING_TODO = 0x100, + POWER_FAULT = 0x101, + INVALID_LENGTH = 0x102, + OUT_OF_RANGE = 0x103, + OUT_OF_HEAP_MEMORY = 0x104, + INVALID_STATE_TRANSITION = 0x105, + MPSOC_ALREADY_BOOTING = 0x106, + MPSOC_ALREADY_OPERATIONAL = 0x107, + MPSOC_BOOT_FAILED = 0x108, + SP_NOT_AVAILABLE = 0x200, + SP_DATA_INSUFFICIENT = 0x201, + SP_MEMORY_ID_INVALID = 0x202, + MPSOC_NOT_IN_RESET = 0x203, + FLASH_INIT_FAILED = 0x204, + FLASH_ERASE_FAILED = 0x205, + FLASH_WRITE_FAILED = 0x206, + FLASH_VERIFY_FAILED = 0x207, + CANNOT_ACCESS_TM = 0x208, + CANNOT_SEND_TM = 0x209, + PG_LOW = 0x300, + PG_5V_LOW = 0x301, + PG_0V85_LOW = 0x302, + PG_1V8_LOW = 0x303, + PG_MISC_LOW = 0x304, + PG_3V3_LOW = 0x305, + PG_MB_VAIO_LOW = 0x306, + PG_MB_MPSOCIO_LOW = 0x307 + }; + + void printStatusInformation() { + StatusCode statusCode = static_cast(getStatusCode()); + switch (statusCode) { + case StatusCode::OK: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Ok" << std::endl; + break; + } + case StatusCode::INIT_ERROR: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Init error" << std::endl; + break; + } + case StatusCode::BAD_PARAM: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Bad param" << std::endl; + break; + } + case StatusCode::NOT_INITIALIZED: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Not initialized" << std::endl; + break; + } + case StatusCode::BAD_PERIPH_ID: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Bad periph ID" << std::endl; + break; + } + case StatusCode::TIMEOUT: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Timeout" << std::endl; + break; + } + case StatusCode::RX_ERROR: { + sif::warning << STATUS_PRINTOUT_PREFIX << "RX error" << std::endl; + break; + } + case StatusCode::TX_ERROR: { + sif::warning << STATUS_PRINTOUT_PREFIX << "TX error" << std::endl; + break; + } + case StatusCode::BUF_EMPTY: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Buf empty" << std::endl; + break; + } + case StatusCode::BUF_FULL: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Buf full" << std::endl; + break; + } + case StatusCode::NAK: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Nak, default error code" << std::endl; + break; + } + case StatusCode::ARB_LOST: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Arb lost" << std::endl; + break; + } + case StatusCode::BUSY: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Busy" << std::endl; + break; + } + case StatusCode::NOT_IMPLEMENTED: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Not implemented" << std::endl; + break; + } + case StatusCode::ALIGNEMENT_ERROR: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Alignment error" << std::endl; + break; + } + case StatusCode::PERIPH_ERR: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Periph error" << std::endl; + break; + } + case StatusCode::FAILED_LATCH: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Failed latch" << std::endl; + break; + } + case StatusCode::GPIO_HIGH: { + sif::warning << STATUS_PRINTOUT_PREFIX << "GPIO high" << std::endl; + break; + } + case StatusCode::GPIO_LOW: { + sif::warning << STATUS_PRINTOUT_PREFIX << "GPIO low" << std::endl; + break; + } + case StatusCode::TEST_PASSED: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Test passed" << std::endl; + break; + } + case StatusCode::TEST_FAILED: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Test failed" << std::endl; + break; + } + case StatusCode::NOTHING_TODO: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Nothing todo, not an error but a warning" + << std::endl; + break; + } + case StatusCode::POWER_FAULT: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Power fault" << std::endl; + break; + } + case StatusCode::INVALID_LENGTH: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Invalid length" << std::endl; + break; + } + case StatusCode::OUT_OF_RANGE: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Out of range, lenght check of parameter failed" + << std::endl; + break; + } + case StatusCode::OUT_OF_HEAP_MEMORY: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Out of heap memory" << std::endl; + break; + } + case StatusCode::INVALID_STATE_TRANSITION: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Invalid state transition" << std::endl; + break; + } + case StatusCode::MPSOC_ALREADY_BOOTING: { + sif::warning << STATUS_PRINTOUT_PREFIX << "MPSoC already booting" << std::endl; + break; + } + case StatusCode::MPSOC_ALREADY_OPERATIONAL: { + sif::warning << STATUS_PRINTOUT_PREFIX << "MPSoC already operational" << std::endl; + break; + } + case StatusCode::MPSOC_BOOT_FAILED: { + sif::warning << STATUS_PRINTOUT_PREFIX << "MPSoC boot failed" << std::endl; + break; + } + case StatusCode::SP_NOT_AVAILABLE: { + sif::warning << STATUS_PRINTOUT_PREFIX << "SP not available" << std::endl; + break; + } + case StatusCode::SP_DATA_INSUFFICIENT: { + sif::warning << STATUS_PRINTOUT_PREFIX << "SP data insufficient" << std::endl; + break; + } + case StatusCode::SP_MEMORY_ID_INVALID: { + sif::warning << STATUS_PRINTOUT_PREFIX << "SP data insufficient" << std::endl; + break; + } + case StatusCode::MPSOC_NOT_IN_RESET: { + sif::warning << STATUS_PRINTOUT_PREFIX << "MPSoC not in reset" << std::endl; + break; + } + case StatusCode::FLASH_INIT_FAILED: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Flash init failed" << std::endl; + break; + } + case StatusCode::FLASH_ERASE_FAILED: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Flash erase failed" << std::endl; + break; + } + case StatusCode::FLASH_WRITE_FAILED: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Flash write failed" << std::endl; + break; + } + case StatusCode::FLASH_VERIFY_FAILED: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Flash verify failed" << std::endl; + break; + } + case StatusCode::CANNOT_ACCESS_TM: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Can not access tm" << std::endl; + break; + } + case StatusCode::CANNOT_SEND_TM: { + sif::warning << STATUS_PRINTOUT_PREFIX << "Can not access tm" << std::endl; + break; + } + case StatusCode::PG_LOW: { + sif::warning << STATUS_PRINTOUT_PREFIX << "PG low" << std::endl; + break; + } + case StatusCode::PG_5V_LOW: { + sif::warning << STATUS_PRINTOUT_PREFIX << "PG 5V low" << std::endl; + break; + } + case StatusCode::PG_0V85_LOW: { + sif::warning << STATUS_PRINTOUT_PREFIX << "PG 0V85 low" << std::endl; + break; + } + case StatusCode::PG_1V8_LOW: { + sif::warning << STATUS_PRINTOUT_PREFIX << "PG 1V8 low" << std::endl; + break; + } + case StatusCode::PG_MISC_LOW: { + sif::warning << STATUS_PRINTOUT_PREFIX << "PG misc low" << std::endl; + break; + } + case StatusCode::PG_3V3_LOW: { + sif::warning << STATUS_PRINTOUT_PREFIX << "PG 3V3 low" << std::endl; + break; + } + case StatusCode::PG_MB_VAIO_LOW: { + sif::warning << STATUS_PRINTOUT_PREFIX << "PG mb vaio low" << std::endl; + break; + } + case StatusCode::PG_MB_MPSOCIO_LOW: { + sif::warning << STATUS_PRINTOUT_PREFIX << "PG mb mpsocio low" << std::endl; + break; + } + default: + sif::warning << "ExecutionReport::printStatusInformation: Invalid status code: 0x" + << std::hex << static_cast(statusCode) << std::endl; + break; + } + } }; /** @@ -1468,8 +1705,8 @@ class BootStatusReport : public StaticLocalDataSet { : StaticLocalDataSet(sid_t(objectId, BOOT_REPORT_SET_ID)) {} /** Information about boot status of MPSoC */ - lp_var_t bootSignal = lp_var_t(sid.objectId, PoolIds::BOOT_SIGNAL, this); - lp_var_t resetCounter = lp_var_t(sid.objectId, PoolIds::RESET_COUNTER, this); + lp_var_t socState = lp_var_t(sid.objectId, PoolIds::BR_SOC_STATE, this); + lp_var_t powerCycles = lp_var_t(sid.objectId, PoolIds::POWER_CYCLES, this); /** Time the MPSoC needs for last boot */ lp_var_t bootAfterMs = lp_var_t(sid.objectId, PoolIds::BOOT_AFTER_MS, this); /** The currently set boot timeout */ @@ -1480,6 +1717,8 @@ class BootStatusReport : public StaticLocalDataSet { lp_var_t bp0State = lp_var_t(sid.objectId, PoolIds::BP0_STATE, this); lp_var_t bp1State = lp_var_t(sid.objectId, PoolIds::BP1_STATE, this); lp_var_t bp2State = lp_var_t(sid.objectId, PoolIds::BP2_STATE, this); + lp_var_t bootState = lp_var_t(sid.objectId, PoolIds::BOOT_STATE, this); + lp_var_t bootCycles = lp_var_t(sid.objectId, PoolIds::BOOT_CYCLES, this); }; /** @@ -1487,6 +1726,8 @@ class BootStatusReport : public StaticLocalDataSet { */ class HkSet : public StaticLocalDataSet { public: + enum class SocState { OFF = 0, BOOTING = 1, OPERATIONAL = 3, SHUTDOWN = 4 }; + HkSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, HK_SET_ID) {} HkSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, HK_SET_ID)) {} @@ -1494,12 +1735,12 @@ class HkSet : public StaticLocalDataSet { lp_var_t tempPs = lp_var_t(sid.objectId, PoolIds::TEMP_PS, this); lp_var_t tempPl = lp_var_t(sid.objectId, PoolIds::TEMP_PS, this); lp_var_t tempSup = lp_var_t(sid.objectId, PoolIds::TEMP_SUP, this); - lp_var_t uptime = lp_var_t(sid.objectId, PoolIds::UPTIME, this); + lp_var_t uptime = lp_var_t(sid.objectId, PoolIds::UPTIME, this); lp_var_t cpuLoad = lp_var_t(sid.objectId, PoolIds::CPULOAD, this); lp_var_t availableHeap = lp_var_t(sid.objectId, PoolIds::AVAILABLEHEAP, this); lp_var_t numTcs = lp_var_t(sid.objectId, PoolIds::NUM_TCS, this); lp_var_t numTms = lp_var_t(sid.objectId, PoolIds::NUM_TMS, this); - lp_var_t socState = lp_var_t(sid.objectId, PoolIds::SOC_STATE, this); + lp_var_t socState = lp_var_t(sid.objectId, PoolIds::HK_SOC_STATE, this); lp_var_t nvm0_1_state = lp_var_t(sid.objectId, PoolIds::NVM0_1_STATE, this); lp_var_t nvm3_state = lp_var_t(sid.objectId, PoolIds::NVM3_STATE, this); lp_var_t missionIoState = @@ -1524,22 +1765,223 @@ class LatchupStatusReport : public StaticLocalDataSet { lp_var_t cnt4 = lp_var_t(sid.objectId, PoolIds::CNT4, this); lp_var_t cnt5 = lp_var_t(sid.objectId, PoolIds::CNT5, this); lp_var_t cnt6 = lp_var_t(sid.objectId, PoolIds::CNT6, this); - lp_var_t timeSec = - lp_var_t(sid.objectId, PoolIds::LATCHUP_RPT_TIME_SEC, this); - lp_var_t timeMin = - lp_var_t(sid.objectId, PoolIds::LATCHUP_RPT_TIME_MIN, this); - lp_var_t timeHour = - lp_var_t(sid.objectId, PoolIds::LATCHUP_RPT_TIME_HOUR, this); - lp_var_t timeDay = - lp_var_t(sid.objectId, PoolIds::LATCHUP_RPT_TIME_DAY, this); - lp_var_t timeMon = - lp_var_t(sid.objectId, PoolIds::LATCHUP_RPT_TIME_MON, this); - lp_var_t timeYear = - lp_var_t(sid.objectId, PoolIds::LATCHUP_RPT_TIME_YEAR, this); - lp_var_t timeMsec = - lp_var_t(sid.objectId, PoolIds::LATCHUP_RPT_TIME_MSEC, this); - lp_var_t isSet = - lp_var_t(sid.objectId, PoolIds::LATCHUP_RPT_TIME_IS_SET, this); + lp_var_t timeMsec = + lp_var_t(sid.objectId, PoolIds::LATCHUP_RPT_TIME_MSEC, this); + lp_var_t timeSec = lp_var_t(sid.objectId, PoolIds::LATCHUP_RPT_TIME_SEC, this); + lp_var_t timeMin = lp_var_t(sid.objectId, PoolIds::LATCHUP_RPT_TIME_MIN, this); + lp_var_t timeHour = + lp_var_t(sid.objectId, PoolIds::LATCHUP_RPT_TIME_HOUR, this); + lp_var_t timeDay = lp_var_t(sid.objectId, PoolIds::LATCHUP_RPT_TIME_DAY, this); + lp_var_t timeMon = lp_var_t(sid.objectId, PoolIds::LATCHUP_RPT_TIME_MON, this); + lp_var_t timeYear = + lp_var_t(sid.objectId, PoolIds::LATCHUP_RPT_TIME_YEAR, this); + lp_var_t isSet = lp_var_t(sid.objectId, PoolIds::LATCHUP_RPT_IS_SET, this); + + static const uint8_t IS_SET_BIT_POS = 15; +}; + +/** + * @brief This dataset stores the logging report. + */ +class LoggingReport : public StaticLocalDataSet { + public: + LoggingReport(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, LOGGING_RPT_ID) {} + + LoggingReport(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, LOGGING_RPT_ID)) {} + + lp_var_t latchupHappenCnt0 = + lp_var_t(sid.objectId, PoolIds::LATCHUP_HAPPENED_CNT_0, this); + lp_var_t latchupHappenCnt1 = + lp_var_t(sid.objectId, PoolIds::LATCHUP_HAPPENED_CNT_1, this); + lp_var_t latchupHappenCnt2 = + lp_var_t(sid.objectId, PoolIds::LATCHUP_HAPPENED_CNT_2, this); + lp_var_t latchupHappenCnt3 = + lp_var_t(sid.objectId, PoolIds::LATCHUP_HAPPENED_CNT_3, this); + lp_var_t latchupHappenCnt4 = + lp_var_t(sid.objectId, PoolIds::LATCHUP_HAPPENED_CNT_4, this); + lp_var_t latchupHappenCnt5 = + lp_var_t(sid.objectId, PoolIds::LATCHUP_HAPPENED_CNT_5, this); + lp_var_t latchupHappenCnt6 = + lp_var_t(sid.objectId, PoolIds::LATCHUP_HAPPENED_CNT_6, this); + lp_var_t adcDeviationTriggersCnt = + lp_var_t(sid.objectId, PoolIds::ADC_DEVIATION_TRIGGERS_CNT, this); + lp_var_t tcReceivedCnt = + lp_var_t(sid.objectId, PoolIds::TC_RECEIVED_CNT, this); + lp_var_t tmAvailableCnt = + lp_var_t(sid.objectId, PoolIds::TM_AVAILABLE_CNT, this); + lp_var_t supervisorBoots = + lp_var_t(sid.objectId, PoolIds::SUPERVISOR_BOOTS, this); + lp_var_t mpsocBoots = lp_var_t(sid.objectId, PoolIds::MPSOC_BOOTS, this); + lp_var_t mpsocBootFailedAttempts = + lp_var_t(sid.objectId, PoolIds::MPSOC_BOOT_FAILED_ATTEMPTS, this); + lp_var_t mpsocPowerup = lp_var_t(sid.objectId, PoolIds::MPSOC_POWER_UP, this); + lp_var_t mpsocUpdates = lp_var_t(sid.objectId, PoolIds::MPSOC_UPDATES, this); + lp_var_t lastRecvdTc = lp_var_t(sid.objectId, PoolIds::LAST_RECVD_TC, this); + + void printSet() { + sif::info << "LoggingReport: Latchup happened count 0: " << this->latchupHappenCnt0 + << std::endl; + sif::info << "LoggingReport: Latchup happened count 1: " << this->latchupHappenCnt1 + << std::endl; + sif::info << "LoggingReport: Latchup happened count 2: " << this->latchupHappenCnt2 + << std::endl; + sif::info << "LoggingReport: Latchup happened count 3: " << this->latchupHappenCnt3 + << std::endl; + sif::info << "LoggingReport: Latchup happened count 4: " << this->latchupHappenCnt4 + << std::endl; + sif::info << "LoggingReport: Latchup happened count 5: " << this->latchupHappenCnt5 + << std::endl; + sif::info << "LoggingReport: Latchup happened count 6: " << this->latchupHappenCnt6 + << std::endl; + sif::info << "LoggingReport: ADC deviation triggers count: " << this->adcDeviationTriggersCnt + << std::endl; + sif::info << "LoggingReport: TC received count: " << this->tcReceivedCnt << std::endl; + sif::info << "LoggingReport: TM available count: " << this->tmAvailableCnt << std::endl; + sif::info << "LoggingReport: Supervisor boots: " << this->supervisorBoots << std::endl; + sif::info << "LoggingReport: MPSoC boots: " << this->mpsocBoots << std::endl; + sif::info << "LoggingReport: MPSoC boot failed attempts: " << this->mpsocBootFailedAttempts + << std::endl; + sif::info << "LoggingReport: MPSoC power up: " << this->mpsocPowerup << std::endl; + sif::info << "LoggingReport: MPSoC updates: " << this->mpsocUpdates << std::endl; + sif::info << "LoggingReport: APID of last received TC: 0x" << std::hex << this->lastRecvdTc + << std::endl; + } +}; + +class UpdateStatusReport : public TmPacket { + public: + UpdateStatusReport() : TmPacket() {} + + ReturnValue_t parseDataField() { + ReturnValue_t result = lengthCheck(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + uint8_t* dataFieldPtr = this->localData.fields.buffer; + size_t size = sizeof(memoryId); + SerializeAdapter::deSerialize(&memoryId, dataFieldPtr, &size, SerializeIF::Endianness::BIG); + dataFieldPtr += size; + size = sizeof(n); + SerializeAdapter::deSerialize(&n, dataFieldPtr, &size, SerializeIF::Endianness::BIG); + dataFieldPtr += size; + size = sizeof(startAddress); + SerializeAdapter::deSerialize(&startAddress, dataFieldPtr, &size, SerializeIF::Endianness::BIG); + dataFieldPtr += size; + size = sizeof(length); + SerializeAdapter::deSerialize(&length, dataFieldPtr, &size, SerializeIF::Endianness::BIG); + dataFieldPtr += size; + size = sizeof(crc); + SerializeAdapter::deSerialize(&crc, dataFieldPtr, &size, SerializeIF::Endianness::BIG); + return HasReturnvaluesIF::RETURN_OK; + } + + ReturnValue_t verifycrc(uint16_t goodCrc) const { + if (crc != goodCrc) { + return SupvReturnValuesIF::UPDATE_CRC_FAILURE; + } + return HasReturnvaluesIF::RETURN_OK; + } + + uint16_t getCrc() const { return crc; } + + uint16_t getNominalSize() const { return FULL_SIZE; } + + private: + // Nominal size of the space packet + static const uint16_t FULL_SIZE = 20; // header, data field and crc + + uint8_t memoryId = 0; + uint8_t n = 0; + uint32_t startAddress = 0; + uint32_t length = 0; + uint16_t crc = 0; + + ReturnValue_t lengthCheck() { + if (this->getFullSize() != FULL_SIZE) { + return SupvReturnValuesIF::UPDATE_STATUS_REPORT_INVALID_LENGTH; + } + return HasReturnvaluesIF::RETURN_OK; + } +}; + +/** + * @brief This dataset stores the ADC report. + */ +class AdcReport : public StaticLocalDataSet { + public: + AdcReport(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, ADC_REPORT_SET_ID) {} + + AdcReport(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, ADC_REPORT_SET_ID)) {} + + lp_var_t adcRaw0 = lp_var_t(sid.objectId, PoolIds::ADC_RAW_0, this); + lp_var_t adcRaw1 = lp_var_t(sid.objectId, PoolIds::ADC_RAW_1, this); + lp_var_t adcRaw2 = lp_var_t(sid.objectId, PoolIds::ADC_RAW_2, this); + lp_var_t adcRaw3 = lp_var_t(sid.objectId, PoolIds::ADC_RAW_3, this); + lp_var_t adcRaw4 = lp_var_t(sid.objectId, PoolIds::ADC_RAW_4, this); + lp_var_t adcRaw5 = lp_var_t(sid.objectId, PoolIds::ADC_RAW_5, this); + lp_var_t adcRaw6 = lp_var_t(sid.objectId, PoolIds::ADC_RAW_6, this); + lp_var_t adcRaw7 = lp_var_t(sid.objectId, PoolIds::ADC_RAW_7, this); + lp_var_t adcRaw8 = lp_var_t(sid.objectId, PoolIds::ADC_RAW_8, this); + lp_var_t adcRaw9 = lp_var_t(sid.objectId, PoolIds::ADC_RAW_9, this); + lp_var_t adcRaw10 = lp_var_t(sid.objectId, PoolIds::ADC_RAW_10, this); + lp_var_t adcRaw11 = lp_var_t(sid.objectId, PoolIds::ADC_RAW_11, this); + lp_var_t adcRaw12 = lp_var_t(sid.objectId, PoolIds::ADC_RAW_12, this); + lp_var_t adcRaw13 = lp_var_t(sid.objectId, PoolIds::ADC_RAW_13, this); + lp_var_t adcRaw14 = lp_var_t(sid.objectId, PoolIds::ADC_RAW_14, this); + lp_var_t adcRaw15 = lp_var_t(sid.objectId, PoolIds::ADC_RAW_15, this); + lp_var_t adcEng0 = lp_var_t(sid.objectId, PoolIds::ADC_ENG_0, this); + lp_var_t adcEng1 = lp_var_t(sid.objectId, PoolIds::ADC_ENG_1, this); + lp_var_t adcEng2 = lp_var_t(sid.objectId, PoolIds::ADC_ENG_2, this); + lp_var_t adcEng3 = lp_var_t(sid.objectId, PoolIds::ADC_ENG_3, this); + lp_var_t adcEng4 = lp_var_t(sid.objectId, PoolIds::ADC_ENG_4, this); + lp_var_t adcEng5 = lp_var_t(sid.objectId, PoolIds::ADC_ENG_5, this); + lp_var_t adcEng6 = lp_var_t(sid.objectId, PoolIds::ADC_ENG_6, this); + lp_var_t adcEng7 = lp_var_t(sid.objectId, PoolIds::ADC_ENG_7, this); + lp_var_t adcEng8 = lp_var_t(sid.objectId, PoolIds::ADC_ENG_8, this); + lp_var_t adcEng9 = lp_var_t(sid.objectId, PoolIds::ADC_ENG_9, this); + lp_var_t adcEng10 = lp_var_t(sid.objectId, PoolIds::ADC_ENG_10, this); + lp_var_t adcEng11 = lp_var_t(sid.objectId, PoolIds::ADC_ENG_11, this); + lp_var_t adcEng12 = lp_var_t(sid.objectId, PoolIds::ADC_ENG_12, this); + lp_var_t adcEng13 = lp_var_t(sid.objectId, PoolIds::ADC_ENG_13, this); + lp_var_t adcEng14 = lp_var_t(sid.objectId, PoolIds::ADC_ENG_14, this); + lp_var_t adcEng15 = lp_var_t(sid.objectId, PoolIds::ADC_ENG_15, this); + + void printSet() { + sif::info << "---- Adc Report: Raw values ----" << std::endl; + sif::info << "AdcReport: ADC raw 0: " << std::dec << this->adcRaw0 << std::endl; + sif::info << "AdcReport: ADC raw 1: " << this->adcRaw1 << std::endl; + sif::info << "AdcReport: ADC raw 2: " << this->adcRaw2 << std::endl; + sif::info << "AdcReport: ADC raw 3: " << this->adcRaw3 << std::endl; + sif::info << "AdcReport: ADC raw 4: " << this->adcRaw4 << std::endl; + sif::info << "AdcReport: ADC raw 5: " << this->adcRaw5 << std::endl; + sif::info << "AdcReport: ADC raw 6: " << this->adcRaw6 << std::endl; + sif::info << "AdcReport: ADC raw 7: " << this->adcRaw7 << std::endl; + sif::info << "AdcReport: ADC raw 8: " << this->adcRaw8 << std::endl; + sif::info << "AdcReport: ADC raw 9: " << this->adcRaw9 << std::endl; + sif::info << "AdcReport: ADC raw 10: " << this->adcRaw10 << std::endl; + sif::info << "AdcReport: ADC raw 11: " << this->adcRaw11 << std::endl; + sif::info << "AdcReport: ADC raw 12: " << this->adcRaw12 << std::endl; + sif::info << "AdcReport: ADC raw 13: " << this->adcRaw13 << std::endl; + sif::info << "AdcReport: ADC raw 14: " << this->adcRaw14 << std::endl; + sif::info << "AdcReport: ADC raw 15: " << this->adcRaw15 << std::endl; + sif::info << "---- Adc Report: Engineering values ----" << std::endl; + sif::info << "AdcReport: ADC eng 0: " << this->adcEng0 << std::endl; + sif::info << "AdcReport: ADC eng 1: " << this->adcEng1 << std::endl; + sif::info << "AdcReport: ADC eng 2: " << this->adcEng2 << std::endl; + sif::info << "AdcReport: ADC eng 3: " << this->adcEng3 << std::endl; + sif::info << "AdcReport: ADC eng 4: " << this->adcEng4 << std::endl; + sif::info << "AdcReport: ADC eng 5: " << this->adcEng5 << std::endl; + sif::info << "AdcReport: ADC eng 6: " << this->adcEng6 << std::endl; + sif::info << "AdcReport: ADC eng 7: " << this->adcEng7 << std::endl; + sif::info << "AdcReport: ADC eng 8: " << this->adcEng8 << std::endl; + sif::info << "AdcReport: ADC eng 9: " << this->adcEng9 << std::endl; + sif::info << "AdcReport: ADC eng 10: " << this->adcEng10 << std::endl; + sif::info << "AdcReport: ADC eng 11: " << this->adcEng11 << std::endl; + sif::info << "AdcReport: ADC eng 12: " << this->adcEng12 << std::endl; + sif::info << "AdcReport: ADC eng 13: " << this->adcEng13 << std::endl; + sif::info << "AdcReport: ADC eng 14: " << this->adcEng14 << std::endl; + sif::info << "AdcReport: ADC eng 15: " << this->adcEng15 << std::endl; + } }; } // namespace supv diff --git a/linux/devices/devicedefinitions/SupvReturnValuesIF.h b/linux/devices/devicedefinitions/SupvReturnValuesIF.h new file mode 100644 index 00000000..307deb0e --- /dev/null +++ b/linux/devices/devicedefinitions/SupvReturnValuesIF.h @@ -0,0 +1,61 @@ +#ifndef SUPV_RETURN_VALUES_IF_H_ +#define SUPV_RETURN_VALUES_IF_H_ + +#include "fsfw/returnvalues/HasReturnvaluesIF.h" + +class SupvReturnValuesIF { + public: + static const uint8_t INTERFACE_ID = CLASS_ID::SUPV_RETURN_VALUES_IF; + + //! [EXPORT] : [COMMENT] Space Packet received from PLOC supervisor has invalid CRC + static const ReturnValue_t CRC_FAILURE = MAKE_RETURN_CODE(0xA0); + //! [EXPORT] : [COMMENT] Received ACK failure reply from PLOC supervisor + static const ReturnValue_t RECEIVED_ACK_FAILURE = MAKE_RETURN_CODE(0xA1); + //! [EXPORT] : [COMMENT] Received execution failure reply from PLOC supervisor + static const ReturnValue_t RECEIVED_EXE_FAILURE = MAKE_RETURN_CODE(0xA2); + //! [EXPORT] : [COMMENT] Received space packet with invalid APID from PLOC supervisor + static const ReturnValue_t INVALID_APID = MAKE_RETURN_CODE(0xA3); + //! [EXPORT] : [COMMENT] Failed to read current system time + static const ReturnValue_t GET_TIME_FAILURE = MAKE_RETURN_CODE(0xA4); + //! [EXPORT] : [COMMENT] Received command with invalid watchdog parameter. Valid watchdogs are 0 + //! for PS, 1 for PL and 2 for INT + static const ReturnValue_t INVALID_WATCHDOG = MAKE_RETURN_CODE(0xA5); + //! [EXPORT] : [COMMENT] Received watchdog timeout config command with invalid timeout. Valid + //! timeouts must be in the range between 1000 and 360000 ms. + static const ReturnValue_t INVALID_WATCHDOG_TIMEOUT = MAKE_RETURN_CODE(0xA6); + //! [EXPORT] : [COMMENT] Received latchup config command with invalid latchup ID + static const ReturnValue_t INVALID_LATCHUP_ID = MAKE_RETURN_CODE(0xA7); + //! [EXPORT] : [COMMENT] Received set adc sweep period command with invalid sweep period. Must be + //! larger than 21. + static const ReturnValue_t SWEEP_PERIOD_TOO_SMALL = MAKE_RETURN_CODE(0xA8); + //! [EXPORT] : [COMMENT] Receive auto EM test command with invalid test param. Valid params are 1 + //! and 2. + static const ReturnValue_t INVALID_TEST_PARAM = MAKE_RETURN_CODE(0xA9); + //! [EXPORT] : [COMMENT] Returned when scanning for MRAM dump packets failed. + static const ReturnValue_t MRAM_PACKET_PARSING_FAILURE = MAKE_RETURN_CODE(0xAA); + //! [EXPORT] : [COMMENT] Returned when the start and stop addresses of the MRAM dump or MRAM wipe + //! commands are invalid (e.g. start address bigger than stop address) + static const ReturnValue_t INVALID_MRAM_ADDRESSES = MAKE_RETURN_CODE(0xAB); + //! [EXPORT] : [COMMENT] Expect reception of an MRAM dump packet but received space packet with + //! other apid. + static const ReturnValue_t NO_MRAM_PACKET = MAKE_RETURN_CODE(0xAC); + //! [EXPORT] : [COMMENT] Path to PLOC directory on SD card does not exist + static const ReturnValue_t PATH_DOES_NOT_EXIST = MAKE_RETURN_CODE(0xAD); + //! [EXPORT] : [COMMENT] MRAM dump file does not exists. The file should actually already have + //! been created with the reception of the first dump packet. + static const ReturnValue_t MRAM_FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xAE); + //! [EXPORT] : [COMMENT] Received action command has invalid length + static const ReturnValue_t INVALID_LENGTH = MAKE_RETURN_CODE(0xAF); + //! [EXPORT] : [COMMENT] Filename too long + static const ReturnValue_t FILENAME_TOO_LONG = MAKE_RETURN_CODE(0xB0); + //! [EXPORT] : [COMMENT] Received update status report with invalid packet length field + static const ReturnValue_t UPDATE_STATUS_REPORT_INVALID_LENGTH = MAKE_RETURN_CODE(0xB1); + //! [EXPORT] : [COMMENT] Update status report does not contain expected CRC. There might be a bit + //! flip in the update memory region. + static const ReturnValue_t UPDATE_CRC_FAILURE = MAKE_RETURN_CODE(0xB2); + //! [EXPORT] : [COMMENT] Supervisor helper task ist currently executing a command (wait until + //! helper tas has finished or interrupt by sending the terminate command) + static const ReturnValue_t SUPV_HELPER_EXECUTING = MAKE_RETURN_CODE(0xB3); +}; + +#endif /* SUPV_RETURN_VALUES_IF_H_ */ diff --git a/linux/devices/ploc/CMakeLists.txt b/linux/devices/ploc/CMakeLists.txt index 2d1e1998..f085eab3 100644 --- a/linux/devices/ploc/CMakeLists.txt +++ b/linux/devices/ploc/CMakeLists.txt @@ -1,7 +1,4 @@ -target_sources(${OBSW_NAME} PRIVATE - PlocSupervisorHandler.cpp - PlocUpdater.cpp - PlocMemoryDumper.cpp - PlocMPSoCHandler.cpp - PlocMPSoCHelper.cpp -) +target_sources( + ${OBSW_NAME} + PRIVATE PlocSupervisorHandler.cpp PlocMemoryDumper.cpp PlocMPSoCHandler.cpp + PlocMPSoCHelper.cpp PlocSupvHelper.cpp) diff --git a/linux/devices/ploc/PlocMPSoCHandler.cpp b/linux/devices/ploc/PlocMPSoCHandler.cpp index 52fd5812..37372b3b 100644 --- a/linux/devices/ploc/PlocMPSoCHandler.cpp +++ b/linux/devices/ploc/PlocMPSoCHandler.cpp @@ -99,6 +99,20 @@ void PlocMPSoCHandler::performOperationHook() { ReturnValue_t PlocMPSoCHandler::executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, const uint8_t* data, size_t size) { ReturnValue_t result = RETURN_OK; + switch (actionId) { + case mpsoc::SET_UART_TX_TRISTATE: { + uartIsolatorSwitch.pullLow(); + return EXECUTION_FINISHED; + break; + } + case mpsoc::RELEASE_UART_TX: { + uartIsolatorSwitch.pullHigh(); + return EXECUTION_FINISHED; + break; + default: + break; + } + } if (plocMPSoCHelperExecuting) { return MPSoCReturnValuesIF::MPSOC_HELPER_EXECUTING; @@ -134,6 +148,7 @@ ReturnValue_t PlocMPSoCHandler::executeAction(ActionId_t actionId, MessageQueueI void PlocMPSoCHandler::doStartUp() { #ifdef XIPHOS_Q7S +#if not OBSW_MPSOC_JTAG_BOOT == 1 switch (powerState) { case PowerState::OFF: commandActionHelper.commandAction(supervisorHandler, supv::START_MPSOC); @@ -147,11 +162,19 @@ void PlocMPSoCHandler::doStartUp() { break; } #else + powerState = PowerState::ON; + setMode(_MODE_TO_ON); + uartIsolatorSwitch.pullHigh(); +#endif /* not MSPOC_JTAG_BOOT == 1 */ +#else + powerState = PowerState::ON; setMode(_MODE_TO_ON); #endif /* XIPHOS_Q7S */ } void PlocMPSoCHandler::doShutDown() { +#ifdef XIPHOS_Q7S +#if not OBSW_MPSOC_JTAG_BOOT == 1 switch (powerState) { case PowerState::ON: uartIsolatorSwitch.pullLow(); @@ -164,6 +187,12 @@ void PlocMPSoCHandler::doShutDown() { default: break; } +#else + uartIsolatorSwitch.pullLow(); + setMode(_MODE_POWER_DOWN); + powerState = PowerState::OFF; +#endif +#endif } ReturnValue_t PlocMPSoCHandler::buildNormalDeviceCommand(DeviceCommandId_t* id) { @@ -252,6 +281,8 @@ void PlocMPSoCHandler::fillCommandAndReplyMap() { this->insertInCommandMap(mpsoc::TC_MODE_REPLAY); this->insertInCommandMap(mpsoc::TC_MODE_IDLE); this->insertInCommandMap(mpsoc::TC_CAM_CMD_SEND); + this->insertInCommandMap(mpsoc::RELEASE_UART_TX); + this->insertInCommandMap(mpsoc::SET_UART_TX_TRISTATE); this->insertInReplyMap(mpsoc::ACK_REPORT, 3, nullptr, mpsoc::SIZE_ACK_REPORT); this->insertInReplyMap(mpsoc::EXE_REPORT, 3, nullptr, mpsoc::SIZE_EXE_REPORT); this->insertInReplyMap(mpsoc::TM_MEMORY_READ_REPORT, 2, nullptr, mpsoc::SIZE_TM_MEM_READ_REPORT); @@ -302,7 +333,7 @@ ReturnValue_t PlocMPSoCHandler::scanForReply(const uint8_t* start, size_t remain sequenceCount++; uint16_t recvSeqCnt = (*(start + 2) << 8 | *(start + 3)) & PACKET_SEQUENCE_COUNT_MASK; if (recvSeqCnt != sequenceCount) { - triggerEvent(MPSOC_HANDLER_SEQ_CNT_MISMATCH, sequenceCount, recvSeqCnt); + triggerEvent(MPSOC_HANDLER_SEQUENCE_COUNT_MISMATCH, sequenceCount, recvSeqCnt); sequenceCount = recvSeqCnt; } return result; @@ -558,14 +589,14 @@ ReturnValue_t PlocMPSoCHandler::handleAckReport(const uint8_t* data) { switch (apid) { case mpsoc::apid::ACK_FAILURE: { - // TODO: Interpretation of status field in acknowledgment report sif::debug << "PlocMPSoCHandler::handleAckReport: Received Ack failure report" << std::endl; DeviceCommandId_t commandId = getPendingCommand(); uint16_t status = getStatus(data); + printStatus(data); if (commandId != DeviceHandlerIF::NO_COMMAND_ID) { triggerEvent(ACK_FAILURE, commandId, status); } - sendFailureReport(mpsoc::ACK_REPORT, MPSoCReturnValuesIF::RECEIVED_ACK_FAILURE); + sendFailureReport(mpsoc::ACK_REPORT, status); disableAllReplies(); nextReplyId = mpsoc::NONE; result = IGNORE_REPLY_DATA; @@ -652,15 +683,18 @@ ReturnValue_t PlocMPSoCHandler::handleCamCmdRpt(const uint8_t* data) { if (result == MPSoCReturnValuesIF::CRC_FAILURE) { sif::warning << "PlocMPSoCHandler::handleCamCmdRpt: CRC failure" << std::endl; } - const uint8_t* dataFieldPtr = data + mpsoc::SPACE_PACKET_HEADER_SIZE; + const uint8_t* dataFieldPtr = data + mpsoc::SPACE_PACKET_HEADER_SIZE + sizeof(uint16_t); std::string camCmdRptMsg( reinterpret_cast(dataFieldPtr), - tmCamCmdRpt.rememberSpacePacketSize - mpsoc::SPACE_PACKET_HEADER_SIZE - 3); + tmCamCmdRpt.rememberSpacePacketSize - mpsoc::SPACE_PACKET_HEADER_SIZE - sizeof(uint16_t) - 3); +#if OBSW_DEBUG_PLOC_MPSOC == 1 uint8_t ackValue = *(packet.getPacketData() + packet.getPacketDataLength() - 2); - sif::info << "CamCmdRpt message: " << camCmdRptMsg << std::endl; - sif::info << "CamCmdRpt Ack value: 0x" << std::hex << static_cast(ackValue) - << std::endl; - handleDeviceTM(packet.getPacketData(), packet.getPacketDataLength() - 1, mpsoc::TM_CAM_CMD_RPT); + sif::info << "PlocMPSoCHandler: CamCmdRpt message: " << camCmdRptMsg << std::endl; + sif::info << "PlocMPSoCHandler: CamCmdRpt Ack value: 0x" << std::hex + << static_cast(ackValue) << std::endl; +#endif /* OBSW_DEBUG_PLOC_MPSOC == 1 */ + handleDeviceTM(packet.getPacketData() + sizeof(uint16_t), packet.getPacketDataLength() - 1, + mpsoc::TM_CAM_CMD_RPT); return result; } @@ -799,6 +833,14 @@ size_t PlocMPSoCHandler::getNextReplyLength(DeviceCommandId_t commandId) { return replyLen; } +ReturnValue_t PlocMPSoCHandler::doSendReadHook() { + // Prevent DHB from polling UART during commands executed by the mpsoc helper task + if (plocMPSoCHelperExecuting) { + return RETURN_FAILED; + } + return RETURN_OK; +} + MessageQueueIF* PlocMPSoCHandler::getCommandQueuePtr() { return commandActionHelperQueue; } void PlocMPSoCHandler::stepSuccessfulReceived(ActionId_t actionId, uint8_t step) { return; } @@ -806,16 +848,19 @@ void PlocMPSoCHandler::stepSuccessfulReceived(ActionId_t actionId, uint8_t step) void PlocMPSoCHandler::stepFailedReceived(ActionId_t actionId, uint8_t step, ReturnValue_t returnCode) { switch (actionId) { - case supv::START_MPSOC: + case supv::START_MPSOC: { sif::warning << "PlocMPSoCHandler::stepFailedReceived: Failed to start MPSoC" << std::endl; + // This usually happens when the supervisor handler is in off mode powerState = PowerState::OFF; + setMode(MODE_OFF); break; - case supv::SHUTDOWN_MPSOC: + } + case supv::SHUTDOWN_MPSOC: { triggerEvent(MPSOC_SHUTDOWN_FAILED); sif::warning << "PlocMPSoCHandler::stepFailedReceived: Failed to shutdown MPSoC" << std::endl; - // TODO: Setting state to on or off here? - powerState = PowerState::ON; + powerState = PowerState::OFF; break; + } default: sif::debug << "PlocMPSoCHandler::stepFailedReceived: Received unexpected action reply" << std::endl; @@ -879,10 +924,11 @@ void PlocMPSoCHandler::handleDeviceTM(const uint8_t* data, size_t dataSize, } void PlocMPSoCHandler::disableAllReplies() { + using namespace mpsoc; DeviceReplyMap::iterator iter; /* Disable ack reply */ - iter = deviceReplyMap.find(mpsoc::ACK_REPORT); + iter = deviceReplyMap.find(ACK_REPORT); DeviceReplyInfo* info = &(iter->second); info->delayCycles = 0; info->command = deviceCommandMap.end(); @@ -891,17 +937,26 @@ void PlocMPSoCHandler::disableAllReplies() { /* If the command expects a telemetry packet the appropriate tm reply will be disabled here */ switch (commandId) { - case mpsoc::TC_MEM_WRITE: + case TC_MEM_WRITE: break; - case mpsoc::TC_MEM_READ: { - iter = deviceReplyMap.find(mpsoc::TM_MEMORY_READ_REPORT); + case TC_MEM_READ: { + iter = deviceReplyMap.find(TM_MEMORY_READ_REPORT); info = &(iter->second); info->delayCycles = 0; + info->active = false; + info->command = deviceCommandMap.end(); + break; + } + case TC_CAM_CMD_SEND: { + iter = deviceReplyMap.find(TM_CAM_CMD_RPT); + info = &(iter->second); + info->delayCycles = 0; + info->active = false; info->command = deviceCommandMap.end(); break; } default: { - sif::debug << "PlocMPSoCHandler::disableAllReplies: Unknown command id" << commandId + sif::debug << "PlocMPSoCHandler::disableAllReplies: Unknown command id: " << commandId << std::endl; break; } @@ -940,7 +995,7 @@ void PlocMPSoCHandler::disableExeReportReply() { void PlocMPSoCHandler::printStatus(const uint8_t* data) { uint16_t status = *(data + STATUS_OFFSET) << 8 | *(data + STATUS_OFFSET + 1); - sif::info << "Verification report status: 0x" << std::hex << status << std::endl; + sif::info << "Verification report status: " << getStatusString(status) << std::endl; } uint16_t PlocMPSoCHandler::getStatus(const uint8_t* data) { @@ -959,15 +1014,19 @@ void PlocMPSoCHandler::handleActionCommandFailure(ActionId_t actionId) { } switch (powerState) { case PowerState::BOOTING: { - sif::warning << "PlocMPSoCHandler::handleActionCommandFailure: Failed to boot MPSoC" - << std::endl; - powerState = PowerState::OFF; + sif::info << "PlocMPSoCHandler::handleActionCommandFailure: MPSoC boot command failed" + << std::endl; + // This is commonly the case when the MPSoC is already operational. Thus the power state is + // set to on here + powerState = PowerState::ON; break; } case PowerState::SHUTDOWN: { + // FDIR will intercept event and switch PLOC power off + triggerEvent(MPSOC_SHUTDOWN_FAILED); sif::warning << "PlocMPSoCHandler::handleActionCommandFailure: Failed to shutdown MPSoC" << std::endl; - powerState = PowerState::ON; + powerState = PowerState::OFF; break; } default: @@ -975,3 +1034,79 @@ void PlocMPSoCHandler::handleActionCommandFailure(ActionId_t actionId) { } return; } + +std::string PlocMPSoCHandler::getStatusString(uint16_t status) { + switch (status) { + case (mpsoc::status_code::UNKNOWN_APID): { + return "Unknown APID"; + break; + } + case (mpsoc::status_code::INCORRECT_LENGTH): { + return "Incorrect length"; + break; + } + case (mpsoc::status_code::INCORRECT_CRC): { + return "Incorrect crc"; + break; + } + case (mpsoc::status_code::INCORRECT_PKT_SEQ_CNT): { + return "Incorrect packet sequence count"; + break; + } + case (mpsoc::status_code::TC_NOT_ALLOWED_IN_MODE): { + return "TC not allowed in this mode"; + break; + } + case (mpsoc::status_code::TC_EXEUTION_DISABLED): { + return "TC execution disabled"; + break; + } + case (mpsoc::status_code::FLASH_MOUNT_FAILED): { + return "Flash mount failed"; + break; + } + case (mpsoc::status_code::FLASH_FILE_ALREADY_CLOSED): { + return "Flash file already closed"; + break; + } + case (mpsoc::status_code::FLASH_FILE_NOT_OPEN): { + return "Flash file not open"; + break; + } + case (mpsoc::status_code::FLASH_UNMOUNT_FAILED): { + return "Flash unmount failed"; + break; + } + case (mpsoc::status_code::HEAP_ALLOCATION_FAILED): { + return "Heap allocation failed"; + break; + } + case (mpsoc::status_code::INVALID_PARAMETER): { + return "Invalid parameter"; + break; + } + case (mpsoc::status_code::NOT_INITIALIZED): { + return "Not initialized"; + break; + } + case (mpsoc::status_code::REBOOT_IMMINENT): { + return "Reboot imminent"; + break; + } + case (mpsoc::status_code::CORRUPT_DATA): { + return "Corrupt data"; + break; + } + case (mpsoc::status_code::FLASH_CORRECTABLE_MISMATCH): { + return "Flash correctable mismatch"; + break; + } + case (mpsoc::status_code::FLASH_UNCORRECTABLE_MISMATCH): { + return "Flash uncorrectable mismatch"; + break; + } + default: + break; + } + return ""; +} diff --git a/linux/devices/ploc/PlocMPSoCHandler.h b/linux/devices/ploc/PlocMPSoCHandler.h index d5ea231b..0d3445d1 100644 --- a/linux/devices/ploc/PlocMPSoCHandler.h +++ b/linux/devices/ploc/PlocMPSoCHandler.h @@ -14,6 +14,7 @@ #include "fsfw_hal/linux/uart/UartComIF.h" #include "linux/devices/devicedefinitions/MPSoCReturnValuesIF.h" #include "linux/devices/devicedefinitions/PlocMPSoCDefinitions.h" +#include "linux/devices/devicedefinitions/PlocSupervisorDefinitions.h" /** * @brief This is the device handler for the MPSoC of the payload computer. @@ -76,6 +77,7 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF { uint8_t expectedReplies = 1, bool useAlternateId = false, DeviceCommandId_t alternateReplyID = 0) override; size_t getNextReplyLength(DeviceCommandId_t deviceCommand) override; + virtual ReturnValue_t doSendReadHook() override; private: static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PLOC_MPSOC_HANDLER; @@ -94,7 +96,7 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF { static const Event MPSOC_HANDLER_CRC_FAILURE = MAKE_EVENT(4, severity::LOW); //! [EXPORT] : [COMMENT] Packet sequence count in received space packet does not match expected //! count P1: Expected sequence count P2: Received sequence count - static const Event MPSOC_HANDLER_SEQ_CNT_MISMATCH = MAKE_EVENT(5, severity::LOW); + static const Event MPSOC_HANDLER_SEQUENCE_COUNT_MISMATCH = MAKE_EVENT(5, severity::LOW); //! [EXPORT] : [COMMENT] Supervisor fails to shutdown MPSoC. Requires to power off the PLOC and //! thus also to shutdown the supervisor. static const Event MPSOC_SHUTDOWN_FAILED = MAKE_EVENT(6, severity::HIGH); @@ -106,7 +108,11 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF { MessageQueueIF* eventQueue = nullptr; MessageQueueIF* commandActionHelperQueue = nullptr; - SourceSequenceCounter sequenceCount; + // Initiate the sequence count with the maximum value. It is incremented before + // a packet is sent, so the first value will be 0 accordingly using + // the wrap around of the counter. + SourceSequenceCounter sequenceCount = + SourceSequenceCounter(SpacePacketBase::LIMIT_SEQUENCE_COUNT - 1); uint8_t commandBuffer[mpsoc::MAX_COMMAND_SIZE]; @@ -257,6 +263,8 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF { uint16_t getStatus(const uint8_t* data); void handleActionCommandFailure(ActionId_t actionId); + + std::string getStatusString(uint16_t status); }; #endif /* BSP_Q7S_DEVICES_PLOC_PLOCMPSOCHANDLER_H_ */ diff --git a/linux/devices/ploc/PlocMPSoCHelper.cpp b/linux/devices/ploc/PlocMPSoCHelper.cpp index e940e8f3..5e6da78b 100644 --- a/linux/devices/ploc/PlocMPSoCHelper.cpp +++ b/linux/devices/ploc/PlocMPSoCHelper.cpp @@ -204,7 +204,7 @@ ReturnValue_t PlocMPSoCHelper::sendCommand(mpsoc::TcBase& tc) { result = uartComIF->sendMessage(comCookie, tc.getWholeData(), tc.getFullSize()); if (result != RETURN_OK) { sif::warning << "PlocMPSoCHelper::sendCommand: Failed to send command" << std::endl; - triggerEvent(SENDING_COMMAND_FAILED, result, static_cast(internalState)); + triggerEvent(MPSOC_SENDING_COMMAND_FAILED, result, static_cast(internalState)); return result; } return result; @@ -227,11 +227,11 @@ ReturnValue_t PlocMPSoCHelper::handleAck() { void PlocMPSoCHelper::handleAckApidFailure(uint16_t apid) { if (apid == mpsoc::apid::ACK_FAILURE) { - triggerEvent(ACK_FAILURE_REPORT, static_cast(internalState)); + triggerEvent(MPSOC_ACK_FAILURE_REPORT, static_cast(internalState)); sif::warning << "PlocMPSoCHelper::handleAckApidFailure: Received acknowledgement failure " << "report" << std::endl; } else { - triggerEvent(ACK_INVALID_APID, apid, static_cast(internalState)); + triggerEvent(MPSOC_ACK_INVALID_APID, apid, static_cast(internalState)); sif::warning << "PlocMPSoCHelper::handleAckApidFailure: Expected acknowledgement report " << "but received space packet with apid " << std::hex << apid << std::endl; } @@ -254,11 +254,11 @@ ReturnValue_t PlocMPSoCHelper::handleExe() { void PlocMPSoCHelper::handleExeApidFailure(uint16_t apid) { if (apid == mpsoc::apid::EXE_FAILURE) { - triggerEvent(EXE_FAILURE_REPORT, static_cast(internalState)); + triggerEvent(MPSOC_EXE_FAILURE_REPORT, static_cast(internalState)); sif::warning << "PlocMPSoCHelper::handleExeApidFailure: Received execution failure " << "report" << std::endl; } else { - triggerEvent(EXE_INVALID_APID, apid, static_cast(internalState)); + triggerEvent(MPSOC_EXE_INVALID_APID, apid, static_cast(internalState)); sif::warning << "PlocMPSoCHelper::handleExeApidFailure: Expected execution report " << "but received space packet with apid " << std::hex << apid << std::endl; } @@ -281,7 +281,7 @@ ReturnValue_t PlocMPSoCHelper::handleTmReception(mpsoc::TmPacket* tmPacket, size } if (remainingBytes != 0) { sif::warning << "PlocMPSoCHelper::handleTmReception: Failed to receive reply" << std::endl; - triggerEvent(MISSING_EXE, remainingBytes, static_cast(internalState)); + triggerEvent(MPSOC_MISSING_EXE, remainingBytes, static_cast(internalState)); return RETURN_FAILED; } result = tmPacket->checkCrc(); diff --git a/linux/devices/ploc/PlocMPSoCHelper.h b/linux/devices/ploc/PlocMPSoCHelper.h index 4cb882c7..3c011b6a 100644 --- a/linux/devices/ploc/PlocMPSoCHelper.h +++ b/linux/devices/ploc/PlocMPSoCHelper.h @@ -29,10 +29,10 @@ class PlocMPSoCHelper : public SystemObject, public ExecutableObjectIF, public H //! [EXPORT] : [COMMENT] Flash write successful static const Event MPSOC_FLASH_WRITE_SUCCESSFUL = MAKE_EVENT(1, severity::LOW); //! [EXPORT] : [COMMENT] Communication interface returned failure when trying to send the command - //! ot the PLOC + //! to the MPSoC //! P1: Return value returned by the communication interface sendMessage function //! P2: Internal state of MPSoC helper - static const Event SENDING_COMMAND_FAILED = MAKE_EVENT(2, severity::LOW); + static const Event MPSOC_SENDING_COMMAND_FAILED = MAKE_EVENT(2, severity::LOW); //! [EXPORT] : [COMMENT] Request receive message of communication interface failed //! P1: Return value returned by the communication interface requestReceiveMessage function //! P2: Internal state of MPSoC helper @@ -41,28 +41,28 @@ class PlocMPSoCHelper : public SystemObject, public ExecutableObjectIF, public H //! P1: Return value returned by the communication interface readingReceivedMessage function //! P2: Internal state of MPSoC helper static const Event MPSOC_HELPER_READING_REPLY_FAILED = MAKE_EVENT(4, severity::LOW); - //! [EXPORT] : [COMMENT] Did not receive acknowledgement report + //! [EXPORT] : [COMMENT] Did not receive acknowledgment report //! P1: Number of bytes missing //! P2: Internal state of MPSoC helper - static const Event MISSING_ACK = MAKE_EVENT(5, severity::LOW); + static const Event MPSOC_MISSING_ACK = MAKE_EVENT(5, severity::LOW); //! [EXPORT] : [COMMENT] Did not receive execution report //! P1: Number of bytes missing //! P2: Internal state of MPSoC helper - static const Event MISSING_EXE = MAKE_EVENT(6, severity::LOW); - //! [EXPORT] : [COMMENT] Received acknowledgement failure report + static const Event MPSOC_MISSING_EXE = MAKE_EVENT(6, severity::LOW); + //! [EXPORT] : [COMMENT] Received acknowledgment failure report //! P1: Internal state of MPSoC - static const Event ACK_FAILURE_REPORT = MAKE_EVENT(7, severity::LOW); + static const Event MPSOC_ACK_FAILURE_REPORT = MAKE_EVENT(7, severity::LOW); //! [EXPORT] : [COMMENT] Received execution failure report //! P1: Internal state of MPSoC - static const Event EXE_FAILURE_REPORT = MAKE_EVENT(8, severity::LOW); - //! [EXPORT] : [COMMENT] Expected acknowledgement report but received space packet with other apid + static const Event MPSOC_EXE_FAILURE_REPORT = MAKE_EVENT(8, severity::LOW); + //! [EXPORT] : [COMMENT] Expected acknowledgment report but received space packet with other apid //! P1: Apid of received space packet //! P2: Internal state of MPSoC - static const Event ACK_INVALID_APID = MAKE_EVENT(9, severity::LOW); + static const Event MPSOC_ACK_INVALID_APID = MAKE_EVENT(9, severity::LOW); //! [EXPORT] : [COMMENT] Expected execution report but received space packet with other apid //! P1: Apid of received space packet //! P2: Internal state of MPSoC - static const Event EXE_INVALID_APID = MAKE_EVENT(10, severity::LOW); + static const Event MPSOC_EXE_INVALID_APID = MAKE_EVENT(10, severity::LOW); //! [EXPORT] : [COMMENT] Received sequence count does not match expected sequence count //! P1: Expected sequence count //! P2: Received sequence count diff --git a/linux/devices/ploc/PlocMemoryDumper.cpp b/linux/devices/ploc/PlocMemoryDumper.cpp index a73a2606..e1fce10e 100644 --- a/linux/devices/ploc/PlocMemoryDumper.cpp +++ b/linux/devices/ploc/PlocMemoryDumper.cpp @@ -78,7 +78,7 @@ MessageQueueIF* PlocMemoryDumper::getCommandQueuePtr() { return commandQueue; } void PlocMemoryDumper::readCommandQueue() { CommandMessage message; - ReturnValue_t result; + ReturnValue_t result = RETURN_OK; for (result = commandQueue->receiveMessage(&message); result == HasReturnvaluesIF::RETURN_OK; result = commandQueue->receiveMessage(&message)) { @@ -121,7 +121,10 @@ void PlocMemoryDumper::doStateMachine() { void PlocMemoryDumper::stepSuccessfulReceived(ActionId_t actionId, uint8_t step) {} void PlocMemoryDumper::stepFailedReceived(ActionId_t actionId, uint8_t step, - ReturnValue_t returnCode) {} + ReturnValue_t returnCode) { + triggerEvent(MRAM_DUMP_FAILED); + state = State::IDLE; +} void PlocMemoryDumper::dataReceived(ActionId_t actionId, const uint8_t* data, uint32_t size) {} @@ -149,10 +152,9 @@ void PlocMemoryDumper::completionFailedReceived(ActionId_t actionId, ReturnValue case (supv::FIRST_MRAM_DUMP): case (supv::CONSECUTIVE_MRAM_DUMP): triggerEvent(MRAM_DUMP_FAILED, mram.lastStartAddress); + pendingCommand = NONE; break; default: - sif::debug << "PlocMemoryDumper::completionFailedReceived: Invalid pending command " - << std::endl; break; } state = State::IDLE; @@ -168,12 +170,12 @@ void PlocMemoryDumper::commandNextMramDump(ActionId_t dumpCommand) { tempStartAddress = mram.startAddress; tempEndAddress = mram.startAddress + MAX_MRAM_DUMP_SIZE; mram.startAddress += MAX_MRAM_DUMP_SIZE; - mram.lastStartAddress = tempStartAddress; } else { tempStartAddress = mram.startAddress; tempEndAddress = mram.endAddress; mram.startAddress = mram.endAddress; } + mram.lastStartAddress = tempStartAddress; MemoryParams params(tempStartAddress, tempEndAddress); diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 5065c7dd..7d38d0c2 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -1,28 +1,34 @@ #include "PlocSupervisorHandler.h" -#include -#include -#include - #include #include #include #include #include "OBSWConfig.h" +#include "eive/definitions.h" +#include "fsfw/datapool/PoolReadGuard.h" +#include "fsfw/globalfunctions/CRC.h" +#include "fsfw/ipc/QueueFactory.h" +#include "fsfw/timemanager/Clock.h" PlocSupervisorHandler::PlocSupervisorHandler(object_id_t objectId, object_id_t uartComIFid, CookieIF* comCookie, Gpio uartIsolatorSwitch, - power::Switch_t powerSwitch) + power::Switch_t powerSwitch, + PlocSupvHelper* supvHelper) : DeviceHandlerBase(objectId, uartComIFid, comCookie), uartIsolatorSwitch(uartIsolatorSwitch), hkset(this), bootStatusReport(this), latchupStatusReport(this), - powerSwitch(powerSwitch) { + loggingReport(this), + adcReport(this), + powerSwitch(powerSwitch), + supvHelper(supvHelper) { if (comCookie == NULL) { sif::error << "PlocSupervisorHandler: Invalid com cookie" << std::endl; } + eventQueue = QueueFactory::instance()->createMessageQueue(EventMessage::EVENT_MESSAGE_SIZE * 5); } PlocSupervisorHandler::~PlocSupervisorHandler() {} @@ -38,20 +44,136 @@ ReturnValue_t PlocSupervisorHandler::initialize() { sif::warning << "PlocSupervisorHandler::initialize: Invalid uart com if" << std::endl; return ObjectManagerIF::CHILD_INIT_FAILED; } -#ifdef TE0720_1CFA +#ifndef TE0720_1CFA sdcMan = SdCardManager::instance(); -#endif /* BOARD_TE0720 == 0 */ +#endif /* TE0720_1CFA */ + if (supvHelper == nullptr) { + sif::warning << "PlocSupervisorHandler::initialize: Invalid supervisor helper" << std::endl; + return ObjectManagerIF::CHILD_INIT_FAILED; + } + result = supvHelper->setComIF(uartComIf); + if (result != RETURN_OK) { + return ObjectManagerIF::CHILD_INIT_FAILED; + } + supvHelper->setComCookie(comCookie); + + result = eventSubscription(); + if (result != RETURN_OK) { + return result; + } return result; } +void PlocSupervisorHandler::performOperationHook() { + EventMessage event; + for (ReturnValue_t result = eventQueue->receiveMessage(&event); result == RETURN_OK; + result = eventQueue->receiveMessage(&event)) { + switch (event.getMessageId()) { + case EventMessage::EVENT_MESSAGE: + handleEvent(&event); + break; + default: + sif::debug << "PlocSupervisorHandler::performOperationHook: Did not subscribe to this event" + << " message" << std::endl; + break; + } + } +} + +ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, + MessageQueueId_t commandedBy, + const uint8_t* data, size_t size) { + using namespace supv; + ReturnValue_t result = RETURN_OK; + + switch (actionId) { + case TERMINATE_SUPV_HELPER: { + supvHelper->stopProcess(); + return EXECUTION_FINISHED; + } + default: + break; + } + + if (plocSupvHelperExecuting) { + return SupvReturnValuesIF::SUPV_HELPER_EXECUTING; + } + + switch (actionId) { + case PERFORM_UPDATE: { + if (size > config::MAX_PATH_SIZE + config::MAX_FILENAME_SIZE) { + return SupvReturnValuesIF::FILENAME_TOO_LONG; + } + std::string file = ""; + uint8_t memoryId = 0; + uint32_t startAddress = 0; + result = extractUpdateCommand(data, size, &file, &memoryId, &startAddress); + if (result != RETURN_OK) { + return result; + } + result = supvHelper->startUpdate(file, memoryId, startAddress); + if (result != RETURN_OK) { + return result; + } + plocSupvHelperExecuting = true; + return EXECUTION_FINISHED; + } + case CONTINUE_UPDATE: { + supvHelper->initiateUpdateContinuation(); + plocSupvHelperExecuting = true; + return EXECUTION_FINISHED; + } + case LOGGING_REQUEST_EVENT_BUFFERS: { + if (size > config::MAX_PATH_SIZE) { + return SupvReturnValuesIF::FILENAME_TOO_LONG; + } + result = supvHelper->startEventbBufferRequest( + std::string(reinterpret_cast(data), size)); + if (result != RETURN_OK) { + return result; + } + plocSupvHelperExecuting = true; + return EXECUTION_FINISHED; + } + default: + break; + } + return DeviceHandlerBase::executeAction(actionId, commandedBy, data, size); +} + void PlocSupervisorHandler::doStartUp() { - setMode(_MODE_TO_ON); - uartIsolatorSwitch.pullHigh(); + if (setTimeDuringStartup) { + switch (startupState) { + case StartupState::OFF: { + bootTimeout.resetTimer(); + startupState = StartupState::BOOTING; + break; + } + case StartupState::BOOTING: { + if (bootTimeout.hasTimedOut()) { + uartIsolatorSwitch.pullHigh(); + startupState = StartupState::SET_TIME; + } + } + case StartupState::SET_TIME_EXECUTING: + break; + case StartupState::ON: { + setMode(_MODE_TO_ON); + break; + } + default: + break; + } + } else { + uartIsolatorSwitch.pullHigh(); + setMode(_MODE_TO_ON); + } } void PlocSupervisorHandler::doShutDown() { setMode(_MODE_POWER_DOWN); uartIsolatorSwitch.pullLow(); + startupState = StartupState::OFF; } ReturnValue_t PlocSupervisorHandler::buildNormalDeviceCommand(DeviceCommandId_t* id) { @@ -59,206 +181,211 @@ ReturnValue_t PlocSupervisorHandler::buildNormalDeviceCommand(DeviceCommandId_t* } ReturnValue_t PlocSupervisorHandler::buildTransitionDeviceCommand(DeviceCommandId_t* id) { + if (startupState == StartupState::SET_TIME) { + *id = supv::SET_TIME_REF; + startupState = StartupState::SET_TIME_EXECUTING; + return buildCommandFromCommand(*id, nullptr, 0); + } return NOTHING_TO_SEND; } ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t* commandData, size_t commandDataLen) { + using namespace supv; ReturnValue_t result = RETURN_FAILED; switch (deviceCommand) { - case (supv::GET_HK_REPORT): { - prepareEmptyCmd(supv::APID_GET_HK_REPORT); + case GET_HK_REPORT: { + prepareEmptyCmd(APID_GET_HK_REPORT); result = RETURN_OK; break; } - case (supv::RESTART_MPSOC): { - prepareEmptyCmd(supv::APID_RESTART_MPSOC); + case START_MPSOC: { + prepareEmptyCmd(APID_START_MPSOC); result = RETURN_OK; break; } - case (supv::START_MPSOC): { - prepareEmptyCmd(supv::APID_START_MPSOC); + case SHUTDOWN_MPSOC: { + prepareEmptyCmd(APID_SHUTWOWN_MPSOC); result = RETURN_OK; break; } - case (supv::SHUTDOWN_MPSOC): { - prepareEmptyCmd(supv::APID_SHUTWOWN_MPSOC); - result = RETURN_OK; - break; - } - case (supv::SEL_MPSOC_BOOT_IMAGE): { + case SEL_MPSOC_BOOT_IMAGE: { prepareSelBootImageCmd(commandData); result = RETURN_OK; break; } - case (supv::RESET_MPSOC): { - prepareEmptyCmd(supv::APID_RESET_MPSOC); + case RESET_MPSOC: { + prepareEmptyCmd(APID_RESET_MPSOC); result = RETURN_OK; break; } - case (supv::SET_TIME_REF): { + case SET_TIME_REF: { result = prepareSetTimeRefCmd(); break; } - case (supv::SET_BOOT_TIMEOUT): { + case SET_BOOT_TIMEOUT: { prepareSetBootTimeoutCmd(commandData); result = RETURN_OK; break; } - case (supv::SET_MAX_RESTART_TRIES): { + case SET_MAX_RESTART_TRIES: { prepareRestartTriesCmd(commandData); result = RETURN_OK; break; } - case (supv::DISABLE_PERIOIC_HK_TRANSMISSION): { + case DISABLE_PERIOIC_HK_TRANSMISSION: { prepareDisableHk(); result = RETURN_OK; break; } - case (supv::GET_BOOT_STATUS_REPORT): { - prepareEmptyCmd(supv::APID_GET_BOOT_STATUS_RPT); + case GET_BOOT_STATUS_REPORT: { + prepareEmptyCmd(APID_GET_BOOT_STATUS_RPT); result = RETURN_OK; break; } - case (supv::WATCHDOGS_ENABLE): { - prepareWatchdogsEnableCmd(commandData); - result = RETURN_OK; - break; - } - case (supv::WATCHDOGS_CONFIG_TIMEOUT): { - result = prepareWatchdogsConfigTimeoutCmd(commandData); - break; - } - case (supv::ENABLE_LATCHUP_ALERT): { + case ENABLE_LATCHUP_ALERT: { result = prepareLatchupConfigCmd(commandData, deviceCommand); break; } - case (supv::DISABLE_LATCHUP_ALERT): { + case DISABLE_LATCHUP_ALERT: { result = prepareLatchupConfigCmd(commandData, deviceCommand); break; } - case (supv::AUTO_CALIBRATE_ALERT): { - result = prepareAutoCalibrateAlertCmd(commandData); - break; - } - case (supv::SET_ALERT_LIMIT): { + case SET_ALERT_LIMIT: { result = prepareSetAlertLimitCmd(commandData); break; } - case (supv::SET_ALERT_IRQ_FILTER): { - result = prepareSetAlertIrqFilterCmd(commandData); - break; - } - case (supv::SET_ADC_SWEEP_PERIOD): { - result = prepareSetAdcSweetPeriodCmd(commandData); - break; - } - case (supv::SET_ADC_ENABLED_CHANNELS): { + case SET_ADC_ENABLED_CHANNELS: { prepareSetAdcEnabledChannelsCmd(commandData); result = RETURN_OK; break; } - case (supv::SET_ADC_WINDOW_AND_STRIDE): { + case SET_ADC_WINDOW_AND_STRIDE: { prepareSetAdcWindowAndStrideCmd(commandData); result = RETURN_OK; break; } - case (supv::SET_ADC_THRESHOLD): { + case SET_ADC_THRESHOLD: { prepareSetAdcThresholdCmd(commandData); result = RETURN_OK; break; } - case (supv::GET_LATCHUP_STATUS_REPORT): { - prepareEmptyCmd(supv::APID_GET_LATCHUP_STATUS_REPORT); + case GET_LATCHUP_STATUS_REPORT: { + prepareEmptyCmd(APID_GET_LATCHUP_STATUS_REPORT); result = RETURN_OK; break; } - case (supv::COPY_ADC_DATA_TO_MRAM): { - prepareEmptyCmd(supv::APID_COPY_ADC_DATA_TO_MRAM); + case COPY_ADC_DATA_TO_MRAM: { + prepareEmptyCmd(APID_COPY_ADC_DATA_TO_MRAM); result = RETURN_OK; break; } - case (supv::ENABLE_NVMS): { - prepareEnableNvmsCmd(commandData); + case REQUEST_ADC_REPORT: { + prepareEmptyCmd(APID_REQUEST_ADC_REPORT); result = RETURN_OK; break; } - case (supv::SELECT_NVM): { - prepareSelectNvmCmd(commandData); - result = RETURN_OK; - break; - } - case (supv::RUN_AUTO_EM_TESTS): { + case RUN_AUTO_EM_TESTS: { result = prepareRunAutoEmTest(commandData); break; } - case (supv::WIPE_MRAM): { + case WIPE_MRAM: { result = prepareWipeMramCmd(commandData); break; } - case (supv::FIRST_MRAM_DUMP): - case (supv::CONSECUTIVE_MRAM_DUMP): + case FIRST_MRAM_DUMP: + case CONSECUTIVE_MRAM_DUMP: result = prepareDumpMramCmd(commandData); break; - case (supv::PRINT_CPU_STATS): { - preparePrintCpuStatsCmd(commandData); - result = RETURN_OK; - break; - } - case (supv::SET_DBG_VERBOSITY): { - prepareSetDbgVerbosityCmd(commandData); - result = RETURN_OK; - break; - } - case (supv::CAN_LOOPBACK_TEST): { - prepareEmptyCmd(supv::APID_CAN_LOOPBACK_TEST); - result = RETURN_OK; - break; - } - case (supv::SET_GPIO): { + case SET_GPIO: { prepareSetGpioCmd(commandData); result = RETURN_OK; break; } - case (supv::READ_GPIO): { + case READ_GPIO: { prepareReadGpioCmd(commandData); result = RETURN_OK; break; } - case (supv::RESTART_SUPERVISOR): { - prepareEmptyCmd(supv::APID_RESTART_SUPERVISOR); + case RESTART_SUPERVISOR: { + prepareEmptyCmd(APID_RESTART_SUPERVISOR); result = RETURN_OK; break; } - case (supv::FACTORY_RESET_CLEAR_ALL): { - supv::FactoryReset packet(supv::FactoryReset::Op::CLEAR_ALL); + case FACTORY_RESET_CLEAR_ALL: { + FactoryReset packet(FactoryReset::Op::CLEAR_ALL); packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); result = RETURN_OK; break; } - case (supv::FACTORY_RESET_CLEAR_MIRROR): { - supv::FactoryReset packet(supv::FactoryReset::Op::MIRROR_ENTRIES); + case FACTORY_RESET_CLEAR_MIRROR: { + FactoryReset packet(FactoryReset::Op::MIRROR_ENTRIES); packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); result = RETURN_OK; break; } - case (supv::FACTORY_RESET_CLEAR_CIRCULAR): { - supv::FactoryReset packet(supv::FactoryReset::Op::CIRCULAR_ENTRIES); + case FACTORY_RESET_CLEAR_CIRCULAR: { + FactoryReset packet(FactoryReset::Op::CIRCULAR_ENTRIES); packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); result = RETURN_OK; break; } - case (supv::UPDATE_AVAILABLE): - case (supv::UPDATE_IMAGE_DATA): - case (supv::UPDATE_VERIFY): - // Simply forward data from PLOC Updater to supervisor - std::memcpy(commandBuffer, commandData, commandDataLen); - rawPacket = commandBuffer; - rawPacketLen = commandDataLen; - nextReplyId = supv::ACK_REPORT; + case START_MPSOC_QUIET: { + prepareEmptyCmd(APID_START_MPSOC_QUIET); result = RETURN_OK; break; + } + case SET_SHUTDOWN_TIMEOUT: { + prepareSetShutdownTimeoutCmd(commandData); + result = RETURN_OK; + break; + } + case FACTORY_FLASH: { + prepareEmptyCmd(APID_FACTORY_FLASH); + result = RETURN_OK; + break; + } + case ENABLE_AUTO_TM: { + EnableAutoTm packet; + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + result = RETURN_OK; + break; + } + case DISABLE_AUTO_TM: { + DisableAutoTm packet; + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + result = RETURN_OK; + break; + } + case LOGGING_REQUEST_COUNTERS: { + RequestLoggingData packet(RequestLoggingData::Sa::REQUEST_COUNTERS); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + result = RETURN_OK; + break; + } + case LOGGING_CLEAR_COUNTERS: { + RequestLoggingData packet(RequestLoggingData::Sa::CLEAR_COUNTERS); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + result = RETURN_OK; + break; + } + case LOGGING_SET_TOPIC: { + uint8_t tpc = *(commandData); + RequestLoggingData packet(RequestLoggingData::Sa::SET_LOGGING_TOPIC, tpc); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + result = RETURN_OK; + break; + } + case RESET_PL: { + prepareEmptyCmd(APID_RESET_PL); + result = RETURN_OK; + break; + } + case ENABLE_NVMS: { + result = prepareEnableNvmsCommand(commandData); + break; + } default: sif::debug << "PlocSupervisorHandler::buildCommandFromCommand: Command not implemented" << std::endl; @@ -277,64 +404,204 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d } void PlocSupervisorHandler::fillCommandAndReplyMap() { - this->insertInCommandMap(supv::GET_HK_REPORT); - this->insertInCommandMap(supv::RESTART_MPSOC); - this->insertInCommandMap(supv::START_MPSOC); - this->insertInCommandMap(supv::SHUTDOWN_MPSOC); - this->insertInCommandMap(supv::SEL_MPSOC_BOOT_IMAGE); - this->insertInCommandMap(supv::SET_BOOT_TIMEOUT); - this->insertInCommandMap(supv::SET_MAX_RESTART_TRIES); - this->insertInCommandMap(supv::RESET_MPSOC); - this->insertInCommandMap(supv::SET_TIME_REF); - this->insertInCommandMap(supv::DISABLE_PERIOIC_HK_TRANSMISSION); - this->insertInCommandMap(supv::GET_BOOT_STATUS_REPORT); - this->insertInCommandMap(supv::UPDATE_AVAILABLE); - this->insertInCommandMap(supv::UPDATE_VERIFY); - this->insertInCommandMap(supv::UPDATE_IMAGE_DATA); - this->insertInCommandMap(supv::WATCHDOGS_ENABLE); - this->insertInCommandMap(supv::WATCHDOGS_CONFIG_TIMEOUT); - this->insertInCommandMap(supv::ENABLE_LATCHUP_ALERT); - this->insertInCommandMap(supv::DISABLE_LATCHUP_ALERT); - this->insertInCommandMap(supv::AUTO_CALIBRATE_ALERT); - this->insertInCommandMap(supv::SET_ALERT_LIMIT); - this->insertInCommandMap(supv::SET_ALERT_IRQ_FILTER); - this->insertInCommandMap(supv::SET_ADC_SWEEP_PERIOD); - this->insertInCommandMap(supv::SET_ADC_ENABLED_CHANNELS); - this->insertInCommandMap(supv::SET_ADC_WINDOW_AND_STRIDE); - this->insertInCommandMap(supv::SET_ADC_THRESHOLD); - this->insertInCommandMap(supv::GET_LATCHUP_STATUS_REPORT); - this->insertInCommandMap(supv::COPY_ADC_DATA_TO_MRAM); - this->insertInCommandMap(supv::ENABLE_NVMS); - this->insertInCommandMap(supv::SELECT_NVM); - this->insertInCommandMap(supv::RUN_AUTO_EM_TESTS); - this->insertInCommandMap(supv::WIPE_MRAM); - this->insertInCommandMap(supv::PRINT_CPU_STATS); - this->insertInCommandMap(supv::SET_DBG_VERBOSITY); - this->insertInCommandMap(supv::SET_GPIO); - this->insertInCommandMap(supv::READ_GPIO); - this->insertInCommandMap(supv::RESTART_SUPERVISOR); - this->insertInCommandMap(supv::FACTORY_RESET_CLEAR_ALL); - this->insertInCommandMap(supv::FACTORY_RESET_CLEAR_MIRROR); - this->insertInCommandMap(supv::FACTORY_RESET_CLEAR_CIRCULAR); - this->insertInCommandMap(supv::CAN_LOOPBACK_TEST); - this->insertInCommandAndReplyMap(supv::FIRST_MRAM_DUMP, 3); - this->insertInCommandAndReplyMap(supv::CONSECUTIVE_MRAM_DUMP, 3); - this->insertInReplyMap(supv::ACK_REPORT, 3, nullptr, supv::SIZE_ACK_REPORT); - this->insertInReplyMap(supv::EXE_REPORT, 3, nullptr, supv::SIZE_EXE_REPORT); - this->insertInReplyMap(supv::HK_REPORT, 3, &hkset, supv::SIZE_HK_REPORT); - this->insertInReplyMap(supv::BOOT_STATUS_REPORT, 3, &bootStatusReport, - supv::SIZE_BOOT_STATUS_REPORT); - this->insertInReplyMap(supv::LATCHUP_REPORT, 3, &latchupStatusReport, - supv::SIZE_LATCHUP_STATUS_REPORT); + using namespace supv; + this->insertInCommandMap(GET_HK_REPORT); + this->insertInCommandMap(START_MPSOC); + this->insertInCommandMap(SHUTDOWN_MPSOC); + this->insertInCommandMap(SEL_MPSOC_BOOT_IMAGE); + this->insertInCommandMap(SET_BOOT_TIMEOUT); + this->insertInCommandMap(SET_MAX_RESTART_TRIES); + this->insertInCommandMap(RESET_MPSOC); + this->insertInCommandMap(SET_TIME_REF); + this->insertInCommandMap(DISABLE_PERIOIC_HK_TRANSMISSION); + this->insertInCommandMap(GET_BOOT_STATUS_REPORT); + this->insertInCommandMap(ENABLE_LATCHUP_ALERT); + this->insertInCommandMap(DISABLE_LATCHUP_ALERT); + this->insertInCommandMap(SET_ALERT_LIMIT); + this->insertInCommandMap(SET_ADC_ENABLED_CHANNELS); + this->insertInCommandMap(SET_ADC_WINDOW_AND_STRIDE); + this->insertInCommandMap(SET_ADC_THRESHOLD); + this->insertInCommandMap(GET_LATCHUP_STATUS_REPORT); + this->insertInCommandMap(COPY_ADC_DATA_TO_MRAM); + this->insertInCommandMap(REQUEST_ADC_REPORT); + this->insertInCommandMap(RUN_AUTO_EM_TESTS); + this->insertInCommandMap(WIPE_MRAM); + this->insertInCommandMap(SET_GPIO); + this->insertInCommandMap(READ_GPIO); + this->insertInCommandMap(RESTART_SUPERVISOR); + this->insertInCommandMap(FACTORY_RESET_CLEAR_ALL); + this->insertInCommandMap(FACTORY_RESET_CLEAR_MIRROR); + this->insertInCommandMap(FACTORY_RESET_CLEAR_CIRCULAR); + this->insertInCommandMap(START_MPSOC_QUIET); + this->insertInCommandMap(SET_SHUTDOWN_TIMEOUT); + this->insertInCommandMap(FACTORY_FLASH); + this->insertInCommandMap(ENABLE_AUTO_TM); + this->insertInCommandMap(DISABLE_AUTO_TM); + this->insertInCommandMap(LOGGING_REQUEST_COUNTERS); + this->insertInCommandMap(LOGGING_CLEAR_COUNTERS); + this->insertInCommandMap(LOGGING_SET_TOPIC); + this->insertInCommandMap(RESET_PL); + this->insertInCommandMap(ENABLE_NVMS); + this->insertInCommandAndReplyMap(FIRST_MRAM_DUMP, 0, nullptr, 0, false, false, FIRST_MRAM_DUMP, + &mramDumpTimeout); + this->insertInCommandAndReplyMap(CONSECUTIVE_MRAM_DUMP, 0, nullptr, 0, false, false, + CONSECUTIVE_MRAM_DUMP, &mramDumpTimeout); + this->insertInReplyMap(ACK_REPORT, 3, nullptr, SIZE_ACK_REPORT, false, + &acknowledgementReportTimeout); + this->insertInReplyMap(EXE_REPORT, 0, nullptr, SIZE_EXE_REPORT, false, &executionReportTimeout); + this->insertInReplyMap(HK_REPORT, 3, &hkset, SIZE_HK_REPORT); + this->insertInReplyMap(BOOT_STATUS_REPORT, 3, &bootStatusReport, SIZE_BOOT_STATUS_REPORT); + this->insertInReplyMap(LATCHUP_REPORT, 3, &latchupStatusReport, SIZE_LATCHUP_STATUS_REPORT); + this->insertInReplyMap(LOGGING_REPORT, 3, &loggingReport, SIZE_LOGGING_REPORT); + this->insertInReplyMap(ADC_REPORT, 3, &adcReport, SIZE_ADC_REPORT); +} + +ReturnValue_t PlocSupervisorHandler::enableReplyInReplyMap(DeviceCommandMap::iterator command, + uint8_t expectedReplies, + bool useAlternateId, + DeviceCommandId_t alternateReplyID) { + using namespace supv; + ReturnValue_t result = RETURN_OK; + + uint8_t enabledReplies = 0; + + switch (command->first) { + case GET_HK_REPORT: { + enabledReplies = 3; + result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, HK_REPORT); + if (result != RETURN_OK) { + sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " << HK_REPORT + << " not in replyMap" << std::endl; + } + break; + } + case GET_BOOT_STATUS_REPORT: { + enabledReplies = 3; + result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, + BOOT_STATUS_REPORT); + if (result != RETURN_OK) { + sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " + << BOOT_STATUS_REPORT << " not in replyMap" << std::endl; + } + break; + } + case GET_LATCHUP_STATUS_REPORT: { + enabledReplies = 3; + result = + DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, LATCHUP_REPORT); + if (result != RETURN_OK) { + sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " + << LATCHUP_REPORT << " not in replyMap" << std::endl; + } + break; + } + case LOGGING_REQUEST_COUNTERS: { + enabledReplies = 3; + result = + DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, LOGGING_REPORT); + if (result != RETURN_OK) { + sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " + << LOGGING_REPORT << " not in replyMap" << std::endl; + } + break; + } + case REQUEST_ADC_REPORT: { + enabledReplies = 3; + result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, ADC_REPORT); + if (result != RETURN_OK) { + sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " << ADC_REPORT + << " not in replyMap" << std::endl; + } + break; + } + case FIRST_MRAM_DUMP: { + enabledReplies = 2; // expected replies will be increased in handleMramDumpPacket + result = + DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, FIRST_MRAM_DUMP); + if (result != RETURN_OK) { + sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " + << FIRST_MRAM_DUMP << " not in replyMap" << std::endl; + } + break; + } + case CONSECUTIVE_MRAM_DUMP: { + enabledReplies = 2; // expected replies will be increased in handleMramDumpPacket + result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, + CONSECUTIVE_MRAM_DUMP); + if (result != RETURN_OK) { + sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " + << CONSECUTIVE_MRAM_DUMP << " not in replyMap" << std::endl; + } + break; + } + case START_MPSOC: + case SHUTDOWN_MPSOC: + case SEL_MPSOC_BOOT_IMAGE: + case SET_BOOT_TIMEOUT: + case SET_MAX_RESTART_TRIES: + case RESET_MPSOC: + case SET_TIME_REF: + case ENABLE_LATCHUP_ALERT: + case DISABLE_LATCHUP_ALERT: + case SET_ALERT_LIMIT: + case SET_ADC_ENABLED_CHANNELS: + case SET_ADC_WINDOW_AND_STRIDE: + case SET_ADC_THRESHOLD: + case COPY_ADC_DATA_TO_MRAM: + case RUN_AUTO_EM_TESTS: + case WIPE_MRAM: + case SET_GPIO: + case READ_GPIO: + case RESTART_SUPERVISOR: + case FACTORY_RESET_CLEAR_ALL: + case FACTORY_RESET_CLEAR_MIRROR: + case FACTORY_RESET_CLEAR_CIRCULAR: + case DISABLE_PERIOIC_HK_TRANSMISSION: + case START_MPSOC_QUIET: + case SET_SHUTDOWN_TIMEOUT: + case FACTORY_FLASH: + case ENABLE_AUTO_TM: + case DISABLE_AUTO_TM: + case LOGGING_CLEAR_COUNTERS: + case LOGGING_SET_TOPIC: + case RESET_PL: + case ENABLE_NVMS: + enabledReplies = 2; + break; + default: + sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Unknown command id" << std::endl; + break; + } + + /** + * Every command causes at least one acknowledgment and one execution report. Therefore both + * replies will be enabled here. + */ + result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, ACK_REPORT); + if (result != RETURN_OK) { + sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " << ACK_REPORT + << " not in replyMap" << std::endl; + } + + setExecutionTimeout(command->first); + + result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, EXE_REPORT); + if (result != RETURN_OK) { + sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " << EXE_REPORT + << " not in replyMap" << std::endl; + } + + return RETURN_OK; } ReturnValue_t PlocSupervisorHandler::scanForReply(const uint8_t* start, size_t remainingSize, DeviceCommandId_t* foundId, size_t* foundLen) { - if (nextReplyId == supv::FIRST_MRAM_DUMP) { - *foundId = supv::FIRST_MRAM_DUMP; + using namespace supv; + if (nextReplyId == FIRST_MRAM_DUMP) { + *foundId = FIRST_MRAM_DUMP; return parseMramPackets(start, remainingSize, foundLen); - } else if (nextReplyId == supv::CONSECUTIVE_MRAM_DUMP) { - *foundId = supv::CONSECUTIVE_MRAM_DUMP; + } else if (nextReplyId == CONSECUTIVE_MRAM_DUMP) { + *foundId = CONSECUTIVE_MRAM_DUMP; return parseMramPackets(start, remainingSize, foundLen); } @@ -343,38 +610,46 @@ ReturnValue_t PlocSupervisorHandler::scanForReply(const uint8_t* start, size_t r uint16_t apid = (*(start) << 8 | *(start + 1)) & APID_MASK; switch (apid) { - case (supv::APID_ACK_SUCCESS): - *foundLen = supv::SIZE_ACK_REPORT; - *foundId = supv::ACK_REPORT; + case (APID_ACK_SUCCESS): + *foundLen = SIZE_ACK_REPORT; + *foundId = ACK_REPORT; break; - case (supv::APID_ACK_FAILURE): - *foundLen = supv::SIZE_ACK_REPORT; - *foundId = supv::ACK_REPORT; + case (APID_ACK_FAILURE): + *foundLen = SIZE_ACK_REPORT; + *foundId = ACK_REPORT; break; - case (supv::APID_HK_REPORT): - *foundLen = supv::SIZE_HK_REPORT; - *foundId = supv::HK_REPORT; + case (APID_HK_REPORT): + *foundLen = SIZE_HK_REPORT; + *foundId = HK_REPORT; break; - case (supv::APID_BOOT_STATUS_REPORT): - *foundLen = supv::SIZE_BOOT_STATUS_REPORT; - *foundId = supv::BOOT_STATUS_REPORT; + case (APID_BOOT_STATUS_REPORT): + *foundLen = SIZE_BOOT_STATUS_REPORT; + *foundId = BOOT_STATUS_REPORT; break; - case (supv::APID_LATCHUP_STATUS_REPORT): - *foundLen = supv::SIZE_LATCHUP_STATUS_REPORT; - *foundId = supv::LATCHUP_REPORT; + case (APID_LATCHUP_STATUS_REPORT): + *foundLen = SIZE_LATCHUP_STATUS_REPORT; + *foundId = LATCHUP_REPORT; break; - case (supv::APID_EXE_SUCCESS): - *foundLen = supv::SIZE_EXE_REPORT; - *foundId = supv::EXE_REPORT; + case (APID_DATA_LOGGER_DATA): + *foundLen = SIZE_LOGGING_REPORT; + *foundId = LOGGING_REPORT; break; - case (supv::APID_EXE_FAILURE): - *foundLen = supv::SIZE_EXE_REPORT; - *foundId = supv::EXE_REPORT; + case (APID_ADC_REPORT): + *foundLen = SIZE_ADC_REPORT; + *foundId = ADC_REPORT; + break; + case (APID_EXE_SUCCESS): + *foundLen = SIZE_EXE_REPORT; + *foundId = EXE_REPORT; + break; + case (APID_EXE_FAILURE): + *foundLen = SIZE_EXE_REPORT; + *foundId = EXE_REPORT; break; default: { sif::debug << "PlocSupervisorHandler::scanForReply: Reply has invalid apid" << std::endl; *foundLen = remainingSize; - return INVALID_APID; + return SupvReturnValuesIF::INVALID_APID; } } @@ -393,30 +668,39 @@ ReturnValue_t PlocSupervisorHandler::getSwitches(const uint8_t** switches, ReturnValue_t PlocSupervisorHandler::interpretDeviceReply(DeviceCommandId_t id, const uint8_t* packet) { + using namespace supv; ReturnValue_t result = RETURN_OK; switch (id) { - case supv::ACK_REPORT: { + case ACK_REPORT: { result = handleAckReport(packet); break; } - case (supv::HK_REPORT): { + case (HK_REPORT): { result = handleHkReport(packet); break; } - case (supv::BOOT_STATUS_REPORT): { + case (BOOT_STATUS_REPORT): { result = handleBootStatusReport(packet); break; } - case (supv::LATCHUP_REPORT): { + case (LATCHUP_REPORT): { result = handleLatchupStatusReport(packet); break; } - case (supv::FIRST_MRAM_DUMP): - case (supv::CONSECUTIVE_MRAM_DUMP): + case (LOGGING_REPORT): { + result = handleLoggingReport(packet); + break; + } + case (ADC_REPORT): { + result = handleAdcReport(packet); + break; + } + case (FIRST_MRAM_DUMP): + case (CONSECUTIVE_MRAM_DUMP): result = handleMramDumpPacket(id); break; - case (supv::EXE_REPORT): { + case (EXE_REPORT): { result = handleExecutionReport(packet); break; } @@ -432,25 +716,27 @@ ReturnValue_t PlocSupervisorHandler::interpretDeviceReply(DeviceCommandId_t id, void PlocSupervisorHandler::setNormalDatapoolEntriesInvalid() {} -uint32_t PlocSupervisorHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; } +uint32_t PlocSupervisorHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { + return 7000; +} ReturnValue_t PlocSupervisorHandler::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, LocalDataPoolManager& poolManager) { localDataPoolMap.emplace(supv::NUM_TMS, new PoolEntry({0})); localDataPoolMap.emplace(supv::TEMP_PS, new PoolEntry({0})); localDataPoolMap.emplace(supv::TEMP_PL, new PoolEntry({0})); - localDataPoolMap.emplace(supv::SOC_STATE, new PoolEntry({0})); + localDataPoolMap.emplace(supv::HK_SOC_STATE, new PoolEntry({0})); localDataPoolMap.emplace(supv::NVM0_1_STATE, new PoolEntry({0})); localDataPoolMap.emplace(supv::NVM3_STATE, new PoolEntry({0})); localDataPoolMap.emplace(supv::MISSION_IO_STATE, new PoolEntry({0})); localDataPoolMap.emplace(supv::FMC_STATE, new PoolEntry({0})); localDataPoolMap.emplace(supv::NUM_TCS, new PoolEntry({0})); - localDataPoolMap.emplace(supv::UPTIME, new PoolEntry({0})); + localDataPoolMap.emplace(supv::UPTIME, new PoolEntry({0})); localDataPoolMap.emplace(supv::CPULOAD, new PoolEntry({0})); localDataPoolMap.emplace(supv::AVAILABLEHEAP, new PoolEntry({0})); - localDataPoolMap.emplace(supv::BOOT_SIGNAL, new PoolEntry({0})); - localDataPoolMap.emplace(supv::RESET_COUNTER, new PoolEntry({0})); + localDataPoolMap.emplace(supv::BR_SOC_STATE, new PoolEntry({0})); + localDataPoolMap.emplace(supv::POWER_CYCLES, new PoolEntry({0})); localDataPoolMap.emplace(supv::BOOT_AFTER_MS, new PoolEntry({0})); localDataPoolMap.emplace(supv::BOOT_TIMEOUT_MS, new PoolEntry({0})); localDataPoolMap.emplace(supv::ACTIVE_NVM, new PoolEntry({0})); @@ -466,229 +752,202 @@ ReturnValue_t PlocSupervisorHandler::initializeLocalDataPool(localpool::DataPool localDataPoolMap.emplace(supv::CNT4, new PoolEntry({0})); localDataPoolMap.emplace(supv::CNT5, new PoolEntry({0})); localDataPoolMap.emplace(supv::CNT6, new PoolEntry({0})); - localDataPoolMap.emplace(supv::LATCHUP_RPT_TIME_SEC, new PoolEntry({0})); - localDataPoolMap.emplace(supv::LATCHUP_RPT_TIME_MIN, new PoolEntry({0})); - localDataPoolMap.emplace(supv::LATCHUP_RPT_TIME_HOUR, new PoolEntry({0})); - localDataPoolMap.emplace(supv::LATCHUP_RPT_TIME_DAY, new PoolEntry({0})); - localDataPoolMap.emplace(supv::LATCHUP_RPT_TIME_MON, new PoolEntry({0})); - localDataPoolMap.emplace(supv::LATCHUP_RPT_TIME_YEAR, new PoolEntry({0})); - localDataPoolMap.emplace(supv::LATCHUP_RPT_TIME_MSEC, new PoolEntry({0})); - localDataPoolMap.emplace(supv::LATCHUP_RPT_TIME_IS_SET, new PoolEntry({0})); + localDataPoolMap.emplace(supv::LATCHUP_RPT_TIME_MSEC, new PoolEntry({0})); + localDataPoolMap.emplace(supv::LATCHUP_RPT_TIME_SEC, new PoolEntry({0})); + localDataPoolMap.emplace(supv::LATCHUP_RPT_TIME_MIN, new PoolEntry({0})); + localDataPoolMap.emplace(supv::LATCHUP_RPT_TIME_HOUR, new PoolEntry({0})); + localDataPoolMap.emplace(supv::LATCHUP_RPT_TIME_DAY, new PoolEntry({0})); + localDataPoolMap.emplace(supv::LATCHUP_RPT_TIME_MON, new PoolEntry({0})); + localDataPoolMap.emplace(supv::LATCHUP_RPT_TIME_YEAR, new PoolEntry({0})); + localDataPoolMap.emplace(supv::LATCHUP_RPT_IS_SET, new PoolEntry({0})); + + localDataPoolMap.emplace(supv::LATCHUP_HAPPENED_CNT_0, new PoolEntry({0})); + localDataPoolMap.emplace(supv::LATCHUP_HAPPENED_CNT_1, new PoolEntry({0})); + localDataPoolMap.emplace(supv::LATCHUP_HAPPENED_CNT_2, new PoolEntry({0})); + localDataPoolMap.emplace(supv::LATCHUP_HAPPENED_CNT_3, new PoolEntry({0})); + localDataPoolMap.emplace(supv::LATCHUP_HAPPENED_CNT_4, new PoolEntry({0})); + localDataPoolMap.emplace(supv::LATCHUP_HAPPENED_CNT_5, new PoolEntry({0})); + localDataPoolMap.emplace(supv::LATCHUP_HAPPENED_CNT_6, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_DEVIATION_TRIGGERS_CNT, new PoolEntry({0})); + localDataPoolMap.emplace(supv::TC_RECEIVED_CNT, new PoolEntry({0})); + localDataPoolMap.emplace(supv::TM_AVAILABLE_CNT, new PoolEntry({0})); + localDataPoolMap.emplace(supv::SUPERVISOR_BOOTS, new PoolEntry({0})); + localDataPoolMap.emplace(supv::MPSOC_BOOTS, new PoolEntry({0})); + localDataPoolMap.emplace(supv::MPSOC_BOOT_FAILED_ATTEMPTS, new PoolEntry({0})); + localDataPoolMap.emplace(supv::MPSOC_POWER_UP, new PoolEntry({0})); + localDataPoolMap.emplace(supv::MPSOC_UPDATES, new PoolEntry({0})); + localDataPoolMap.emplace(supv::LAST_RECVD_TC, new PoolEntry({0})); + + localDataPoolMap.emplace(supv::ADC_RAW_0, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_RAW_1, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_RAW_2, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_RAW_3, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_RAW_4, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_RAW_5, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_RAW_6, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_RAW_7, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_RAW_8, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_RAW_9, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_RAW_10, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_RAW_11, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_RAW_12, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_RAW_13, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_RAW_14, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_RAW_15, new PoolEntry({0})); + + localDataPoolMap.emplace(supv::ADC_ENG_0, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_ENG_1, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_ENG_2, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_ENG_3, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_ENG_4, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_ENG_5, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_ENG_6, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_ENG_7, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_ENG_8, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_ENG_9, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_ENG_10, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_ENG_11, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_ENG_12, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_ENG_13, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_ENG_14, new PoolEntry({0})); + localDataPoolMap.emplace(supv::ADC_ENG_15, new PoolEntry({0})); return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t PlocSupervisorHandler::enableReplyInReplyMap(DeviceCommandMap::iterator command, - uint8_t expectedReplies, - bool useAlternateId, - DeviceCommandId_t alternateReplyID) { +void PlocSupervisorHandler::handleEvent(EventMessage* eventMessage) { ReturnValue_t result = RETURN_OK; + object_id_t objectId = eventMessage->getReporter(); + Event event = eventMessage->getEvent(); + switch (objectId) { + case objects::PLOC_SUPERVISOR_HELPER: { + plocSupvHelperExecuting = false; + // After execution of update procedure, PLOC is in a state where it draws approx. 700 mA of + // current. To leave this state the shutdown MPSoC command must be sent here. + if (event == PlocSupvHelper::SUPV_UPDATE_FAILED || + event == PlocSupvHelper::SUPV_UPDATE_SUCCESSFUL || + event == PlocSupvHelper::SUPV_CONTINUE_UPDATE_FAILED || + event == PlocSupvHelper::SUPV_CONTINUE_UPDATE_SUCCESSFUL) { + result = this->executeAction(supv::SHUTDOWN_MPSOC, NO_COMMANDER, nullptr, 0); + if (result != RETURN_OK) { + triggerEvent(SUPV_MPSOC_SHUWDOWN_BUILD_FAILED); + sif::warning << "PlocSupervisorHandler::handleEvent: Failed to build MPSoC shutdown " + "command" + << std::endl; + return; + } + } + break; + } + default: + sif::debug << "PlocMPSoCHandler::handleEvent: Did not subscribe to this event" << std::endl; + break; + } +} - uint8_t enabledReplies = 0; - - switch (command->first) { - case supv::GET_HK_REPORT: { - enabledReplies = 3; - result = - DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, supv::HK_REPORT); - if (result != RETURN_OK) { - sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " - << supv::HK_REPORT << " not in replyMap" << std::endl; - } +void PlocSupervisorHandler::setExecutionTimeout(DeviceCommandId_t command) { + using namespace supv; + switch (command) { + case FIRST_MRAM_DUMP: + case CONSECUTIVE_MRAM_DUMP: + executionReportTimeout.setTimeout(MRAM_DUMP_EXECUTION_TIMEOUT); break; - } - case supv::GET_BOOT_STATUS_REPORT: { - enabledReplies = 3; - result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, - supv::BOOT_STATUS_REPORT); - if (result != RETURN_OK) { - sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " - << supv::BOOT_STATUS_REPORT << " not in replyMap" << std::endl; - } - break; - } - case supv::GET_LATCHUP_STATUS_REPORT: { - enabledReplies = 3; - result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, - supv::LATCHUP_REPORT); - if (result != RETURN_OK) { - sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " - << supv::LATCHUP_REPORT << " not in replyMap" << std::endl; - } - break; - } - case supv::FIRST_MRAM_DUMP: { - enabledReplies = 2; // expected replies will be increased in handleMramDumpPacket - result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, - supv::FIRST_MRAM_DUMP); - if (result != RETURN_OK) { - sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " - << supv::FIRST_MRAM_DUMP << " not in replyMap" << std::endl; - } - break; - } - case supv::CONSECUTIVE_MRAM_DUMP: { - enabledReplies = 2; // expected replies will be increased in handleMramDumpPacket - result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, - supv::CONSECUTIVE_MRAM_DUMP); - if (result != RETURN_OK) { - sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " - << supv::CONSECUTIVE_MRAM_DUMP << " not in replyMap" << std::endl; - } - break; - } - case supv::RESTART_MPSOC: - case supv::START_MPSOC: - case supv::SHUTDOWN_MPSOC: - case supv::SEL_MPSOC_BOOT_IMAGE: - case supv::SET_BOOT_TIMEOUT: - case supv::SET_MAX_RESTART_TRIES: - case supv::RESET_MPSOC: - case supv::SET_TIME_REF: - case supv::UPDATE_AVAILABLE: - case supv::UPDATE_IMAGE_DATA: - case supv::UPDATE_VERIFY: - case supv::WATCHDOGS_ENABLE: - case supv::WATCHDOGS_CONFIG_TIMEOUT: - case supv::ENABLE_LATCHUP_ALERT: - case supv::DISABLE_LATCHUP_ALERT: - case supv::AUTO_CALIBRATE_ALERT: - case supv::SET_ALERT_LIMIT: - case supv::SET_ALERT_IRQ_FILTER: - case supv::SET_ADC_SWEEP_PERIOD: - case supv::SET_ADC_ENABLED_CHANNELS: - case supv::SET_ADC_WINDOW_AND_STRIDE: - case supv::SET_ADC_THRESHOLD: - case supv::COPY_ADC_DATA_TO_MRAM: - case supv::ENABLE_NVMS: - case supv::SELECT_NVM: - case supv::RUN_AUTO_EM_TESTS: - case supv::WIPE_MRAM: - case supv::SET_DBG_VERBOSITY: - case supv::CAN_LOOPBACK_TEST: - case supv::PRINT_CPU_STATS: - case supv::SET_GPIO: - case supv::READ_GPIO: - case supv::RESTART_SUPERVISOR: - case supv::FACTORY_RESET_CLEAR_ALL: - case supv::FACTORY_RESET_CLEAR_MIRROR: - case supv::FACTORY_RESET_CLEAR_CIRCULAR: - case supv::REQUEST_LOGGING_DATA: - case supv::DISABLE_PERIOIC_HK_TRANSMISSION: - enabledReplies = 2; + case COPY_ADC_DATA_TO_MRAM: + executionReportTimeout.setTimeout(COPY_ADC_TO_MRAM_TIMEOUT); break; default: - sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Unknown command id" << std::endl; + executionReportTimeout.setTimeout(EXECUTION_DEFAULT_TIMEOUT); break; } - - /** - * Every command causes at least one acknowledgment and one execution report. Therefore both - * replies will be enabled here. - */ - result = - DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, supv::ACK_REPORT); - if (result != RETURN_OK) { - sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " << supv::ACK_REPORT - << " not in replyMap" << std::endl; - } - - result = - DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, supv::EXE_REPORT); - if (result != RETURN_OK) { - sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " << supv::EXE_REPORT - << " not in replyMap" << std::endl; - } - - return RETURN_OK; } ReturnValue_t PlocSupervisorHandler::verifyPacket(const uint8_t* start, size_t foundLen) { uint16_t receivedCrc = *(start + foundLen - 2) << 8 | *(start + foundLen - 1); uint16_t recalculatedCrc = CRC::crc16ccitt(start, foundLen - 2); if (receivedCrc != recalculatedCrc) { - return CRC_FAILURE; + return SupvReturnValuesIF::CRC_FAILURE; } return RETURN_OK; } ReturnValue_t PlocSupervisorHandler::handleAckReport(const uint8_t* data) { + using namespace supv; ReturnValue_t result = RETURN_OK; - result = verifyPacket(data, supv::SIZE_ACK_REPORT); - if (result == CRC_FAILURE) { + AcknowledgmentReport ack; + ack.addWholeData(data, SIZE_ACK_REPORT); + + result = ack.checkCrc(); + if (result != RETURN_OK) { sif::error << "PlocSupervisorHandler::handleAckReport: CRC failure" << std::endl; nextReplyId = supv::NONE; replyRawReplyIfnotWiretapped(data, supv::SIZE_ACK_REPORT); triggerEvent(SUPV_CRC_FAILURE_EVENT); - sendFailureReport(supv::ACK_REPORT, CRC_FAILURE); + sendFailureReport(supv::ACK_REPORT, SupvReturnValuesIF::CRC_FAILURE); disableAllReplies(); return RETURN_OK; } - uint16_t apid = (*(data) << 8 | *(data + 1)) & APID_MASK; + result = ack.checkApid(); - switch (apid) { - case supv::APID_ACK_FAILURE: { - // TODO: Interpretation of status field in acknowledgment report - sif::debug << "PlocSupervisorHandler::handleAckReport: Received Ack failure report" - << std::endl; + switch (result) { + case SupvReturnValuesIF::RECEIVED_ACK_FAILURE: { DeviceCommandId_t commandId = getPendingCommand(); if (commandId != DeviceHandlerIF::NO_COMMAND_ID) { - triggerEvent(SUPV_ACK_FAILURE, commandId); + triggerEvent(SUPV_ACK_FAILURE, commandId, static_cast(ack.getStatusCode())); } - sendFailureReport(supv::ACK_REPORT, RECEIVED_ACK_FAILURE); + printAckFailureInfo(ack.getStatusCode(), commandId); + sendFailureReport(supv::ACK_REPORT, SupvReturnValuesIF::RECEIVED_ACK_FAILURE); disableAllReplies(); nextReplyId = supv::NONE; result = IGNORE_REPLY_DATA; break; } - case supv::APID_ACK_SUCCESS: { + case RETURN_OK: { setNextReplyId(); break; } + case SupvReturnValuesIF::INVALID_APID: + sif::warning << "PlocSupervisorHandler::handleAckReport: Invalid APID in Ack report" + << std::endl; + sendFailureReport(supv::ACK_REPORT, result); + disableAllReplies(); + nextReplyId = supv::NONE; + result = IGNORE_REPLY_DATA; + break; default: { - sif::debug << "PlocSupervisorHandler::handleAckReport: Invalid APID in Ack report" - << std::endl; + sif::error << "PlocSupervisorHandler::handleAckReport: APID parsing failed" << std::endl; result = RETURN_FAILED; break; } } - return result; } ReturnValue_t PlocSupervisorHandler::handleExecutionReport(const uint8_t* data) { + using namespace supv; ReturnValue_t result = RETURN_OK; - result = verifyPacket(data, supv::SIZE_EXE_REPORT); - if (result == CRC_FAILURE) { + ExecutionReport exe; + exe.addWholeData(data, SIZE_EXE_REPORT); + + result = exe.checkCrc(); + if (result != RETURN_OK) { sif::error << "PlocSupervisorHandler::handleExecutionReport: CRC failure" << std::endl; nextReplyId = supv::NONE; return result; } - uint16_t apid = (*(data) << 8 | *(data + 1)) & APID_MASK; + result = exe.checkApid(); - switch (apid) { - case (supv::APID_EXE_SUCCESS): { + switch (result) { + case (RETURN_OK): { + handleExecutionSuccessReport(data); break; } - case (supv::APID_EXE_FAILURE): { - // TODO: Interpretation of status field in execution report - sif::error - << "PlocSupervisorHandler::handleExecutionReport: Received execution failure report" - << std::endl; - DeviceCommandId_t commandId = getPendingCommand(); - if (commandId != DeviceHandlerIF::NO_COMMAND_ID) { - triggerEvent(SUPV_EXE_FAILURE, commandId); - } else { - sif::debug << "PlocSupervisorHandler::handleExecutionReport: Unknown command id" - << std::endl; - } - sendFailureReport(supv::EXE_REPORT, RECEIVED_EXE_FAILURE); - disableExeReportReply(); - result = IGNORE_REPLY_DATA; + case (SupvReturnValuesIF::RECEIVED_EXE_FAILURE): { + handleExecutionFailureReport(exe.getStatusCode()); + result = RETURN_OK; break; } default: { @@ -697,9 +956,7 @@ ReturnValue_t PlocSupervisorHandler::handleExecutionReport(const uint8_t* data) break; } } - nextReplyId = supv::NONE; - return result; } @@ -708,8 +965,9 @@ ReturnValue_t PlocSupervisorHandler::handleHkReport(const uint8_t* data) { result = verifyPacket(data, supv::SIZE_HK_REPORT); - if (result == CRC_FAILURE) { + if (result == SupvReturnValuesIF::CRC_FAILURE) { sif::error << "PlocSupervisorHandler::handleHkReport: Hk report has invalid crc" << std::endl; + return result; } uint16_t offset = supv::DATA_FIELD_OFFSET; @@ -722,9 +980,10 @@ ReturnValue_t PlocSupervisorHandler::handleHkReport(const uint8_t* data) { hkset.tempSup = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 | *(data + offset + 3); offset += 4; - hkset.uptime = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 | - *(data + offset + 3); - offset += 4; + size_t size = sizeof(hkset.uptime.value); + result = SerializeAdapter::deSerialize(&hkset.uptime, data + offset, &size, + SerializeIF::Endianness::BIG); + offset += 8; hkset.cpuLoad = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 | *(data + offset + 3); offset += 4; @@ -766,7 +1025,7 @@ ReturnValue_t PlocSupervisorHandler::handleHkReport(const uint8_t* data) { << static_cast(hkset.nvm0_1_state.value) << std::endl; sif::info << "PlocSupervisorHandler::handleHkReport: nvm3_state: " << static_cast(hkset.nvm3_state.value) << std::endl; - sif::info << "PlocSupervisorHandler::handleHkReport: missoin_io_state: " + sif::info << "PlocSupervisorHandler::handleHkReport: mission_io_state: " << static_cast(hkset.missionIoState.value) << std::endl; sif::info << "PlocSupervisorHandler::handleHkReport: fmc_state: " << static_cast(hkset.fmcState.value) << std::endl; @@ -781,7 +1040,7 @@ ReturnValue_t PlocSupervisorHandler::handleBootStatusReport(const uint8_t* data) result = verifyPacket(data, supv::SIZE_BOOT_STATUS_REPORT); - if (result == CRC_FAILURE) { + if (result == SupvReturnValuesIF::CRC_FAILURE) { sif::error << "PlocSupervisorHandler::handleBootStatusReport: Boot status report has invalid" " crc" << std::endl; @@ -789,9 +1048,9 @@ ReturnValue_t PlocSupervisorHandler::handleBootStatusReport(const uint8_t* data) } uint16_t offset = supv::DATA_FIELD_OFFSET; - bootStatusReport.bootSignal = *(data + offset); + bootStatusReport.socState = *(data + offset); offset += 1; - bootStatusReport.resetCounter = *(data + offset); + bootStatusReport.powerCycles = *(data + offset); offset += 1; bootStatusReport.bootAfterMs = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 | *(data + offset + 3); @@ -806,17 +1065,23 @@ ReturnValue_t PlocSupervisorHandler::handleBootStatusReport(const uint8_t* data) bootStatusReport.bp1State = *(data + offset); offset += 1; bootStatusReport.bp2State = *(data + offset); + offset += 1; + bootStatusReport.bootState = *(data + offset); + offset += 1; + bootStatusReport.bootCycles = *(data + offset); nextReplyId = supv::EXE_REPORT; #if OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_PLOC_SUPERVISOR == 1 - sif::info << "PlocSupervisorHandler::handleBootStatusReport: Boot signal: " - << static_cast(bootStatusReport.bootSignal.value) << std::endl; - sif::info << "PlocSupervisorHandler::handleBootStatusReport: Reset counter: " - << static_cast(bootStatusReport.resetCounter.value) << std::endl; + sif::info << "PlocSupervisorHandler::handleBootStatusReport: SoC State (0 - off, 1 - booting, 2 " + "- Update, 3 " + "- operating, 4 - Shutdown, 5 - Reset): " + << static_cast(bootStatusReport.socState.value) << std::endl; + sif::info << "PlocSupervisorHandler::handleBootStatusReport: Power Cycles: " + << static_cast(bootStatusReport.powerCycles.value) << std::endl; sif::info << "PlocSupervisorHandler::handleBootStatusReport: BootAfterMs: " << bootStatusReport.bootAfterMs << " ms" << std::endl; - sif::info << "PlocSupervisorHandler::handleBootStatusReport: BootTimeoutMs: " + sif::info << "PlocSupervisorHandler::handleBootStatusReport: BootTimeoutMs: " << std::dec << bootStatusReport.bootTimeoutMs << " ms" << std::endl; sif::info << "PlocSupervisorHandler::handleBootStatusReport: Active NVM: " << static_cast(bootStatusReport.activeNvm.value) << std::endl; @@ -826,6 +1091,10 @@ ReturnValue_t PlocSupervisorHandler::handleBootStatusReport(const uint8_t* data) << static_cast(bootStatusReport.bp1State.value) << std::endl; sif::info << "PlocSupervisorHandler::handleBootStatusReport: BP2: " << static_cast(bootStatusReport.bp2State.value) << std::endl; + sif::info << "PlocSupervisorHandler::handleBootStatusReport: Boot state: " + << static_cast(bootStatusReport.bootState.value) << std::endl; + sif::info << "PlocSupervisorHandler::handleBootStatusReport: Boot cycles: " + << static_cast(bootStatusReport.bootCycles.value) << std::endl; #endif return result; @@ -836,7 +1105,7 @@ ReturnValue_t PlocSupervisorHandler::handleLatchupStatusReport(const uint8_t* da result = verifyPacket(data, supv::SIZE_LATCHUP_STATUS_REPORT); - if (result == CRC_FAILURE) { + if (result == SupvReturnValuesIF::CRC_FAILURE) { sif::error << "PlocSupervisorHandler::handleLatchupStatusReport: Latchup status report has " << "invalid crc" << std::endl; return result; @@ -859,30 +1128,21 @@ ReturnValue_t PlocSupervisorHandler::handleLatchupStatusReport(const uint8_t* da offset += 2; latchupStatusReport.cnt6 = *(data + offset) << 8 | *(data + offset + 1); offset += 2; - latchupStatusReport.timeSec = *(data + offset) << 24 | *(data + offset + 1) << 16 | - *(data + offset + 2) << 8 | *(data + offset + 3); - offset += 4; - latchupStatusReport.timeMin = *(data + offset) << 24 | *(data + offset + 1) << 16 | - *(data + offset + 2) << 8 | *(data + offset + 3); - offset += 4; - latchupStatusReport.timeHour = *(data + offset) << 24 | *(data + offset + 1) << 16 | - *(data + offset + 2) << 8 | *(data + offset + 3); - offset += 4; - latchupStatusReport.timeDay = *(data + offset) << 24 | *(data + offset + 1) << 16 | - *(data + offset + 2) << 8 | *(data + offset + 3); - offset += 4; - latchupStatusReport.timeMon = *(data + offset) << 24 | *(data + offset + 1) << 16 | - *(data + offset + 2) << 8 | *(data + offset + 3); - offset += 4; - latchupStatusReport.timeYear = *(data + offset) << 24 | *(data + offset + 1) << 16 | - *(data + offset + 2) << 8 | *(data + offset + 3); - offset += 4; - latchupStatusReport.timeMsec = *(data + offset) << 24 | *(data + offset + 1) << 16 | - *(data + offset + 2) << 8 | *(data + offset + 3); - offset += 4; - latchupStatusReport.isSet = *(data + offset) << 24 | *(data + offset + 1) << 16 | - *(data + offset + 2) << 8 | *(data + offset + 3); - offset += 4; + uint16_t msec = *(data + offset) << 8 | *(data + offset + 1); + latchupStatusReport.isSet = msec >> supv::LatchupStatusReport::IS_SET_BIT_POS; + latchupStatusReport.timeMsec = msec & (~(1 << latchupStatusReport.IS_SET_BIT_POS)); + offset += 2; + latchupStatusReport.timeSec = *(data + offset); + offset += 1; + latchupStatusReport.timeMin = *(data + offset); + offset += 1; + latchupStatusReport.timeHour = *(data + offset); + offset += 1; + latchupStatusReport.timeDay = *(data + offset); + offset += 1; + latchupStatusReport.timeMon = *(data + offset); + offset += 1; + latchupStatusReport.timeYear = *(data + offset); nextReplyId = supv::EXE_REPORT; @@ -904,26 +1164,97 @@ ReturnValue_t PlocSupervisorHandler::handleLatchupStatusReport(const uint8_t* da sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: CNT6: " << latchupStatusReport.cnt6 << std::endl; sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Sec: " - << latchupStatusReport.timeSec << std::endl; + << static_cast(latchupStatusReport.timeSec.value) << std::endl; sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Min: " - << latchupStatusReport.timeMin << std::endl; + << static_cast(latchupStatusReport.timeMin.value) << std::endl; sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Hour: " - << latchupStatusReport.timeHour << std::endl; + << static_cast(latchupStatusReport.timeHour.value) << std::endl; sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Day: " - << latchupStatusReport.timeDay << std::endl; + << static_cast(latchupStatusReport.timeDay.value) << std::endl; sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Mon: " - << latchupStatusReport.timeMon << std::endl; + << static_cast(latchupStatusReport.timeMon.value) << std::endl; sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Year: " - << latchupStatusReport.timeYear << std::endl; + << static_cast(latchupStatusReport.timeYear.value) << std::endl; sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Msec: " - << latchupStatusReport.timeMsec << std::endl; - sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: isSet: 0x" << std::hex - << latchupStatusReport.timeMsec << std::dec << std::endl; + << static_cast(latchupStatusReport.timeMsec.value) << std::endl; + sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: isSet: " + << static_cast(latchupStatusReport.isSet.value) << std::endl; #endif return result; } +ReturnValue_t PlocSupervisorHandler::handleLoggingReport(const uint8_t* data) { + ReturnValue_t result = RETURN_OK; + + result = verifyPacket(data, supv::SIZE_LOGGING_REPORT); + + if (result == SupvReturnValuesIF::CRC_FAILURE) { + sif::warning << "PlocSupervisorHandler::handleLoggingReport: Logging report has " + << "invalid crc" << std::endl; + return result; + } + + const uint8_t* dataField = data + supv::DATA_FIELD_OFFSET + sizeof(supv::RequestLoggingData::Sa); + result = loggingReport.read(); + if (result != RETURN_OK) { + return result; + } + loggingReport.setValidityBufferGeneration(false); + size_t size = loggingReport.getSerializedSize(); + result = loggingReport.deSerialize(&dataField, &size, SerializeIF::Endianness::BIG); + if (result != RETURN_OK) { + sif::warning << "PlocSupervisorHandler::handleLoggingReport: Deserialization failed" + << std::endl; + } + loggingReport.setValidityBufferGeneration(true); + loggingReport.setValidity(true, true); + result = loggingReport.commit(); + if (result != RETURN_OK) { + return result; + } +#if OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_PLOC_SUPERVISOR == 1 + loggingReport.printSet(); +#endif + nextReplyId = supv::EXE_REPORT; + return result; +} + +ReturnValue_t PlocSupervisorHandler::handleAdcReport(const uint8_t* data) { + ReturnValue_t result = RETURN_OK; + + result = verifyPacket(data, supv::SIZE_ADC_REPORT); + + if (result == SupvReturnValuesIF::CRC_FAILURE) { + sif::error << "PlocSupervisorHandler::handleAdcReport: ADC report has " + << "invalid crc" << std::endl; + return result; + } + + const uint8_t* dataField = data + supv::DATA_FIELD_OFFSET; + result = adcReport.read(); + if (result != RETURN_OK) { + return result; + } + adcReport.setValidityBufferGeneration(false); + size_t size = adcReport.getSerializedSize(); + result = adcReport.deSerialize(&dataField, &size, SerializeIF::Endianness::BIG); + if (result != RETURN_OK) { + sif::warning << "PlocSupervisorHandler::handleAdcReport: Deserialization failed" << std::endl; + } + adcReport.setValidityBufferGeneration(true); + adcReport.setValidity(true, true); + result = adcReport.commit(); + if (result != RETURN_OK) { + return result; + } +#if OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_PLOC_SUPERVISOR == 1 + adcReport.printSet(); +#endif + nextReplyId = supv::EXE_REPORT; + return result; +} + void PlocSupervisorHandler::setNextReplyId() { switch (getPendingCommand()) { case supv::GET_HK_REPORT: @@ -941,6 +1272,12 @@ void PlocSupervisorHandler::setNextReplyId() { case supv::CONSECUTIVE_MRAM_DUMP: nextReplyId = supv::CONSECUTIVE_MRAM_DUMP; break; + case supv::LOGGING_REQUEST_COUNTERS: + nextReplyId = supv::LOGGING_REPORT; + break; + case supv::REQUEST_ADC_REPORT: + nextReplyId = supv::ADC_REPORT; + break; default: /* If no telemetry is expected the next reply is always the execution report */ nextReplyId = supv::EXE_REPORT; @@ -967,7 +1304,8 @@ size_t PlocSupervisorHandler::getNextReplyLength(DeviceCommandId_t commandId) { DeviceReplyIter iter = deviceReplyMap.find(nextReplyId); if (iter != deviceReplyMap.end()) { - if (iter->second.delayCycles == 0) { + if ((iter->second.delayCycles == 0 && iter->second.countdown == nullptr) || + (not iter->second.active && iter->second.countdown != nullptr)) { /* Reply inactive */ return replyLen; } @@ -980,6 +1318,16 @@ size_t PlocSupervisorHandler::getNextReplyLength(DeviceCommandId_t commandId) { return replyLen; } +ReturnValue_t PlocSupervisorHandler::doSendReadHook() { + // Prevent DHB from polling UART during commands executed by the supervisor helper task + if (plocSupvHelperExecuting) { + return RETURN_FAILED; + } + return RETURN_OK; +} + +void PlocSupervisorHandler::doOffActivity() { startupState = StartupState::OFF; } + void PlocSupervisorHandler::handleDeviceTM(const uint8_t* data, size_t dataSize, DeviceCommandId_t replyId) { ReturnValue_t result = RETURN_OK; @@ -1007,7 +1355,7 @@ void PlocSupervisorHandler::handleDeviceTM(const uint8_t* data, size_t dataSize, } void PlocSupervisorHandler::prepareEmptyCmd(uint16_t apid) { - supv::EmptyPacket packet(apid); + supv::ApidOnlyPacket packet(apid); packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); } @@ -1023,7 +1371,7 @@ ReturnValue_t PlocSupervisorHandler::prepareSetTimeRefCmd() { if (result != RETURN_OK) { sif::warning << "PlocSupervisorHandler::prepareSetTimeRefCmd: Failed to get current time" << std::endl; - return GET_TIME_FAILURE; + return SupvReturnValuesIF::GET_TIME_FAILURE; } supv::SetTimeRef packet(&time); packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); @@ -1048,40 +1396,12 @@ void PlocSupervisorHandler::prepareRestartTriesCmd(const uint8_t* commandData) { packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); } -void PlocSupervisorHandler::prepareWatchdogsEnableCmd(const uint8_t* commandData) { - uint8_t offset = 0; - uint8_t watchdogPs = *(commandData + offset); - offset += 1; - uint8_t watchdogPl = *(commandData + offset); - offset += 1; - uint8_t watchdogInt = *(commandData + offset); - supv::WatchdogsEnable packet(watchdogPs, watchdogPl, watchdogInt); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); -} - -ReturnValue_t PlocSupervisorHandler::prepareWatchdogsConfigTimeoutCmd(const uint8_t* commandData) { - uint8_t offset = 0; - uint8_t watchdog = *(commandData + offset); - offset += 1; - if (watchdog > 2) { - return INVALID_WATCHDOG; - } - uint32_t timeout = *(commandData + offset) << 24 | *(commandData + offset + 1) << 16 | - *(commandData + offset + 2) << 8 | *(commandData + offset + 3); - if (timeout < 1000 || timeout > 360000) { - return INVALID_WATCHDOG_TIMEOUT; - } - supv::WatchdogsConfigTimeout packet(watchdog, timeout); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - return RETURN_OK; -} - ReturnValue_t PlocSupervisorHandler::prepareLatchupConfigCmd(const uint8_t* commandData, DeviceCommandId_t deviceCommand) { ReturnValue_t result = RETURN_OK; uint8_t latchupId = *commandData; if (latchupId > 6) { - return INVALID_LATCHUP_ID; + return SupvReturnValuesIF::INVALID_LATCHUP_ID; } switch (deviceCommand) { case (supv::ENABLE_LATCHUP_ALERT): { @@ -1104,32 +1424,6 @@ ReturnValue_t PlocSupervisorHandler::prepareLatchupConfigCmd(const uint8_t* comm return result; } -ReturnValue_t PlocSupervisorHandler::prepareAutoCalibrateAlertCmd(const uint8_t* commandData) { - uint8_t offset = 0; - uint8_t latchupId = *commandData; - offset += 1; - uint32_t mg = *(commandData + offset) << 24 | *(commandData + offset + 1) << 16 | - *(commandData + offset + 2) << 8 | *(commandData + offset + 3); - if (latchupId > 6) { - return INVALID_LATCHUP_ID; - } - supv::AutoCalibrateAlert packet(latchupId, mg); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - return RETURN_OK; -} - -ReturnValue_t PlocSupervisorHandler::prepareSetAlertIrqFilterCmd(const uint8_t* commandData) { - uint8_t latchupId = *commandData; - uint8_t tp = *(commandData + 1); - uint8_t div = *(commandData + 2); - if (latchupId > 6) { - return INVALID_LATCHUP_ID; - } - supv::SetAlertIrqFilter packet(latchupId, tp, div); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - return RETURN_OK; -} - ReturnValue_t PlocSupervisorHandler::prepareSetAlertLimitCmd(const uint8_t* commandData) { uint8_t offset = 0; uint8_t latchupId = *commandData; @@ -1137,24 +1431,13 @@ ReturnValue_t PlocSupervisorHandler::prepareSetAlertLimitCmd(const uint8_t* comm uint32_t dutycycle = *(commandData + offset) << 24 | *(commandData + offset + 1) << 16 | *(commandData + offset + 2) << 8 | *(commandData + offset + 3); if (latchupId > 6) { - return INVALID_LATCHUP_ID; + return SupvReturnValuesIF::INVALID_LATCHUP_ID; } supv::SetAlertlimit packet(latchupId, dutycycle); packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); return RETURN_OK; } -ReturnValue_t PlocSupervisorHandler::prepareSetAdcSweetPeriodCmd(const uint8_t* commandData) { - uint32_t sweepPeriod = *(commandData) << 24 | *(commandData + 1) << 16 | *(commandData + 2) << 8 | - *(commandData + 3); - if (sweepPeriod < 21) { - return SWEEP_PERIOD_TOO_SMALL; - } - supv::SetAdcSweepPeriod packet(sweepPeriod); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - return RETURN_OK; -} - void PlocSupervisorHandler::prepareSetAdcEnabledChannelsCmd(const uint8_t* commandData) { uint16_t ch = *(commandData) << 8 | *(commandData + 1); supv::SetAdcEnabledChannels packet(ch); @@ -1177,23 +1460,10 @@ void PlocSupervisorHandler::prepareSetAdcThresholdCmd(const uint8_t* commandData packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); } -void PlocSupervisorHandler::prepareEnableNvmsCmd(const uint8_t* commandData) { - uint8_t n01 = *commandData; - uint8_t n3 = *(commandData + 1); - supv::EnableNvms packet(n01, n3); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); -} - -void PlocSupervisorHandler::prepareSelectNvmCmd(const uint8_t* commandData) { - uint8_t mem = *commandData; - supv::SelectNvm packet(mem); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); -} - ReturnValue_t PlocSupervisorHandler::prepareRunAutoEmTest(const uint8_t* commandData) { uint8_t test = *commandData; if (test != 1 && test != 2) { - return INVALID_TEST_PARAM; + return SupvReturnValuesIF::INVALID_TEST_PARAM; } supv::RunAutoEmTests packet(test); packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); @@ -1207,7 +1477,7 @@ ReturnValue_t PlocSupervisorHandler::prepareWipeMramCmd(const uint8_t* commandDa SerializeAdapter::deSerialize(&start, &commandData, &size, SerializeIF::Endianness::BIG); SerializeAdapter::deSerialize(&stop, &commandData, &size, SerializeIF::Endianness::BIG); if ((stop - start) <= 0) { - return INVALID_MRAM_ADDRESSES; + return SupvReturnValuesIF::INVALID_MRAM_ADDRESSES; } supv::MramCmd packet(start, stop, supv::MramCmd::MramAction::WIPE); packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); @@ -1223,7 +1493,7 @@ ReturnValue_t PlocSupervisorHandler::prepareDumpMramCmd(const uint8_t* commandDa supv::MramCmd packet(start, stop, supv::MramCmd::MramAction::DUMP); packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); if ((stop - start) <= 0) { - return INVALID_MRAM_ADDRESSES; + return SupvReturnValuesIF::INVALID_MRAM_ADDRESSES; } expectedMramDumpPackets = (stop - start) / supv::MAX_DATA_CAPACITY; if ((stop - start) % supv::MAX_DATA_CAPACITY) { @@ -1233,18 +1503,6 @@ ReturnValue_t PlocSupervisorHandler::prepareDumpMramCmd(const uint8_t* commandDa return RETURN_OK; } -void PlocSupervisorHandler::preparePrintCpuStatsCmd(const uint8_t* commandData) { - uint8_t en = *commandData; - supv::PrintCpuStats packet(en); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); -} - -void PlocSupervisorHandler::prepareSetDbgVerbosityCmd(const uint8_t* commandData) { - uint8_t vb = *commandData; - supv::SetDbgVerbosity packet(vb); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); -} - void PlocSupervisorHandler::prepareSetGpioCmd(const uint8_t* commandData) { uint8_t port = *commandData; uint8_t pin = *(commandData + 1); @@ -1267,11 +1525,46 @@ void PlocSupervisorHandler::packetToOutBuffer(uint8_t* packetData, size_t fullSi nextReplyId = supv::ACK_REPORT; } +void PlocSupervisorHandler::prepareSetShutdownTimeoutCmd(const uint8_t* commandData) { + uint32_t timeout = 0; + ReturnValue_t result = RETURN_OK; + size_t size = sizeof(timeout); + result = + SerializeAdapter::deSerialize(&timeout, &commandData, &size, SerializeIF::Endianness::BIG); + if (result != RETURN_OK) { + sif::warning + << "PlocSupervisorHandler::prepareSetShutdownTimeoutCmd: Failed to deserialize timeout" + << std::endl; + } + supv::SetShutdownTimeout packet(timeout); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); +} + +ReturnValue_t PlocSupervisorHandler::prepareLoggingRequest(const uint8_t* commandData, + size_t commandDataLen) { + using namespace supv; + RequestLoggingData::Sa sa = static_cast(*commandData); + uint8_t tpc = *(commandData + 1); + RequestLoggingData packet(sa, tpc); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + return RETURN_OK; +} + +ReturnValue_t PlocSupervisorHandler::prepareEnableNvmsCommand(const uint8_t* commandData) { + using namespace supv; + uint8_t nvm01 = *(commandData); + uint8_t nvm3 = *(commandData + 1); + EnableNvms packet(nvm01, nvm3); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + return RETURN_OK; +} + void PlocSupervisorHandler::disableAllReplies() { + using namespace supv; DeviceReplyMap::iterator iter; /* Disable ack reply */ - iter = deviceReplyMap.find(supv::ACK_REPORT); + iter = deviceReplyMap.find(ACK_REPORT); DeviceReplyInfo* info = &(iter->second); info->delayCycles = 0; info->command = deviceCommandMap.end(); @@ -1280,11 +1573,29 @@ void PlocSupervisorHandler::disableAllReplies() { /* If the command expects a telemetry packet the appropriate tm reply will be disabled here */ switch (commandId) { - case supv::GET_HK_REPORT: { - iter = deviceReplyMap.find(supv::GET_HK_REPORT); - info = &(iter->second); - info->delayCycles = 0; - info->command = deviceCommandMap.end(); + case GET_HK_REPORT: { + disableReply(GET_HK_REPORT); + break; + } + case FIRST_MRAM_DUMP: + case CONSECUTIVE_MRAM_DUMP: { + disableReply(commandId); + break; + } + case REQUEST_ADC_REPORT: { + disableReply(ADC_REPORT); + break; + } + case GET_BOOT_STATUS_REPORT: { + disableReply(BOOT_STATUS_REPORT); + break; + } + case GET_LATCHUP_STATUS_REPORT: { + disableReply(LATCHUP_REPORT); + break; + } + case LOGGING_REQUEST_COUNTERS: { + disableReply(LOGGING_REPORT); break; } default: { @@ -1296,6 +1607,14 @@ void PlocSupervisorHandler::disableAllReplies() { disableExeReportReply(); } +void PlocSupervisorHandler::disableReply(DeviceCommandId_t replyId) { + DeviceReplyMap::iterator iter = deviceReplyMap.find(replyId); + DeviceReplyInfo* info = &(iter->second); + info->delayCycles = 0; + info->active = false; + info->command = deviceCommandMap.end(); +} + void PlocSupervisorHandler::sendFailureReport(DeviceCommandId_t replyId, ReturnValue_t status) { DeviceReplyIter iter = deviceReplyMap.find(replyId); @@ -1323,6 +1642,7 @@ void PlocSupervisorHandler::disableExeReportReply() { DeviceReplyInfo* info = &(iter->second); info->delayCycles = 0; info->command = deviceCommandMap.end(); + info->active = false; /* Expected replies is set to one here. The value will set to 0 in replyToReply() */ info->command->second.expectedReplies = 1; } @@ -1351,7 +1671,10 @@ ReturnValue_t PlocSupervisorHandler::parseMramPackets(const uint8_t* packet, siz *foundLen = remainingSize; disableAllReplies(); bufferTop = 0; - return MRAM_PACKET_PARSING_FAILURE; + sif::info << "PlocSupervisorHandler::parseMramPackets: Can not find MRAM packet in space " + "packet buffer" + << std::endl; + return SupvReturnValuesIF::MRAM_PACKET_PARSING_FAILURE; } } @@ -1369,9 +1692,13 @@ ReturnValue_t PlocSupervisorHandler::handleMramDumpPacket(DeviceCommandId_t id) sif::warning << "PlocSupervisorHandler::handleMramDumpPacket: CRC failure" << std::endl; return result; } - handleMramDumpFile(id); - if (downlinkMramDump == true) { - handleDeviceTM(spacePacketBuffer + supv::SPACE_PACKET_HEADER_LENGTH, packetLen - 1, id); + result = handleMramDumpFile(id); + if (result != RETURN_OK) { + DeviceCommandMap::iterator iter = deviceCommandMap.find(id); + actionHelper.finish(false, iter->second.sendReplyTo, id, result); + disableAllReplies(); + nextReplyId = supv::NONE; + return result; } packetInBuffer = false; receivedMramDumpPackets++; @@ -1420,22 +1747,20 @@ void PlocSupervisorHandler::increaseExpectedMramReplies(DeviceCommandId_t id) { (sequenceFlags != static_cast(supv::SequenceFlags::STANDALONE_PKT))) { // Command expects at least one MRAM packet more and the execution report info->expectedReplies = 2; - // Wait maximum of 2 cycles for next MRAM packet - mramReplyInfo->delayCycles = 2; - // Also adapting delay cycles for execution report - exeReplyInfo->delayCycles = 3; + mramReplyInfo->countdown->resetTimer(); } else { // Command expects the execution report info->expectedReplies = 1; - mramReplyInfo->delayCycles = 0; + mramReplyInfo->active = false; } + exeReplyInfo->countdown->resetTimer(); return; } ReturnValue_t PlocSupervisorHandler::checkMramPacketApid() { uint16_t apid = (spacePacketBuffer[0] << 8 | spacePacketBuffer[1]) & supv::APID_MASK; if (apid != supv::APID_MRAM_DUMP_TM) { - return NO_MRAM_PACKET; + return SupvReturnValuesIF::NO_MRAM_PACKET; } return APERIODIC_REPLY; } @@ -1456,7 +1781,7 @@ ReturnValue_t PlocSupervisorHandler::handleMramDumpFile(DeviceCommandId_t id) { if (not std::filesystem::exists(activeMramFile)) { sif::warning << "PlocSupervisorHandler::handleMramDumpFile: MRAM file does not exist" << std::endl; - return MRAM_FILE_NOT_EXISTS; + return SupvReturnValuesIF::MRAM_FILE_NOT_EXISTS; } std::ofstream file(activeMramFile, std::ios_base::app | std::ios_base::out); file.write(reinterpret_cast(spacePacketBuffer + supv::SPACE_PACKET_HEADER_LENGTH), @@ -1483,19 +1808,19 @@ ReturnValue_t PlocSupervisorHandler::createMramDumpFile() { std::string filename = "mram-dump--" + timeStamp + ".bin"; -#ifdef TE0720_1CFA +#ifndef TE0720_1CFA std::string currentMountPrefix = sdcMan->getCurrentMountPrefix(); #else std::string currentMountPrefix("/mnt/sd0"); #endif /* BOARD_TE0720 == 0 */ // Check if path to PLOC directory exists - if (not std::filesystem::exists(std::string(currentMountPrefix + "/" + plocFilePath))) { - sif::warning << "PlocSupervisorHandler::createMramDumpFile: Ploc path does not exist" + if (not std::filesystem::exists(std::string(currentMountPrefix + "/" + supervisorFilePath))) { + sif::warning << "PlocSupervisorHandler::createMramDumpFile: Supervisor path does not exist" << std::endl; - return PATH_DOES_NOT_EXIST; + return SupvReturnValuesIF::PATH_DOES_NOT_EXIST; } - activeMramFile = currentMountPrefix + "/" + plocFilePath + "/" + filename; + activeMramFile = currentMountPrefix + "/" + supervisorFilePath + "/" + filename; // Create new file std::ofstream file(activeMramFile, std::ios_base::out); file.close(); @@ -1507,12 +1832,131 @@ ReturnValue_t PlocSupervisorHandler::getTimeStampString(std::string& timeStamp) Clock::TimeOfDay_t time; ReturnValue_t result = Clock::getDateAndTime(&time); if (result != RETURN_OK) { - sif::warning << "PlocSupervisorHandler::createMramDumpFile: Failed to get current time" + sif::warning << "PlocSupervisorHandler::getTimeStampString: Failed to get current time" << std::endl; - return GET_TIME_FAILURE; + return SupvReturnValuesIF::GET_TIME_FAILURE; } timeStamp = std::to_string(time.year) + "-" + std::to_string(time.month) + "-" + std::to_string(time.day) + "--" + std::to_string(time.hour) + "-" + std::to_string(time.minute) + "-" + std::to_string(time.second); return RETURN_OK; } + +ReturnValue_t PlocSupervisorHandler::extractUpdateCommand(const uint8_t* commandData, size_t size, + std::string* file, uint8_t* memoryId, + uint32_t* startAddress) { + ReturnValue_t result = RETURN_OK; + if (size > (config::MAX_FILENAME_SIZE + config::MAX_PATH_SIZE + sizeof(*memoryId)) + + sizeof(*startAddress)) { + sif::warning << "PlocSupervisorHandler::extractUpdateCommand: Data size too big" << std::endl; + return SupvReturnValuesIF::INVALID_LENGTH; + } + *file = std::string(reinterpret_cast(commandData)); + if (file->size() > (config::MAX_FILENAME_SIZE + config::MAX_PATH_SIZE)) { + sif::warning << "PlocSupervisorHandler::extractUpdateCommand: Filename too long" << std::endl; + return SupvReturnValuesIF::FILENAME_TOO_LONG; + } + *memoryId = *(commandData + file->size() + SIZE_NULL_TERMINATOR); + const uint8_t* startAddressPtr = + commandData + file->size() + SIZE_NULL_TERMINATOR + sizeof(*memoryId); + size_t remainingSize = 4; + result = SerializeAdapter::deSerialize(startAddress, startAddressPtr, &remainingSize, + SerializeIF::Endianness::BIG); + if (result != RETURN_OK) { + sif::warning + << "PlocSupervisorHandler::extractUpdateCommand: Failed to deserialize start address" + << std::endl; + return result; + } + return RETURN_OK; +} + +ReturnValue_t PlocSupervisorHandler::eventSubscription() { + ReturnValue_t result = RETURN_OK; + EventManagerIF* manager = ObjectManager::instance()->get(objects::EVENT_MANAGER); + if (manager == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::error << "PlocSupervisorHandler::eventSubscritpion: Invalid event manager" << std::endl; +#endif + return ObjectManagerIF::CHILD_INIT_FAILED; + ; + } + result = manager->registerListener(eventQueue->getId()); + if (result != RETURN_OK) { + return result; + } + result = manager->subscribeToEventRange( + eventQueue->getId(), event::getEventId(PlocSupvHelper::SUPV_UPDATE_FAILED), + event::getEventId(PlocSupvHelper::SUPV_EVENT_BUFFER_REQUEST_TERMINATED)); + if (result != RETURN_OK) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "PlocSupervisorHandler::eventSubscritpion: Failed to subscribe to events from " + " ploc supervisor helper" + << std::endl; +#endif + return ObjectManagerIF::CHILD_INIT_FAILED; + } + return result; +} + +void PlocSupervisorHandler::handleExecutionSuccessReport(const uint8_t* data) { + DeviceCommandId_t commandId = getPendingCommand(); + switch (commandId) { + case supv::READ_GPIO: { + supv::ExecutionReport exe; + exe.addWholeData(data, supv::SIZE_EXE_REPORT); + uint16_t gpioState = exe.getStatusCode(); +#if OBSW_DEBUG_PLOC_SUPERVISOR == 1 + sif::info << "PlocSupervisorHandler: Read GPIO TM, State: " << gpioState << std::endl; +#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ + DeviceCommandMap::iterator iter = deviceCommandMap.find(commandId); + if (iter->second.sendReplyTo == NO_COMMAND_ID) { + return; + } + uint8_t data[sizeof(gpioState)]; + size_t size = 0; + ReturnValue_t result = SerializeAdapter::serialize(&gpioState, data, &size, sizeof(gpioState), + SerializeIF::Endianness::BIG); + if (result != RETURN_OK) { + sif::debug << "PlocSupervisorHandler: Failed to deserialize GPIO state" << std::endl; + } + result = actionHelper.reportData(iter->second.sendReplyTo, commandId, data, sizeof(data)); + if (result != RETURN_OK) { + sif::warning << "PlocSupervisorHandler: Read GPIO, failed to report data" << std::endl; + } + break; + } + case supv::SET_TIME_REF: { + if (startupState == StartupState::SET_TIME_EXECUTING) { + startupState = StartupState::ON; + } + break; + } + default: + break; + } +} + +void PlocSupervisorHandler::handleExecutionFailureReport(uint16_t statusCode) { + using namespace supv; + DeviceCommandId_t commandId = getPendingCommand(); + if (commandId != DeviceHandlerIF::NO_COMMAND_ID) { + triggerEvent(SUPV_EXE_FAILURE, commandId, static_cast(statusCode)); + } + sendFailureReport(EXE_REPORT, SupvReturnValuesIF::RECEIVED_EXE_FAILURE); + disableExeReportReply(); +} + +void PlocSupervisorHandler::printAckFailureInfo(uint16_t statusCode, DeviceCommandId_t commandId) { + sif::warning << "PlocSupervisorHandler: Received Ack failure report with status code: 0x" + << std::hex << statusCode << std::endl; + switch (commandId) { + case (supv::SET_TIME_REF): { + sif::info << "PlocSupervisoHandler: Setting time failed. Make sure the OBC has a valid time" + << std::endl; + break; + } + default: + break; + } +} diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index b21ecf91..9946a1d5 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -2,19 +2,22 @@ #define MISSION_DEVICES_PLOCSUPERVISORHANDLER_H_ #include "OBSWConfig.h" +#include "PlocSupvHelper.h" #include "bsp_q7s/memory/SdCardManager.h" #include "devices/powerSwitcherList.h" #include "fsfw/devicehandlers/DeviceHandlerBase.h" +#include "fsfw/timemanager/Countdown.h" #include "fsfw_hal/linux/gpio/Gpio.h" #include "fsfw_hal/linux/gpio/LinuxLibgpioIF.h" #include "fsfw_hal/linux/uart/UartComIF.h" #include "linux/devices/devicedefinitions/PlocSupervisorDefinitions.h" +#include "linux/devices/devicedefinitions/SupvReturnValuesIF.h" /** * @brief This is the device handler for the supervisor of the PLOC which is programmed by * Thales. * - * @details The PLOC uses the space packet protocol for communication. To each command the PLOC + * @details The PLOC uses the space packet protocol for communication. On each command the PLOC * answers with at least one acknowledgment and one execution report. * Flight manual: * https://egit.irs.uni-stuttgart.de/redmine/projects/eive-flight-manual/wiki/PLOC_Commands @@ -25,10 +28,14 @@ class PlocSupervisorHandler : public DeviceHandlerBase { public: PlocSupervisorHandler(object_id_t objectId, object_id_t uartComIFid, CookieIF* comCookie, - Gpio uartIsolatorSwitch, power::Switch_t powerSwitch); + Gpio uartIsolatorSwitch, power::Switch_t powerSwitch, + PlocSupvHelper* supvHelper); virtual ~PlocSupervisorHandler(); virtual ReturnValue_t initialize() override; + void performOperationHook() override; + ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, + const uint8_t* data, size_t size) override; protected: void doStartUp() override; @@ -49,48 +56,10 @@ class PlocSupervisorHandler : public DeviceHandlerBase { uint8_t expectedReplies = 1, bool useAlternateId = false, DeviceCommandId_t alternateReplyID = 0) override; size_t getNextReplyLength(DeviceCommandId_t deviceCommand) override; + ReturnValue_t doSendReadHook() override; + void doOffActivity() override; private: - static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_SUPERVISOR_HANDLER; - - //! [EXPORT] : [COMMENT] Space Packet received from PLOC supervisor has invalid CRC - static const ReturnValue_t CRC_FAILURE = MAKE_RETURN_CODE(0xA0); - //! [EXPORT] : [COMMENT] Received ACK failure reply from PLOC supervisor - static const ReturnValue_t RECEIVED_ACK_FAILURE = MAKE_RETURN_CODE(0xA1); - //! [EXPORT] : [COMMENT] Received execution failure reply from PLOC supervisor - static const ReturnValue_t RECEIVED_EXE_FAILURE = MAKE_RETURN_CODE(0xA2); - //! [EXPORT] : [COMMENT] Received space packet with invalid APID from PLOC supervisor - static const ReturnValue_t INVALID_APID = MAKE_RETURN_CODE(0xA3); - //! [EXPORT] : [COMMENT] Failed to read current system time - static const ReturnValue_t GET_TIME_FAILURE = MAKE_RETURN_CODE(0xA4); - //! [EXPORT] : [COMMENT] Received command with invalid watchdog parameter. Valid watchdogs are 0 - //! for PS, 1 for PL and 2 for INT - static const ReturnValue_t INVALID_WATCHDOG = MAKE_RETURN_CODE(0xA5); - //! [EXPORT] : [COMMENT] Received watchdog timeout config command with invalid timeout. Valid - //! timeouts must be in the range between 1000 and 360000 ms. - static const ReturnValue_t INVALID_WATCHDOG_TIMEOUT = MAKE_RETURN_CODE(0xA6); - //! [EXPORT] : [COMMENT] Received latchup config command with invalid latchup ID - static const ReturnValue_t INVALID_LATCHUP_ID = MAKE_RETURN_CODE(0xA7); - //! [EXPORT] : [COMMENT] Received set adc sweep period command with invalid sweep period. Must be - //! larger than 21. - static const ReturnValue_t SWEEP_PERIOD_TOO_SMALL = MAKE_RETURN_CODE(0xA8); - //! [EXPORT] : [COMMENT] Receive auto EM test command with invalid test param. Valid params are 1 - //! and 2. - static const ReturnValue_t INVALID_TEST_PARAM = MAKE_RETURN_CODE(0xA9); - //! [EXPORT] : [COMMENT] Returned when scanning for MRAM dump packets failed. - static const ReturnValue_t MRAM_PACKET_PARSING_FAILURE = MAKE_RETURN_CODE(0xAA); - //! [EXPORT] : [COMMENT] Returned when the start and stop addresses of the MRAM dump or MRAM wipe - //! commands are invalid (e.g. start address bigger than stop address) - static const ReturnValue_t INVALID_MRAM_ADDRESSES = MAKE_RETURN_CODE(0xAB); - //! [EXPORT] : [COMMENT] Expect reception of an MRAM dump packet but received space packet with - //! other apid. - static const ReturnValue_t NO_MRAM_PACKET = MAKE_RETURN_CODE(0xAC); - //! [EXPORT] : [COMMENT] Path to PLOC directory on SD card does not exist - static const ReturnValue_t PATH_DOES_NOT_EXIST = MAKE_RETURN_CODE(0xAD); - //! [EXPORT] : [COMMENT] MRAM dump file does not exists. The file should actually already have - //! been created with the reception of the first dump packet. - static const ReturnValue_t MRAM_FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xAE); - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PLOC_SUPERVISOR_HANDLER; //! [EXPORT] : [COMMENT] PLOC supervisor crc failure in telemetry packet @@ -98,12 +67,37 @@ class PlocSupervisorHandler : public DeviceHandlerBase { //! [EXPORT] : [COMMENT] PLOC supervisor received acknowledgment failure report static const Event SUPV_ACK_FAILURE = MAKE_EVENT(2, severity::LOW); //! [EXPORT] : [COMMENT] PLOC received execution failure report + //! P1: ID of command for which the execution failed + //! P2: Status code sent by the supervisor handler static const Event SUPV_EXE_FAILURE = MAKE_EVENT(3, severity::LOW); //! [EXPORT] : [COMMENT] PLOC supervisor reply has invalid crc static const Event SUPV_CRC_FAILURE_EVENT = MAKE_EVENT(4, severity::LOW); + //! [EXPORT] : [COMMENT] Supervisor helper currently executing a command + static const Event SUPV_HELPER_EXECUTING = MAKE_EVENT(5, severity::LOW); + //! [EXPORT] : [COMMENT] Failed to build the command to shutdown the MPSoC + static const Event SUPV_MPSOC_SHUWDOWN_BUILD_FAILED = MAKE_EVENT(5, severity::LOW); static const uint16_t APID_MASK = 0x7FF; static const uint16_t PACKET_SEQUENCE_COUNT_MASK = 0x3FFF; + static const uint8_t EXE_STATUS_OFFSET = 10; + static const uint8_t SIZE_NULL_TERMINATOR = 1; + // 5 s + static const uint32_t EXECUTION_DEFAULT_TIMEOUT = 5000; + // 70 S + static const uint32_t ACKNOWLEDGE_DEFAULT_TIMEOUT = 70000; + // 60 s + static const uint32_t MRAM_DUMP_EXECUTION_TIMEOUT = 60000; + // 70 s + static const uint32_t COPY_ADC_TO_MRAM_TIMEOUT = 70000; + // 60 s + static const uint32_t MRAM_DUMP_TIMEOUT = 60000; + // 2 s + static const uint32_t BOOT_TIMEOUT = 2000; + enum class StartupState : uint8_t { OFF, BOOTING, SET_TIME, SET_TIME_EXECUTING, ON }; + + bool setTimeDuringStartup = true; + + StartupState startupState = StartupState::OFF; uint8_t commandBuffer[supv::MAX_COMMAND_SIZE]; @@ -121,9 +115,14 @@ class PlocSupervisorHandler : public DeviceHandlerBase { supv::HkSet hkset; supv::BootStatusReport bootStatusReport; supv::LatchupStatusReport latchupStatusReport; + supv::LoggingReport loggingReport; + supv::AdcReport adcReport; const power::Switch_t powerSwitch = power::NO_SWITCH; + PlocSupvHelper* supvHelper = nullptr; + MessageQueueIF* eventQueue = nullptr; + /** Number of expected replies following the MRAM dump command */ uint32_t expectedMramDumpPackets = 0; uint32_t receivedMramDumpPackets = 0; @@ -135,16 +134,32 @@ class PlocSupervisorHandler : public DeviceHandlerBase { /** This buffer is used to concatenate space packets received in two different read steps */ uint8_t spacePacketBuffer[supv::MAX_PACKET_SIZE]; -#ifdef TE0720_1CFA +#ifndef TE0720_1CFA SdCardManager* sdcMan = nullptr; #endif /* BOARD_TE0720 == 0 */ - /** Path to PLOC specific files on SD card */ - std::string plocFilePath = "ploc"; + // Path to supervisor specific files on SD card + std::string supervisorFilePath = "ploc/supervisor"; std::string activeMramFile; - /** Setting this variable to true will enable direct downlink of MRAM packets */ - bool downlinkMramDump = false; + // Supervisor helper class currently executing a command + bool plocSupvHelperExecuting = false; + + Countdown executionReportTimeout = Countdown(EXECUTION_DEFAULT_TIMEOUT, false); + Countdown acknowledgementReportTimeout = Countdown(ACKNOWLEDGE_DEFAULT_TIMEOUT, false); + // Vorago nees some time to boot properly + Countdown bootTimeout = Countdown(BOOT_TIMEOUT); + Countdown mramDumpTimeout = Countdown(MRAM_DUMP_TIMEOUT); + + /** + * @brief Adjusts the timeout of the execution report dependent on command + */ + void setExecutionTimeout(DeviceCommandId_t command); + + /** + * @brief Handles event messages received from the supervisor helper + */ + void handleEvent(EventMessage* eventMessage); ReturnValue_t getSwitches(const uint8_t** switches, uint8_t* numberOfSwitches); @@ -193,6 +208,8 @@ class PlocSupervisorHandler : public DeviceHandlerBase { ReturnValue_t handleBootStatusReport(const uint8_t* data); ReturnValue_t handleLatchupStatusReport(const uint8_t* data); + ReturnValue_t handleLoggingReport(const uint8_t* data); + ReturnValue_t handleAdcReport(const uint8_t* data); /** * @brief Depending on the current active command, this function sets the reply id of the @@ -253,22 +270,17 @@ class PlocSupervisorHandler : public DeviceHandlerBase { ReturnValue_t prepareLatchupConfigCmd(const uint8_t* commandData, DeviceCommandId_t deviceCommand); - ReturnValue_t prepareAutoCalibrateAlertCmd(const uint8_t* commandData); ReturnValue_t prepareSetAlertLimitCmd(const uint8_t* commandData); - ReturnValue_t prepareSetAlertIrqFilterCmd(const uint8_t* commandData); - ReturnValue_t prepareSetAdcSweetPeriodCmd(const uint8_t* commandData); void prepareSetAdcEnabledChannelsCmd(const uint8_t* commandData); void prepareSetAdcWindowAndStrideCmd(const uint8_t* commandData); void prepareSetAdcThresholdCmd(const uint8_t* commandData); - void prepareEnableNvmsCmd(const uint8_t* commandData); - void prepareSelectNvmCmd(const uint8_t* commandData); ReturnValue_t prepareRunAutoEmTest(const uint8_t* commandData); ReturnValue_t prepareWipeMramCmd(const uint8_t* commandData); ReturnValue_t prepareDumpMramCmd(const uint8_t* commandData); - void preparePrintCpuStatsCmd(const uint8_t* commandData); - void prepareSetDbgVerbosityCmd(const uint8_t* commandData); void prepareSetGpioCmd(const uint8_t* commandData); void prepareReadGpioCmd(const uint8_t* commandData); + ReturnValue_t prepareLoggingRequest(const uint8_t* commandData, size_t commandDataLen); + ReturnValue_t prepareEnableNvmsCommand(const uint8_t* commandData); /** * @brief Copies the content of a space packet to the command buffer. @@ -282,6 +294,8 @@ class PlocSupervisorHandler : public DeviceHandlerBase { */ void disableAllReplies(); + void disableReply(DeviceCommandId_t replyId); + /** * @brief This function sends a failure report if the active action was commanded by an other * object. @@ -348,6 +362,17 @@ class PlocSupervisorHandler : public DeviceHandlerBase { ReturnValue_t createMramDumpFile(); ReturnValue_t getTimeStampString(std::string& timeStamp); + + void prepareSetShutdownTimeoutCmd(const uint8_t* commandData); + + ReturnValue_t extractUpdateCommand(const uint8_t* commandData, size_t size, std::string* file, + uint8_t* memoryId, uint32_t* startAddress); + ReturnValue_t eventSubscription(); + + void handleExecutionSuccessReport(const uint8_t* data); + void handleExecutionFailureReport(uint16_t statusCode); + + void printAckFailureInfo(uint16_t statusCode, DeviceCommandId_t commandId); }; #endif /* MISSION_DEVICES_PLOCSUPERVISORHANDLER_H_ */ diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp new file mode 100644 index 00000000..544a98eb --- /dev/null +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -0,0 +1,562 @@ +#include "PlocSupvHelper.h" + +#include +#include + +#include "OBSWConfig.h" +#ifdef XIPHOS_Q7S +#include "bsp_q7s/memory/FilesystemHelper.h" +#include "bsp_q7s/memory/SdCardManager.h" +#endif + +#include "fsfw/globalfunctions/CRC.h" +#include "fsfw/tasks/TaskFactory.h" +#include "fsfw/timemanager/Countdown.h" +#include "mission/utility/Filenaming.h" +#include "mission/utility/ProgressPrinter.h" +#include "mission/utility/Timestamp.h" + +PlocSupvHelper::PlocSupvHelper(object_id_t objectId) : SystemObject(objectId) {} + +PlocSupvHelper::~PlocSupvHelper() {} + +ReturnValue_t PlocSupvHelper::initialize() { +#ifdef XIPHOS_Q7S + sdcMan = SdCardManager::instance(); + if (sdcMan == nullptr) { + sif::warning << "PlocSupvHelper::initialize: Invalid SD Card Manager" << std::endl; + return RETURN_FAILED; + } +#endif + return RETURN_OK; +} + +ReturnValue_t PlocSupvHelper::performOperation(uint8_t operationCode) { + ReturnValue_t result = RETURN_OK; + semaphore.acquire(); + while (true) { + switch (internalState) { + case InternalState::IDLE: { + semaphore.acquire(); + break; + } + case InternalState::UPDATE: { + result = performUpdate(); + if (result == RETURN_OK) { + triggerEvent(SUPV_UPDATE_SUCCESSFUL, result); + } else if (result == PROCESS_TERMINATED) { + // Event already triggered + } else { + triggerEvent(SUPV_UPDATE_FAILED, result); + } + internalState = InternalState::IDLE; + break; + } + case InternalState::CONTINUE_UPDATE: { + result = continueUpdate(); + if (result == RETURN_OK) { + triggerEvent(SUPV_CONTINUE_UPDATE_SUCCESSFUL, result); + } else if (result == PROCESS_TERMINATED) { + // Event already triggered + } else { + triggerEvent(SUPV_CONTINUE_UPDATE_FAILED, result); + } + internalState = InternalState::IDLE; + break; + } + case InternalState::REQUEST_EVENT_BUFFER: { + result = performEventBufferRequest(); + if (result == RETURN_OK) { + triggerEvent(SUPV_EVENT_BUFFER_REQUEST_SUCCESSFUL, result); + } else if (result == PROCESS_TERMINATED) { + // Event already triggered + break; + } else { + triggerEvent(SUPV_EVENT_BUFFER_REQUEST_FAILED, result); + } + internalState = InternalState::IDLE; + break; + } + default: + sif::debug << "PlocSupvHelper::performOperation: Invalid state" << std::endl; + break; + } + } +} + +ReturnValue_t PlocSupvHelper::setComIF(UartComIF* uartComIF_) { + if (uartComIF_ == nullptr) { + sif::warning << "PlocSupvHelper::initialize: Provided invalid uart com if" << std::endl; + return RETURN_FAILED; + } + uartComIF = uartComIF_; + return RETURN_OK; +} + +void PlocSupvHelper::setComCookie(CookieIF* comCookie_) { comCookie = comCookie_; } + +ReturnValue_t PlocSupvHelper::startUpdate(std::string file, uint8_t memoryId, + uint32_t startAddress) { + ReturnValue_t result = RETURN_OK; +#ifdef XIPHOS_Q7S + result = FilesystemHelper::checkPath(file); + if (result != RETURN_OK) { + sif::warning << "PlocSupvHelper::startUpdate: File " << file << " does not exist" << std::endl; + return result; + } + result = FilesystemHelper::fileExists(file); + if (result != RETURN_OK) { + sif::warning << "PlocSupvHelper::startUpdate: The file " << file << " does not exist" + << std::endl; + return result; + } +#endif +#ifdef TE0720_1CFA + if (not std::filesystem::exists(file)) { + sif::warning << "PlocSupvHelper::startUpdate: The file " << file << " does not exist" + << std::endl; + return RETURN_FAILED; + } +#endif + update.file = file; + update.length = getFileSize(update.file); + update.memoryId = memoryId; + update.startAddress = startAddress; + update.remainingSize = update.length; + update.bytesWritten = 0; + update.packetNum = 1; + update.sequenceCount = 1; + internalState = InternalState::UPDATE; + uartComIF->flushUartTxAndRxBuf(comCookie); + semaphore.release(); + return result; +} + +void PlocSupvHelper::initiateUpdateContinuation() { + internalState = InternalState::CONTINUE_UPDATE; + semaphore.release(); +} + +ReturnValue_t PlocSupvHelper::startEventbBufferRequest(std::string path) { +#ifdef XIPHOS_Q7S + ReturnValue_t result = FilesystemHelper::checkPath(path); + if (result != RETURN_OK) { + return result; + } +#endif + if (not std::filesystem::exists(path)) { + return PATH_NOT_EXISTS; + } + eventBufferReq.path = path; + internalState = InternalState::REQUEST_EVENT_BUFFER; + uartComIF->flushUartTxAndRxBuf(comCookie); + semaphore.release(); + return RETURN_OK; +} + +void PlocSupvHelper::stopProcess() { terminate = true; } + +ReturnValue_t PlocSupvHelper::performUpdate() { + ReturnValue_t result = RETURN_OK; + result = calcImageCrc(); + if (result != RETURN_OK) { + return result; + } + result = selectMemory(); + if (result != RETURN_OK) { + return result; + } + result = prepareUpdate(); + if (result != RETURN_OK) { + return result; + } + result = eraseMemory(); + if (result != RETURN_OK) { + return result; + } + result = writeUpdatePackets(); + if (result != RETURN_OK) { + return result; + } + result = handleCheckMemoryCommand(); + if (result != RETURN_OK) { + return result; + } + return result; +} + +ReturnValue_t PlocSupvHelper::continueUpdate() { + ReturnValue_t result = prepareUpdate(); + if (result != RETURN_OK) { + return result; + } + result = writeUpdatePackets(); + if (result != RETURN_OK) { + return result; + } + result = handleCheckMemoryCommand(); + if (result != RETURN_OK) { + return result; + } + return result; +} + +ReturnValue_t PlocSupvHelper::writeUpdatePackets() { + ReturnValue_t result = RETURN_OK; +#if OBSW_DEBUG_PLOC_SUPERVISOR == 1 + ProgressPrinter progressPrinter("Supervisor update", update.length, + ProgressPrinter::HALF_PERCENT); +#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ + uint8_t tempData[supv::WriteMemory::CHUNK_MAX]; + std::ifstream file(update.file, std::ifstream::binary); + uint16_t dataLength = 0; + supv::SequenceFlags seqFlags; + while (update.remainingSize > 0) { + if (terminate) { + terminate = false; + triggerEvent(TERMINATED_UPDATE_PROCEDURE); + return PROCESS_TERMINATED; + } + if (update.remainingSize > supv::WriteMemory::CHUNK_MAX) { + dataLength = supv::WriteMemory::CHUNK_MAX; + } else { + dataLength = static_cast(update.remainingSize); + } + if (file.is_open()) { + file.seekg(update.bytesWritten, file.beg); + file.read(reinterpret_cast(tempData), dataLength); + if (!file) { + sif::warning << "PlocSupvHelper::performUpdate: Read only " << file.gcount() << " of " + << dataLength << " bytes" << std::endl; + sif::info << "PlocSupvHelper::performUpdate: Failed when trying to read byte " + << update.bytesWritten << std::endl; + } + } else { + return FILE_CLOSED_ACCIDENTALLY; + } + if (update.bytesWritten == 0) { + seqFlags = supv::SequenceFlags::FIRST_PKT; + } else if (update.remainingSize == 0) { + seqFlags = supv::SequenceFlags::LAST_PKT; + } else { + seqFlags = supv::SequenceFlags::CONTINUED_PKT; + } + supv::WriteMemory packet(seqFlags, update.sequenceCount++, update.memoryId, + update.startAddress + update.bytesWritten, dataLength, tempData); + result = handlePacketTransmission(packet); + if (result != RETURN_OK) { + update.sequenceCount--; + triggerEvent(WRITE_MEMORY_FAILED, update.packetNum); + return result; + } + update.remainingSize -= dataLength; + update.packetNum += 1; + update.bytesWritten += dataLength; +#if OBSW_DEBUG_PLOC_SUPERVISOR == 1 + progressPrinter.print(update.bytesWritten); +#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ + } + return result; +} + +ReturnValue_t PlocSupvHelper::performEventBufferRequest() { + using namespace supv; + ReturnValue_t result = RETURN_OK; + RequestLoggingData packet(RequestLoggingData::Sa::REQUEST_EVENT_BUFFERS); + result = sendCommand(packet); + if (result != RETURN_OK) { + return result; + } + result = handleAck(); + if (result != RETURN_OK) { + return result; + } + result = handleEventBufferReception(); + if (result != RETURN_OK) { + return result; + } + result = handleExe(); + if (result != RETURN_OK) { + return result; + } + return result; +} + +ReturnValue_t PlocSupvHelper::selectMemory() { + ReturnValue_t result = RETURN_OK; + supv::MPSoCBootSelect packet(update.memoryId); + result = handlePacketTransmission(packet); + if (result != RETURN_OK) { + return result; + } + return RETURN_OK; +} + +ReturnValue_t PlocSupvHelper::prepareUpdate() { + ReturnValue_t result = RETURN_OK; + supv::ApidOnlyPacket packet(supv::APID_PREPARE_UPDATE); + result = handlePacketTransmission(packet, PREPARE_UPDATE_EXECUTION_REPORT); + if (result != RETURN_OK) { + return result; + } + return RETURN_OK; +} + +ReturnValue_t PlocSupvHelper::eraseMemory() { + ReturnValue_t result = RETURN_OK; + supv::EraseMemory eraseMemory(update.memoryId, update.startAddress, update.length); + result = handlePacketTransmission(eraseMemory, supv::recv_timeout::ERASE_MEMORY); + if (result != RETURN_OK) { + return result; + } + return RETURN_OK; +} + +ReturnValue_t PlocSupvHelper::handlePacketTransmission(SpacePacket& packet, + uint32_t timeoutExecutionReport) { + ReturnValue_t result = RETURN_OK; + result = sendCommand(packet); + if (result != RETURN_OK) { + return result; + } + result = handleAck(); + if (result != RETURN_OK) { + return result; + } + result = handleExe(timeoutExecutionReport); + if (result != RETURN_OK) { + return result; + } + return RETURN_OK; +} + +ReturnValue_t PlocSupvHelper::sendCommand(SpacePacket& packet) { + ReturnValue_t result = RETURN_OK; + rememberApid = packet.getAPID(); + result = uartComIF->sendMessage(comCookie, packet.getWholeData(), packet.getFullSize()); + if (result != RETURN_OK) { + sif::warning << "PlocSupvHelper::sendCommand: Failed to send command" << std::endl; + triggerEvent(SUPV_SENDING_COMMAND_FAILED, result, static_cast(internalState)); + return result; + } + return result; +} + +ReturnValue_t PlocSupvHelper::handleAck() { + ReturnValue_t result = RETURN_OK; + supv::AcknowledgmentReport ackReport; + result = handleTmReception(&ackReport, supv::SIZE_ACK_REPORT); + if (result != RETURN_OK) { + triggerEvent(ACK_RECEPTION_FAILURE, result, static_cast(rememberApid)); + sif::warning << "PlocSupvHelper::handleAck: Error in reception of acknowledgment report" + << std::endl; + return result; + } + result = ackReport.checkApid(); + if (result != RETURN_OK) { + if (result == SupvReturnValuesIF::RECEIVED_ACK_FAILURE) { + triggerEvent(SUPV_ACK_FAILURE_REPORT, static_cast(ackReport.getRefApid())); + } else if (result == SupvReturnValuesIF::INVALID_APID) { + triggerEvent(SUPV_ACK_INVALID_APID, static_cast(rememberApid)); + } + return result; + } + return RETURN_OK; +} + +ReturnValue_t PlocSupvHelper::handleExe(uint32_t timeout) { + ReturnValue_t result = RETURN_OK; + supv::ExecutionReport exeReport; + result = handleTmReception(&exeReport, supv::SIZE_EXE_REPORT, timeout); + if (result != RETURN_OK) { + triggerEvent(EXE_RECEPTION_FAILURE, result, static_cast(rememberApid)); + sif::warning << "PlocSupvHelper::handleExe: Error in reception of execution report" + << std::endl; + return result; + } + result = exeReport.checkApid(); + if (result != RETURN_OK) { + if (result == SupvReturnValuesIF::RECEIVED_EXE_FAILURE) { + triggerEvent(SUPV_EXE_FAILURE_REPORT, static_cast(exeReport.getRefApid())); + } else if (result == SupvReturnValuesIF::INVALID_APID) { + triggerEvent(SUPV_EXE_INVALID_APID, static_cast(rememberApid)); + } + return result; + } + return RETURN_OK; +} + +ReturnValue_t PlocSupvHelper::handleTmReception(supv::TmPacket* tmPacket, size_t remainingBytes, + uint32_t timeout) { + ReturnValue_t result = RETURN_OK; + size_t readBytes = 0; + size_t currentBytes = 0; + Countdown countdown(timeout); + while (!countdown.hasTimedOut()) { + result = receive(tmPacket->getWholeData() + readBytes, ¤tBytes, remainingBytes); + if (result != RETURN_OK) { + return result; + } + readBytes += currentBytes; + remainingBytes = remainingBytes - currentBytes; + if (remainingBytes == 0) { + break; + } + } + if (remainingBytes != 0) { + sif::warning << "PlocSupvHelper::handleTmReception: Failed to read " << std::dec + << remainingBytes << " bytes" << std::endl; + return RETURN_FAILED; + } + result = tmPacket->checkCrc(); + if (result != RETURN_OK) { + sif::warning << "PlocSupvHelper::handleTmReception: CRC check failed" << std::endl; + return result; + } + return result; +} + +ReturnValue_t PlocSupvHelper::receive(uint8_t* data, size_t* readBytes, size_t requestBytes) { + ReturnValue_t result = RETURN_OK; + uint8_t* buffer = nullptr; + result = uartComIF->requestReceiveMessage(comCookie, requestBytes); + if (result != RETURN_OK) { + sif::warning << "PlocSupvHelper::receive: Failed to request reply" << std::endl; + triggerEvent(SUPV_HELPER_REQUESTING_REPLY_FAILED, result, + static_cast(static_cast(internalState))); + return RETURN_FAILED; + } + result = uartComIF->readReceivedMessage(comCookie, &buffer, readBytes); + if (result != RETURN_OK) { + sif::warning << "PlocSupvHelper::receive: Failed to read received message" << std::endl; + triggerEvent(SUPV_HELPER_READING_REPLY_FAILED, result, static_cast(internalState)); + return RETURN_FAILED; + } + if (*readBytes > 0) { + std::memcpy(data, buffer, *readBytes); + } else { + TaskFactory::delayTask(40); + } + return result; +} + +ReturnValue_t PlocSupvHelper::calcImageCrc() { + ReturnValue_t result = RETURN_OK; +#ifdef XIPHOS_Q7S + result = FilesystemHelper::checkPath(update.file); +#endif + if (result != RETURN_OK) { + sif::warning << "PlocSupvHelper::calcImageCrc: File " << update.file << " does not exist" + << std::endl; + return result; + } + std::ifstream file(update.file, std::ifstream::binary); + uint16_t remainder = CRC16_INIT; + uint8_t input; +#if OBSW_DEBUG_PLOC_SUPERVISOR == 1 + ProgressPrinter progress("Supervisor update crc calculation", update.length, + ProgressPrinter::ONE_PERCENT); +#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ + uint32_t byteCount = 0; + for (byteCount = 0; byteCount < update.length; byteCount++) { + file.seekg(byteCount, file.beg); + file.read(reinterpret_cast(&input), 1); + remainder = CRC::crc16ccitt(&input, sizeof(input), remainder); +#if OBSW_DEBUG_PLOC_SUPERVISOR == 1 + progress.print(byteCount); +#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ + } +#if OBSW_DEBUG_PLOC_SUPERVISOR == 1 + progress.print(byteCount); +#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ + file.close(); + update.crc = remainder; + return result; +} + +ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { + ReturnValue_t result = RETURN_OK; + // Verification of update write procedure + supv::CheckMemory packet(update.memoryId, update.startAddress, update.length); + result = sendCommand(packet); + if (result != RETURN_OK) { + return result; + } + result = handleAck(); + if (result != RETURN_OK) { + return result; + } + supv::UpdateStatusReport updateStatusReport; + result = handleTmReception(&updateStatusReport, + static_cast(updateStatusReport.getNominalSize()), + supv::recv_timeout::UPDATE_STATUS_REPORT); + if (result != RETURN_OK) { + sif::warning + << "PlocSupvHelper::handleCheckMemoryCommand: Failed to receive update status report" + << std::endl; + return result; + } + result = handleExe(CRC_EXECUTION_TIMEOUT); + if (result != RETURN_OK) { + return result; + } + result = updateStatusReport.parseDataField(); + if (result != RETURN_OK) { + return result; + } + result = updateStatusReport.verifycrc(update.crc); + if (result != RETURN_OK) { + sif::warning << "PlocSupvHelper::handleCheckMemoryCommand: CRC failure. Expected CRC 0x" + << std::hex << update.crc << " but received CRC 0x" << updateStatusReport.getCrc() + << std::endl; + return result; + } + return result; +} + +uint32_t PlocSupvHelper::getFileSize(std::string filename) { + std::ifstream file(filename, std::ifstream::binary); + file.seekg(0, file.end); + uint32_t size = file.tellg(); + file.close(); + return size; +} + +ReturnValue_t PlocSupvHelper::handleEventBufferReception() { + ReturnValue_t result = RETURN_OK; + std::string filename = Filenaming::generateAbsoluteFilename( + eventBufferReq.path, eventBufferReq.filename, timestamping); + std::ofstream file(filename, std::ios_base::app | std::ios_base::out); + uint32_t packetsRead = 0; + size_t requestLen = 0; + supv::TmPacket tmPacket; + for (packetsRead = 0; packetsRead < NUM_EVENT_BUFFER_PACKETS; packetsRead++) { + if (terminate) { + triggerEvent(SUPV_EVENT_BUFFER_REQUEST_TERMINATED, packetsRead - 1); + file.close(); + return PROCESS_TERMINATED; + } + if (packetsRead == NUM_EVENT_BUFFER_PACKETS - 1) { + requestLen = SIZE_EVENT_BUFFER_LAST_PACKET; + } else { + requestLen = SIZE_EVENT_BUFFER_FULL_PACKET; + } + result = handleTmReception(&tmPacket, requestLen); + if (result != RETURN_OK) { + sif::debug << "PlocSupvHelper::handleEventBufferReception: Failed while trying to read packet" + << " " << packetsRead + 1 << std::endl; + file.close(); + return result; + } + uint16_t apid = tmPacket.getAPID(); + if (apid != supv::APID_MRAM_DUMP_TM) { + sif::warning << "PlocSupvHelper::handleEventBufferReception: Did not expect space packet " + << "with APID 0x" << std::hex << apid << std::endl; + file.close(); + return EVENT_BUFFER_REPLY_INVALID_APID; + } + file.write(reinterpret_cast(tmPacket.getPacketData()), + tmPacket.getPayloadDataLength()); + } + return result; +} diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h new file mode 100644 index 00000000..69d26264 --- /dev/null +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -0,0 +1,241 @@ +#ifndef BSP_Q7S_DEVICES_PLOCSUPVHELPER_H_ +#define BSP_Q7S_DEVICES_PLOCSUPVHELPER_H_ + +#include + +#include "OBSWConfig.h" +#include "fsfw/devicehandlers/CookieIF.h" +#include "fsfw/objectmanager/SystemObject.h" +#include "fsfw/osal/linux/BinarySemaphore.h" +#include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "fsfw/tasks/ExecutableObjectIF.h" +#include "fsfw_hal/linux/uart/UartComIF.h" +#include "linux/devices/devicedefinitions/PlocSupervisorDefinitions.h" +#ifdef XIPHOS_Q7S +#include "bsp_q7s/memory/SdCardManager.h" +#endif + +/** + * @brief Helper class for supervisor of PLOC intended to accelerate large data transfers between + * the supervisor and the OBC. + * @author J. Meier + */ +class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public HasReturnvaluesIF { + public: + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PLOC_SUPV_HELPER; + + //! [EXPORT] : [COMMENT] update failed + static const Event SUPV_UPDATE_FAILED = MAKE_EVENT(0, severity::LOW); + //! [EXPORT] : [COMMENT] update successful + static const Event SUPV_UPDATE_SUCCESSFUL = MAKE_EVENT(1, severity::LOW); + //! [EXPORT] : [COMMENT] Continue update command failed + static const Event SUPV_CONTINUE_UPDATE_FAILED = MAKE_EVENT(2, severity::LOW); + //! [EXPORT] : [COMMENT] Continue update command successful + static const Event SUPV_CONTINUE_UPDATE_SUCCESSFUL = MAKE_EVENT(3, severity::LOW); + //! [EXPORT] : [COMMENT] Terminated update procedure by command + static const Event TERMINATED_UPDATE_PROCEDURE = MAKE_EVENT(4, severity::LOW); + //! [EXPORT] : [COMMENT] Requesting event buffer was successful + static const Event SUPV_EVENT_BUFFER_REQUEST_SUCCESSFUL = MAKE_EVENT(5, severity::LOW); + //! [EXPORT] : [COMMENT] Requesting event buffer failed + static const Event SUPV_EVENT_BUFFER_REQUEST_FAILED = MAKE_EVENT(6, severity::LOW); + //! [EXPORT] : [COMMENT] Terminated event buffer request by command + //! P1: Number of packets read before process was terminated + static const Event SUPV_EVENT_BUFFER_REQUEST_TERMINATED = MAKE_EVENT(7, severity::LOW); + //! [EXPORT] : [COMMENT] Communication interface returned failure when trying to send the command + //! to the supervisor + //! P1: Return value returned by the communication interface sendMessage function + //! P2: Internal state of supervisor helper + static const Event SUPV_SENDING_COMMAND_FAILED = MAKE_EVENT(8, severity::LOW); + //! [EXPORT] : [COMMENT] Request receive message of communication interface failed + //! P1: Return value returned by the communication interface requestReceiveMessage function + //! P2: Internal state of supervisor helper + static const Event SUPV_HELPER_REQUESTING_REPLY_FAILED = MAKE_EVENT(9, severity::LOW); + //! [EXPORT] : [COMMENT] Reading receive message of communication interface failed + //! P1: Return value returned by the communication interface readingReceivedMessage function + //! P2: Internal state of supervisor helper + static const Event SUPV_HELPER_READING_REPLY_FAILED = MAKE_EVENT(10, severity::LOW); + //! [EXPORT] : [COMMENT] Did not receive acknowledgement report + //! P1: Number of bytes missing + //! P2: Internal state of MPSoC helper + static const Event SUPV_MISSING_ACK = MAKE_EVENT(11, severity::LOW); + //! [EXPORT] : [COMMENT] Supervisor did not receive execution report + //! P1: Number of bytes missing + //! P2: Internal state of supervisor helper + static const Event SUPV_MISSING_EXE = MAKE_EVENT(12, severity::LOW); + //! [EXPORT] : [COMMENT] Supervisor received acknowledgment failure report + //! P1: Internal state of supervisor helper + static const Event SUPV_ACK_FAILURE_REPORT = MAKE_EVENT(13, severity::LOW); + //! [EXPORT] : [COMMENT] Execution report failure + //! P1: + static const Event SUPV_EXE_FAILURE_REPORT = MAKE_EVENT(14, severity::LOW); + //! [EXPORT] : [COMMENT] Supervisor expected acknowledgment report but received space packet with + //! other apid P1: Apid of received space packet P2: Internal state of supervisor helper + static const Event SUPV_ACK_INVALID_APID = MAKE_EVENT(15, severity::LOW); + //! [EXPORT] : [COMMENT] Supervisor helper expected execution report but received space packet + //! with other apid P1: Apid of received space packet P2: Internal state of supervisor helper + static const Event SUPV_EXE_INVALID_APID = MAKE_EVENT(16, severity::LOW); + //! [EXPORT] : [COMMENT] Failed to receive acknowledgment report + //! P1: Return value + //! P2: Apid of command for which the reception of the acknowledgment report failed + static const Event ACK_RECEPTION_FAILURE = MAKE_EVENT(17, severity::LOW); + //! [EXPORT] : [COMMENT] Failed to receive execution report + //! P1: Return value + //! P2: Apid of command for which the reception of the execution report failed + static const Event EXE_RECEPTION_FAILURE = MAKE_EVENT(18, severity::LOW); + //! [EXPORT] : [COMMENT] Update procedure failed when sending packet with number P1 + //! P1: Packet number for which the memory write command fails + static const Event WRITE_MEMORY_FAILED = MAKE_EVENT(19, severity::LOW); + + PlocSupvHelper(object_id_t objectId); + virtual ~PlocSupvHelper(); + + ReturnValue_t initialize() override; + ReturnValue_t performOperation(uint8_t operationCode = 0) override; + + ReturnValue_t setComIF(UartComIF* uartComfIF_); + void setComCookie(CookieIF* comCookie_); + + /** + * @brief Starts update procedure + * + * @param file File containing the update data + * @param memoryId ID of the memory where to write to + * @param startAddress Address where to write data + * + * @return RETURN_OK if successful, otherwise error return value + */ + ReturnValue_t startUpdate(std::string file, uint8_t memoryId, uint32_t startAddress); + + /** + * @brief This initiate the continuation of a failed update. + */ + void initiateUpdateContinuation(); + + /** + * @brief Calling this function will initiate the procedure to request the event buffer + */ + ReturnValue_t startEventbBufferRequest(std::string path); + + /** + * @brief Can be used to interrupt a running data transfer. + */ + void stopProcess(); + + private: + static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_SUPV_HELPER; + + //! [EXPORT] : [COMMENT] File accidentally close + static const ReturnValue_t FILE_CLOSED_ACCIDENTALLY = MAKE_RETURN_CODE(0xA0); + //! [EXPORT] : [COMMENT] Process has been terminated by command + static const ReturnValue_t PROCESS_TERMINATED = MAKE_RETURN_CODE(0xA1); + //! [EXPORT] : [COMMENT] Received command with invalid pathname + static const ReturnValue_t PATH_NOT_EXISTS = MAKE_RETURN_CODE(0xA2); + //! [EXPORT] : [COMMENT] Expected event buffer TM but received space packet with other APID + static const ReturnValue_t EVENT_BUFFER_REPLY_INVALID_APID = MAKE_RETURN_CODE(0xA3); + + static const uint16_t CRC16_INIT = 0xFFFF; + // Event buffer reply will carry 24 space packets with 1016 bytes and one space packet with + // 192 bytes + static const uint8_t NUM_EVENT_BUFFER_PACKETS = 25; + static const size_t SIZE_EVENT_BUFFER_FULL_PACKET = 1024; + static const size_t SIZE_EVENT_BUFFER_LAST_PACKET = 200; + static const uint32_t CRC_EXECUTION_TIMEOUT = 60000; + static const uint32_t PREPARE_UPDATE_EXECUTION_REPORT = 2000; + + struct Update { + uint8_t memoryId; + uint32_t startAddress; + // Absolute name of file containing update data + std::string file; + // Size of update + uint32_t length; + uint32_t crc; + size_t remainingSize; + size_t bytesWritten; + uint32_t packetNum; + uint16_t sequenceCount; + }; + + struct Update update; + + struct EventBufferRequest { + std::string path = ""; + // Default name of file where event buffer data will be written to. Timestamp will be added to + // name when new file is created + std::string filename = "event-buffer.bin"; + }; + + EventBufferRequest eventBufferReq; + + enum class InternalState { IDLE, UPDATE, CONTINUE_UPDATE, REQUEST_EVENT_BUFFER }; + + InternalState internalState = InternalState::IDLE; + + BinarySemaphore semaphore; +#ifdef XIPHOS_Q7S + SdCardManager* sdcMan = nullptr; +#endif + uint8_t commandBuffer[supv::MAX_COMMAND_SIZE]; + + bool terminate = false; + + /** + * Communication interface responsible for data transactions between OBC and Supervisor. + */ + UartComIF* uartComIF = nullptr; + // Communication cookie. Must be set by the supervisor Handler + CookieIF* comCookie = nullptr; + + bool timestamping = true; + + // Remembers APID to know at which command a procedure failed + uint16_t rememberApid = 0; + + ReturnValue_t performUpdate(); + ReturnValue_t continueUpdate(); + ReturnValue_t writeUpdatePackets(); + ReturnValue_t performEventBufferRequest(); + ReturnValue_t handlePacketTransmission(SpacePacket& packet, + uint32_t timeoutExecutionReport = 60000); + ReturnValue_t sendCommand(SpacePacket& packet); + /** + * @brief Function which reads form the communication interface + * + * @param data Pointer to buffer where read data will be written to + * @param raedBytes Actual number of bytes read + * @param requestBytes Number of bytes to read + */ + ReturnValue_t receive(uint8_t* data, size_t* readBytes, size_t requestBytes); + ReturnValue_t handleAck(); + ReturnValue_t handleExe(uint32_t timeout = 1000); + /** + * @brief Handles reading of TM packets from the communication interface + * + * @param tmPacket Pointer to space packet where received data will be written to + * @param reaminingBytes Number of bytes to read in the space packet + * @param timeout Receive timeout in milliseconds + * + * @note It can take up to 70 seconds until the supervisor replies with an acknowledgment + * failure report. + */ + ReturnValue_t handleTmReception(supv::TmPacket* tmPacket, size_t remainingBytes, + uint32_t timeout = 70000); + ReturnValue_t selectMemory(); + ReturnValue_t prepareUpdate(); + ReturnValue_t eraseMemory(); + // Calculates CRC over image. Will be used for verification after update writing has + // finished. + ReturnValue_t calcImageCrc(); + ReturnValue_t handleCheckMemoryCommand(); + /** + * @brief Return size of file with name filename + * + * @param filename + * + * @return The size of the file + */ + uint32_t getFileSize(std::string filename); + ReturnValue_t handleEventBufferReception(); +}; + +#endif /* BSP_Q7S_DEVICES_PLOCSUPVHELPER_H_ */ diff --git a/linux/devices/ploc/PlocUpdater.cpp b/linux/devices/ploc/PlocUpdater.cpp deleted file mode 100644 index 37a553da..00000000 --- a/linux/devices/ploc/PlocUpdater.cpp +++ /dev/null @@ -1,385 +0,0 @@ -#include "PlocUpdater.h" - -#include -#include -#include - -#include "fsfw/ipc/QueueFactory.h" - -PlocUpdater::PlocUpdater(object_id_t objectId) - : SystemObject(objectId), commandActionHelper(this), actionHelper(this, nullptr) { - auto mqArgs = MqArgs(this->getObjectId()); - commandQueue = QueueFactory::instance()->createMessageQueue( - QUEUE_SIZE, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs); -} - -PlocUpdater::~PlocUpdater() {} - -ReturnValue_t PlocUpdater::initialize() { -#ifdef XIPHOS_Q7S - sdcMan = SdCardManager::instance(); -#endif - ReturnValue_t result = SystemObject::initialize(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = commandActionHelper.initialize(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = actionHelper.initialize(commandQueue); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t PlocUpdater::performOperation(uint8_t operationCode) { - readCommandQueue(); - doStateMachine(); - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t PlocUpdater::executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, - const uint8_t* data, size_t size) { - ReturnValue_t result = RETURN_FAILED; - - if (state != State::IDLE) { - return IS_BUSY; - } - - if (size > MAX_PLOC_UPDATE_PATH) { - return NAME_TOO_LONG; - } - - switch (actionId) { - case UPDATE_A_UBOOT: - image = Image::A; - partition = Partition::UBOOT; - break; - case UPDATE_A_BITSTREAM: - image = Image::A; - partition = Partition::BITSTREAM; - break; - case UPDATE_A_LINUX: - image = Image::A; - partition = Partition::LINUX_OS; - break; - case UPDATE_A_APP_SW: - image = Image::A; - partition = Partition::APP_SW; - break; - case UPDATE_B_UBOOT: - image = Image::B; - partition = Partition::UBOOT; - break; - case UPDATE_B_BITSTREAM: - image = Image::B; - partition = Partition::BITSTREAM; - break; - case UPDATE_B_LINUX: - image = Image::B; - partition = Partition::LINUX_OS; - break; - case UPDATE_B_APP_SW: - image = Image::B; - partition = Partition::APP_SW; - break; - default: - return INVALID_ACTION_ID; - } - - result = getImageLocation(data, size); - - if (result != RETURN_OK) { - return result; - } - - state = State::UPDATE_AVAILABLE; - - return EXECUTION_FINISHED; -} - -MessageQueueId_t PlocUpdater::getCommandQueue() const { return commandQueue->getId(); } - -MessageQueueIF* PlocUpdater::getCommandQueuePtr() { return commandQueue; } - -void PlocUpdater::readCommandQueue() { - CommandMessage message; - ReturnValue_t result; - - for (result = commandQueue->receiveMessage(&message); result == HasReturnvaluesIF::RETURN_OK; - result = commandQueue->receiveMessage(&message)) { - if (result != RETURN_OK) { - continue; - } - result = actionHelper.handleActionMessage(&message); - if (result == HasReturnvaluesIF::RETURN_OK) { - continue; - } - - result = commandActionHelper.handleReply(&message); - if (result == HasReturnvaluesIF::RETURN_OK) { - continue; - } - } -} - -void PlocUpdater::doStateMachine() { - switch (state) { - case State::IDLE: - break; - case State::UPDATE_AVAILABLE: - commandUpdateAvailable(); - break; - case State::UPDATE_TRANSFER: - commandUpdatePacket(); - break; - case State::UPDATE_VERIFY: - commandUpdateVerify(); - break; - case State::COMMAND_EXECUTING: - break; - default: - break; - } -} - -ReturnValue_t PlocUpdater::checkNameLength(size_t size) { - if (size > MAX_PLOC_UPDATE_PATH) { - return NAME_TOO_LONG; - } - return RETURN_OK; -} - -ReturnValue_t PlocUpdater::getImageLocation(const uint8_t* data, size_t size) { - ReturnValue_t result = checkNameLength(size); - if (result != RETURN_OK) { - return result; - } - -#ifdef XIPHOS_Q7S - // Check if file is stored on SD card and if associated SD card is mounted - if (std::string(reinterpret_cast(data), SD_PREFIX_LENGTH) == - std::string(SdCardManager::SD_0_MOUNT_POINT)) { - if (!sdcMan->isSdCardMounted(sd::SLOT_0)) { - sif::warning << "PlocUpdater::getImageLocation: SD card 0 not mounted" << std::endl; - return SD_NOT_MOUNTED; - } - } else if (std::string(reinterpret_cast(data), SD_PREFIX_LENGTH) == - std::string(SdCardManager::SD_1_MOUNT_POINT)) { - if (!sdcMan->isSdCardMounted(sd::SLOT_0)) { - sif::warning << "PlocUpdater::getImageLocation: SD card 1 not mounted" << std::endl; - return SD_NOT_MOUNTED; - } - } else { - // update image not stored on SD card - } -#endif /* BOARD_TE0720 == 0 */ - - updateFile = std::string(reinterpret_cast(data), size); - - // Check if file exists - if (not std::filesystem::exists(updateFile)) { - return FILE_NOT_EXISTS; - } - return RETURN_OK; -} - -void PlocUpdater::stepSuccessfulReceived(ActionId_t actionId, uint8_t step) {} - -void PlocUpdater::stepFailedReceived(ActionId_t actionId, uint8_t step, ReturnValue_t returnCode) {} - -void PlocUpdater::dataReceived(ActionId_t actionId, const uint8_t* data, uint32_t size) {} - -void PlocUpdater::completionSuccessfulReceived(ActionId_t actionId) { - switch (pendingCommand) { - case (supv::UPDATE_AVAILABLE): - state = State::UPDATE_TRANSFER; - break; - case (supv::UPDATE_IMAGE_DATA): - if (remainingPackets == 0) { - packetsSent = 0; // Reset packets sent variable for next update sequence - state = State::UPDATE_VERIFY; - } else { - state = State::UPDATE_TRANSFER; - } - break; - case (supv::UPDATE_VERIFY): - triggerEvent(UPDATE_FINISHED); - state = State::IDLE; - pendingCommand = supv::NONE; - break; - default: - state = State::IDLE; - break; - } -} - -void PlocUpdater::completionFailedReceived(ActionId_t actionId, ReturnValue_t returnCode) { - switch (pendingCommand) { - case (supv::UPDATE_AVAILABLE): { - triggerEvent(UPDATE_AVAILABLE_FAILED); - break; - } - case (supv::UPDATE_IMAGE_DATA): { - triggerEvent(UPDATE_TRANSFER_FAILED, packetsSent); - break; - } - case (supv::UPDATE_VERIFY): { - triggerEvent(UPDATE_VERIFY_FAILED); - break; - } - default: - break; - } - state = State::IDLE; -} - -void PlocUpdater::commandUpdateAvailable() { - ReturnValue_t result = RETURN_OK; - - if (not std::filesystem::exists(updateFile)) { - triggerEvent(UPDATE_FILE_NOT_EXISTS, static_cast(state)); - state = State::IDLE; - return; - } - - std::ifstream file(updateFile, std::ifstream::binary); - file.seekg(0, file.end); - imageSize = static_cast(file.tellg()); - file.close(); - - numOfUpdatePackets = imageSize / MAX_SP_DATA; - if (imageSize % MAX_SP_DATA) { - numOfUpdatePackets++; - } - - remainingPackets = numOfUpdatePackets; - packetsSent = 0; - - calcImageCrc(); - - supv::UpdateInfo packet(supv::APID_UPDATE_AVAILABLE, static_cast(image), - static_cast(partition), imageSize, imageCrc, numOfUpdatePackets); - - result = - commandActionHelper.commandAction(objects::PLOC_SUPERVISOR_HANDLER, supv::UPDATE_AVAILABLE, - packet.getWholeData(), packet.getFullSize()); - if (result != RETURN_OK) { - sif::warning << "PlocUpdater::commandUpdateAvailable: Failed to send update available" - << " packet to supervisor handler" << std::endl; - triggerEvent(ACTION_COMMANDING_FAILED, result, supv::UPDATE_AVAILABLE); - state = State::IDLE; - pendingCommand = supv::NONE; - return; - } - - pendingCommand = supv::UPDATE_AVAILABLE; - state = State::COMMAND_EXECUTING; - return; -} - -void PlocUpdater::commandUpdatePacket() { - ReturnValue_t result = RETURN_OK; - uint16_t payloadLength = 0; - - if (not std::filesystem::exists(updateFile)) { - triggerEvent(UPDATE_FILE_NOT_EXISTS, static_cast(state), packetsSent); - state = State::IDLE; - return; - } - - std::ifstream file(updateFile, std::ifstream::binary); - file.seekg(packetsSent * MAX_SP_DATA, file.beg); - - if (remainingPackets == 1) { - payloadLength = imageSize - static_cast(file.tellg()); - } else { - payloadLength = MAX_SP_DATA; - } - - supv::UpdatePacket packet(payloadLength); - file.read(reinterpret_cast(packet.getDataFieldPointer()), payloadLength); - file.close(); - // sequence count of first packet is 1 - packet.setPacketSequenceCount((packetsSent + 1) & supv::SEQUENCE_COUNT_MASK); - if (numOfUpdatePackets > 1) { - adjustSequenceFlags(packet); - } - packet.makeCrc(); - - result = - commandActionHelper.commandAction(objects::PLOC_SUPERVISOR_HANDLER, supv::UPDATE_IMAGE_DATA, - packet.getWholeData(), packet.getFullSize()); - - if (result != RETURN_OK) { - sif::warning << "PlocUpdater::commandUpdateAvailable: Failed to send update" - << " packet to supervisor handler" << std::endl; - triggerEvent(ACTION_COMMANDING_FAILED, result, supv::UPDATE_IMAGE_DATA); - state = State::IDLE; - pendingCommand = supv::NONE; - return; - } - - remainingPackets--; - packetsSent++; - - pendingCommand = supv::UPDATE_IMAGE_DATA; - state = State::COMMAND_EXECUTING; -} - -void PlocUpdater::commandUpdateVerify() { - ReturnValue_t result = RETURN_OK; - - supv::UpdateInfo packet(supv::APID_UPDATE_VERIFY, static_cast(image), - static_cast(partition), imageSize, imageCrc, numOfUpdatePackets); - - result = commandActionHelper.commandAction(objects::PLOC_SUPERVISOR_HANDLER, supv::UPDATE_VERIFY, - packet.getWholeData(), packet.getFullSize()); - if (result != RETURN_OK) { - sif::warning << "PlocUpdater::commandUpdateAvailable: Failed to send update available" - << " packet to supervisor handler" << std::endl; - triggerEvent(ACTION_COMMANDING_FAILED, result, supv::UPDATE_VERIFY); - state = State::IDLE; - pendingCommand = supv::NONE; - return; - } - state = State::COMMAND_EXECUTING; - pendingCommand = supv::UPDATE_VERIFY; - return; -} - -void PlocUpdater::calcImageCrc() { - std::ifstream file(updateFile, std::ifstream::binary); - file.seekg(0, file.end); - uint32_t count; - uint32_t bit; - uint32_t remainder = INITIAL_REMAINDER_32; - char input; - for (count = 0; count < imageSize; count++) { - file.seekg(count, file.beg); - file.read(&input, 1); - remainder ^= (input << 16); - for (bit = 8; bit > 0; --bit) { - if (remainder & TOPBIT_32) { - remainder = (remainder << 1) ^ POLYNOMIAL_32; - } else { - remainder = (remainder << 1); - } - } - } - file.close(); - imageCrc = (remainder ^ FINAL_XOR_VALUE_32); -} - -void PlocUpdater::adjustSequenceFlags(supv::UpdatePacket& packet) { - if (packetsSent == 0) { - packet.setSequenceFlags(static_cast(supv::SequenceFlags::FIRST_PKT)); - } else if (remainingPackets == 1) { - packet.setSequenceFlags(static_cast(supv::SequenceFlags::LAST_PKT)); - } else { - packet.setSequenceFlags(static_cast(supv::SequenceFlags::CONTINUED_PKT)); - } -} diff --git a/linux/devices/ploc/PlocUpdater.h b/linux/devices/ploc/PlocUpdater.h deleted file mode 100644 index 1bb9a1bd..00000000 --- a/linux/devices/ploc/PlocUpdater.h +++ /dev/null @@ -1,174 +0,0 @@ -#ifndef MISSION_DEVICES_PLOCUPDATER_H_ -#define MISSION_DEVICES_PLOCUPDATER_H_ - -#include - -#include "OBSWConfig.h" -#include "bsp_q7s/memory/SdCardManager.h" -#include "eive/definitions.h" -#include "fsfw/action/ActionHelper.h" -#include "fsfw/action/CommandActionHelper.h" -#include "fsfw/action/CommandsActionsIF.h" -#include "fsfw/action/HasActionsIF.h" -#include "fsfw/objectmanager/SystemObject.h" -#include "fsfw/returnvalues/HasReturnvaluesIF.h" -#include "fsfw/tasks/ExecutableObjectIF.h" -#include "fsfw/tmtcpacket/SpacePacket.h" -#include "linux/devices/devicedefinitions/PlocSupervisorDefinitions.h" -#include "linux/fsfwconfig/objects/systemObjectList.h" - -/** - * @brief An object of this class can be used to perform the software updates of the PLOC. The - * software update will be read from one of the SD cards, split into multiple space - * packets and sent to the PlocSupervisorHandler. - * - * @details The MPSoC has two boot memories (NVM0 and NVM1) where each stores two images (Partition - * A and Partition B) - * - * @author J. Meier - */ -class PlocUpdater : public SystemObject, - public HasActionsIF, - public ExecutableObjectIF, - public HasReturnvaluesIF, - public CommandsActionsIF { - public: - static const ActionId_t UPDATE_A_UBOOT = 0; - static const ActionId_t UPDATE_A_BITSTREAM = 1; - static const ActionId_t UPDATE_A_LINUX = 2; - static const ActionId_t UPDATE_A_APP_SW = 3; - static const ActionId_t UPDATE_B_UBOOT = 4; - static const ActionId_t UPDATE_B_BITSTREAM = 5; - static const ActionId_t UPDATE_B_LINUX = 6; - static const ActionId_t UPDATE_B_APP_SW = 7; - - PlocUpdater(object_id_t objectId); - virtual ~PlocUpdater(); - - ReturnValue_t performOperation(uint8_t operationCode = 0) override; - ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, - const uint8_t* data, size_t size); - MessageQueueId_t getCommandQueue() const; - ReturnValue_t initialize() override; - MessageQueueIF* getCommandQueuePtr() override; - void stepSuccessfulReceived(ActionId_t actionId, uint8_t step) override; - void stepFailedReceived(ActionId_t actionId, uint8_t step, ReturnValue_t returnCode) override; - void dataReceived(ActionId_t actionId, const uint8_t* data, uint32_t size) override; - void completionSuccessfulReceived(ActionId_t actionId) override; - void completionFailedReceived(ActionId_t actionId, ReturnValue_t returnCode) override; - - private: - static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_UPDATER; - - //! [EXPORT] : [COMMENT] Updater is already performing an update - static const ReturnValue_t UPDATER_BUSY = MAKE_RETURN_CODE(0xA0); - //! [EXPORT] : [COMMENT] Received update command with invalid path string (too long). - static const ReturnValue_t NAME_TOO_LONG = MAKE_RETURN_CODE(0xA1); - //! [EXPORT] : [COMMENT] Received command to initiate update but SD card with update image not - //! mounted. - static const ReturnValue_t SD_NOT_MOUNTED = MAKE_RETURN_CODE(0xA2); - //! [EXPORT] : [COMMENT] Update file received with update command does not exist. - static const ReturnValue_t FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xA3); - - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PLOC_UPDATER; - - //! [EXPORT] : [COMMENT] Try to read update file but the file does not exist. - //! P1: Indicates in which state the file read fails - //! P2: During the update transfer the second parameter gives information about the number of - //! already sent packets - static const Event UPDATE_FILE_NOT_EXISTS = MAKE_EVENT(0, severity::LOW); - //! [EXPORT] : [COMMENT] Failed to send command to supervisor handler - //! P1: Return value of CommandActionHelper::commandAction - //! P2: Action ID of command to send - static const Event ACTION_COMMANDING_FAILED = MAKE_EVENT(1, severity::LOW); - //! [EXPORT] : [COMMENT] Supervisor handler replied action message indicating a command execution - //! failure of the update available command - static const Event UPDATE_AVAILABLE_FAILED = MAKE_EVENT(2, severity::LOW); - //! [EXPORT] : [COMMENT] Supervisor handler failed to transfer an update space packet. - //! P1: Parameter holds the number of update packets already sent (inclusive the failed packet) - static const Event UPDATE_TRANSFER_FAILED = MAKE_EVENT(3, severity::LOW); - //! [EXPORT] : [COMMENT] Supervisor failed to execute the update verify command. - static const Event UPDATE_VERIFY_FAILED = MAKE_EVENT(4, severity::LOW); - //! [EXPORT] : [COMMENT] MPSoC update successful completed - static const Event UPDATE_FINISHED = MAKE_EVENT(5, severity::INFO); - - static const uint32_t QUEUE_SIZE = config::PLOC_UPDATER_QUEUE_SIZE; - static const size_t MAX_PLOC_UPDATE_PATH = 50; - static const size_t SD_PREFIX_LENGTH = 8; - // Maximum size of update payload data per space packet (max size of space packet is 1024 bytes) - static const size_t MAX_SP_DATA = 1016; - - static const uint32_t TOPBIT_32 = (1 << 31); - static const uint32_t POLYNOMIAL_32 = 0x04C11DB7; - static const uint32_t INITIAL_REMAINDER_32 = 0xFFFFFFFF; - static const uint32_t FINAL_XOR_VALUE_32 = 0xFFFFFFFF; - - MessageQueueIF* commandQueue = nullptr; - -#ifdef XIPHOS_Q7S - SdCardManager* sdcMan = nullptr; -#endif - CommandActionHelper commandActionHelper; - - ActionHelper actionHelper; - - enum class State : uint8_t { - IDLE, - UPDATE_AVAILABLE, - UPDATE_TRANSFER, - UPDATE_VERIFY, - COMMAND_EXECUTING - }; - - State state = State::IDLE; - - ActionId_t pendingCommand = supv::NONE; - - enum class Image : uint8_t { NONE, A, B }; - - Image image = Image::NONE; - - enum class Partition : uint8_t { NONE, UBOOT, BITSTREAM, LINUX_OS, APP_SW }; - - Partition partition = Partition::NONE; - - uint32_t packetsSent = 0; - uint32_t remainingPackets = 0; - // Number of packets required to transfer the update image - uint32_t numOfUpdatePackets = 0; - - std::string updateFile; - uint32_t imageSize = 0; - uint32_t imageCrc = 0; - - void readCommandQueue(); - void doStateMachine(); - - /** - * @brief Extracts the path and name of the update image from the service 8 command data. - */ - ReturnValue_t getImageLocation(const uint8_t* data, size_t size); - - ReturnValue_t checkNameLength(size_t size); - - /** - * @brief Prepares and sends update available command to PLOC supervisor handler. - */ - void commandUpdateAvailable(); - - /** - * @brief Prepares and sends and update packet to the PLOC supervisor handler. - */ - void commandUpdatePacket(); - - /** - * @brief Prepares and sends the update verification packet to the PLOC supervisor handler. - */ - void commandUpdateVerify(); - - void calcImageCrc(); - - void adjustSequenceFlags(supv::UpdatePacket& packet); -}; - -#endif /* MISSION_DEVICES_PLOCUPDATER_H_ */ diff --git a/linux/devices/startracker/CMakeLists.txt b/linux/devices/startracker/CMakeLists.txt index be2bf861..963b2a44 100644 --- a/linux/devices/startracker/CMakeLists.txt +++ b/linux/devices/startracker/CMakeLists.txt @@ -1,7 +1,4 @@ -target_sources(${OBSW_NAME} PRIVATE - StarTrackerHandler.cpp - StarTrackerJsonCommands.cpp - ArcsecDatalinkLayer.cpp - ArcsecJsonParamBase.cpp - StrHelper.cpp -) \ No newline at end of file +target_sources( + ${OBSW_NAME} + PRIVATE StarTrackerHandler.cpp StarTrackerJsonCommands.cpp + ArcsecDatalinkLayer.cpp ArcsecJsonParamBase.cpp StrHelper.cpp) diff --git a/linux/devices/startracker/StrHelper.cpp b/linux/devices/startracker/StrHelper.cpp index 599b706f..b2f02f24 100644 --- a/linux/devices/startracker/StrHelper.cpp +++ b/linux/devices/startracker/StrHelper.cpp @@ -6,6 +6,7 @@ #include "OBSWConfig.h" #include "fsfw/timemanager/Countdown.h" #include "linux/devices/devicedefinitions/StarTrackerDefinitions.h" +#include "mission/utility/Filenaming.h" #include "mission/utility/ProgressPrinter.h" #include "mission/utility/Timestamp.h" @@ -181,7 +182,8 @@ ReturnValue_t StrHelper::performImageDownload() { struct DownloadActionRequest downloadReq; uint32_t size = 0; uint32_t retries = 0; - std::string image = makeFullFilename(downloadImage.path, downloadImage.filename); + std::string image = Filenaming::generateAbsoluteFilename(downloadImage.path, + downloadImage.filename, timestamping); std::ofstream file(image, std::ios_base::out); if (not std::filesystem::exists(image)) { return FILE_CREATION_FAILED; @@ -400,7 +402,8 @@ ReturnValue_t StrHelper::performFlashRead() { uint32_t size = 0; uint32_t retries = 0; Timestamp timestamp; - std::string fullname = makeFullFilename(flashRead.path, flashRead.filename); + std::string fullname = + Filenaming::generateAbsoluteFilename(flashRead.path, flashRead.filename, timestamping); std::ofstream file(fullname, std::ios_base::app | std::ios_base::out); if (not std::filesystem::exists(fullname)) { return FILE_CREATION_FAILED; @@ -588,14 +591,3 @@ ReturnValue_t StrHelper::unlockAndEraseRegions(uint32_t from, uint32_t to) { } return result; } - -std::string StrHelper::makeFullFilename(std::string path, std::string filename) { - std::string image; - Timestamp timestamp; - if (timestamping) { - image = path + "/" + timestamp.str() + filename; - } else { - image = path + "/" + filename; - } - return image; -} diff --git a/linux/devices/startracker/StrHelper.h b/linux/devices/startracker/StrHelper.h index f34e96ce..63f85233 100644 --- a/linux/devices/startracker/StrHelper.h +++ b/linux/devices/startracker/StrHelper.h @@ -173,8 +173,7 @@ class StrHelper : public SystemObject, public ExecutableObjectIF, public HasRetu static const size_t SIZE_IMAGE_PART = 1024; static const uint32_t FLASH_REGION_SIZE = 0x20000; - class ImageDownload { - public: + struct ImageDownload { static const uint32_t LAST_POSITION = 4095; }; @@ -199,15 +198,13 @@ class StrHelper : public SystemObject, public ExecutableObjectIF, public HasRetu BinarySemaphore semaphore; - class UploadImage { - public: + struct UploadImage { // Name including absolute path of image to upload std::string uploadFile; }; UploadImage uploadImage; - class DownloadImage { - public: + struct DownloadImage { // Path where the downloaded image will be stored std::string path; // Default name of downloaded image, can be changed via command @@ -215,8 +212,7 @@ class StrHelper : public SystemObject, public ExecutableObjectIF, public HasRetu }; DownloadImage downloadImage; - class FlashWrite { - public: + struct FlashWrite { // File which contains data to write when executing the flash write command std::string fullname; // The first region to write to @@ -229,8 +225,7 @@ class StrHelper : public SystemObject, public ExecutableObjectIF, public HasRetu }; FlashWrite flashWrite; - class FlashRead { - public: + struct FlashRead { // Path where the file containing the read data will be stored std::string path = ""; // Default name of file containing the data read from flash, can be changed via command @@ -349,16 +344,6 @@ class StrHelper : public SystemObject, public ExecutableObjectIF, public HasRetu * */ ReturnValue_t unlockAndEraseRegions(uint32_t from, uint32_t to); - - /** - * @brief Creates full filename either with timestamp or without - * - * @param path Path where to create the file - * @param filename Name fo the file - * - * @return Full filename - */ - std::string makeFullFilename(std::string path, std::string filename); }; #endif /* BSP_Q7S_DEVICES_STRHELPER_H_ */ diff --git a/linux/fsfwconfig/CMakeLists.txt b/linux/fsfwconfig/CMakeLists.txt index 8d13e67b..bfede452 100644 --- a/linux/fsfwconfig/CMakeLists.txt +++ b/linux/fsfwconfig/CMakeLists.txt @@ -1,28 +1,16 @@ -target_sources(${OBSW_NAME} PRIVATE - ipc/MissionMessageTypes.cpp - pollingsequence/pollingSequenceFactory.cpp -) +target_sources(${OBSW_NAME} PRIVATE ipc/MissionMessageTypes.cpp + pollingsequence/pollingSequenceFactory.cpp) -target_include_directories(${OBSW_NAME} PUBLIC - ${CMAKE_CURRENT_SOURCE_DIR} -) +target_include_directories(${OBSW_NAME} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) # If a special translation file for object IDs exists, compile it. if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/objects/translateObjects.cpp") - target_sources(${OBSW_NAME} PRIVATE - objects/translateObjects.cpp - ) - target_sources(${UNITTEST_NAME} PRIVATE - objects/translateObjects.cpp - ) + target_sources(${OBSW_NAME} PRIVATE objects/translateObjects.cpp) + target_sources(${UNITTEST_NAME} PRIVATE objects/translateObjects.cpp) endif() # If a special translation file for events exists, compile it. if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/objects/translateObjects.cpp") - target_sources(${OBSW_NAME} PRIVATE - events/translateEvents.cpp - ) - target_sources(${UNITTEST_NAME} PRIVATE - events/translateEvents.cpp - ) + target_sources(${OBSW_NAME} PRIVATE events/translateEvents.cpp) + target_sources(${UNITTEST_NAME} PRIVATE events/translateEvents.cpp) endif() diff --git a/linux/fsfwconfig/devices/addresses.h b/linux/fsfwconfig/devices/addresses.h index 0016c6a4..ec794490 100644 --- a/linux/fsfwconfig/devices/addresses.h +++ b/linux/fsfwconfig/devices/addresses.h @@ -24,18 +24,18 @@ enum logicalAddresses : address_t { RAD_SENSOR = objects::RAD_SENSOR, - SUS_0 = objects::SUS_0, - SUS_1 = objects::SUS_1, - SUS_2 = objects::SUS_2, - SUS_3 = objects::SUS_3, - SUS_4 = objects::SUS_4, - SUS_5 = objects::SUS_5, - SUS_6 = objects::SUS_6, - SUS_7 = objects::SUS_7, - SUS_8 = objects::SUS_8, - SUS_9 = objects::SUS_9, - SUS_10 = objects::SUS_10, - SUS_11 = objects::SUS_11, + SUS_0 = objects::SUS_0_N_LOC_XFYFZM_PT_XF, + SUS_1 = objects::SUS_1_N_LOC_XBYFZM_PT_XB, + SUS_2 = objects::SUS_2_N_LOC_XFYBZB_PT_YB, + SUS_3 = objects::SUS_3_N_LOC_XFYBZF_PT_YF, + SUS_4 = objects::SUS_4_N_LOC_XMYFZF_PT_ZF, + SUS_5 = objects::SUS_5_N_LOC_XFYMZB_PT_ZB, + SUS_6 = objects::SUS_6_R_LOC_XFYBZM_PT_XF, + SUS_7 = objects::SUS_7_R_LOC_XBYBZM_PT_XB, + SUS_8 = objects::SUS_8_R_LOC_XBYBZB_PT_YB, + SUS_9 = objects::SUS_9_R_LOC_XBYBZB_PT_YF, + SUS_10 = objects::SUS_10_N_LOC_XMYBZF_PT_ZF, + SUS_11 = objects::SUS_11_R_LOC_XBYMZB_PT_ZB, /* Dummy and Test Addresses */ DUMMY_ECHO = 129, diff --git a/linux/fsfwconfig/events/subsystemIdRanges.h b/linux/fsfwconfig/events/subsystemIdRanges.h index 768797b5..f0a0316c 100644 --- a/linux/fsfwconfig/events/subsystemIdRanges.h +++ b/linux/fsfwconfig/events/subsystemIdRanges.h @@ -13,7 +13,7 @@ namespace SUBSYSTEM_ID { enum : uint8_t { SUBSYSTEM_ID_START = COMMON_SUBSYSTEM_ID_END, - CORE = 136, + CORE = 137, }; } diff --git a/linux/fsfwconfig/events/translateEvents.cpp b/linux/fsfwconfig/events/translateEvents.cpp index 1a155186..7f9cfc78 100644 --- a/linux/fsfwconfig/events/translateEvents.cpp +++ b/linux/fsfwconfig/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 187 translations. + * @brief Auto-generated event translation file. Contains 209 translations. * @details - * Generated on: 2022-05-03 16:32:00 + * Generated on: 2022-06-27 09:14:37 */ #include "translateEvents.h" @@ -82,6 +82,7 @@ const char *BIT_LOCK_LOST_STRING = "BIT_LOCK_LOST"; const char *FRAME_PROCESSING_FAILED_STRING = "FRAME_PROCESSING_FAILED"; const char *CLOCK_SET_STRING = "CLOCK_SET"; const char *CLOCK_SET_FAILURE_STRING = "CLOCK_SET_FAILURE"; +const char *TC_DELETION_FAILED_STRING = "TC_DELETION_FAILED"; const char *TEST_STRING = "TEST"; const char *CHANGE_OF_SETUP_PARAMETER_STRING = "CHANGE_OF_SETUP_PARAMETER"; const char *SWITCH_CMD_SENT_STRING = "SWITCH_CMD_SENT"; @@ -90,9 +91,12 @@ const char *SWITCHING_Q7S_DENIED_STRING = "SWITCHING_Q7S_DENIED"; const char *FDIR_REACTION_IGNORED_STRING = "FDIR_REACTION_IGNORED"; const char *GPIO_PULL_HIGH_FAILED_STRING = "GPIO_PULL_HIGH_FAILED"; const char *GPIO_PULL_LOW_FAILED_STRING = "GPIO_PULL_LOW_FAILED"; +const char *HEATER_WENT_ON_STRING = "HEATER_WENT_ON"; +const char *HEATER_WENT_OFF_STRING = "HEATER_WENT_OFF"; const char *SWITCH_ALREADY_ON_STRING = "SWITCH_ALREADY_ON"; const char *SWITCH_ALREADY_OFF_STRING = "SWITCH_ALREADY_OFF"; const char *MAIN_SWITCH_TIMEOUT_STRING = "MAIN_SWITCH_TIMEOUT"; +const char *FAULTY_HEATER_WAS_ON_STRING = "FAULTY_HEATER_WAS_ON"; const char *MAIN_SWITCH_ON_TIMEOUT_STRING = "MAIN_SWITCH_ON_TIMEOUT"; const char *MAIN_SWITCH_OFF_TIMEOUT_STRING = "MAIN_SWITCH_OFF_TIMEOUT"; const char *DEPLOYMENT_FAILED_STRING = "DEPLOYMENT_FAILED"; @@ -102,7 +106,7 @@ const char *MEMORY_READ_RPT_CRC_FAILURE_STRING = "MEMORY_READ_RPT_CRC_FAILURE"; const char *ACK_FAILURE_STRING = "ACK_FAILURE"; const char *EXE_FAILURE_STRING = "EXE_FAILURE"; const char *MPSOC_HANDLER_CRC_FAILURE_STRING = "MPSOC_HANDLER_CRC_FAILURE"; -const char *MPSOC_HANDLER_SEQ_CNT_MISMATCH_STRING = "MPSOC_HANDLER_SEQ_CNT_MISMATCH"; +const char *MPSOC_HANDLER_SEQUENCE_COUNT_MISMATCH_STRING = "MPSOC_HANDLER_SEQUENCE_COUNT_MISMATCH"; const char *MPSOC_SHUTDOWN_FAILED_STRING = "MPSOC_SHUTDOWN_FAILED"; const char *SELF_TEST_I2C_FAILURE_STRING = "SELF_TEST_I2C_FAILURE"; const char *SELF_TEST_SPI_FAILURE_STRING = "SELF_TEST_SPI_FAILURE"; @@ -113,20 +117,16 @@ const char *SELF_TEST_MTM_RANGE_FAILURE_STRING = "SELF_TEST_MTM_RANGE_FAILURE"; const char *SELF_TEST_COIL_CURRENT_FAILURE_STRING = "SELF_TEST_COIL_CURRENT_FAILURE"; const char *INVALID_ERROR_BYTE_STRING = "INVALID_ERROR_BYTE"; const char *ERROR_STATE_STRING = "ERROR_STATE"; +const char *RESET_OCCURED_STRING = "RESET_OCCURED"; const char *BOOTING_FIRMWARE_FAILED_STRING = "BOOTING_FIRMWARE_FAILED"; const char *BOOTING_BOOTLOADER_FAILED_STRING = "BOOTING_BOOTLOADER_FAILED"; const char *SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING = "SUPV_MEMORY_READ_RPT_CRC_FAILURE"; const char *SUPV_ACK_FAILURE_STRING = "SUPV_ACK_FAILURE"; const char *SUPV_EXE_FAILURE_STRING = "SUPV_EXE_FAILURE"; const char *SUPV_CRC_FAILURE_EVENT_STRING = "SUPV_CRC_FAILURE_EVENT"; +const char *SUPV_MPSOC_SHUWDOWN_BUILD_FAILED_STRING = "SUPV_MPSOC_SHUWDOWN_BUILD_FAILED"; const char *SANITIZATION_FAILED_STRING = "SANITIZATION_FAILED"; const char *MOUNTED_SD_CARD_STRING = "MOUNTED_SD_CARD"; -const char *UPDATE_FILE_NOT_EXISTS_STRING = "UPDATE_FILE_NOT_EXISTS"; -const char *ACTION_COMMANDING_FAILED_STRING = "ACTION_COMMANDING_FAILED"; -const char *UPDATE_AVAILABLE_FAILED_STRING = "UPDATE_AVAILABLE_FAILED"; -const char *UPDATE_TRANSFER_FAILED_STRING = "UPDATE_TRANSFER_FAILED"; -const char *UPDATE_VERIFY_FAILED_STRING = "UPDATE_VERIFY_FAILED"; -const char *UPDATE_FINISHED_STRING = "UPDATE_FINISHED"; const char *SEND_MRAM_DUMP_FAILED_STRING = "SEND_MRAM_DUMP_FAILED"; const char *MRAM_DUMP_FAILED_STRING = "MRAM_DUMP_FAILED"; const char *MRAM_DUMP_FINISHED_STRING = "MRAM_DUMP_FINISHED"; @@ -134,6 +134,8 @@ const char *INVALID_TC_FRAME_STRING = "INVALID_TC_FRAME"; const char *INVALID_FAR_STRING = "INVALID_FAR"; const char *CARRIER_LOCK_STRING = "CARRIER_LOCK"; const char *BIT_LOCK_PDEC_STRING = "BIT_LOCK_PDEC"; +const char *LOST_CARRIER_LOCK_PDEC_STRING = "LOST_CARRIER_LOCK_PDEC"; +const char *LOST_BIT_LOCK_PDEC_STRING = "LOST_BIT_LOCK_PDEC"; const char *IMAGE_UPLOAD_FAILED_STRING = "IMAGE_UPLOAD_FAILED"; const char *IMAGE_DOWNLOAD_FAILED_STRING = "IMAGE_DOWNLOAD_FAILED"; const char *IMAGE_UPLOAD_SUCCESSFUL_STRING = "IMAGE_UPLOAD_SUCCESSFUL"; @@ -153,15 +155,15 @@ const char *STR_HELPER_SENDING_PACKET_FAILED_STRING = "STR_HELPER_SENDING_PACKET const char *STR_HELPER_REQUESTING_MSG_FAILED_STRING = "STR_HELPER_REQUESTING_MSG_FAILED"; const char *MPSOC_FLASH_WRITE_FAILED_STRING = "MPSOC_FLASH_WRITE_FAILED"; const char *MPSOC_FLASH_WRITE_SUCCESSFUL_STRING = "MPSOC_FLASH_WRITE_SUCCESSFUL"; -const char *SENDING_COMMAND_FAILED_STRING = "SENDING_COMMAND_FAILED"; +const char *MPSOC_SENDING_COMMAND_FAILED_STRING = "MPSOC_SENDING_COMMAND_FAILED"; const char *MPSOC_HELPER_REQUESTING_REPLY_FAILED_STRING = "MPSOC_HELPER_REQUESTING_REPLY_FAILED"; const char *MPSOC_HELPER_READING_REPLY_FAILED_STRING = "MPSOC_HELPER_READING_REPLY_FAILED"; -const char *MISSING_ACK_STRING = "MISSING_ACK"; -const char *MISSING_EXE_STRING = "MISSING_EXE"; -const char *ACK_FAILURE_REPORT_STRING = "ACK_FAILURE_REPORT"; -const char *EXE_FAILURE_REPORT_STRING = "EXE_FAILURE_REPORT"; -const char *ACK_INVALID_APID_STRING = "ACK_INVALID_APID"; -const char *EXE_INVALID_APID_STRING = "EXE_INVALID_APID"; +const char *MPSOC_MISSING_ACK_STRING = "MPSOC_MISSING_ACK"; +const char *MPSOC_MISSING_EXE_STRING = "MPSOC_MISSING_EXE"; +const char *MPSOC_ACK_FAILURE_REPORT_STRING = "MPSOC_ACK_FAILURE_REPORT"; +const char *MPSOC_EXE_FAILURE_REPORT_STRING = "MPSOC_EXE_FAILURE_REPORT"; +const char *MPSOC_ACK_INVALID_APID_STRING = "MPSOC_ACK_INVALID_APID"; +const char *MPSOC_EXE_INVALID_APID_STRING = "MPSOC_EXE_INVALID_APID"; const char *MPSOC_HELPER_SEQ_CNT_MISMATCH_STRING = "MPSOC_HELPER_SEQ_CNT_MISMATCH"; const char *TRANSITION_BACK_TO_OFF_STRING = "TRANSITION_BACK_TO_OFF"; const char *NEG_V_OUT_OF_BOUNDS_STRING = "NEG_V_OUT_OF_BOUNDS"; @@ -184,6 +186,26 @@ const char *GPS_FIX_CHANGE_STRING = "GPS_FIX_CHANGE"; const char *P60_BOOT_COUNT_STRING = "P60_BOOT_COUNT"; const char *BATT_MODE_STRING = "BATT_MODE"; const char *BATT_MODE_CHANGED_STRING = "BATT_MODE_CHANGED"; +const char *SUPV_UPDATE_FAILED_STRING = "SUPV_UPDATE_FAILED"; +const char *SUPV_UPDATE_SUCCESSFUL_STRING = "SUPV_UPDATE_SUCCESSFUL"; +const char *SUPV_CONTINUE_UPDATE_FAILED_STRING = "SUPV_CONTINUE_UPDATE_FAILED"; +const char *SUPV_CONTINUE_UPDATE_SUCCESSFUL_STRING = "SUPV_CONTINUE_UPDATE_SUCCESSFUL"; +const char *TERMINATED_UPDATE_PROCEDURE_STRING = "TERMINATED_UPDATE_PROCEDURE"; +const char *SUPV_EVENT_BUFFER_REQUEST_SUCCESSFUL_STRING = "SUPV_EVENT_BUFFER_REQUEST_SUCCESSFUL"; +const char *SUPV_EVENT_BUFFER_REQUEST_FAILED_STRING = "SUPV_EVENT_BUFFER_REQUEST_FAILED"; +const char *SUPV_EVENT_BUFFER_REQUEST_TERMINATED_STRING = "SUPV_EVENT_BUFFER_REQUEST_TERMINATED"; +const char *SUPV_SENDING_COMMAND_FAILED_STRING = "SUPV_SENDING_COMMAND_FAILED"; +const char *SUPV_HELPER_REQUESTING_REPLY_FAILED_STRING = "SUPV_HELPER_REQUESTING_REPLY_FAILED"; +const char *SUPV_HELPER_READING_REPLY_FAILED_STRING = "SUPV_HELPER_READING_REPLY_FAILED"; +const char *SUPV_MISSING_ACK_STRING = "SUPV_MISSING_ACK"; +const char *SUPV_MISSING_EXE_STRING = "SUPV_MISSING_EXE"; +const char *SUPV_ACK_FAILURE_REPORT_STRING = "SUPV_ACK_FAILURE_REPORT"; +const char *SUPV_EXE_FAILURE_REPORT_STRING = "SUPV_EXE_FAILURE_REPORT"; +const char *SUPV_ACK_INVALID_APID_STRING = "SUPV_ACK_INVALID_APID"; +const char *SUPV_EXE_INVALID_APID_STRING = "SUPV_EXE_INVALID_APID"; +const char *ACK_RECEPTION_FAILURE_STRING = "ACK_RECEPTION_FAILURE"; +const char *EXE_RECEPTION_FAILURE_STRING = "EXE_RECEPTION_FAILURE"; +const char *WRITE_MEMORY_FAILED_STRING = "WRITE_MEMORY_FAILED"; const char *ALLOC_FAILURE_STRING = "ALLOC_FAILURE"; const char *REBOOT_SW_STRING = "REBOOT_SW"; const char *REBOOT_MECHANISM_TRIGGERED_STRING = "REBOOT_MECHANISM_TRIGGERED"; @@ -345,6 +367,8 @@ const char *translateEvents(Event event) { return CLOCK_SET_STRING; case (8901): return CLOCK_SET_FAILURE_STRING; + case (9100): + return TC_DELETION_FAILED_STRING; case (9700): return TEST_STRING; case (10600): @@ -362,11 +386,17 @@ const char *translateEvents(Event event) { case (11401): return GPIO_PULL_LOW_FAILED_STRING; case (11402): - return SWITCH_ALREADY_ON_STRING; + return HEATER_WENT_ON_STRING; case (11403): - return SWITCH_ALREADY_OFF_STRING; + return HEATER_WENT_OFF_STRING; case (11404): + return SWITCH_ALREADY_ON_STRING; + case (11405): + return SWITCH_ALREADY_OFF_STRING; + case (11406): return MAIN_SWITCH_TIMEOUT_STRING; + case (11407): + return FAULTY_HEATER_WAS_ON_STRING; case (11500): return MAIN_SWITCH_ON_TIMEOUT_STRING; case (11501): @@ -386,7 +416,7 @@ const char *translateEvents(Event event) { case (11604): return MPSOC_HANDLER_CRC_FAILURE_STRING; case (11605): - return MPSOC_HANDLER_SEQ_CNT_MISMATCH_STRING; + return MPSOC_HANDLER_SEQUENCE_COUNT_MISMATCH_STRING; case (11606): return MPSOC_SHUTDOWN_FAILED_STRING; case (11701): @@ -407,6 +437,8 @@ const char *translateEvents(Event event) { return INVALID_ERROR_BYTE_STRING; case (11801): return ERROR_STATE_STRING; + case (11802): + return RESET_OCCURED_STRING; case (11901): return BOOTING_FIRMWARE_FAILED_STRING; case (11902): @@ -419,22 +451,12 @@ const char *translateEvents(Event event) { return SUPV_EXE_FAILURE_STRING; case (12004): return SUPV_CRC_FAILURE_EVENT_STRING; + case (12005): + return SUPV_MPSOC_SHUWDOWN_BUILD_FAILED_STRING; case (12100): return SANITIZATION_FAILED_STRING; case (12101): return MOUNTED_SD_CARD_STRING; - case (12200): - return UPDATE_FILE_NOT_EXISTS_STRING; - case (12201): - return ACTION_COMMANDING_FAILED_STRING; - case (12202): - return UPDATE_AVAILABLE_FAILED_STRING; - case (12203): - return UPDATE_TRANSFER_FAILED_STRING; - case (12204): - return UPDATE_VERIFY_FAILED_STRING; - case (12205): - return UPDATE_FINISHED_STRING; case (12300): return SEND_MRAM_DUMP_FAILED_STRING; case (12301): @@ -449,6 +471,10 @@ const char *translateEvents(Event event) { return CARRIER_LOCK_STRING; case (12404): return BIT_LOCK_PDEC_STRING; + case (12405): + return LOST_CARRIER_LOCK_PDEC_STRING; + case (12406): + return LOST_BIT_LOCK_PDEC_STRING; case (12500): return IMAGE_UPLOAD_FAILED_STRING; case (12501): @@ -488,23 +514,23 @@ const char *translateEvents(Event event) { case (12601): return MPSOC_FLASH_WRITE_SUCCESSFUL_STRING; case (12602): - return SENDING_COMMAND_FAILED_STRING; + return MPSOC_SENDING_COMMAND_FAILED_STRING; case (12603): return MPSOC_HELPER_REQUESTING_REPLY_FAILED_STRING; case (12604): return MPSOC_HELPER_READING_REPLY_FAILED_STRING; case (12605): - return MISSING_ACK_STRING; + return MPSOC_MISSING_ACK_STRING; case (12606): - return MISSING_EXE_STRING; + return MPSOC_MISSING_EXE_STRING; case (12607): - return ACK_FAILURE_REPORT_STRING; + return MPSOC_ACK_FAILURE_REPORT_STRING; case (12608): - return EXE_FAILURE_REPORT_STRING; + return MPSOC_EXE_FAILURE_REPORT_STRING; case (12609): - return ACK_INVALID_APID_STRING; + return MPSOC_ACK_INVALID_APID_STRING; case (12610): - return EXE_INVALID_APID_STRING; + return MPSOC_EXE_INVALID_APID_STRING; case (12611): return MPSOC_HELPER_SEQ_CNT_MISMATCH_STRING; case (12700): @@ -550,12 +576,52 @@ const char *translateEvents(Event event) { case (13202): return BATT_MODE_CHANGED_STRING; case (13600): - return ALLOC_FAILURE_STRING; + return SUPV_UPDATE_FAILED_STRING; case (13601): - return REBOOT_SW_STRING; + return SUPV_UPDATE_SUCCESSFUL_STRING; case (13602): - return REBOOT_MECHANISM_TRIGGERED_STRING; + return SUPV_CONTINUE_UPDATE_FAILED_STRING; case (13603): + return SUPV_CONTINUE_UPDATE_SUCCESSFUL_STRING; + case (13604): + return TERMINATED_UPDATE_PROCEDURE_STRING; + case (13605): + return SUPV_EVENT_BUFFER_REQUEST_SUCCESSFUL_STRING; + case (13606): + return SUPV_EVENT_BUFFER_REQUEST_FAILED_STRING; + case (13607): + return SUPV_EVENT_BUFFER_REQUEST_TERMINATED_STRING; + case (13608): + return SUPV_SENDING_COMMAND_FAILED_STRING; + case (13609): + return SUPV_HELPER_REQUESTING_REPLY_FAILED_STRING; + case (13610): + return SUPV_HELPER_READING_REPLY_FAILED_STRING; + case (13611): + return SUPV_MISSING_ACK_STRING; + case (13612): + return SUPV_MISSING_EXE_STRING; + case (13613): + return SUPV_ACK_FAILURE_REPORT_STRING; + case (13614): + return SUPV_EXE_FAILURE_REPORT_STRING; + case (13615): + return SUPV_ACK_INVALID_APID_STRING; + case (13616): + return SUPV_EXE_INVALID_APID_STRING; + case (13617): + return ACK_RECEPTION_FAILURE_STRING; + case (13618): + return EXE_RECEPTION_FAILURE_STRING; + case (13619): + return WRITE_MEMORY_FAILED_STRING; + case (13700): + return ALLOC_FAILURE_STRING; + case (13701): + return REBOOT_SW_STRING; + case (13702): + return REBOOT_MECHANISM_TRIGGERED_STRING; + case (13703): return REBOOT_HW_STRING; default: return "UNKNOWN_EVENT"; diff --git a/linux/fsfwconfig/objects/systemObjectList.h b/linux/fsfwconfig/objects/systemObjectList.h index a03e4d38..669fcc9f 100644 --- a/linux/fsfwconfig/objects/systemObjectList.h +++ b/linux/fsfwconfig/objects/systemObjectList.h @@ -1,5 +1,5 @@ -#ifndef HOSTED_CONFIG_OBJECTS_SYSTEMOBJECTLIST_H_ -#define HOSTED_CONFIG_OBJECTS_SYSTEMOBJECTLIST_H_ +#ifndef LINUX_FSFWCONFIG_OBJECTS_SYSTEMOBJECTLIST_H_ +#define LINUX_FSFWCONFIG_OBJECTS_SYSTEMOBJECTLIST_H_ #include @@ -47,15 +47,10 @@ enum sourceObjects : uint32_t { CSP_COM_IF = 0x49050001, I2C_COM_IF = 0x49040002, UART_COM_IF = 0x49030003, - SPI_COM_IF = 0x49020004, + SPI_MAIN_COM_IF = 0x49020004, GPIO_IF = 0x49010005, - - /* Custom device handler */ - PCDU_HANDLER = 0x442000A1, - SOLAR_ARRAY_DEPL_HANDLER = 0x444100A2, - SYRLINKS_HK_HANDLER = 0x445300A3, - HEATER_HANDLER = 0x444100A4, - RAD_SENSOR = 0x443200A5, + SPI_RW_COM_IF = 0x49020005, + SPI_RTD_COM_IF = 0x49020006, /* 0x54 ('T') for test handlers */ TEST_TASK = 0x54694269, @@ -66,7 +61,8 @@ enum sourceObjects : uint32_t { DUMMY_INTERFACE = 0x5400CAFE, DUMMY_HANDLER = 0x5400AFFE, P60DOCK_TEST_TASK = 0x00005060, + DUMMY_COM_IF = 0x54000040 }; } -#endif /* BSP_CONFIG_OBJECTS_SYSTEMOBJECTLIST_H_ */ +#endif /* LINUX_FSFWCONFIG_OBJECTS_SYSTEMOBJECTLIST_H_ */ diff --git a/linux/fsfwconfig/objects/translateObjects.cpp b/linux/fsfwconfig/objects/translateObjects.cpp index 62e0d583..2b6dc330 100644 --- a/linux/fsfwconfig/objects/translateObjects.cpp +++ b/linux/fsfwconfig/objects/translateObjects.cpp @@ -1,8 +1,8 @@ /** * @brief Auto-generated object translation file. * @details - * Contains 117 translations. - * Generated on: 2022-05-03 16:32:00 + * Contains 132 translations. + * Generated on: 2022-06-27 09:14:34 */ #include "translateObjects.h" @@ -12,18 +12,18 @@ const char *ACS_CONTROLLER_STRING = "ACS_CONTROLLER"; const char *THERMAL_CONTROLLER_STRING = "THERMAL_CONTROLLER"; const char *MGM_0_LIS3_HANDLER_STRING = "MGM_0_LIS3_HANDLER"; const char *GYRO_0_ADIS_HANDLER_STRING = "GYRO_0_ADIS_HANDLER"; -const char *SUS_0_STRING = "SUS_0"; -const char *SUS_1_STRING = "SUS_1"; -const char *SUS_2_STRING = "SUS_2"; -const char *SUS_3_STRING = "SUS_3"; -const char *SUS_4_STRING = "SUS_4"; -const char *SUS_5_STRING = "SUS_5"; -const char *SUS_6_STRING = "SUS_6"; -const char *SUS_7_STRING = "SUS_7"; -const char *SUS_8_STRING = "SUS_8"; -const char *SUS_9_STRING = "SUS_9"; -const char *SUS_10_STRING = "SUS_10"; -const char *SUS_11_STRING = "SUS_11"; +const char *SUS_0_N_LOC_XFYFZM_PT_XF_STRING = "SUS_0_N_LOC_XFYFZM_PT_XF"; +const char *SUS_1_N_LOC_XBYFZM_PT_XB_STRING = "SUS_1_N_LOC_XBYFZM_PT_XB"; +const char *SUS_2_N_LOC_XFYBZB_PT_YB_STRING = "SUS_2_N_LOC_XFYBZB_PT_YB"; +const char *SUS_3_N_LOC_XFYBZF_PT_YF_STRING = "SUS_3_N_LOC_XFYBZF_PT_YF"; +const char *SUS_4_N_LOC_XMYFZF_PT_ZF_STRING = "SUS_4_N_LOC_XMYFZF_PT_ZF"; +const char *SUS_5_N_LOC_XFYMZB_PT_ZB_STRING = "SUS_5_N_LOC_XFYMZB_PT_ZB"; +const char *SUS_6_R_LOC_XFYBZM_PT_XF_STRING = "SUS_6_R_LOC_XFYBZM_PT_XF"; +const char *SUS_7_R_LOC_XBYBZM_PT_XB_STRING = "SUS_7_R_LOC_XBYBZM_PT_XB"; +const char *SUS_8_R_LOC_XBYBZB_PT_YB_STRING = "SUS_8_R_LOC_XBYBZB_PT_YB"; +const char *SUS_9_R_LOC_XBYBZB_PT_YF_STRING = "SUS_9_R_LOC_XBYBZB_PT_YF"; +const char *SUS_10_N_LOC_XMYBZF_PT_ZF_STRING = "SUS_10_N_LOC_XMYBZF_PT_ZF"; +const char *SUS_11_R_LOC_XBYMZB_PT_ZB_STRING = "SUS_11_R_LOC_XBYMZB_PT_ZB"; const char *RW1_STRING = "RW1"; const char *MGM_1_RM3100_HANDLER_STRING = "MGM_1_RM3100_HANDLER"; const char *GYRO_1_L3G_HANDLER_STRING = "GYRO_1_L3G_HANDLER"; @@ -49,6 +49,8 @@ const char *PLOC_UPDATER_STRING = "PLOC_UPDATER"; const char *PLOC_MEMORY_DUMPER_STRING = "PLOC_MEMORY_DUMPER"; const char *STR_HELPER_STRING = "STR_HELPER"; const char *PLOC_MPSOC_HELPER_STRING = "PLOC_MPSOC_HELPER"; +const char *AXI_PTME_CONFIG_STRING = "AXI_PTME_CONFIG"; +const char *PTME_CONFIG_STRING = "PTME_CONFIG"; const char *PLOC_MPSOC_HANDLER_STRING = "PLOC_MPSOC_HANDLER"; const char *PLOC_SUPERVISOR_HANDLER_STRING = "PLOC_SUPERVISOR_HANDLER"; const char *PLOC_SUPERVISOR_HELPER_STRING = "PLOC_SUPERVISOR_HELPER"; @@ -56,26 +58,28 @@ const char *SOLAR_ARRAY_DEPL_HANDLER_STRING = "SOLAR_ARRAY_DEPL_HANDLER"; const char *HEATER_HANDLER_STRING = "HEATER_HANDLER"; const char *TMP1075_HANDLER_1_STRING = "TMP1075_HANDLER_1"; const char *TMP1075_HANDLER_2_STRING = "TMP1075_HANDLER_2"; -const char *RTD_IC_3_STRING = "RTD_IC_3"; -const char *RTD_IC_4_STRING = "RTD_IC_4"; -const char *RTD_IC_5_STRING = "RTD_IC_5"; -const char *RTD_IC_6_STRING = "RTD_IC_6"; -const char *RTD_IC_7_STRING = "RTD_IC_7"; -const char *RTD_IC_8_STRING = "RTD_IC_8"; -const char *RTD_IC_9_STRING = "RTD_IC_9"; -const char *RTD_IC_10_STRING = "RTD_IC_10"; -const char *RTD_IC_11_STRING = "RTD_IC_11"; -const char *RTD_IC_12_STRING = "RTD_IC_12"; -const char *RTD_IC_13_STRING = "RTD_IC_13"; -const char *RTD_IC_14_STRING = "RTD_IC_14"; -const char *RTD_IC_15_STRING = "RTD_IC_15"; -const char *RTD_IC_16_STRING = "RTD_IC_16"; -const char *RTD_IC_17_STRING = "RTD_IC_17"; -const char *RTD_IC_18_STRING = "RTD_IC_18"; +const char *RTD_0_IC3_PLOC_HEATSPREADER_STRING = "RTD_0_IC3_PLOC_HEATSPREADER"; +const char *RTD_1_IC4_PLOC_MISSIONBOARD_STRING = "RTD_1_IC4_PLOC_MISSIONBOARD"; +const char *RTD_2_IC5_4K_CAMERA_STRING = "RTD_2_IC5_4K_CAMERA"; +const char *RTD_3_IC6_DAC_HEATSPREADER_STRING = "RTD_3_IC6_DAC_HEATSPREADER"; +const char *RTD_4_IC7_STARTRACKER_STRING = "RTD_4_IC7_STARTRACKER"; +const char *RTD_5_IC8_RW1_MX_MY_STRING = "RTD_5_IC8_RW1_MX_MY"; +const char *RTD_6_IC9_DRO_STRING = "RTD_6_IC9_DRO"; +const char *RTD_7_IC10_SCEX_STRING = "RTD_7_IC10_SCEX"; +const char *RTD_8_IC11_X8_STRING = "RTD_8_IC11_X8"; +const char *RTD_9_IC12_HPA_STRING = "RTD_9_IC12_HPA"; +const char *RTD_10_IC13_PL_TX_STRING = "RTD_10_IC13_PL_TX"; +const char *RTD_11_IC14_MPA_STRING = "RTD_11_IC14_MPA"; +const char *RTD_12_IC15_ACU_STRING = "RTD_12_IC15_ACU"; +const char *RTD_13_IC16_PLPCDU_HEATSPREADER_STRING = "RTD_13_IC16_PLPCDU_HEATSPREADER"; +const char *RTD_14_IC17_TCS_BOARD_STRING = "RTD_14_IC17_TCS_BOARD"; +const char *RTD_15_IC18_IMTQ_STRING = "RTD_15_IC18_IMTQ"; const char *SYRLINKS_HK_HANDLER_STRING = "SYRLINKS_HK_HANDLER"; const char *ARDUINO_COM_IF_STRING = "ARDUINO_COM_IF"; const char *GPIO_IF_STRING = "GPIO_IF"; -const char *SPI_COM_IF_STRING = "SPI_COM_IF"; +const char *SPI_MAIN_COM_IF_STRING = "SPI_MAIN_COM_IF"; +const char *SPI_RW_COM_IF_STRING = "SPI_RW_COM_IF"; +const char *SPI_RTD_COM_IF_STRING = "SPI_RTD_COM_IF"; const char *UART_COM_IF_STRING = "UART_COM_IF"; const char *I2C_COM_IF_STRING = "I2C_COM_IF"; const char *CSP_COM_IF_STRING = "CSP_COM_IF"; @@ -96,6 +100,7 @@ const char *PUS_SERVICE_3_HOUSEKEEPING_STRING = "PUS_SERVICE_3_HOUSEKEEPING"; const char *PUS_SERVICE_5_EVENT_REPORTING_STRING = "PUS_SERVICE_5_EVENT_REPORTING"; const char *PUS_SERVICE_8_FUNCTION_MGMT_STRING = "PUS_SERVICE_8_FUNCTION_MGMT"; const char *PUS_SERVICE_9_TIME_MGMT_STRING = "PUS_SERVICE_9_TIME_MGMT"; +const char *PUS_SERVICE_11_TC_SCHEDULER_STRING = "PUS_SERVICE_11_TC_SCHEDULER"; const char *PUS_SERVICE_17_TEST_STRING = "PUS_SERVICE_17_TEST"; const char *PUS_SERVICE_20_PARAMETERS_STRING = "PUS_SERVICE_20_PARAMETERS"; const char *PUS_SERVICE_200_MODE_MGMT_STRING = "PUS_SERVICE_200_MODE_MGMT"; @@ -113,13 +118,23 @@ const char *FSFW_OBJECTS_END_STRING = "FSFW_OBJECTS_END"; const char *SPI_TEST_STRING = "SPI_TEST"; const char *UART_TEST_STRING = "UART_TEST"; const char *I2C_TEST_STRING = "I2C_TEST"; +const char *DUMMY_COM_IF_STRING = "DUMMY_COM_IF"; const char *DUMMY_HANDLER_STRING = "DUMMY_HANDLER"; const char *DUMMY_INTERFACE_STRING = "DUMMY_INTERFACE"; const char *LIBGPIOD_TEST_STRING = "LIBGPIOD_TEST"; const char *TEST_TASK_STRING = "TEST_TASK"; +const char *HEATER_0_PLOC_PROC_BRD_STRING = "HEATER_0_PLOC_PROC_BRD"; +const char *HEATER_1_PCDU_BRD_STRING = "HEATER_1_PCDU_BRD"; +const char *HEATER_2_ACS_BRD_STRING = "HEATER_2_ACS_BRD"; +const char *HEATER_3_OBC_BRD_STRING = "HEATER_3_OBC_BRD"; +const char *HEATER_4_CAMERA_STRING = "HEATER_4_CAMERA"; +const char *HEATER_5_STR_STRING = "HEATER_5_STR"; +const char *HEATER_6_DRO_STRING = "HEATER_6_DRO"; +const char *HEATER_7_HPA_STRING = "HEATER_7_HPA"; const char *ACS_BOARD_ASS_STRING = "ACS_BOARD_ASS"; const char *SUS_BOARD_ASS_STRING = "SUS_BOARD_ASS"; const char *TCS_BOARD_ASS_STRING = "TCS_BOARD_ASS"; +const char *RW_ASS_STRING = "RW_ASS"; const char *TM_FUNNEL_STRING = "TM_FUNNEL"; const char *CCSDS_IP_CORE_BRIDGE_STRING = "CCSDS_IP_CORE_BRIDGE"; const char *NO_OBJECT_STRING = "NO_OBJECT"; @@ -139,29 +154,29 @@ const char *translateObject(object_id_t object) { case 0x44120010: return GYRO_0_ADIS_HANDLER_STRING; case 0x44120032: - return SUS_0_STRING; + return SUS_0_N_LOC_XFYFZM_PT_XF_STRING; case 0x44120033: - return SUS_1_STRING; + return SUS_1_N_LOC_XBYFZM_PT_XB_STRING; case 0x44120034: - return SUS_2_STRING; + return SUS_2_N_LOC_XFYBZB_PT_YB_STRING; case 0x44120035: - return SUS_3_STRING; + return SUS_3_N_LOC_XFYBZF_PT_YF_STRING; case 0x44120036: - return SUS_4_STRING; + return SUS_4_N_LOC_XMYFZF_PT_ZF_STRING; case 0x44120037: - return SUS_5_STRING; + return SUS_5_N_LOC_XFYMZB_PT_ZB_STRING; case 0x44120038: - return SUS_6_STRING; + return SUS_6_R_LOC_XFYBZM_PT_XF_STRING; case 0x44120039: - return SUS_7_STRING; + return SUS_7_R_LOC_XBYBZM_PT_XB_STRING; case 0x44120040: - return SUS_8_STRING; + return SUS_8_R_LOC_XBYBZB_PT_YB_STRING; case 0x44120041: - return SUS_9_STRING; + return SUS_9_R_LOC_XBYBZB_PT_YF_STRING; case 0x44120042: - return SUS_10_STRING; + return SUS_10_N_LOC_XMYBZF_PT_ZF_STRING; case 0x44120043: - return SUS_11_STRING; + return SUS_11_R_LOC_XBYMZB_PT_ZB_STRING; case 0x44120047: return RW1_STRING; case 0x44120107: @@ -212,6 +227,10 @@ const char *translateObject(object_id_t object) { return STR_HELPER_STRING; case 0x44330003: return PLOC_MPSOC_HELPER_STRING; + case 0x44330004: + return AXI_PTME_CONFIG_STRING; + case 0x44330005: + return PTME_CONFIG_STRING; case 0x44330015: return PLOC_MPSOC_HANDLER_STRING; case 0x44330016: @@ -227,37 +246,37 @@ const char *translateObject(object_id_t object) { case 0x44420005: return TMP1075_HANDLER_2_STRING; case 0x44420016: - return RTD_IC_3_STRING; + return RTD_0_IC3_PLOC_HEATSPREADER_STRING; case 0x44420017: - return RTD_IC_4_STRING; + return RTD_1_IC4_PLOC_MISSIONBOARD_STRING; case 0x44420018: - return RTD_IC_5_STRING; + return RTD_2_IC5_4K_CAMERA_STRING; case 0x44420019: - return RTD_IC_6_STRING; + return RTD_3_IC6_DAC_HEATSPREADER_STRING; case 0x44420020: - return RTD_IC_7_STRING; + return RTD_4_IC7_STARTRACKER_STRING; case 0x44420021: - return RTD_IC_8_STRING; + return RTD_5_IC8_RW1_MX_MY_STRING; case 0x44420022: - return RTD_IC_9_STRING; + return RTD_6_IC9_DRO_STRING; case 0x44420023: - return RTD_IC_10_STRING; + return RTD_7_IC10_SCEX_STRING; case 0x44420024: - return RTD_IC_11_STRING; + return RTD_8_IC11_X8_STRING; case 0x44420025: - return RTD_IC_12_STRING; + return RTD_9_IC12_HPA_STRING; case 0x44420026: - return RTD_IC_13_STRING; + return RTD_10_IC13_PL_TX_STRING; case 0x44420027: - return RTD_IC_14_STRING; + return RTD_11_IC14_MPA_STRING; case 0x44420028: - return RTD_IC_15_STRING; + return RTD_12_IC15_ACU_STRING; case 0x44420029: - return RTD_IC_16_STRING; + return RTD_13_IC16_PLPCDU_HEATSPREADER_STRING; case 0x44420030: - return RTD_IC_17_STRING; + return RTD_14_IC17_TCS_BOARD_STRING; case 0x44420031: - return RTD_IC_18_STRING; + return RTD_15_IC18_IMTQ_STRING; case 0x445300A3: return SYRLINKS_HK_HANDLER_STRING; case 0x49000000: @@ -265,7 +284,11 @@ const char *translateObject(object_id_t object) { case 0x49010005: return GPIO_IF_STRING; case 0x49020004: - return SPI_COM_IF_STRING; + return SPI_MAIN_COM_IF_STRING; + case 0x49020005: + return SPI_RW_COM_IF_STRING; + case 0x49020006: + return SPI_RTD_COM_IF_STRING; case 0x49030003: return UART_COM_IF_STRING; case 0x49040002: @@ -306,6 +329,8 @@ const char *translateObject(object_id_t object) { return PUS_SERVICE_8_FUNCTION_MGMT_STRING; case 0x53000009: return PUS_SERVICE_9_TIME_MGMT_STRING; + case 0x53000011: + return PUS_SERVICE_11_TC_SCHEDULER_STRING; case 0x53000017: return PUS_SERVICE_17_TEST_STRING; case 0x53000020: @@ -340,6 +365,8 @@ const char *translateObject(object_id_t object) { return UART_TEST_STRING; case 0x54000030: return I2C_TEST_STRING; + case 0x54000040: + return DUMMY_COM_IF_STRING; case 0x5400AFFE: return DUMMY_HANDLER_STRING; case 0x5400CAFE: @@ -348,12 +375,30 @@ const char *translateObject(object_id_t object) { return LIBGPIOD_TEST_STRING; case 0x54694269: return TEST_TASK_STRING; + case 0x60000000: + return HEATER_0_PLOC_PROC_BRD_STRING; + case 0x60000001: + return HEATER_1_PCDU_BRD_STRING; + case 0x60000002: + return HEATER_2_ACS_BRD_STRING; + case 0x60000003: + return HEATER_3_OBC_BRD_STRING; + case 0x60000004: + return HEATER_4_CAMERA_STRING; + case 0x60000005: + return HEATER_5_STR_STRING; + case 0x60000006: + return HEATER_6_DRO_STRING; + case 0x60000007: + return HEATER_7_HPA_STRING; case 0x73000001: return ACS_BOARD_ASS_STRING; case 0x73000002: return SUS_BOARD_ASS_STRING; case 0x73000003: return TCS_BOARD_ASS_STRING; + case 0x73000004: + return RW_ASS_STRING; case 0x73000100: return TM_FUNNEL_STRING; case 0x73500000: diff --git a/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp b/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp index 02130d6b..87bd9c51 100644 --- a/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp +++ b/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp @@ -5,6 +5,8 @@ #include #include +#include "mission/devices/devicedefinitions/Max31865Definitions.h" + #ifndef RPI_TEST_ADIS16507 #define RPI_TEST_ADIS16507 0 #endif @@ -29,138 +31,69 @@ ReturnValue_t pst::pstGpio(FixedTimeslotTaskIF *thisSequence) { return HasReturnvaluesIF::RETURN_FAILED; } +ReturnValue_t pst::pstSpiRw(FixedTimeslotTaskIF *thisSequence) { + uint32_t length = thisSequence->getPeriodMs(); + static_cast(length); + thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + + thisSequence->addSlot(objects::RW1, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RW2, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RW3, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RW4, length * 0.2, DeviceHandlerIF::SEND_WRITE); + + thisSequence->addSlot(objects::RW1, length * 0.8, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RW2, length * 0.8, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RW3, length * 0.8, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RW4, length * 0.8, DeviceHandlerIF::GET_WRITE); + + thisSequence->addSlot(objects::RW1, length * 0.8, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RW2, length * 0.8, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RW3, length * 0.8, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RW4, length * 0.8, DeviceHandlerIF::SEND_READ); + + thisSequence->addSlot(objects::RW1, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::RW2, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::RW3, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::RW4, length * 0.8, DeviceHandlerIF::GET_READ); + return thisSequence->checkSequence(); +} + ReturnValue_t pst::pstSpi(FixedTimeslotTaskIF *thisSequence) { uint32_t length = thisSequence->getPeriodMs(); static_cast(length); #if OBSW_ADD_PL_PCDU == 1 thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0, DeviceHandlerIF::GET_READ); #endif #if OBSW_ADD_TMP_DEVICES == 1 thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0, DeviceHandlerIF::PERFORM_OPERATION); thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0, DeviceHandlerIF::PERFORM_OPERATION); #endif -#if OBSW_ADD_RTD_DEVICES == 1 - thisSequence->addSlot(objects::RTD_IC_3, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC_4, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC_5, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC_6, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC_7, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC_8, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC_9, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC_10, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC_11, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC_12, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC_13, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC_14, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC_15, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC_16, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC_17, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC_18, length * 0, DeviceHandlerIF::PERFORM_OPERATION); -#endif /* OBSW_ADD_RTD_DEVICES */ #if OBSW_ADD_TMP_DEVICES == 1 thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.2, DeviceHandlerIF::SEND_WRITE); thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.2, DeviceHandlerIF::SEND_WRITE); #endif -#if OBSW_ADD_RTD_DEVICES == 1 - thisSequence->addSlot(objects::RTD_IC_3, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC_4, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC_5, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC_6, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC_7, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC_8, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC_9, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC_10, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC_11, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC_12, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC_13, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC_14, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC_15, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC_16, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC_17, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC_18, length * 0.2, DeviceHandlerIF::SEND_WRITE); -#endif /* OBSW_ADD_RTD_DEVICES */ #if OBSW_ADD_TMP_DEVICES == 1 - thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.2, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.2, DeviceHandlerIF::GET_WRITE); #endif -#if OBSW_ADD_RTD_DEVICES == 1 - thisSequence->addSlot(objects::RTD_IC_3, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC_4, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC_5, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC_6, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC_7, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC_8, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC_9, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC_10, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC_11, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC_12, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC_13, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC_14, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC_15, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC_16, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC_17, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC_18, length * 0.4, DeviceHandlerIF::GET_WRITE); -#endif /* OBSW_ADD_RTD_DEVICES */ #if OBSW_ADD_TMP_DEVICES == 1 - thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.2, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.2, DeviceHandlerIF::SEND_READ); #endif -#if OBSW_ADD_RTD_DEVICES == 1 - thisSequence->addSlot(objects::RTD_IC_3, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC_4, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC_5, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC_6, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC_7, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC_8, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC_9, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC_10, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC_11, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC_12, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC_13, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC_14, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC_15, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC_16, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC_17, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC_18, length * 0.6, DeviceHandlerIF::SEND_READ); -#endif /* OBSW_ADD_RTD_DEVICES */ #if OBSW_ADD_TMP_DEVICES == 1 - thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.8, DeviceHandlerIF::GET_READ); -#endif -#if OBSW_ADD_RTD_DEVICES == 1 - thisSequence->addSlot(objects::RTD_IC_3, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC_4, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC_5, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC_6, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC_7, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC_8, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC_9, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC_10, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC_11, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC_12, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC_13, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC_14, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC_15, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC_16, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC_17, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC_18, length * 0.8, DeviceHandlerIF::GET_READ); -#endif /* OBSW_ADD_RTD_DEVICES */ - -#if OBSW_ADD_RAD_SENSORS == 1 - /* Radiation sensor */ - thisSequence->addSlot(objects::RAD_SENSOR, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RAD_SENSOR, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RAD_SENSOR, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RAD_SENSOR, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RAD_SENSOR, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.2, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.2, DeviceHandlerIF::GET_READ); #endif #if OBSW_ADD_SUN_SENSORS == 1 @@ -180,180 +113,261 @@ ReturnValue_t pst::pstSpi(FixedTimeslotTaskIF *thisSequence) { if (addSus0) { /* Write setup */ - thisSequence->addSlot(objects::SUS_0, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_0, length * 0, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_0, length * 0, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_0, length * 0, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_0, length * 0, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_0_N_LOC_XFYFZM_PT_XF, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::SUS_0_N_LOC_XFYFZM_PT_XF, length * 0, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_0_N_LOC_XFYFZM_PT_XF, length * 0, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_0_N_LOC_XFYFZM_PT_XF, length * 0, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_0_N_LOC_XFYFZM_PT_XF, length * 0, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::SUS_0, length * 0.4, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_0, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_0, length * 0.4, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_0, length * 0.4, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_0_N_LOC_XFYFZM_PT_XF, length * 0.4, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_0_N_LOC_XFYFZM_PT_XF, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_0_N_LOC_XFYFZM_PT_XF, length * 0.4, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_0_N_LOC_XFYFZM_PT_XF, length * 0.4, + DeviceHandlerIF::GET_READ); } if (addSus1) { - thisSequence->addSlot(objects::SUS_1, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_1, length * 0, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_1, length * 0, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_1, length * 0, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_1, length * 0, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_1_N_LOC_XBYFZM_PT_XB, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::SUS_1_N_LOC_XBYFZM_PT_XB, length * 0, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_1_N_LOC_XBYFZM_PT_XB, length * 0, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_1_N_LOC_XBYFZM_PT_XB, length * 0, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_1_N_LOC_XBYFZM_PT_XB, length * 0, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::SUS_1, length * 0.4, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_1, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_1, length * 0.4, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_1, length * 0.4, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_1_N_LOC_XBYFZM_PT_XB, length * 0.4, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_1_N_LOC_XBYFZM_PT_XB, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_1_N_LOC_XBYFZM_PT_XB, length * 0.4, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_1_N_LOC_XBYFZM_PT_XB, length * 0.4, + DeviceHandlerIF::GET_READ); } if (addSus2) { - thisSequence->addSlot(objects::SUS_2, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_2, length * 0, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_2, length * 0, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_2, length * 0, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_2, length * 0, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_2_N_LOC_XFYBZB_PT_YB, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::SUS_2_N_LOC_XFYBZB_PT_YB, length * 0, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_2_N_LOC_XFYBZB_PT_YB, length * 0, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_2_N_LOC_XFYBZB_PT_YB, length * 0, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_2_N_LOC_XFYBZB_PT_YB, length * 0, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::SUS_2, length * 0.4, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_2, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_2, length * 0.4, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_2, length * 0.4, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_2_N_LOC_XFYBZB_PT_YB, length * 0.4, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_2_N_LOC_XFYBZB_PT_YB, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_2_N_LOC_XFYBZB_PT_YB, length * 0.4, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_2_N_LOC_XFYBZB_PT_YB, length * 0.4, + DeviceHandlerIF::GET_READ); } if (addSus3) { - thisSequence->addSlot(objects::SUS_3, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_3, length * 0, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_3, length * 0, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_3, length * 0, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_3, length * 0, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_3_N_LOC_XFYBZF_PT_YF, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::SUS_3_N_LOC_XFYBZF_PT_YF, length * 0, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_3_N_LOC_XFYBZF_PT_YF, length * 0, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_3_N_LOC_XFYBZF_PT_YF, length * 0, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_3_N_LOC_XFYBZF_PT_YF, length * 0, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::SUS_3, length * 0.4, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_3, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_3, length * 0.4, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_3, length * 0.4, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_3_N_LOC_XFYBZF_PT_YF, length * 0.4, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_3_N_LOC_XFYBZF_PT_YF, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_3_N_LOC_XFYBZF_PT_YF, length * 0.4, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_3_N_LOC_XFYBZF_PT_YF, length * 0.4, + DeviceHandlerIF::GET_READ); } if (addSus4) { - thisSequence->addSlot(objects::SUS_4, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_4, length * 0, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_4, length * 0, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_4, length * 0, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_4, length * 0, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, length * 0, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, length * 0, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, length * 0, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, length * 0, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::SUS_4, length * 0.4, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_4, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_4, length * 0.4, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_4, length * 0.4, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, length * 0.4, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, length * 0.4, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, length * 0.4, + DeviceHandlerIF::GET_READ); } if (addSus5) { - thisSequence->addSlot(objects::SUS_5, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_5, length * 0, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_5, length * 0, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_5, length * 0, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_5, length * 0, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, length * 0, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, length * 0, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, length * 0, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, length * 0, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::SUS_5, length * 0.4, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_5, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_5, length * 0.4, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_5, length * 0.4, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, length * 0.4, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, length * 0.4, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, length * 0.4, + DeviceHandlerIF::GET_READ); } if (addSus6) { - thisSequence->addSlot(objects::SUS_6, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_6, length * 0, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_6, length * 0, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_6, length * 0, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_6, length * 0, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_6_R_LOC_XFYBZM_PT_XF, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::SUS_6_R_LOC_XFYBZM_PT_XF, length * 0, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_6_R_LOC_XFYBZM_PT_XF, length * 0, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_6_R_LOC_XFYBZM_PT_XF, length * 0, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_6_R_LOC_XFYBZM_PT_XF, length * 0, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::SUS_6, length * 0.4, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_6, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_6, length * 0.4, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_6, length * 0.4, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_6_R_LOC_XFYBZM_PT_XF, length * 0.4, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_6_R_LOC_XFYBZM_PT_XF, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_6_R_LOC_XFYBZM_PT_XF, length * 0.4, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_6_R_LOC_XFYBZM_PT_XF, length * 0.4, + DeviceHandlerIF::GET_READ); } if (addSus7) { - thisSequence->addSlot(objects::SUS_7, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_7, length * 0, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_7, length * 0, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_7, length * 0, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_7, length * 0, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_7_R_LOC_XBYBZM_PT_XB, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::SUS_7_R_LOC_XBYBZM_PT_XB, length * 0, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_7_R_LOC_XBYBZM_PT_XB, length * 0, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_7_R_LOC_XBYBZM_PT_XB, length * 0, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_7_R_LOC_XBYBZM_PT_XB, length * 0, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::SUS_7, length * 0.4, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_7, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_7, length * 0.4, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_7, length * 0.4, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_7_R_LOC_XBYBZM_PT_XB, length * 0.4, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_7_R_LOC_XBYBZM_PT_XB, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_7_R_LOC_XBYBZM_PT_XB, length * 0.4, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_7_R_LOC_XBYBZM_PT_XB, length * 0.4, + DeviceHandlerIF::GET_READ); } if (addSus8) { - thisSequence->addSlot(objects::SUS_8, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_8, length * 0, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_8, length * 0, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_8, length * 0, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_8, length * 0, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_8_R_LOC_XBYBZB_PT_YB, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::SUS_8_R_LOC_XBYBZB_PT_YB, length * 0, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_8_R_LOC_XBYBZB_PT_YB, length * 0, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_8_R_LOC_XBYBZB_PT_YB, length * 0, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_8_R_LOC_XBYBZB_PT_YB, length * 0, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::SUS_8, length * 0.4, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_8, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_8, length * 0.4, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_8, length * 0.4, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_8_R_LOC_XBYBZB_PT_YB, length * 0.4, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_8_R_LOC_XBYBZB_PT_YB, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_8_R_LOC_XBYBZB_PT_YB, length * 0.4, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_8_R_LOC_XBYBZB_PT_YB, length * 0.4, + DeviceHandlerIF::GET_READ); } if (addSus9) { - thisSequence->addSlot(objects::SUS_9, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_9, length * 0, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_9, length * 0, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_9, length * 0, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_9, length * 0, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::SUS_9, length * 0.4, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_9, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_9, length * 0.4, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_9, length * 0.4, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, length * 0, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, length * 0, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, length * 0, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, length * 0, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, length * 0.4, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, length * 0.4, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, length * 0.4, + DeviceHandlerIF::GET_READ); } if (addSus10) { - thisSequence->addSlot(objects::SUS_10, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_10, length * 0, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_10, length * 0, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_10, length * 0, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_10, length * 0, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, length * 0, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, length * 0, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, length * 0, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, length * 0, + DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::SUS_10, length * 0.4, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_10, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_10, length * 0.4, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_10, length * 0.4, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, length * 0.4, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, length * 0.4, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, length * 0.4, + DeviceHandlerIF::GET_READ); } if (addSus11) { - thisSequence->addSlot(objects::SUS_11, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_11, length * 0, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_11, length * 0, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_11, length * 0, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_11, length * 0, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, length * 0, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, length * 0, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, length * 0, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, length * 0, + DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::SUS_11, length * 0.4, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_11, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_11, length * 0.4, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_11, length * 0.4, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, length * 0.4, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, length * 0.4, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, length * 0.4, + DeviceHandlerIF::GET_READ); } #endif /* OBSW_ADD_SUN_SENSORS == 1 */ -#if OBSW_ADD_RW == 1 - thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RW1, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RW1, length * 0.5, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RW1, length * 0.65, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RW1, length * 0.8, DeviceHandlerIF::GET_READ); - - thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RW2, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RW2, length * 0.5, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RW2, length * 0.65, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RW2, length * 0.8, DeviceHandlerIF::GET_READ); - - thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RW3, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RW3, length * 0.5, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RW3, length * 0.65, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RW3, length * 0.8, DeviceHandlerIF::GET_READ); - - thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RW4, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RW4, length * 0.5, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RW4, length * 0.65, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RW4, length * 0.8, DeviceHandlerIF::GET_READ); +#if OBSW_ADD_RAD_SENSORS == 1 + /* Radiation sensor */ + thisSequence->addSlot(objects::RAD_SENSOR, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RAD_SENSOR, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RAD_SENSOR, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RAD_SENSOR, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RAD_SENSOR, length * 0.8, DeviceHandlerIF::GET_READ); #endif #if OBSW_ADD_ACS_BOARD == 1 && OBSW_ADD_ACS_HANDLERS == 1 @@ -464,11 +478,8 @@ ReturnValue_t pst::pstUart(FixedTimeslotTaskIF *thisSequence) { thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); #endif -#ifdef XIPHOS_Q7S - thisSequence->addSlot(objects::PLOC_UPDATER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); thisSequence->addSlot(objects::PLOC_MEMORY_DUMPER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); -#endif #if OBSW_ADD_PLOC_SUPERVISOR == 1 thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); diff --git a/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.h b/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.h index 19c86e52..03b0afb5 100644 --- a/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.h +++ b/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.h @@ -46,6 +46,8 @@ ReturnValue_t pstUart(FixedTimeslotTaskIF* thisSequence); ReturnValue_t pstSpi(FixedTimeslotTaskIF* thisSequence); +ReturnValue_t pstSpiRw(FixedTimeslotTaskIF* thisSequence); + ReturnValue_t pstI2c(FixedTimeslotTaskIF* thisSequence); /** diff --git a/linux/fsfwconfig/tmtc/pusIds.h b/linux/fsfwconfig/tmtc/pusIds.h deleted file mode 100644 index 37503786..00000000 --- a/linux/fsfwconfig/tmtc/pusIds.h +++ /dev/null @@ -1,23 +0,0 @@ -#ifndef CONFIG_TMTC_PUSIDS_HPP_ -#define CONFIG_TMTC_PUSIDS_HPP_ - -namespace pus { -enum Ids { - PUS_SERVICE_1 = 1, - PUS_SERVICE_2 = 2, - PUS_SERVICE_3 = 3, - PUS_SERVICE_3_PSB = 3, - PUS_SERVICE_5 = 5, - PUS_SERVICE_6 = 6, - PUS_SERVICE_8 = 8, - PUS_SERVICE_9 = 9, - PUS_SERVICE_17 = 17, - PUS_SERVICE_19 = 19, - PUS_SERVICE_20 = 20, - PUS_SERVICE_23 = 23, - PUS_SERVICE_200 = 200, - PUS_SERVICE_201 = 201, -}; -}; - -#endif /* CONFIG_TMTC_PUSIDS_HPP_ */ diff --git a/linux/obc/CMakeLists.txt b/linux/obc/CMakeLists.txt index 6d5c4436..e45a1fe2 100644 --- a/linux/obc/CMakeLists.txt +++ b/linux/obc/CMakeLists.txt @@ -1,10 +1,3 @@ -target_sources(${OBSW_NAME} PUBLIC - PapbVcInterface.cpp - Ptme.cpp - PdecHandler.cpp - PdecConfig.cpp - PtmeConfig.cpp - AxiPtmeConfig.cpp -) - - +target_sources( + ${OBSW_NAME} PUBLIC PapbVcInterface.cpp Ptme.cpp PdecHandler.cpp + PdecConfig.cpp PtmeConfig.cpp AxiPtmeConfig.cpp) diff --git a/linux/obc/PdecHandler.cpp b/linux/obc/PdecHandler.cpp index 48816512..7843ee5c 100644 --- a/linux/obc/PdecHandler.cpp +++ b/linux/obc/PdecHandler.cpp @@ -6,7 +6,6 @@ #include #include -#include "OBSWConfig.h" #include "fsfw/ipc/QueueFactory.h" #include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/serviceinterface/ServiceInterface.h" @@ -191,15 +190,20 @@ bool PdecHandler::newTcReceived() { void PdecHandler::checkLocks() { uint32_t clcw = getClcw(); - if (!(clcw & NO_RF_MASK) && (lastClcw & NO_RF_MASK)) { - // Rf available changed from 0 to 1 + if (not(clcw & NO_RF_MASK) && not carrierLock) { triggerEvent(CARRIER_LOCK); + carrierLock = true; + } else if ((clcw & NO_RF_MASK) && carrierLock) { + carrierLock = false; + triggerEvent(LOST_CARRIER_LOCK_PDEC); } - if (!(clcw & NO_BITLOCK_MASK) && (lastClcw & NO_BITLOCK_MASK)) { - // Bit lock changed from 0 to 1 + if (not(clcw & NO_BITLOCK_MASK) && not bitLock) { triggerEvent(BIT_LOCK_PDEC); + bitLock = true; + } else if ((clcw & NO_BITLOCK_MASK) && bitLock) { + bitLock = false; + triggerEvent(LOST_BIT_LOCK_PDEC); } - lastClcw = clcw; } bool PdecHandler::checkFrameAna(uint32_t pdecFar) { diff --git a/linux/obc/PdecHandler.h b/linux/obc/PdecHandler.h index 14863627..aeb571fc 100644 --- a/linux/obc/PdecHandler.h +++ b/linux/obc/PdecHandler.h @@ -73,6 +73,10 @@ class PdecHandler : public SystemObject, static const Event CARRIER_LOCK = MAKE_EVENT(3, severity::INFO); //! [EXPORT] : [COMMENT] Bit lock detected (data valid) static const Event BIT_LOCK_PDEC = MAKE_EVENT(4, severity::INFO); + //! [EXPORT] : [COMMENT] Lost carrier lock + static const Event LOST_CARRIER_LOCK_PDEC = MAKE_EVENT(5, severity::INFO); + //! [EXPORT] : [COMMENT] Lost bit lock + static const Event LOST_BIT_LOCK_PDEC = MAKE_EVENT(6, severity::INFO); private: static const uint8_t INTERFACE_ID = CLASS_ID::PDEC_HANDLER; @@ -391,6 +395,9 @@ class PdecHandler : public SystemObject, // Used to check carrier and bit lock changes (default set to no rf and no bitlock) uint32_t lastClcw = 0xC000; + + bool carrierLock = false; + bool bitLock = false; }; #endif /* LINUX_OBC_PDECHANDLER_H_ */ diff --git a/linux/utility/CMakeLists.txt b/linux/utility/CMakeLists.txt index 56937cea..f0d4e69c 100644 --- a/linux/utility/CMakeLists.txt +++ b/linux/utility/CMakeLists.txt @@ -1,7 +1 @@ -target_sources(${OBSW_NAME} PUBLIC - utility.cpp -) - - - - +target_sources(${OBSW_NAME} PUBLIC utility.cpp) diff --git a/misc/eclipse/.cproject b/misc/eclipse/.cproject index cf991ff4..d30ef1ec 100644 --- a/misc/eclipse/.cproject +++ b/misc/eclipse/.cproject @@ -57,7 +57,7 @@ - + @@ -119,7 +119,7 @@ - + @@ -187,7 +187,7 @@ - + @@ -215,10 +215,10 @@ @@ -699,7 +700,8 @@ - + +